MoveIt Pro Behavior
Core Behaviors for MoveIt Pro
|
Backprojects a number of image masks onto a point cloud with a camera model. More...
#include <get_masks3d_from_masks2d.hpp>
Public Member Functions | |
GetMasks3DFromMasks2D (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) | |
![]() | |
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(). | |
BT::NodeStatus | onRunning () override |
Required implementation of BT::StatefulActionNode::onRunning(). | |
void | onHalted () override |
Required implementation of BT::StatefulActionNode::onHalted(). | |
void | resetStatus () |
Resets the internal status of this node. | |
![]() | |
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 () |
Protected Member Functions | |
tl::expected< bool, std::string > | doWork () override |
User-implemented function which handles executing the potentially-long-running process. | |
tl::expected< Eigen::Isometry3d, std::string > | lookupTransform (const std::string &base_frame, const std_msgs::msg::Header &child_header) |
![]() | |
virtual tl::expected< void, std::string > | doHalt () |
Optionally implement additional work needed to cleanly interrupt the async process. | |
void | notifyCanHalt () |
Called when runAsync() finishes to notify onHalted() that the async process has finished. | |
Additional Inherited Members | |
![]() | |
std::shared_ptr< BehaviorContext > | shared_resources_ |
Backprojects a number of image masks onto a point cloud with a camera model.
Data Port Name | Port Type | Object Type |
---|---|---|
point_cloud | input | sensor_msgs::msg::PointCloud2 |
masks2d | input | std::vector<moveit_studio_vision_msgs::msg::Mask2D> |
camera_info | input | sensor_msgs::msg::CameraInfo |
masks3d | output | std::vector<moveit_studio_vision_msgs::msg::Mask3D> |
moveit_studio::behaviors::GetMasks3DFromMasks2D::GetMasks3DFromMasks2D | ( | const std::string & | name, |
const BT::NodeConfiguration & | config, | ||
const std::shared_ptr< BehaviorContext > & | shared_resources | ||
) |
|
overrideprotectedvirtual |
User-implemented function which handles executing the potentially-long-running process.
This function is called within an async process in a separate thread.
Implements moveit_studio::behaviors::AsyncBehaviorBase.
|
protected |
|
static |
|
static |