|
MoveIt Pro API
Core Behaviors for MoveIt Pro
|
Base class for Behaviors that send a message to a topic. The message contents and topic name are specified as input ports. More...
#include <send_message_to_topic.hpp>


Public Member Functions | |
| SendMessageToTopicBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) | |
| Constructs SendMessageToTopicBehaviorBase using the RclcppPublisherInterface. | |
| SendMessageToTopicBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources, std::unique_ptr< PublisherInterfaceBase< MessageT > > publisher_interface) | |
| Constructs SendMessageToTopicBehaviorBase using a user-provided implementation of PublisherInterfaceBase. | |
| virtual | ~SendMessageToTopicBehaviorBase ()=default |
| BT::NodeStatus | tick () override |
Public Member Functions inherited from moveit_pro::behaviors::SharedResourcesNode< BT::SyncActionNode > | |
| 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 Attributes | |
| static constexpr auto | kPortIDMessage = "message" |
| Port names. | |
| static constexpr auto | kPortIDTopicName = "topic" |
| static constexpr auto | kPortIDQueueSize = "queue_size" |
| static constexpr auto | kPortIDUseBestEffort = "use_best_effort" |
Additional Inherited Members | |
Protected Attributes inherited from moveit_pro::behaviors::SharedResourcesNode< BT::SyncActionNode > | |
| std::shared_ptr< BehaviorContext > | shared_resources_ |
Base class for Behaviors that send a message to a topic. The message contents and topic name are specified as input ports.
| MessageT | ROS message type used to specialize this class. |
The "queue_size" (for the underlying publisher's quality of service) input port value must be > 0.
If The "use_best_effort" (for the underlying publisher's quality of service) is set to true, "best effort" reliability is used. If false, "reliable" reliability is used.
| Data Port Name | Port Type | Object Type |
|---|---|---|
| message | Input | MessageT |
| topic | Input | std::string |
| queue_size | Input | size_t |
| use_best_effort | Input | bool |
| moveit_pro::behaviors::SendMessageToTopicBehaviorBase< MessageT >::SendMessageToTopicBehaviorBase | ( | const std::string & | name, |
| const BT::NodeConfiguration & | config, | ||
| const std::shared_ptr< BehaviorContext > & | shared_resources | ||
| ) |
Constructs SendMessageToTopicBehaviorBase using the RclcppPublisherInterface.
| moveit_pro::behaviors::SendMessageToTopicBehaviorBase< MessageT >::SendMessageToTopicBehaviorBase | ( | const std::string & | name, |
| const BT::NodeConfiguration & | config, | ||
| const std::shared_ptr< BehaviorContext > & | shared_resources, | ||
| std::unique_ptr< PublisherInterfaceBase< MessageT > > | publisher_interface | ||
| ) |
Constructs SendMessageToTopicBehaviorBase using a user-provided implementation of PublisherInterfaceBase.
|
virtualdefault |
|
override |
|
staticconstexpr |
Port names.
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |