MoveIt Pro Behavior
Core Behaviors for MoveIt Pro
|
Transforms an input stamped pose with the transform specified by another stamped pose. More...
#include <transform_pose_with_pose.hpp>
Public Member Functions | |
TransformPoseWithPose (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) | |
Constructor for TransformPoseFrame behavior. More... | |
BT::NodeStatus | tick () override |
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 an input stamped pose with the transform specified by another stamped pose.
The frame IDs of the input point cloud and transform pose must match, or this Behavior will fail. The output point cloud will similarly be with respect to this frame. Its pose matrix results from pre-mulitplying the transform pose matrix to the input pose matrix.
Data Port Name | Port Type | Object Type |
---|---|---|
input_pose | input | geometry_msgs::msg::PoseStamped |
transform_pose | input | geometry_msgs::msg::PoseStamped |
output_pose | output | geometry_msgs::msg::PoseStamped |
moveit_studio::behaviors::TransformPoseWithPose::TransformPoseWithPose | ( | const std::string & | name, |
const BT::NodeConfiguration & | config, | ||
const std::shared_ptr< BehaviorContext > & | shared_resources | ||
) |
Constructor for TransformPoseFrame 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 |