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 <ros/ros.h>
12 
13 namespace mrs_lib
14 {
15 
16  static const ros::Duration no_timeout = ros::Duration(0);
17 
18  /* struct SubscribeHandlerOptions //{ */
19 
30  {
31  SubscribeHandlerOptions(const ros::NodeHandle& nh) : nh(nh) {}
32  SubscribeHandlerOptions() = default;
33 
34  ros::NodeHandle nh;
36  std::string node_name = {};
38  std::string topic_name = {};
40  std::shared_ptr<mrs_lib::TimeoutManager> timeout_manager = nullptr;
42  ros::Duration no_message_timeout = mrs_lib::no_timeout;
44  std::function<void(const std::string& topic_name, const ros::Time& last_msg)> timeout_callback = {};
46  bool threadsafe = true;
48  bool autostart = true;
50  uint32_t queue_size = 3;
52  ros::TransportHints transport_hints = ros::TransportHints();
53  };
54 
55  //}
56 
57  /* SubscribeHandler class //{ */
79  template <typename MessageType>
81  {
82  public:
86  using message_type = MessageType;
87 
91  using timeout_callback_t = std::function<void(const std::string& topic_name, const ros::Time& last_msg)>;
92 
96  using message_callback_t = std::function<void(typename MessageType::ConstPtr)>;
97 
98  public:
106  virtual typename MessageType::ConstPtr getMsg() {assert(m_pimpl); return m_pimpl->getMsg();};
107 
113  virtual typename MessageType::ConstPtr peekMsg() const {assert(m_pimpl); return m_pimpl->peekMsg();};
114 
120  virtual bool hasMsg() const {assert(m_pimpl); return m_pimpl->hasMsg();};
121 
127  virtual bool newMsg() const {assert(m_pimpl); return m_pimpl->newMsg();};
128 
134  virtual bool usedMsg() const {assert(m_pimpl); return m_pimpl->usedMsg();};
135 
141  virtual typename MessageType::ConstPtr waitForNew(const ros::WallDuration& timeout) {assert(m_pimpl); return m_pimpl->waitForNew(timeout);};
142 
148  virtual ros::Time lastMsgTime() const {assert(m_pimpl); return m_pimpl->lastMsgTime();};
149 
155  virtual std::string topicName() const {assert(m_pimpl); return m_pimpl->topicName();};
156 
162  virtual std::string subscribedTopicName() const {assert(m_pimpl); return m_pimpl->m_topic_name;};
163 
170  virtual void start() {assert(m_pimpl); return m_pimpl->start();};
171 
178  virtual void stop() {assert(m_pimpl); return m_pimpl->stop();};
179 
180  public:
188 
197  template<class ... Types>
199  const SubscribeHandlerOptions& options,
200  const std::string& topic_name,
201  Types ... args
202  )
203  :
205  [options, topic_name]()
206  {
207  SubscribeHandlerOptions opts = options;
208  opts.topic_name = topic_name;
209  return opts;
210  }(),
211  args...
212  )
213  {
214  }
215 
224  const SubscribeHandlerOptions& options,
225  const message_callback_t& message_callback = {}
226  )
227  {
228  if (options.threadsafe)
229  {
230  m_pimpl = std::make_unique<ImplThreadsafe>
231  (
232  options,
233  message_callback
234  );
235  }
236  else
237  {
238  m_pimpl = std::make_unique<Impl>
239  (
240  options,
241  message_callback
242  );
243  }
244  if (options.autostart)
245  start();
246  };
247 
256  template <class ... Types>
258  const SubscribeHandlerOptions& options,
259  const timeout_callback_t& timeout_callback,
260  Types ... args
261  )
262  :
264  [options, timeout_callback]()
265  {
266  SubscribeHandlerOptions opts = options;
267  opts.timeout_callback = timeout_callback;
268  return opts;
269  }(),
270  args...
271  )
272  {
273  }
274 
284  template <class ObjectType1, class ... Types>
286  const SubscribeHandlerOptions& options,
287  void (ObjectType1::*const timeout_callback) (const std::string& topic_name, const ros::Time& last_msg),
288  ObjectType1* const obj1,
289  Types ... args
290  )
291  :
293  [options, timeout_callback, obj1]()
294  {
295  SubscribeHandlerOptions opts = options;
296  opts.timeout_callback = timeout_callback == nullptr ? timeout_callback_t() : std::bind(timeout_callback, obj1, std::placeholders::_1, std::placeholders::_2);
297  return opts;
298  }(),
299  args...
300  )
301  {
302  }
303 
313  template <class ObjectType2, class ... Types>
315  const SubscribeHandlerOptions& options,
316  void (ObjectType2::*const message_callback) (typename MessageType::ConstPtr),
317  ObjectType2* const obj2,
318  Types ... args
319  )
320  :
322  options,
323  message_callback == nullptr ? message_callback_t() : std::bind(message_callback, obj2, std::placeholders::_1),
324  args...
325  )
326  {
327  }
328 
340  template <class ObjectType1, class ObjectType2, class ... Types>
342  const SubscribeHandlerOptions& options,
343  void (ObjectType2::*const message_callback) (typename MessageType::ConstPtr),
344  ObjectType2* const obj2,
345  void (ObjectType1::*const timeout_callback) (const std::string& topic_name, const ros::Time& last_msg),
346  ObjectType1* const obj1,
347  Types ... args
348  )
349  :
351  [options, timeout_callback, obj1]()
352  {
353  SubscribeHandlerOptions opts = options;
354  opts.timeout_callback = timeout_callback == nullptr ? timeout_callback_t() : std::bind(timeout_callback, obj1, std::placeholders::_1, std::placeholders::_2);
355  return opts;
356  }(),
357  message_callback == nullptr ? message_callback_t() : std::bind(message_callback, obj2, std::placeholders::_1),
358  args...
359  )
360  {
361  }
362 
371  template<class ... Types>
373  const SubscribeHandlerOptions& options,
374  const ros::Duration& no_message_timeout,
375  Types ... args
376  )
377  :
379  [options, no_message_timeout]()
380  {
381  SubscribeHandlerOptions opts = options;
382  opts.no_message_timeout = no_message_timeout;
383  return opts;
384  }(),
385  args...
386  )
387  {
388  }
389 
398  template <class ... Types>
400  const SubscribeHandlerOptions& options,
401  mrs_lib::TimeoutManager& timeout_manager,
402  Types ... args
403  )
404  :
406  options,
407  timeout_manager = timeout_manager,
408  args...
409  )
410  {
411  }
412 
413  ~SubscribeHandler() = default;
414  // delete copy constructor and assignment operator (forbid copying shandlers)
415  SubscribeHandler(const SubscribeHandler&) = delete;
416  SubscribeHandler& operator=(const SubscribeHandler&) = delete;
417  // define only move constructor and assignemnt operator
419  {
420  this->m_pimpl = std::move(other.m_pimpl);
421  other.m_pimpl = nullptr;
422  }
423  SubscribeHandler& operator=(SubscribeHandler&& other)
424  {
425  this->m_pimpl = std::move(other.m_pimpl);
426  other.m_pimpl = nullptr;
427  return *this;
428  }
429 
430  private:
431  class Impl;
432  class ImplThreadsafe;
433  std::unique_ptr<Impl> m_pimpl;
434  };
435  //}
436 
440  template<typename SubscribeHandler>
442 
452  template<typename Class, class ... Types>
454  Class& object,
455  Types ... args
456  )
457  {
458  object = Class(args...);
459  }
460 }
461 
462 #include <mrs_lib/impl/subscribe_handler.hpp>
463 
464 #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:50
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:120
mrs_lib::SubscribeHandler::SubscribeHandler
SubscribeHandler(const SubscribeHandlerOptions &options, const timeout_callback_t &timeout_callback, Types ... args)
Convenience constructor overload.
Definition: subscribe_handler.h:257
mrs_lib::SubscribeHandler::message_type
MessageType message_type
Convenience type for the template parameter to enable nice aliasing.
Definition: subscribe_handler.h:86
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:91
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:40
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:134
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:52
mrs_lib::SubscribeHandlerOptions
A helper class to simplify setup of SubscribeHandler construction. This class is passed to the Subscr...
Definition: subscribe_handler.h:29
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:314
mrs_lib::SubscribeHandler::stop
virtual void stop()
Disables the callbacks for the handled topic.
Definition: subscribe_handler.h:178
mrs_lib::SubscribeHandler::SubscribeHandler
SubscribeHandler(const SubscribeHandlerOptions &options, const std::string &topic_name, Types ... args)
Main constructor.
Definition: subscribe_handler.h:198
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:106
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:341
mrs_lib::SubscribeHandler::start
virtual void start()
Enables the callbacks for the handled topic.
Definition: subscribe_handler.h:170
mrs_lib::SubscribeHandler
The main class for ROS topic subscription, message timeout handling etc.
Definition: subscribe_handler.h:80
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:42
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:141
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:441
mrs_lib::SubscribeHandler::SubscribeHandler
SubscribeHandler()
Default constructor to avoid having to use pointers.
Definition: subscribe_handler.h:187
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:36
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:285
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:113
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:44
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:223
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:155
mrs_lib::SubscribeHandlerOptions::topic_name
std::string topic_name
Name of the ROS topic to be handled.
Definition: subscribe_handler.h:38
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:96
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:162
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:127
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:46
mrs_lib::SubscribeHandlerOptions::nh
ros::NodeHandle nh
The ROS NodeHandle to be used for subscription.
Definition: subscribe_handler.h:34
mrs_lib::SubscribeHandler::SubscribeHandler
SubscribeHandler(const SubscribeHandlerOptions &options, mrs_lib::TimeoutManager &timeout_manager, Types ... args)
Convenience constructor overload.
Definition: subscribe_handler.h:399
mrs_lib::SubscribeHandler::SubscribeHandler
SubscribeHandler(const SubscribeHandlerOptions &options, const ros::Duration &no_message_timeout, Types ... args)
Convenience constructor overload.
Definition: subscribe_handler.h:372
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:148
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:453
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:48