![]() |
MoveIt Pro API
Core Behaviors for MoveIt Pro
|
Given a target GraspableObject and planning details about the arm, generate grasp poses. More...
#include <generate_cuboid_grasp_poses.hpp>
Public Member Functions | |
GenerateCuboidGraspPoses (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 | kPortIDTargetObject = "target_object" |
static constexpr auto | kPortIDEndEffectorGroupName = "end_effector_group_name" |
static constexpr auto | kPortIDGenerateXAxisGrasps = "generate_x_axis_grasps" |
static constexpr auto | kPortIDGenerateYAxisGrasps = "generate_y_axis_grasps" |
static constexpr auto | kPortIDGenerateZAxisGrasps = "generate_z_axis_grasps" |
static constexpr auto | kPortIDSamplesPerQuadrant = "samples_per_quadrant" |
static constexpr auto | kPortIDMaxGraspWidth = "max_grasp_width" |
static constexpr auto | kPortIDEEToTCPTransform = "ee_to_tcp_tf" |
static constexpr auto | kPortIDGraspPoses = "grasp_poses" |
Additional Inherited Members | |
![]() | |
std::shared_ptr< BehaviorContext > | shared_resources_ |
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. |
end_effector_group_name | Input | std::string | Name of the end effector group. |
generate_x_axis_grasps | Input | bool | If true, grasp samples will be generated along the X axis of the target object. |
generate_y_axis_grasps | Input | bool | If true, grasp samples will be generated along the Y axis of the target object. |
generate_z_axis_grasps | Input | bool | If true, grasp samples will be generated along the Z axis of the target object. |
samples_per_quadrant | Input | int | Number of samples to generate for each quadrant of the cuboid. |
max_grasp_width | Input | double | Maximum allowed finger width from a grasp. |
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. |
moveit_studio::behaviors::GenerateCuboidGraspPoses::GenerateCuboidGraspPoses | ( | const std::string & | name, |
const BT::NodeConfiguration & | config, | ||
const std::shared_ptr< BehaviorContext > & | shared_resources | ||
) |
|
static |
|
static |
|
override |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |