MoveIt Pro Behavior
Core Behaviors for MoveIt Pro
|
Finds the line segment that best fits a point cloud fragment. More...
#include <fit_line_segment_to_mask3d.hpp>
Public Member Functions | |
FitLineSegmentToMask3D (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) | |
FitLineSegmentToMask3D (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources, const common::visualization::VisualizationClient &visualization_client) | |
Alternate constructor to allow mocking the rviz_visual_tools interface. | |
![]() | |
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_ |
Finds the line segment that best fits a point cloud fragment.
The point cloud fragment is defined by a 3D mask over an input point cloud. The line parameters are estimated with the RANSAC algorithm. The RANSAC iterative process hypothesizes line models from random point subsets, selecting the hypothesis that explains the most points in the set. A point is considered explained by a line hypothesis (a.k.a. "inlier") if it is closer than a distance threshold to it. The output segment is contained in the resulting line, and is the shortest segment containing all inlier points.
Data Port Name | Port Type | Object Type |
---|---|---|
point_cloud | input | sensor_msgs::msg::PointCloud2 |
masks3d | input | std::vector<moveit_studio_vision_msgs::msg::Mask3D> |
base_frame | input | std::string |
max_distance_from_line_for_inlier | input | double |
line_segment_poses | output | std::vector<geometry_msgs::msg::PoseStamped> |
moveit_studio::behaviors::FitLineSegmentToMask3D::FitLineSegmentToMask3D | ( | const std::string & | name, |
const BT::NodeConfiguration & | config, | ||
const std::shared_ptr< BehaviorContext > & | shared_resources | ||
) |
moveit_studio::behaviors::FitLineSegmentToMask3D::FitLineSegmentToMask3D | ( | const std::string & | name, |
const BT::NodeConfiguration & | config, | ||
const std::shared_ptr< BehaviorContext > & | shared_resources, | ||
const common::visualization::VisualizationClient & | visualization_client | ||
) |
Alternate constructor to allow mocking the rviz_visual_tools interface.
|
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 |