MoveIt Pro Behavior
Core Behaviors for MoveIt Pro
|
Transforms a stamped pose given an input translation and orientation. More...
#include <transform_pose.hpp>
Public Member Functions | |
TransformPose (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) | |
Constructor for TransformPose behavior. More... | |
BT::NodeStatus | tick () override |
Contains the logic to transform a geometry_msgs::msg::PoseStamped message. More... | |
Public Member Functions inherited from moveit_studio::behaviors::SharedResourcesNode< BT::SyncActionNode > | |
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. More... | |
Static Public Member Functions | |
static BT::PortsList | providedPorts () |
Custom tree nodes that have input and/or output ports must define them in this static function. More... | |
static BT::KeyValueVector | metadata () |
Additional Inherited Members | |
Protected Attributes inherited from moveit_studio::behaviors::SharedResourcesNode< BT::SyncActionNode > | |
std::shared_ptr< BehaviorContext > | shared_resources_ |
Transforms a stamped pose given an input translation and orientation.
The transformation occurs in the reference frame specified by the pose stamp. For example, if the input pose is expressed in the "world" frame, the translation and orientation are also applied in the "world" frame to produce the output pose.
Data Port Name | Port Type | Object Type |
---|---|---|
input_pose | input | geometry_msgs::msg::PoseStamped |
position_xyz | input | std::vector<double> |
orientation_xyzw | input | std::vector<double> |
output_pose | output | geometry_msgs::msg::PoseStamped |
moveit_studio::behaviors::TransformPose::TransformPose | ( | const std::string & | name, |
const BT::NodeConfiguration & | config, | ||
const std::shared_ptr< BehaviorContext > & | shared_resources | ||
) |
Constructor for TransformPose behavior.
name | Name of the node. Must match the name used for this node in the behavior tree definition file (the .xml file). |
config | Node configuration. Only used here because the BehaviorTree.CPP expects constructor signature with name and config first before custom constructor parameters. |
shared_resources | Provides access to common resources such as the node handle and failure logger that are shared between all the behaviors that inherit from moveit_studio::behaviors::SharedResourcesNode. |
|
static |
|
static |
Custom tree nodes that have input and/or output ports must define them in this static function.
This function must be static. It is a requirement set by the BehaviorTree.CPP library.
|
override |
Contains the logic to transform a geometry_msgs::msg::PoseStamped message.