MoveIt Pro Behavior Interface  5.0.1
Library for developing custom behaviors for use in MoveIt Pro
moveit_studio::behaviors::GetMessageFromTopicBehaviorBase< MessageT >::RclcppSubscriberInterface Class Reference

Implementation of the subscriber interface for a rclcpp subscription. More...

#include <get_message_from_topic.hpp>

Inheritance diagram for moveit_studio::behaviors::GetMessageFromTopicBehaviorBase< MessageT >::RclcppSubscriberInterface:
Collaboration diagram for moveit_studio::behaviors::GetMessageFromTopicBehaviorBase< MessageT >::RclcppSubscriberInterface:

Public Member Functions

 RclcppSubscriberInterface (const std::shared_ptr< rclcpp::Node > node)
 
tl::expected< void, std::string > initialize (const std::string &topic_name, const std::chrono::duration< double > wait_for_message_timeout) override
 Initializes the rclcpp subscriber interface to listen on the provided topic. More...
 
tl::expected< MessageT, std::string > syncGetNextMessage () override
 Block until a message is received on the topic. More...
 
- Public Member Functions inherited from moveit_studio::behaviors::GetMessageFromTopicBehaviorBase< MessageT >::SubscriberInterfaceBase
virtual ~SubscriberInterfaceBase ()=default
 

Detailed Description

template<typename MessageT>
class moveit_studio::behaviors::GetMessageFromTopicBehaviorBase< MessageT >::RclcppSubscriberInterface

Implementation of the subscriber interface for a rclcpp subscription.

Constructor & Destructor Documentation

◆ RclcppSubscriberInterface()

template<typename MessageT >
moveit_studio::behaviors::GetMessageFromTopicBehaviorBase< MessageT >::RclcppSubscriberInterface::RclcppSubscriberInterface ( const std::shared_ptr< rclcpp::Node >  node)
explicit

Member Function Documentation

◆ initialize()

template<typename MessageT >
tl::expected< void, std::string > moveit_studio::behaviors::GetMessageFromTopicBehaviorBase< MessageT >::RclcppSubscriberInterface::initialize ( const std::string &  topic_name,
const std::chrono::duration< double >  wait_for_message_timeout 
)
overridevirtual

Initializes the rclcpp subscriber interface to listen on the provided topic.

This blocks for a brief duration until a publisher is available on the topic. If no publisher appears before the timeout, returns an error result.

After the publisher appears, get its current QoS settings, and set the subscriber's QoS settings to have the same reliability setting as the publisher. This ensures that the subscriber QoS always matches the publisher in situations where the same behavior may need to get messages from different sources which use different QoS settings (for example, retrieving images from a simulated camera publisher vs. a real-hardware camera driver).

If a subscriber was previously created for this behavior (for example, if the behavior is under a RepeatUntilFailure decorator node), the new topic name and QoS settings are compared to the existing subscriber's topic name and QoS settings. The subscriber is reinitialized if the topic name and QoS settings have changed since it was created. Otherwise the same subscriber is reused.

Parameters
topic_nameThe topic name to use when creating the subscriber.
wait_for_message_timeoutThe timeout duration to use when waiting for a message to be received on the topic.
Returns
Void if the subscriber interface was initialized successfully. Returns an error result if no publisher appeared on the topic or the subscriber could not be created.

Implements moveit_studio::behaviors::GetMessageFromTopicBehaviorBase< MessageT >::SubscriberInterfaceBase.

◆ syncGetNextMessage()

template<typename MessageT >
tl::expected< MessageT, std::string > moveit_studio::behaviors::GetMessageFromTopicBehaviorBase< MessageT >::RclcppSubscriberInterface::syncGetNextMessage
overridevirtual

Block until a message is received on the topic.

Returns
If the message was received, returns the message. Returns an error result if the timeout duration was exceeded before a message was received.

Implements moveit_studio::behaviors::GetMessageFromTopicBehaviorBase< MessageT >::SubscriberInterfaceBase.


The documentation for this class was generated from the following files: