mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
Loading...
Searching...
No Matches
subscriber_handler.h
Go to the documentation of this file.
1// clang: MatousFormat
7#ifndef SUBRSCRIBER_HANDLER_H
8#define SUBRSCRIBER_HANDLER_H
9
10#include <rclcpp/rclcpp.hpp>
11#include <rclcpp/node.hpp>
12#include <rclcpp/time_source.hpp>
13
15
16namespace mrs_lib
17{
18
19 static const rclcpp::Duration no_timeout = rclcpp::Duration(0, 0);
20
21 /* struct SubscriberHandlerOptions //{ */
22
33 {
34 SubscriberHandlerOptions(const rclcpp::Node::SharedPtr& node) : node(node)
35 {
36 }
37 SubscriberHandlerOptions() = default;
38
39 rclcpp::Node::SharedPtr node;
41 std::string node_name = {};
43 std::string topic_name = {};
45 std::shared_ptr<mrs_lib::TimeoutManager> timeout_manager = nullptr;
48 rclcpp::Duration no_message_timeout =
49 mrs_lib::no_timeout;
52 std::function<void(const std::string& topic_name, const rclcpp::Time& last_msg)> timeout_callback =
53 {};
56 bool threadsafe = true;
58 bool autostart =
59 true;
61 rclcpp::QoS qos = rclcpp::SystemDefaultsQoS();
62
63 rclcpp::SubscriptionOptions subscription_options = rclcpp::SubscriptionOptions();
64 };
65
66 //}
67
68 /* SubscriberHandler class //{ */
90 template <typename MessageType>
92 {
93 public:
97 using message_type = MessageType;
98
102 using timeout_callback_t = std::function<void(const std::string& topic_name, const rclcpp::Time& last_msg)>;
103
107 using message_callback_t = std::function<void(typename MessageType::ConstSharedPtr)>;
108
109 public:
117 virtual typename MessageType::ConstSharedPtr getMsg()
118 {
119 assert(m_pimpl);
120 return m_pimpl->getMsg();
121 };
122
128 virtual typename MessageType::ConstSharedPtr peekMsg() const
129 {
130 assert(m_pimpl);
131 return m_pimpl->peekMsg();
132 };
133
139 virtual bool hasMsg() const
140 {
141 assert(m_pimpl);
142 return m_pimpl->hasMsg();
143 };
144
150 virtual bool newMsg() const
151 {
152 assert(m_pimpl);
153 return m_pimpl->newMsg();
154 };
155
161 virtual bool usedMsg() const
162 {
163 assert(m_pimpl);
164 return m_pimpl->usedMsg();
165 };
166
173 virtual typename MessageType::ConstSharedPtr waitForNew(const rclcpp::Duration& timeout)
174 {
175 assert(m_pimpl);
176 return m_pimpl->waitForNew(timeout);
177 };
178
184 virtual rclcpp::Time lastMsgTime() const
185 {
186 assert(m_pimpl);
187 return m_pimpl->lastMsgTime();
188 };
189
195 virtual std::string topicName() const
196 {
197 assert(m_pimpl);
198 return m_pimpl->topicName();
199 };
200
206 virtual std::string subscribedTopicName() const
207 {
208 assert(m_pimpl);
209 return m_pimpl->m_topic_name;
210 };
211
217 virtual uint32_t getNumPublishers() const
218 {
219 assert(m_pimpl);
220 return m_pimpl->getNumPublishers();
221 };
222
228 virtual void setNoMessageTimeout(const rclcpp::Duration& timeout)
229 {
230 assert(m_pimpl);
231 return m_pimpl->setNoMessageTimeout(timeout);
232 };
233
240 virtual void start()
241 {
242 assert(m_pimpl);
243 return m_pimpl->start();
244 };
245
252 virtual void stop()
253 {
254 assert(m_pimpl);
255 return m_pimpl->stop();
256 };
257
258 public:
266
275 template <class... Types>
276 SubscriberHandler(const SubscriberHandlerOptions& options, const std::string& topic_name, Types... args)
278 [options, topic_name]() {
279 SubscriberHandlerOptions opts = options;
280 opts.topic_name = topic_name;
281 return opts;
282 }(),
283 args...)
284 {
285 }
286
295 SubscriberHandler(const SubscriberHandlerOptions& options, const message_callback_t& message_callback = {})
296 {
297 if (options.threadsafe)
298 {
299 m_pimpl = std::make_unique<ImplThreadsafe>(options, message_callback);
300 } else
301 {
302 m_pimpl = std::make_unique<Impl>(options, message_callback);
303 }
304 if (options.autostart)
305 start();
306 };
307
316 template <class... Types>
317 SubscriberHandler(const SubscriberHandlerOptions& options, const timeout_callback_t& timeout_callback, Types... args)
319 [options, timeout_callback]() {
320 SubscriberHandlerOptions opts = options;
321 opts.timeout_callback = timeout_callback;
322 return opts;
323 }(),
324 args...)
325 {
326 }
327
337 template <class ObjectType1, class... Types>
339 void (ObjectType1::*const timeout_callback)(const std::string& topic_name, const rclcpp::Time& last_msg), ObjectType1* const obj1,
340 Types... args)
342 [options, timeout_callback, obj1]() {
343 SubscriberHandlerOptions opts = options;
344 opts.timeout_callback =
345 timeout_callback == nullptr ? timeout_callback_t() : std::bind(timeout_callback, obj1, std::placeholders::_1, std::placeholders::_2);
346 return opts;
347 }(),
348 args...)
349 {
350 }
351
361 template <class ObjectType2, class... Types>
362 SubscriberHandler(const SubscriberHandlerOptions& options, void (ObjectType2::*const message_callback)(typename MessageType::ConstSharedPtr),
363 ObjectType2* const obj2, Types... args)
364 : SubscriberHandler(options, message_callback == nullptr ? message_callback_t() : std::bind(message_callback, obj2, std::placeholders::_1), args...)
365 {
366 }
367
379 template <class ObjectType1, class ObjectType2, class... Types>
380 SubscriberHandler(const SubscriberHandlerOptions& options, void (ObjectType2::*const message_callback)(typename MessageType::ConstSharedPtr),
381 ObjectType2* const obj2, void (ObjectType1::*const timeout_callback)(const std::string& topic_name, const rclcpp::Time& last_msg),
382 ObjectType1* const obj1, Types... args)
384 [options, timeout_callback, obj1]() {
385 SubscriberHandlerOptions opts = options;
386 opts.timeout_callback =
387 timeout_callback == nullptr ? timeout_callback_t() : std::bind(timeout_callback, obj1, std::placeholders::_1, std::placeholders::_2);
388 return opts;
389 }(),
390 message_callback == nullptr ? message_callback_t() : std::bind(message_callback, obj2, std::placeholders::_1), args...)
391 {
392 }
393
402 template <class... Types>
403 SubscriberHandler(const SubscriberHandlerOptions& options, const rclcpp::Duration& no_message_timeout, Types... args)
405 [options, no_message_timeout]() {
406 SubscriberHandlerOptions opts = options;
407 opts.no_message_timeout = no_message_timeout;
408 return opts;
409 }(),
410 args...)
411 {
412 }
413
422 template <class... Types>
423 SubscriberHandler(const SubscriberHandlerOptions& options, std::shared_ptr<mrs_lib::TimeoutManager>& timeout_manager, Types... args)
424 : SubscriberHandler(options, timeout_manager, args...)
425 {
426 }
427
428 ~SubscriberHandler() = default;
429 // delete copy constructor and assignment operator (forbid copying shandlers)
430 SubscriberHandler(const SubscriberHandler&) = delete;
431 SubscriberHandler& operator=(const SubscriberHandler&) = delete;
432 // define only move constructor and assignemnt operator
434 {
435 this->m_pimpl = std::move(other.m_pimpl);
436 other.m_pimpl = nullptr;
437 }
438 SubscriberHandler& operator=(SubscriberHandler&& other)
439 {
440 this->m_pimpl = std::move(other.m_pimpl);
441 other.m_pimpl = nullptr;
442 return *this;
443 }
444
445 private:
446 class Impl;
447 class ImplThreadsafe;
448 std::unique_ptr<Impl> m_pimpl;
449 };
450 //}
451
455 template <typename SubscriberHandler>
457
467 template <typename Class, class... Types>
468 void construct_object(Class& object, Types... args)
469 {
470 object = Class(args...);
471 }
472} // namespace mrs_lib
473
474#ifndef SUBSCRIBER_HANDLER_HPP
475#include <mrs_lib/impl/subscriber_handler.hpp>
476#endif // SUBSCRIBER_HANDLER_HPP
477
478#endif // SUBRSCRIBER_HANDLER_H
The main class for ROS topic subscription, message timeout handling etc.
Definition subscriber_handler.h:92
virtual bool newMsg() const
Used to check whether at least one message has been received on the handled topic since the last call...
Definition subscriber_handler.h:150
SubscriberHandler(const SubscriberHandlerOptions &options, std::shared_ptr< mrs_lib::TimeoutManager > &timeout_manager, Types... args)
Convenience constructor overload.
Definition subscriber_handler.h:423
virtual void stop()
Disables the callbacks for the handled topic.
Definition subscriber_handler.h:252
virtual MessageType::ConstSharedPtr getMsg()
Returns the last received message on the topic, handled by this SubscriberHandler....
Definition subscriber_handler.h:117
SubscriberHandler(const SubscriberHandlerOptions &options, const std::string &topic_name, Types... args)
Main constructor.
Definition subscriber_handler.h:276
SubscriberHandler(const SubscriberHandlerOptions &options, const rclcpp::Duration &no_message_timeout, Types... args)
Convenience constructor overload.
Definition subscriber_handler.h:403
virtual uint32_t getNumPublishers() const
Returns number of publishers registered at the topic.
Definition subscriber_handler.h:217
MessageType message_type
Convenience type for the template parameter to enable nice aliasing.
Definition subscriber_handler.h:97
SubscriberHandler(const SubscriberHandlerOptions &options, void(ObjectType2::*const message_callback)(typename MessageType::ConstSharedPtr), ObjectType2 *const obj2, void(ObjectType1::*const timeout_callback)(const std::string &topic_name, const rclcpp::Time &last_msg), ObjectType1 *const obj1, Types... args)
Convenience constructor overload.
Definition subscriber_handler.h:380
SubscriberHandler(const SubscriberHandlerOptions &options, const timeout_callback_t &timeout_callback, Types... args)
Convenience constructor overload.
Definition subscriber_handler.h:317
virtual void setNoMessageTimeout(const rclcpp::Duration &timeout)
Sets the timeout for no received message.
Definition subscriber_handler.h:228
SubscriberHandler(const SubscriberHandlerOptions &options, const message_callback_t &message_callback={})
Convenience constructor overload.
Definition subscriber_handler.h:295
virtual std::string subscribedTopicName() const
Returns the subscribed (unresolved) name of the topic, handled by this SubscriberHandler.
Definition subscriber_handler.h:206
SubscriberHandler(const SubscriberHandlerOptions &options, void(ObjectType1::*const timeout_callback)(const std::string &topic_name, const rclcpp::Time &last_msg), ObjectType1 *const obj1, Types... args)
Convenience constructor overload.
Definition subscriber_handler.h:338
virtual std::string topicName() const
Returns the resolved (full) name of the topic, handled by this SubscriberHandler.
Definition subscriber_handler.h:195
SubscriberHandler()
Default constructor to avoid having to use pointers.
Definition subscriber_handler.h:265
virtual bool usedMsg() const
Used to check whether getMsg() was called at least once on this SubscriberHandler.
Definition subscriber_handler.h:161
SubscriberHandler(const SubscriberHandlerOptions &options, void(ObjectType2::*const message_callback)(typename MessageType::ConstSharedPtr), ObjectType2 *const obj2, Types... args)
Convenience constructor overload.
Definition subscriber_handler.h:362
virtual MessageType::ConstSharedPtr waitForNew(const rclcpp::Duration &timeout)
Blocks until new data becomes available or until the timeout runs out or until a spurious wake-up.
Definition subscriber_handler.h:173
virtual bool hasMsg() const
Used to check whether at least one message has been received on the handled topic.
Definition subscriber_handler.h:139
virtual void start()
Enables the callbacks for the handled topic.
Definition subscriber_handler.h:240
virtual MessageType::ConstSharedPtr peekMsg() const
Returns the last received message on the topic without modifying the newMsg() or usedMsg() flags.
Definition subscriber_handler.h:128
std::function< void(typename MessageType::ConstSharedPtr)> message_callback_t
Convenience type for the message callback function.
Definition subscriber_handler.h:107
std::function< void(const std::string &topic_name, const rclcpp::Time &last_msg)> timeout_callback_t
Type for the timeout callback function.
Definition subscriber_handler.h:102
virtual rclcpp::Time lastMsgTime() const
Returns time of the last received message on the topic, handled by this SubscriberHandler.
Definition subscriber_handler.h:184
All mrs_lib functions, classes, variables and definitions are contained in this namespace.
Definition attitude_converter.h:24
void construct_object(Class &object, Types... args)
Helper function for object construstion e.g. in case of member objects. This function is useful to av...
Definition subscriber_handler.h:468
typename SubscriberHandler::message_type message_type
Helper alias for convenient extraction of handled message type from a SubscribeHandlerPtr.
Definition subscriber_handler.h:456
A helper class to simplify setup of SubscriberHandler construction. This class is passed to the Subsc...
Definition subscriber_handler.h:33
rclcpp::Node::SharedPtr node
The ROS NodeHandle to be used for subscription.
Definition subscriber_handler.h:39
bool autostart
If true, the SubscriberHandler will be started after construction. Otherwise it has to be started usi...
Definition subscriber_handler.h:58
std::string topic_name
Name of the ROS topic to be handled.
Definition subscriber_handler.h:43
std::shared_ptr< mrs_lib::TimeoutManager > timeout_manager
Will be used for handling message timouts if necessary. If no manager is specified,...
Definition subscriber_handler.h:45
bool threadsafe
If true, all methods of the SubscriberHandler will be mutexed (using a recursive mutex) to avoid data...
Definition subscriber_handler.h:56
std::function< void(const std::string &topic_name, const rclcpp::Time &last_msg)> timeout_callback
This function will be called if no new message is received for the no_message_timeout duration....
Definition subscriber_handler.h:52
std::string node_name
Name of the ROS node, using this handle (used for messages printed to console).
Definition subscriber_handler.h:41
rclcpp::Duration no_message_timeout
If no new message is received for this duration, the timeout_callback function will be called....
Definition subscriber_handler.h:48