MoveIt Pro Behavior
Core Behaviors for MoveIt Pro
moveit_studio::behaviors::GetCentroidFromPointCloud Class Reference

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>

Inheritance diagram for moveit_studio::behaviors::GetCentroidFromPointCloud:
Collaboration diagram for moveit_studio::behaviors::GetCentroidFromPointCloud:

Public Member Functions

 GetCentroidFromPointCloud (const std::string &name, const BT::NodeConfiguration &config)
 
BT::NodeStatus tick () override
 

Static Public Member Functions

static BT::PortsList providedPorts ()
 
static BT::KeyValueVector metadata ()
 

Detailed Description

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

Constructor & Destructor Documentation

◆ GetCentroidFromPointCloud()

moveit_studio::behaviors::GetCentroidFromPointCloud::GetCentroidFromPointCloud ( const std::string &  name,
const BT::NodeConfiguration &  config 
)

Member Function Documentation

◆ 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: