![]() |
MoveIt Pro API
Core Behaviors for MoveIt Pro
|
Given an existing MTC Task object and a target object, appends MTC stages to generate cuboid grasp poses. More...
#include <setup_mtc_generate_cuboid_grasps.hpp>
Public Member Functions | |
SetupMTCGenerateCuboidGrasps (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) | |
BT::NodeStatus | tick () override |
![]() | |
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 () |
Static Public Attributes | |
static constexpr auto | kStageNameGeneratePose = "generate pose" |
static constexpr auto | kStageNamePoseIK = "pose IK" |
Additional Inherited Members | |
![]() | |
std::shared_ptr< BehaviorContext > | shared_resources_ |
Given an existing MTC Task object and a target object, appends MTC stages to generate cuboid grasp poses.
The monitored_stage
input provides the name of the MTC stage containing the initial (pre-aproach) planning scene, which can be used by the grasp generation stage(s) in this Behavior.
Data Port Name | Port Type | Object Type |
---|---|---|
task | Bidirectional | std::shared_ptr<moveit::task_constructor::Task> |
target_object | Input | moveit_studio_vision_msgs::msg::GraspableObject |
monitored_stage | Input | std::string |
parameters | Input | YAML::Node |
moveit_studio::behaviors::SetupMTCGenerateCuboidGrasps::SetupMTCGenerateCuboidGrasps | ( | const std::string & | name, |
const BT::NodeConfiguration & | config, | ||
const std::shared_ptr< BehaviorContext > & | shared_resources | ||
) |
|
static |
|
static |
|
override |
|
staticconstexpr |
|
staticconstexpr |