|
MoveIt Pro API
Core Behaviors for MoveIt Pro
|
Publishes a static transform into the tf2 buffer. More...
#include <publish_static_frame.hpp>


Public Member Functions | |
| PublishStaticFrame (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) | |
| BT::NodeStatus | onStart () override |
| BT::NodeStatus | onRunning () override |
| void | onHalted () override |
Public Member Functions inherited from moveit_studio::behaviors::SharedResourcesNode< BT::StatefulActionNode > | |
| SharedResourcesNode (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) | |
| Constructor for SharedResourcesNode. Called by BT::BehaviorTreeFactory when creating a new behavior tree containing this node. | |
Static Public Member Functions | |
| static BT::PortsList | providedPorts () |
| static BT::KeyValueVector | metadata () |
Additional Inherited Members | |
Protected Attributes inherited from moveit_studio::behaviors::SharedResourcesNode< BT::StatefulActionNode > | |
| std::shared_ptr< BehaviorContext > | shared_resources_ |
Publishes a static transform into the tf2 buffer.
| Data Port Name | Port Type | Object Type |
|---|---|---|
| pose | input | geometry_msgs::msg::PoseStamped |
| child_frame_id | input | std::string |
| publish_rate | input | int |
| moveit_studio::behaviors::PublishStaticFrame::PublishStaticFrame | ( | const std::string & | name, |
| const BT::NodeConfiguration & | config, | ||
| const std::shared_ptr< BehaviorContext > & | shared_resources | ||
| ) |
|
static |
|
override |
|
override |
|
override |
|
static |