6#ifndef PUBLISHER_HANDLER_H
7#define PUBLISHER_HANDLER_H
11#include <rclcpp/rclcpp.hpp>
12#include <rclcpp/node.hpp>
13#include <rclcpp/time_source.hpp>
29 rclcpp::Node::SharedPtr node;
36 rclcpp::QoS qos = rclcpp::SystemDefaultsQoS();
44template <
class TopicType>
72 void publish(
const TopicType& msg);
79 void publish(
const std::shared_ptr<TopicType>& msg);
93 void publish(
typename TopicType::ConstSharedPtr msg);
103 rclcpp::Node::SharedPtr node_;
105 std::shared_ptr<rclcpp::Publisher<TopicType>> publisher_;
107 std::mutex mutex_publisher_;
109 std::atomic<bool> publisher_initialized_;
111 std::string address_;
113 bool throttle_ =
false;
114 double throttle_min_dt_ = 0;
116 rclcpp::Time last_time_published_;
126template <
class TopicType>
162 PublisherHandler(
const rclcpp::Node::SharedPtr& node,
const std::string& address);
177 void publish(
const TopicType& msg);
184 void publish(
const std::shared_ptr<TopicType>& msg);
198 void publish(
typename TopicType::ConstSharedPtr msg);
208 std::shared_ptr<PublisherHandler_impl<TopicType>> impl_;
215#ifndef PUBLISHER_HANDLER_HPP
216#include <mrs_lib/impl/publisher_handler.hpp>
implementation of the publisher handler
Definition publisher_handler.h:45
unsigned int getNumSubscribers(void)
get number of subscribers
Definition publisher_handler.hpp:146
void publish(const TopicType &msg)
publish message
Definition publisher_handler.hpp:53
~PublisherHandler_impl(void)
default destructor
Definition publisher_handler.h:56
PublisherHandler_impl(void)
default constructor
Definition publisher_handler.hpp:17
user wrapper of the publisher handler implementation
Definition publisher_handler.h:127
void publish(const TopicType &msg)
publish message
Definition publisher_handler.hpp:218
PublisherHandler & operator=(const PublisherHandler &other)
operator=
Definition publisher_handler.hpp:164
~PublisherHandler(void)
generic destructor
Definition publisher_handler.h:138
unsigned int getNumSubscribers(void)
get number of subscribers
Definition publisher_handler.hpp:258
PublisherHandler(void)
generic constructor
Definition publisher_handler.h:133
All mrs_lib functions, classes, variables and definitions are contained in this namespace.
Definition attitude_converter.h:24
Definition publisher_handler.h:23
double throttle_rate
when > 0, the publisher output is limited to this rate in [Hz]
Definition publisher_handler.h:34