|
MoveIt Pro API
Core Behaviors for MoveIt Pro
|
Finds well-singulated cuboids supported by a surface within a point cloud. More...
#include <find_singular_cuboids.hpp>


Public Member Functions | |
| FindSingularCuboids (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) | |
| BT::NodeStatus | onStart () override |
| BT::NodeStatus | onRunning () override |
| void | onHalted () override |
Public Member Functions inherited from moveit_studio::behaviors::SharedResourcesNode< BT::StatefulActionNode > | |
| 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 | kPortIDPointCloud = "point_cloud" |
| static constexpr auto | kPortIDBaseFrame = "base_frame" |
| static constexpr auto | kPortIDPlaneModelThreshold = "plane_model_threshold" |
| static constexpr auto | kPortIDClusterDistanceThreshold = "cluster_distance_threshold" |
| static constexpr auto | kPortIDCropBoxOriginXYZ = "crop_box_origin_xyz" |
| static constexpr auto | kPortIDCropBoxSizeXYZ = "crop_box_size_xyz" |
| static constexpr auto | kPortIDDetectedShapes = "detected_shapes" |
Additional Inherited Members | |
Protected Attributes inherited from moveit_studio::behaviors::SharedResourcesNode< BT::StatefulActionNode > | |
| std::shared_ptr< BehaviorContext > | shared_resources_ |
Finds well-singulated cuboids supported by a surface within a point cloud.
This behavior makes some assumptions about the environment:
The output GraspableObjects will be transformed so that their parent frame is the frame defined by the base_frame config parameter.
| Data Port Name | Port Type | Object Type |
|---|---|---|
| point_cloud | input | sensor_msgs::msg::PointCloud2 |
| base_frame | input | std::string |
| plane_model_threshold | input | double |
| cluster_distance_threshold | input | double |
| crop_box_origin_xyz | input | std::vector<double> |
| crop_box_size_xyz | input | std::vector<double> |
| detected_shapes | output | std::vector<GraspableObject> |
| moveit_studio::behaviors::FindSingularCuboids::FindSingularCuboids | ( | const std::string & | name, |
| const BT::NodeConfiguration & | config, | ||
| const std::shared_ptr< BehaviorContext > & | shared_resources | ||
| ) |
|
static |
|
override |
|
override |
|
override |
|
static |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |