MoveIt Pro API
Core Behaviors for MoveIt Pro
Loading...
Searching...
No Matches
moveit_pro::behaviors::RotateTwistToFrame Class Referencefinal

Rotates a stamped twist into a different frame's orientation. More...

#include <rotate_twist_to_frame.hpp>

Inheritance diagram for moveit_pro::behaviors::RotateTwistToFrame:
Collaboration diagram for moveit_pro::behaviors::RotateTwistToFrame:

Public Member Functions

 RotateTwistToFrame (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 Constructor for RotateTwistToFrame behavior.
 
BT::NodeStatus tick () override
 
- Public Member Functions inherited from moveit_pro::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.
 

Static Public Member Functions

static BT::PortsList providedPorts ()
 
static BT::KeyValueVector metadata ()
 

Additional Inherited Members

- Protected Attributes inherited from moveit_pro::behaviors::SharedResourcesNode< BT::SyncActionNode >
std::shared_ptr< BehaviorContextshared_resources_
 

Detailed Description

Rotates a stamped twist into a different frame's orientation.

Re-expresses the linear and angular components of the input twist in the target frame's basis using cartesian_planning::twistRotationMatrix. Only the rotation part of the source-to-target transform is applied; any translation between the two frames is ignored, so this Behavior does not add the omega-cross-r reference-point shift that a full rigid-body twist transform would. This matches the common case of remapping a velocity command between frames without changing what point on the body is being commanded.

TF lookup uses tf2::TimePointZero (latest available transform); the input twist's header.stamp is intentionally ignored, since twists are typically control signals rather than measurements with a meaningful timestamp.

Returns FAILURE on a missing TF lookup (with the source / target frame names in the error message), or when required ports are missing.

Data Port Name Port Type Object Type
twist_in input geometry_msgs::msg::TwistStamped
target_frame_id input std::string
twist_out output geometry_msgs::msg::TwistStamped

Constructor & Destructor Documentation

◆ RotateTwistToFrame()

moveit_pro::behaviors::RotateTwistToFrame::RotateTwistToFrame ( const std::string &  name,
const BT::NodeConfiguration &  config,
const std::shared_ptr< BehaviorContext > &  shared_resources 
)

Constructor for RotateTwistToFrame behavior.

Parameters
nameName of the node. Must match the name used for this node in the behavior tree definition file (the .xml file).
configNode configuration. Only used here because BehaviorTree.CPP expects the constructor signature with name and config first before custom constructor parameters.
shared_resourcesProvides access to common resources such as the node handle and failure logger that are shared between all the behaviors that inherit from moveit_pro::behaviors::SharedResourcesNode.

Member Function Documentation

◆ metadata()

BT::KeyValueVector moveit_pro::behaviors::RotateTwistToFrame::metadata ( )
static

◆ providedPorts()

BT::PortsList moveit_pro::behaviors::RotateTwistToFrame::providedPorts ( )
static

◆ tick()

BT::NodeStatus moveit_pro::behaviors::RotateTwistToFrame::tick ( )
override

The documentation for this class was generated from the following files: