|
MoveIt Pro API
Core Behaviors for MoveIt Pro
|
Replaces the orientation of a PoseStamped with a fixed quaternion. More...
#include <override_pose_orientation.hpp>


Public Member Functions | |
| OverridePoseOrientation (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) | |
| 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< BehaviorContext > | shared_resources_ |
Replaces the orientation of a PoseStamped with a fixed quaternion.
This decouples grasp orientation from detection noise — the source pose's position is preserved while the orientation is overridden. Useful when a detected pose (e.g. from an AprilTag) has accurate position but noisy orientation. Use TransformPose if you also need to apply a positional offset.
| Data Port Name | Port Type | Object Type |
|---|---|---|
| input_pose | input | geometry_msgs::msg::PoseStamped |
| orientation_xyzw | input | std::vector<double> |
| output_pose | output | geometry_msgs::msg::PoseStamped |
| moveit_pro::behaviors::OverridePoseOrientation::OverridePoseOrientation | ( | const std::string & | name, |
| const BT::NodeConfiguration & | config, | ||
| const std::shared_ptr< BehaviorContext > & | shared_resources | ||
| ) |
|
static |
|
static |
|
override |