mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
subscribe_handler.h
Go to the documentation of this file.
1 // clang: MatousFormat
7 #ifndef SUBRSCRIBE_HANDLER_H
8 #define SUBRSCRIBE_HANDLER_H
9 
10 #include <optional>
11 
12 #include <ros/ros.h>
14 
15 namespace mrs_lib
16 {
17 
18  static const ros::Duration no_timeout = ros::Duration(0);
19 
20  /* struct SubscribeHandlerOptions //{ */
21 
32  {
33  SubscribeHandlerOptions(const ros::NodeHandle& nh) : nh(nh) {}
34  SubscribeHandlerOptions() = default;
35 
36  ros::NodeHandle nh;
38  std::string node_name = {};
40  std::string topic_name = {};
42  std::shared_ptr<mrs_lib::TimeoutManager> timeout_manager = nullptr;
44  ros::Duration no_message_timeout = mrs_lib::no_timeout;
46  std::function<void(const std::string& topic_name, const ros::Time& last_msg)> timeout_callback = {};
48  bool threadsafe = true;
50  bool autostart = true;
52  uint32_t queue_size = 3;
54  ros::TransportHints transport_hints = ros::TransportHints();
55  };
56 
57  //}
58 
59  /* SubscribeHandler class //{ */
81  template <typename MessageType>
83  {
84  public:
88  using message_type = MessageType;
89 
93  using timeout_callback_t = std::function<void(const std::string& topic_name, const ros::Time& last_msg)>;
94 
98  using message_callback_t = std::function<void(typename MessageType::ConstPtr)>;
99 
100  public:
108  virtual typename MessageType::ConstPtr getMsg() {assert(m_pimpl); return m_pimpl->getMsg();};
109 
115  virtual typename MessageType::ConstPtr peekMsg() const {assert(m_pimpl); return m_pimpl->peekMsg();};
116 
122  virtual bool hasMsg() const {assert(m_pimpl); return m_pimpl->hasMsg();};
123 
129  virtual bool newMsg() const {assert(m_pimpl); return m_pimpl->newMsg();};
130 
136  virtual bool usedMsg() const {assert(m_pimpl); return m_pimpl->usedMsg();};
137 
144  virtual typename MessageType::ConstPtr waitForNew(const ros::WallDuration& timeout) {assert(m_pimpl); return m_pimpl->waitForNew(timeout);};
145 
151  virtual ros::Time lastMsgTime() const {assert(m_pimpl); return m_pimpl->lastMsgTime();};
152 
158  virtual std::string topicName() const {assert(m_pimpl); return m_pimpl->topicName();};
159 
165  virtual std::string subscribedTopicName() const {assert(m_pimpl); return m_pimpl->m_topic_name;};
166 
172  virtual uint32_t getNumPublishers() const {assert(m_pimpl); return m_pimpl->getNumPublishers();};
173 
179  virtual void setNoMessageTimeout(const ros::Duration& timeout) {assert(m_pimpl); return m_pimpl->setNoMessageTimeout(timeout);};
180 
187  virtual void start() {assert(m_pimpl); return m_pimpl->start();};
188 
195  virtual void stop() {assert(m_pimpl); return m_pimpl->stop();};
196 
197  public:
205 
214  template<class ... Types>
216  const SubscribeHandlerOptions& options,
217  const std::string& topic_name,
218  Types ... args
219  )
220  :
222  [options, topic_name]()
223  {
224  SubscribeHandlerOptions opts = options;
225  opts.topic_name = topic_name;
226  return opts;
227  }(),
228  args...
229  )
230  {
231  }
232 
241  const SubscribeHandlerOptions& options,
242  const message_callback_t& message_callback = {}
243  )
244  {
245  if (options.threadsafe)
246  {
247  m_pimpl = std::make_unique<ImplThreadsafe>
248  (
249  options,
250  message_callback
251  );
252  }
253  else
254  {
255  m_pimpl = std::make_unique<Impl>
256  (
257  options,
258  message_callback
259  );
260  }
261  if (options.autostart)
262  start();
263  };
264 
273  template <class ... Types>
275  const SubscribeHandlerOptions& options,
276  const timeout_callback_t& timeout_callback,
277  Types ... args
278  )
279  :
281  [options, timeout_callback]()
282  {
283  SubscribeHandlerOptions opts = options;
284  opts.timeout_callback = timeout_callback;
285  return opts;
286  }(),
287  args...
288  )
289  {
290  }
291 
301  template <class ObjectType1, class ... Types>
303  const SubscribeHandlerOptions& options,
304  void (ObjectType1::*const timeout_callback) (const std::string& topic_name, const ros::Time& last_msg),
305  ObjectType1* const obj1,
306  Types ... args
307  )
308  :
310  [options, timeout_callback, obj1]()
311  {
312  SubscribeHandlerOptions opts = options;
313  opts.timeout_callback = timeout_callback == nullptr ? timeout_callback_t() : std::bind(timeout_callback, obj1, std::placeholders::_1, std::placeholders::_2);
314  return opts;
315  }(),
316  args...
317  )
318  {
319  }
320 
330  template <class ObjectType2, class ... Types>
332  const SubscribeHandlerOptions& options,
333  void (ObjectType2::*const message_callback) (typename MessageType::ConstPtr),
334  ObjectType2* const obj2,
335  Types ... args
336  )
337  :
339  options,
340  message_callback == nullptr ? message_callback_t() : std::bind(message_callback, obj2, std::placeholders::_1),
341  args...
342  )
343  {
344  }
345 
357  template <class ObjectType1, class ObjectType2, class ... Types>
359  const SubscribeHandlerOptions& options,
360  void (ObjectType2::*const message_callback) (typename MessageType::ConstPtr),
361  ObjectType2* const obj2,
362  void (ObjectType1::*const timeout_callback) (const std::string& topic_name, const ros::Time& last_msg),
363  ObjectType1* const obj1,
364  Types ... args
365  )
366  :
368  [options, timeout_callback, obj1]()
369  {
370  SubscribeHandlerOptions opts = options;
371  opts.timeout_callback = timeout_callback == nullptr ? timeout_callback_t() : std::bind(timeout_callback, obj1, std::placeholders::_1, std::placeholders::_2);
372  return opts;
373  }(),
374  message_callback == nullptr ? message_callback_t() : std::bind(message_callback, obj2, std::placeholders::_1),
375  args...
376  )
377  {
378  }
379 
388  template<class ... Types>
390  const SubscribeHandlerOptions& options,
391  const ros::Duration& no_message_timeout,
392  Types ... args
393  )
394  :
396  [options, no_message_timeout]()
397  {
398  SubscribeHandlerOptions opts = options;
399  opts.no_message_timeout = no_message_timeout;
400  return opts;
401  }(),
402  args...
403  )
404  {
405  }
406 
415  template <class ... Types>
417  const SubscribeHandlerOptions& options,
418  mrs_lib::TimeoutManager& timeout_manager,
419  Types ... args
420  )
421  :
423  options,
424  timeout_manager = timeout_manager,
425  args...
426  )
427  {
428  }
429 
430  ~SubscribeHandler() = default;
431  // delete copy constructor and assignment operator (forbid copying shandlers)
432  SubscribeHandler(const SubscribeHandler&) = delete;
433  SubscribeHandler& operator=(const SubscribeHandler&) = delete;
434  // define only move constructor and assignemnt operator
436  {
437  this->m_pimpl = std::move(other.m_pimpl);
438  other.m_pimpl = nullptr;
439  }
440  SubscribeHandler& operator=(SubscribeHandler&& other)
441  {
442  this->m_pimpl = std::move(other.m_pimpl);
443  other.m_pimpl = nullptr;
444  return *this;
445  }
446 
447  private:
448  class Impl;
449  class ImplThreadsafe;
450  std::unique_ptr<Impl> m_pimpl;
451  };
452  //}
453 
457  template<typename SubscribeHandler>
459 
469  template<typename Class, class ... Types>
471  Class& object,
472  Types ... args
473  )
474  {
475  object = Class(args...);
476  }
477 }
478 
479 #include <mrs_lib/impl/subscribe_handler.hpp>
480 
481 #endif // SUBRSCRIBE_HANDLER_H
mrs_lib::SubscribeHandlerOptions::queue_size
uint32_t queue_size
This parameter is passed to the NodeHandle when subscribing to the topic.
Definition: subscribe_handler.h:52
mrs_lib::SubscribeHandler::hasMsg
virtual bool hasMsg() const
Used to check whether at least one message has been received on the handled topic.
Definition: subscribe_handler.h:122
mrs_lib::SubscribeHandler::SubscribeHandler
SubscribeHandler(const SubscribeHandlerOptions &options, const timeout_callback_t &timeout_callback, Types ... args)
Convenience constructor overload.
Definition: subscribe_handler.h:274
mrs_lib::SubscribeHandler::setNoMessageTimeout
virtual void setNoMessageTimeout(const ros::Duration &timeout)
Sets the timeout for no received message.
Definition: subscribe_handler.h:179
mrs_lib::SubscribeHandler::message_type
MessageType message_type
Convenience type for the template parameter to enable nice aliasing.
Definition: subscribe_handler.h:88
mrs_lib::SubscribeHandler::timeout_callback_t
std::function< void(const std::string &topic_name, const ros::Time &last_msg)> timeout_callback_t
Type for the timeout callback function.
Definition: subscribe_handler.h:93
mrs_lib::SubscribeHandlerOptions::timeout_manager
std::shared_ptr< mrs_lib::TimeoutManager > timeout_manager
Will be used for handling message timouts if necessary. If no manager is specified,...
Definition: subscribe_handler.h:42
mrs_lib::SubscribeHandler::usedMsg
virtual bool usedMsg() const
Used to check whether getMsg() was called at least once on this SubscribeHandler.
Definition: subscribe_handler.h:136
mrs_lib::SubscribeHandlerOptions::transport_hints
ros::TransportHints transport_hints
This parameter is passed to the NodeHandle when subscribing to the topic.
Definition: subscribe_handler.h:54
mrs_lib::SubscribeHandlerOptions
A helper class to simplify setup of SubscribeHandler construction. This class is passed to the Subscr...
Definition: subscribe_handler.h:31
mrs_lib::SubscribeHandler::SubscribeHandler
SubscribeHandler(const SubscribeHandlerOptions &options, void(ObjectType2::*const message_callback)(typename MessageType::ConstPtr), ObjectType2 *const obj2, Types ... args)
Convenience constructor overload.
Definition: subscribe_handler.h:331
mrs_lib::SubscribeHandler::stop
virtual void stop()
Disables the callbacks for the handled topic.
Definition: subscribe_handler.h:195
mrs_lib::SubscribeHandler::SubscribeHandler
SubscribeHandler(const SubscribeHandlerOptions &options, const std::string &topic_name, Types ... args)
Main constructor.
Definition: subscribe_handler.h:215
mrs_lib::SubscribeHandler::getMsg
virtual MessageType::ConstPtr getMsg()
Returns the last received message on the topic, handled by this SubscribeHandler. Use hasMsg() first ...
Definition: subscribe_handler.h:108
mrs_lib::SubscribeHandler::SubscribeHandler
SubscribeHandler(const SubscribeHandlerOptions &options, void(ObjectType2::*const message_callback)(typename MessageType::ConstPtr), ObjectType2 *const obj2, void(ObjectType1::*const timeout_callback)(const std::string &topic_name, const ros::Time &last_msg), ObjectType1 *const obj1, Types ... args)
Convenience constructor overload.
Definition: subscribe_handler.h:358
mrs_lib::SubscribeHandler::start
virtual void start()
Enables the callbacks for the handled topic.
Definition: subscribe_handler.h:187
mrs_lib::SubscribeHandler
The main class for ROS topic subscription, message timeout handling etc.
Definition: subscribe_handler.h:82
timeout_manager.h
TODO.
mrs_lib::SubscribeHandlerOptions::no_message_timeout
ros::Duration no_message_timeout
If no new message is received for this duration, the timeout_callback function will be called....
Definition: subscribe_handler.h:44
mrs_lib::SubscribeHandler::waitForNew
virtual MessageType::ConstPtr waitForNew(const ros::WallDuration &timeout)
Blocks until new data becomes available or until the timeout runs out or until a spurious wake-up.
Definition: subscribe_handler.h:144
mrs_lib::message_type
typename SubscribeHandler::message_type message_type
Helper alias for convenient extraction of handled message type from a SubscribeHandlerPtr.
Definition: subscribe_handler.h:458
mrs_lib::SubscribeHandler::SubscribeHandler
SubscribeHandler()
Default constructor to avoid having to use pointers.
Definition: subscribe_handler.h:204
mrs_lib::SubscribeHandlerOptions::node_name
std::string node_name
Name of the ROS node, using this handle (used for messages printed to console).
Definition: subscribe_handler.h:38
mrs_lib::SubscribeHandler::SubscribeHandler
SubscribeHandler(const SubscribeHandlerOptions &options, void(ObjectType1::*const timeout_callback)(const std::string &topic_name, const ros::Time &last_msg), ObjectType1 *const obj1, Types ... args)
Convenience constructor overload.
Definition: subscribe_handler.h:302
mrs_lib
All mrs_lib functions, classes, variables and definitions are contained in this namespace.
Definition: attitude_converter.h:29
mrs_lib::SubscribeHandler::peekMsg
virtual MessageType::ConstPtr peekMsg() const
Returns the last received message on the topic without modifying the newMsg() or usedMsg() flags.
Definition: subscribe_handler.h:115
mrs_lib::SubscribeHandlerOptions::timeout_callback
std::function< void(const std::string &topic_name, const ros::Time &last_msg)> timeout_callback
This function will be called if no new message is received for the no_message_timeout duration....
Definition: subscribe_handler.h:46
mrs_lib::TimeoutManager
TODO.
Definition: timeout_manager.h:19
mrs_lib::SubscribeHandler::SubscribeHandler
SubscribeHandler(const SubscribeHandlerOptions &options, const message_callback_t &message_callback={})
Convenience constructor overload.
Definition: subscribe_handler.h:240
mrs_lib::SubscribeHandler::topicName
virtual std::string topicName() const
Returns the resolved (full) name of the topic, handled by this SubscribeHandler.
Definition: subscribe_handler.h:158
mrs_lib::SubscribeHandlerOptions::topic_name
std::string topic_name
Name of the ROS topic to be handled.
Definition: subscribe_handler.h:40
mrs_lib::SubscribeHandler::message_callback_t
std::function< void(typename MessageType::ConstPtr)> message_callback_t
Convenience type for the message callback function.
Definition: subscribe_handler.h:98
mrs_lib::SubscribeHandler::subscribedTopicName
virtual std::string subscribedTopicName() const
Returns the subscribed (unresolved) name of the topic, handled by this SubscribeHandler.
Definition: subscribe_handler.h:165
mrs_lib::SubscribeHandler::newMsg
virtual bool newMsg() const
Used to check whether at least one message has been received on the handled topic since the last call...
Definition: subscribe_handler.h:129
mrs_lib::SubscribeHandlerOptions::threadsafe
bool threadsafe
If true, all methods of the SubscribeHandler will be mutexed (using a recursive mutex) to avoid data ...
Definition: subscribe_handler.h:48
mrs_lib::SubscribeHandlerOptions::nh
ros::NodeHandle nh
The ROS NodeHandle to be used for subscription.
Definition: subscribe_handler.h:36
mrs_lib::SubscribeHandler::getNumPublishers
virtual uint32_t getNumPublishers() const
Returns number of publishers registered at the topic.
Definition: subscribe_handler.h:172
mrs_lib::SubscribeHandler::SubscribeHandler
SubscribeHandler(const SubscribeHandlerOptions &options, mrs_lib::TimeoutManager &timeout_manager, Types ... args)
Convenience constructor overload.
Definition: subscribe_handler.h:416
mrs_lib::SubscribeHandler::SubscribeHandler
SubscribeHandler(const SubscribeHandlerOptions &options, const ros::Duration &no_message_timeout, Types ... args)
Convenience constructor overload.
Definition: subscribe_handler.h:389
mrs_lib::SubscribeHandler::lastMsgTime
virtual ros::Time lastMsgTime() const
Returns time of the last received message on the topic, handled by this SubscribeHandler.
Definition: subscribe_handler.h:151
mrs_lib::construct_object
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: subscribe_handler.h:470
mrs_lib::SubscribeHandlerOptions::autostart
bool autostart
If true, the SubscribeHandler will be started after construction. Otherwise it has to be started usin...
Definition: subscribe_handler.h:50