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 PublisherHandlerOptions() = default;
28
29 rclcpp::Node::SharedPtr node;
30
34 double throttle_rate = 0;
35
36 rclcpp::QoS qos = rclcpp::SystemDefaultsQoS();
37};
38
39/* class PublisherHandler_impl //{ */
40
44template <class TopicType>
46
47public:
52
57
64 PublisherHandler_impl(const PublisherHandlerOptions& options, const std::string& address);
65
72 void publish(const TopicType& msg);
73
79 void publish(const std::shared_ptr<TopicType>& msg);
80
86 /* void publish(const std::shared_ptr<TopicType const>& msg); */
87
93 void publish(typename TopicType::ConstSharedPtr msg);
94
100 unsigned int getNumSubscribers(void);
101
102private:
103 rclcpp::Node::SharedPtr node_;
104
105 std::shared_ptr<rclcpp::Publisher<TopicType>> publisher_;
106
107 std::mutex mutex_publisher_;
108
109 std::atomic<bool> publisher_initialized_;
110
111 std::string address_;
112
113 bool throttle_ = false;
114 double throttle_min_dt_ = 0;
115
116 rclcpp::Time last_time_published_;
117};
118
119//}
120
121/* class PublisherHandler //{ */
122
126template <class TopicType>
128
129public:
134
139
148
155
162 PublisherHandler(const rclcpp::Node::SharedPtr& node, const std::string& address);
163
170 PublisherHandler(const PublisherHandlerOptions& options, const std::string& address);
171
177 void publish(const TopicType& msg);
178
184 void publish(const std::shared_ptr<TopicType>& msg);
185
191 /* void publish(const std::shared_ptr<TopicType const>& msg); */
192
198 void publish(typename TopicType::ConstSharedPtr msg);
199
205 unsigned int getNumSubscribers(void);
206
207private:
208 std::shared_ptr<PublisherHandler_impl<TopicType>> impl_;
209};
210
211//}
212
213} // namespace mrs_lib
214
215#ifndef PUBLISHER_HANDLER_HPP
216#include <mrs_lib/impl/publisher_handler.hpp>
217#endif // PUBLISHER_HANDLER_H
218
219#endif // PUBLISHER_HANDLER_H
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