![]() |
MoveIt Pro API
Core Behaviors for MoveIt Pro
|
Registers a target point cloud to a base point cloud and outputs the pose of the target point cloud relative to the origin of the base point cloud which aligns the target cloud with the base cloud. More...
#include <register_pointclouds.hpp>
Public Member Functions | |
RegisterPointClouds (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. | |
![]() | |
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_ |
Registers a target point cloud to a base point cloud and outputs the pose of the target point cloud relative to the origin of the base point cloud which aligns the target cloud with the base cloud.
This Behavior uses the the Iterative Closest Point (ICP) algorithm to align the two clouds.
Data Port Name | Port Type | Object Type |
---|---|---|
base_point_cloud | input | sensor_msgs::msg::PointCloud2 |
target_point_cloud | input | sensor_msgs::msg::PointCloud2 |
max_iterations | input | int |
max_correspondence_distance | input | double |
target_pose_in_base_frame | output | geometry_msgs::msg::PoseStamped |
moveit_studio::behaviors::RegisterPointClouds::RegisterPointClouds | ( | 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.
|
static |
|
static |