MoveIt Pro Behavior
Core Behaviors for MoveIt Pro
moveit_studio::behaviors::GetPointCloudFromMask3D Class Reference

Gets the fragment of a point cloud for a 3D mask. More...

#include <get_pointcloud_from_mask3d.hpp>

Inheritance diagram for moveit_studio::behaviors::GetPointCloudFromMask3D:
Collaboration diagram for moveit_studio::behaviors::GetPointCloudFromMask3D:

Public Member Functions

 GetPointCloudFromMask3D (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 
- Public Member Functions inherited from moveit_studio::behaviors::AsyncBehaviorBase
 AsyncBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 
virtual ~AsyncBehaviorBase ()=default
 
BT::NodeStatus onStart () override
 Required implementation of BT::StatefulActionNode::onStart(). More...
 
BT::NodeStatus onRunning () override
 Required implementation of BT::StatefulActionNode::onRunning(). More...
 
void onHalted () override
 Required implementation of BT::StatefulActionNode::onHalted(). More...
 
void resetStatus ()
 Resets the internal status of this node. More...
 
- 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. More...
 

Static Public Member Functions

static BT::PortsList providedPorts ()
 
static BT::KeyValueVector metadata ()
 

Protected Member Functions

tl::expected< bool, std::string > doWork () override
 User-implemented function which handles executing the potentially-long-running process. More...
 
- Protected Member Functions inherited from moveit_studio::behaviors::AsyncBehaviorBase
virtual tl::expected< void, std::string > doHalt ()
 Optionally implement additional work needed to cleanly interrupt the async process. More...
 
void notifyCanHalt ()
 Called when runAsync() finishes to notify onHalted() that the async process has finished. More...
 

Additional Inherited Members

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

Detailed Description

Gets the fragment of a point cloud for a 3D mask.

Data Port Name Port Type Object Type
point_cloud input sensor_msgs::msg::PointCloud2
mask3d input moveit_studio_vision_msgs::msg::Mask3D
point_cloud_fragment output sensor_msgs::msg::PointCloud2

Constructor & Destructor Documentation

◆ GetPointCloudFromMask3D()

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

Member Function Documentation

◆ doWork()

tl::expected< bool, std::string > moveit_studio::behaviors::GetPointCloudFromMask3D::doWork ( )
overrideprotectedvirtual

User-implemented function which handles executing the potentially-long-running process.

This function is called within an async process in a separate thread.

Returns
A tl::expected which contains a bool indicating task success if the process completed successfully or was canceled, or an error message if the process failed unexpectedly.

Implements moveit_studio::behaviors::AsyncBehaviorBase.

◆ metadata()

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

◆ providedPorts()

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

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