|
MoveIt Pro API
Core Behaviors for MoveIt Pro
|
Changes an input GraspableObject into a PoseStamped by getting its pose and its ID. More...
#include <extract_graspable_object_pose.hpp>


Public Member Functions | |
| ExtractGraspableObjectPose (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_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. | |
Static Public Member Functions | |
| static BT::PortsList | providedPorts () |
| static BT::KeyValueVector | metadata () |
Additional Inherited Members | |
Protected Attributes inherited from moveit_studio::behaviors::SharedResourcesNode< BT::SyncActionNode > | |
| std::shared_ptr< BehaviorContext > | shared_resources_ |
Changes an input GraspableObject into a PoseStamped by getting its pose and its ID.
This is used to create a new PoseStamped message, with the pose being the GraspableObject message's pose.
| Data Port Name | Port Type | Object Type |
|---|---|---|
| graspable_object | Input | moveit_studio_vision_msgs::msg::GraspableObject |
| port | Output | geometry_msgs::msg::PoseStamped |
| moveit_studio::behaviors::ExtractGraspableObjectPose::ExtractGraspableObjectPose | ( | const std::string & | name, |
| const BT::NodeConfiguration & | config, | ||
| const std::shared_ptr< BehaviorContext > & | shared_resources | ||
| ) |
|
static |
|
static |
|
override |