Get data from time-synchronized image and point cloud topics and populate them in output ports.
More...
#include <get_synced_image_and_point_cloud.hpp>
Get data from time-synchronized image and point cloud topics and populate them in output ports.
Data Port Name | Port Type | Object Type |
rgb_camera_info_topic_name | Input | std::string |
rgb_image_topic_name | Input | std::string |
point_cloud_topic_name | Input | std::string |
point_cloud | Output | sensor_msgs::msg::PointCloud2 |
rgb_image | Output | sensor_msgs::msg::Image |
rgb_camera_info | Output | sensor_msgs::msg::CameraInfo |
◆ GetSyncedImageAndPointCloud()
moveit_studio::behaviors::GetSyncedImageAndPointCloud::GetSyncedImageAndPointCloud |
( |
const std::string & |
name, |
|
|
const BT::NodeConfiguration & |
config, |
|
|
const std::shared_ptr< moveit_studio::behaviors::BehaviorContext > & |
shared_resources |
|
) |
| |
◆ metadata()
BT::KeyValueVector moveit_studio::behaviors::GetSyncedImageAndPointCloud::metadata |
( |
| ) |
|
|
static |
◆ onHalted()
void moveit_studio::behaviors::GetSyncedImageAndPointCloud::onHalted |
( |
| ) |
|
|
override |
◆ onRunning()
BT::NodeStatus moveit_studio::behaviors::GetSyncedImageAndPointCloud::onRunning |
( |
| ) |
|
|
override |
◆ onStart()
BT::NodeStatus moveit_studio::behaviors::GetSyncedImageAndPointCloud::onStart |
( |
| ) |
|
|
override |
◆ providedPorts()
BT::PortsList moveit_studio::behaviors::GetSyncedImageAndPointCloud::providedPorts |
( |
| ) |
|
|
static |
The documentation for this class was generated from the following files: