|
MoveIt Pro API
Core Behaviors for MoveIt Pro
|
Base class for Behaviors that get the latest message from a topic specified on an input data port and set that message to an output data port. More...
#include <get_message_from_topic.hpp>


Public Member Functions | |
| GetMessageFromTopicBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) | |
| Constructs GetMessageFromTopicBehaviorBase using the RclcppSubscriberInterface. | |
| GetMessageFromTopicBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources, std::unique_ptr< SubscriberInterface< MessageT > > subscriber_interface) | |
| Constructs GetMessageFromTopicBehaviorBase using a user-provided implementation of SubscriberInterface. | |
| ~GetMessageFromTopicBehaviorBase () override=default | |
Public Member Functions inherited from moveit_studio::behaviors::AsyncBehaviorBase | |
| AsyncBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) | |
| virtual | ~AsyncBehaviorBase ()=default |
| BT::NodeStatus | onStart () override |
| Required implementation of BT::StatefulActionNode::onStart(). | |
| BT::NodeStatus | onRunning () override |
| Required implementation of BT::StatefulActionNode::onRunning(). | |
| void | onHalted () override |
| Required implementation of BT::StatefulActionNode::onHalted(). | |
| void | resetStatus () |
| Resets the internal status of this node. | |
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 Attributes | |
| static constexpr auto | kPortIDTopicName = "topic_name" |
| Port names. | |
| static constexpr auto | kPortIDMessageOut = "message_out" |
| static constexpr auto | kPortIDTimeoutDuration = "timeout_sec" |
| static constexpr auto | kPortIDPublisherTimeoutDuration = "publisher_timeout_sec" |
Protected Member Functions | |
| virtual tl::expected< std::chrono::duration< double >, std::string > | getWaitForMessageTimeout () |
| Optional user-provided function to set the timeout used when waiting for a message to be received on the topic. | |
| virtual tl::expected< std::chrono::duration< double >, std::string > | getWaitForPublisherTimeout () |
| Optional user-provided function to set the timeout used when waiting for a publisher to advertise a topic. | |
Protected Member Functions inherited from moveit_studio::behaviors::AsyncBehaviorBase | |
| virtual std::shared_future< tl::expected< bool, std::string > > & | getFuture ()=0 |
| Gets the shared future which is used to monitor the progress of the async process. | |
| void | notifyCanHalt () |
| Called when runAsync() finishes to notify onHalted() that the async process has finished. | |
Additional Inherited Members | |
Protected Attributes inherited from moveit_studio::behaviors::SharedResourcesNode< BT::StatefulActionNode > | |
| std::shared_ptr< BehaviorContext > | shared_resources_ |
Base class for Behaviors that get the latest message from a topic specified on an input data port and set that message to an output data port.
| MessageT | ROS message type used to specialize this class. |
| moveit_studio::behaviors::GetMessageFromTopicBehaviorBase< MessageT >::GetMessageFromTopicBehaviorBase | ( | const std::string & | name, |
| const BT::NodeConfiguration & | config, | ||
| const std::shared_ptr< BehaviorContext > & | shared_resources | ||
| ) |
Constructs GetMessageFromTopicBehaviorBase using the RclcppSubscriberInterface.
| moveit_studio::behaviors::GetMessageFromTopicBehaviorBase< MessageT >::GetMessageFromTopicBehaviorBase | ( | const std::string & | name, |
| const BT::NodeConfiguration & | config, | ||
| const std::shared_ptr< BehaviorContext > & | shared_resources, | ||
| std::unique_ptr< SubscriberInterface< MessageT > > | subscriber_interface | ||
| ) |
Constructs GetMessageFromTopicBehaviorBase using a user-provided implementation of SubscriberInterface.
|
overridedefault |
|
inlineprotectedvirtual |
Optional user-provided function to set the timeout used when waiting for a message to be received on the topic.
If no user-defined implementation is provided, the default implementation returns a negative duration, which will cause the subscriber to wait for the result without timing out.
|
inlineprotectedvirtual |
Optional user-provided function to set the timeout used when waiting for a publisher to advertise a topic.
If no user-defined implementation is provided, the default implementation returns a negative duration, which will cause the subscriber to wait for the result without timing out.
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |
Port names.