Given an input point cloud, estimates the cloud centroid using pcl::compute3DCentroid and outputs that as a pose stamped with the same header as the point cloud.
More...
#include <get_centroid_from_pointcloud.hpp>
Given an input point cloud, estimates the cloud centroid using pcl::compute3DCentroid and outputs that as a pose stamped with the same header as the point cloud.
This utilizes the find centroid function from PCL on the passed point cloud.
Data Port Name | Port Type | Object Type |
point_cloud | input | sensor_msgs::msg::PointCloud2 |
output_pose | output | geometry_msgs::msg::PoseStamped |
◆ GetCentroidFromPointCloud()
moveit_studio::behaviors::GetCentroidFromPointCloud::GetCentroidFromPointCloud |
( |
const std::string & |
name, |
|
|
const BT::NodeConfiguration & |
config |
|
) |
| |
◆ metadata()
BT::KeyValueVector moveit_studio::behaviors::GetCentroidFromPointCloud::metadata |
( |
| ) |
|
|
static |
◆ providedPorts()
BT::PortsList moveit_studio::behaviors::GetCentroidFromPointCloud::providedPorts |
( |
| ) |
|
|
static |
◆ tick()
BT::NodeStatus moveit_studio::behaviors::GetCentroidFromPointCloud::tick |
( |
| ) |
|
|
override |
The documentation for this class was generated from the following files: