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

Implementation of the publisher interface for a rclcpp publisher. More...

#include <publisher_interface.hpp>

Inheritance diagram for moveit_studio::behaviors::RclcppPublisherInterface< MessageT >:
Collaboration diagram for moveit_studio::behaviors::RclcppPublisherInterface< MessageT >:

Public Member Functions

 RclcppPublisherInterface (const std::shared_ptr< rclcpp::Node > node)
 
tl::expected< void, std::string > initialize (const std::string &topic_name, const size_t queue_size, const bool use_best_effort) override
 Initializes the rclcpp publisher interface to publish on the provided topic. More...
 
tl::expected< void, std::string > publish (const MessageT &message) override
 Publish a message to a topic. More...
 
- Public Member Functions inherited from moveit_studio::behaviors::PublisherInterfaceBase< MessageT >
virtual ~PublisherInterfaceBase ()=default
 

Detailed Description

template<typename MessageT>
class moveit_studio::behaviors::RclcppPublisherInterface< MessageT >

Implementation of the publisher interface for a rclcpp publisher.

Constructor & Destructor Documentation

◆ RclcppPublisherInterface()

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

Member Function Documentation

◆ initialize()

template<typename MessageT >
tl::expected< void, std::string > moveit_studio::behaviors::RclcppPublisherInterface< MessageT >::initialize ( const std::string &  topic_name,
const size_t  queue_size,
const bool  use_best_effort 
)
overridevirtual

Initializes the rclcpp publisher interface to publish on the provided topic.

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

Implements moveit_studio::behaviors::PublisherInterfaceBase< MessageT >.

◆ publish()

template<typename MessageT >
tl::expected< void, std::string > moveit_studio::behaviors::RclcppPublisherInterface< MessageT >::publish ( const MessageT &  message)
overridevirtual

Publish a message to a topic.

Implements moveit_studio::behaviors::PublisherInterfaceBase< MessageT >.


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