mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
Loading...
Searching...
No Matches
publisher_handler.h
Go to the documentation of this file.
1// clang: TomasFormat
6#ifndef PUBLISHER_HANDLER_H
7#define PUBLISHER_HANDLER_H
8
9#include <memory>
10
11#include <rclcpp/rclcpp.hpp>
12#include <rclcpp/node.hpp>
13#include <rclcpp/time_source.hpp>
14
15#include <atomic>
16#include <string>
17#include <mutex>
18
19namespace mrs_lib
20{
21
23 {
24 PublisherHandlerOptions(const rclcpp::Node::SharedPtr& node) : node(node)
25 {
26 }
27
28 PublisherHandlerOptions() = default;
29
30 rclcpp::Node::SharedPtr node;
31
35 double throttle_rate = 0;
36
37 rclcpp::QoS qos = rclcpp::SystemDefaultsQoS();
38 };
39
40 /* class PublisherHandler_impl //{ */
41
45 template <class TopicType>
47 {
48
49 public:
54
59
66 PublisherHandler_impl(const PublisherHandlerOptions& options, const std::string& address);
67
74 void publish(const TopicType& msg);
75
81 void publish(const std::shared_ptr<TopicType>& msg);
82
88 /* void publish(const std::shared_ptr<TopicType const>& msg); */
89
95 void publish(typename TopicType::ConstSharedPtr msg);
96
102 unsigned int getNumSubscribers(void);
103
104 private:
105 rclcpp::Node::SharedPtr node_;
106
107 std::shared_ptr<rclcpp::Publisher<TopicType>> publisher_;
108
109 std::mutex mutex_publisher_;
110
111 std::atomic<bool> publisher_initialized_;
112
113 std::string address_;
114
115 bool throttle_ = false;
116 double throttle_min_dt_ = 0;
117
118 rclcpp::Time last_time_published_;
119 };
120
121 //}
122
123 /* class PublisherHandler //{ */
124
128 template <class TopicType>
130 {
131
132 public:
137
142
151
158
165 PublisherHandler(const rclcpp::Node::SharedPtr& node, const std::string& address);
166
173 PublisherHandler(const PublisherHandlerOptions& options, const std::string& address);
174
180 void publish(const TopicType& msg);
181
187 void publish(const std::shared_ptr<TopicType>& msg);
188
194 /* void publish(const std::shared_ptr<TopicType const>& msg); */
195
201 void publish(typename TopicType::ConstSharedPtr msg);
202
208 unsigned int getNumSubscribers(void);
209
210 private:
211 std::shared_ptr<PublisherHandler_impl<TopicType>> impl_;
212 };
213
214 //}
215
216} // namespace mrs_lib
217
218#ifndef PUBLISHER_HANDLER_HPP
219#include <mrs_lib/impl/publisher_handler.hpp>
220#endif // PUBLISHER_HANDLER_H
221
222#endif // PUBLISHER_HANDLER_H
implementation of the publisher handler
Definition publisher_handler.h:47
unsigned int getNumSubscribers(void)
get number of subscribers
Definition publisher_handler.hpp:161
void publish(const TopicType &msg)
publish message
Definition publisher_handler.hpp:56
~PublisherHandler_impl(void)
default destructor
Definition publisher_handler.h:58
PublisherHandler_impl(void)
default constructor
Definition publisher_handler.hpp:17
user wrapper of the publisher handler implementation
Definition publisher_handler.h:130
void publish(const TopicType &msg)
publish message
Definition publisher_handler.hpp:241
PublisherHandler & operator=(const PublisherHandler &other)
operator=
Definition publisher_handler.hpp:180
~PublisherHandler(void)
generic destructor
Definition publisher_handler.h:141
unsigned int getNumSubscribers(void)
get number of subscribers
Definition publisher_handler.hpp:284
PublisherHandler(void)
generic constructor
Definition publisher_handler.h:136
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:35