MoveIt Pro API
Core Behaviors for MoveIt Pro
Loading...
Searching...
No Matches
moveit_studio::behaviors::GenerateVacuumGraspPoses Class Referencefinal

Given a target GraspableObject and planning details about the arm, generate grasp poses. More...

#include <generate_vacuum_grasp_poses.hpp>

Inheritance diagram for moveit_studio::behaviors::GenerateVacuumGraspPoses:
Collaboration diagram for moveit_studio::behaviors::GenerateVacuumGraspPoses:

Public Member Functions

 GenerateVacuumGraspPoses (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 ()
 

Static Public Attributes

static constexpr auto kPortIDTargetObject = "target_object"
 
static constexpr auto kPortIDPlanningSceneMsg = "planning_scene_msg"
 
static constexpr auto kPortIDEndEffectorGroupName = "end_effector_group_name"
 
static constexpr auto kPortIDUIGraspFrameName = "ui_grasp_link"
 
static constexpr auto kPortIDGenerateCentroidGrasps = "generate_centroid_grasps"
 
static constexpr auto kPortIDPaddingDimension = "padding_dimension"
 
static constexpr auto kPortIDSamplesPerPlane = "samples_per_plane"
 
static constexpr auto kPortIDNumOrientationSamples = "num_orientation_samples"
 
static constexpr auto kPortIDEEToTCPTransform = "ee_to_tcp_tf"
 
static constexpr auto kPortIDGraspPoses = "grasp_poses"
 

Additional Inherited Members

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

Detailed Description

Given a target GraspableObject and planning details about the arm, generate grasp poses.

Data Port Name Port Type Object Type Description
target_object Input moveit_studio_vision_msgs::msg::GraspableObject Cuboid object to grasp, represented as a moveit_studio_vision_msgs/GraspableObject.
planning_scene Input moveit_msgs::msg::PlanningScene Planning scene message.
end_effector_group_name Input std::string Name of the end effector group.
ui_grasp_frame_name Input std::string Name of the UI grasp frame link.
generate_centroid_grasps Input bool If true, generate grasps at the centroid of each surface.
padding_dimension Input double Padding on planar faces to avoid sampling on edges.
samples_per_plane Input int Number of samples per plane for grasp generation.
num_orientation_samples Input int Number of orientation samples for grasp generation.
ee_to_tcp_transform Input geometry_msgs::msg::PoseStamped Transform from the end effector to the tool center point provided as a PoseStamped msg.
grasp_poses Output std::vector<geometry_msgs::msg::PoseStamped> Generated grasp poses.

Constructor & Destructor Documentation

◆ GenerateVacuumGraspPoses()

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

Member Function Documentation

◆ metadata()

BT::KeyValueVector moveit_studio::behaviors::GenerateVacuumGraspPoses::metadata ( )
static

◆ providedPorts()

BT::PortsList moveit_studio::behaviors::GenerateVacuumGraspPoses::providedPorts ( )
static

◆ tick()

BT::NodeStatus moveit_studio::behaviors::GenerateVacuumGraspPoses::tick ( )
override

Member Data Documentation

◆ kPortIDEEToTCPTransform

constexpr auto moveit_studio::behaviors::GenerateVacuumGraspPoses::kPortIDEEToTCPTransform = "ee_to_tcp_tf"
staticconstexpr

◆ kPortIDEndEffectorGroupName

constexpr auto moveit_studio::behaviors::GenerateVacuumGraspPoses::kPortIDEndEffectorGroupName = "end_effector_group_name"
staticconstexpr

◆ kPortIDGenerateCentroidGrasps

constexpr auto moveit_studio::behaviors::GenerateVacuumGraspPoses::kPortIDGenerateCentroidGrasps = "generate_centroid_grasps"
staticconstexpr

◆ kPortIDGraspPoses

constexpr auto moveit_studio::behaviors::GenerateVacuumGraspPoses::kPortIDGraspPoses = "grasp_poses"
staticconstexpr

◆ kPortIDNumOrientationSamples

constexpr auto moveit_studio::behaviors::GenerateVacuumGraspPoses::kPortIDNumOrientationSamples = "num_orientation_samples"
staticconstexpr

◆ kPortIDPaddingDimension

constexpr auto moveit_studio::behaviors::GenerateVacuumGraspPoses::kPortIDPaddingDimension = "padding_dimension"
staticconstexpr

◆ kPortIDPlanningSceneMsg

constexpr auto moveit_studio::behaviors::GenerateVacuumGraspPoses::kPortIDPlanningSceneMsg = "planning_scene_msg"
staticconstexpr

◆ kPortIDSamplesPerPlane

constexpr auto moveit_studio::behaviors::GenerateVacuumGraspPoses::kPortIDSamplesPerPlane = "samples_per_plane"
staticconstexpr

◆ kPortIDTargetObject

constexpr auto moveit_studio::behaviors::GenerateVacuumGraspPoses::kPortIDTargetObject = "target_object"
staticconstexpr

◆ kPortIDUIGraspFrameName

constexpr auto moveit_studio::behaviors::GenerateVacuumGraspPoses::kPortIDUIGraspFrameName = "ui_grasp_link"
staticconstexpr

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