Appends a point cloud to a vector of point clouds.
More...
#include <add_pointcloud_to_vector.hpp>
|
| AddPointCloudToVector (const std::string &name, const BT::NodeConfiguration &config) |
|
BT::NodeStatus | tick () override |
| Contains the logic of this behavior. More...
|
|
|
static BT::PortsList | providedPorts () |
| Custom tree nodes that have input and/or output ports must define them in this static function. More...
|
|
static BT::KeyValueVector | metadata () |
|
Appends a point cloud to a vector of point clouds.
If the vector does not exist, it is created the first time the Behavior is run.
Data Port Name | Port Type | Object Type |
point_cloud | input | sensor_msgs::msg::PointCloud2 |
point_cloud_vector | bidirectional | std::vector<sensor_msgs::msg::PointCloud2> |
◆ AddPointCloudToVector()
moveit_studio::behaviors::AddPointCloudToVector::AddPointCloudToVector |
( |
const std::string & |
name, |
|
|
const BT::NodeConfiguration & |
config |
|
) |
| |
◆ metadata()
BT::KeyValueVector moveit_studio::behaviors::AddPointCloudToVector::metadata |
( |
| ) |
|
|
static |
◆ providedPorts()
BT::PortsList moveit_studio::behaviors::AddPointCloudToVector::providedPorts |
( |
| ) |
|
|
static |
Custom tree nodes that have input and/or output ports must define them in this static function.
This function must be static. It is a requirement set by the BehaviorTree.CPP library.
- Returns
- List of ports with the names and port info. The return value is for the internal use of the behavior tree.
◆ tick()
BT::NodeStatus moveit_studio::behaviors::AddPointCloudToVector::tick |
( |
| ) |
|
|
override |
Contains the logic of this behavior.
- Returns
- Returns SUCCESS if successful, else FAILURE.
The documentation for this class was generated from the following files: