MoveIt Pro Behavior
Core Behaviors for MoveIt Pro
|
Get data from time-synchronized image topics and populate them in output ports. More...
#include <get_synced_images.hpp>
Public Member Functions | |
GetSyncedImages (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< moveit_studio::behaviors::BehaviorContext > &shared_resources) | |
BT::NodeStatus | onStart () override |
BT::NodeStatus | onRunning () override |
void | onHalted () override |
Public Member Functions inherited from moveit_studio::behaviors::SharedResourcesNode< BT::StatefulActionNode > | |
SharedResourcesNode (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) | |
Constructor for SharedResourcesNode. Called by BT::BehaviorTreeFactory when creating a new behavior tree containing this node. | |
Static Public Member Functions | |
static BT::PortsList | providedPorts () |
static BT::KeyValueVector | metadata () |
Additional Inherited Members | |
Protected Attributes inherited from moveit_studio::behaviors::SharedResourcesNode< BT::StatefulActionNode > | |
std::shared_ptr< BehaviorContext > | shared_resources_ |
Get data from time-synchronized image topics and populate them in output ports.
Data Port Name | Port Type | Object Type |
---|---|---|
camera_info_1_topic_name | Input | std::string |
image_1_topic_name | Input | std::string |
camera_info_2_topic_name | Input | std::string |
image_2_topic_name | Input | std::string |
image_1 | Output | sensor_msgs::msg::Image |
camera_info_1 | Output | sensor_msgs::msg::CameraInfo |
image_2 | Output | sensor_msgs::msg::Image |
camera_info_2 | Output | sensor_msgs::msg::CameraInfo |
moveit_studio::behaviors::GetSyncedImages::GetSyncedImages | ( | const std::string & | name, |
const BT::NodeConfiguration & | config, | ||
const std::shared_ptr< moveit_studio::behaviors::BehaviorContext > & | shared_resources | ||
) |
|
static |
|
override |
|
override |
|
override |
|
static |