Given an input point cloud, finds the oriented bounding box (OBB) using pcl::MomentOfInertiaEstimation and outputs that as a center pose and box dimensions. The OBB orientation is disambiguated by choosing the orientation closest to the reference_pose.
More...
#include <get_oriented_bounding_box_from_pointcloud.hpp>
|
| 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.
|
| |
Given an input point cloud, finds the oriented bounding box (OBB) using pcl::MomentOfInertiaEstimation and outputs that as a center pose and box dimensions. The OBB orientation is disambiguated by choosing the orientation closest to the reference_pose.
| Data Port Name | Port Type | Object Type |
| point_cloud | input | sensor_msgs::msg::PointCloud2 |
| reference_pose | input | geometry_msgs::msg::PoseStamped |
| box_center_pose | output | geometry_msgs::msg::PoseStamped |
| box_dimensions | output | std::vector<double> |
◆ GetOrientedBoundingBoxFromPointCloud()
| moveit_pro::behaviors::GetOrientedBoundingBoxFromPointCloud::GetOrientedBoundingBoxFromPointCloud |
( |
const std::string & |
name, |
|
|
const BT::NodeConfiguration & |
config, |
|
|
const std::shared_ptr< BehaviorContext > & |
shared_resources |
|
) |
| |
◆ doWork()
| tl::expected< bool, std::string > moveit_pro::behaviors::GetOrientedBoundingBoxFromPointCloud::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_pro::behaviors::AsyncBehaviorBase.
◆ metadata()
| BT::KeyValueVector moveit_pro::behaviors::GetOrientedBoundingBoxFromPointCloud::metadata |
( |
| ) |
|
|
static |
◆ providedPorts()
| BT::PortsList moveit_pro::behaviors::GetOrientedBoundingBoxFromPointCloud::providedPorts |
( |
| ) |
|
|
static |
The documentation for this class was generated from the following files: