|
mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
|
Go to the documentation of this file.
7 #ifndef SUBRSCRIBE_HANDLER_H
8 #define SUBRSCRIBE_HANDLER_H
16 static const ros::Duration no_timeout = ros::Duration(0);
79 template <
typename MessageType>
91 using timeout_callback_t = std::function<void(
const std::string& topic_name,
const ros::Time& last_msg)>;
106 virtual typename MessageType::ConstPtr
getMsg() {assert(m_pimpl);
return m_pimpl->getMsg();};
113 virtual typename MessageType::ConstPtr
peekMsg()
const {assert(m_pimpl);
return m_pimpl->peekMsg();};
120 virtual bool hasMsg()
const {assert(m_pimpl);
return m_pimpl->hasMsg();};
127 virtual bool newMsg()
const {assert(m_pimpl);
return m_pimpl->newMsg();};
134 virtual bool usedMsg()
const {assert(m_pimpl);
return m_pimpl->usedMsg();};
141 virtual typename MessageType::ConstPtr
waitForNew(
const ros::WallDuration& timeout) {assert(m_pimpl);
return m_pimpl->waitForNew(timeout);};
148 virtual ros::Time
lastMsgTime()
const {assert(m_pimpl);
return m_pimpl->lastMsgTime();};
155 virtual std::string
topicName()
const {assert(m_pimpl);
return m_pimpl->topicName();};
170 virtual void start() {assert(m_pimpl);
return m_pimpl->start();};
178 virtual void stop() {assert(m_pimpl);
return m_pimpl->stop();};
197 template<
class ... Types>
200 const std::string& topic_name,
205 [options, topic_name]()
230 m_pimpl = std::make_unique<ImplThreadsafe>
238 m_pimpl = std::make_unique<Impl>
256 template <
class ... Types>
264 [options, timeout_callback]()
284 template <
class ObjectType1,
class ... Types>
287 void (ObjectType1::*
const timeout_callback) (
const std::string& topic_name,
const ros::Time& last_msg),
288 ObjectType1*
const obj1,
293 [options, timeout_callback, obj1]()
313 template <
class ObjectType2,
class ... Types>
316 void (ObjectType2::*
const message_callback) (
typename MessageType::ConstPtr),
317 ObjectType2*
const obj2,
323 message_callback == nullptr ?
message_callback_t() : std::bind(message_callback, obj2, std::placeholders::_1),
340 template <
class ObjectType1,
class ObjectType2,
class ... Types>
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,
351 [options, timeout_callback, obj1]()
357 message_callback ==
nullptr ?
message_callback_t() : std::bind(message_callback, obj2, std::placeholders::_1),
371 template<
class ... Types>
374 const ros::Duration& no_message_timeout,
379 [options, no_message_timeout]()
398 template <
class ... Types>
407 timeout_manager = timeout_manager,
420 this->m_pimpl = std::move(other.m_pimpl);
421 other.m_pimpl =
nullptr;
425 this->m_pimpl = std::move(other.m_pimpl);
426 other.m_pimpl =
nullptr;
432 class ImplThreadsafe;
433 std::unique_ptr<Impl> m_pimpl;
440 template<
typename SubscribeHandler>
452 template<
typename Class,
class ... Types>
458 object = Class(args...);
462 #include <mrs_lib/impl/subscribe_handler.hpp>
464 #endif // SUBRSCRIBE_HANDLER_H
uint32_t queue_size
This parameter is passed to the NodeHandle when subscribing to the topic.
Definition: subscribe_handler.h:50
virtual bool hasMsg() const
Used to check whether at least one message has been received on the handled topic.
Definition: subscribe_handler.h:120
SubscribeHandler(const SubscribeHandlerOptions &options, const timeout_callback_t &timeout_callback, Types ... args)
Convenience constructor overload.
Definition: subscribe_handler.h:257
MessageType message_type
Convenience type for the template parameter to enable nice aliasing.
Definition: subscribe_handler.h:86
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
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
virtual bool usedMsg() const
Used to check whether getMsg() was called at least once on this SubscribeHandler.
Definition: subscribe_handler.h:134
ros::TransportHints transport_hints
This parameter is passed to the NodeHandle when subscribing to the topic.
Definition: subscribe_handler.h:52
A helper class to simplify setup of SubscribeHandler construction. This class is passed to the Subscr...
Definition: subscribe_handler.h:29
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
virtual void stop()
Disables the callbacks for the handled topic.
Definition: subscribe_handler.h:178
SubscribeHandler(const SubscribeHandlerOptions &options, const std::string &topic_name, Types ... args)
Main constructor.
Definition: subscribe_handler.h:198
virtual MessageType::ConstPtr getMsg()
Returns the last received message on the topic, handled by this SubscribeHandler. Use hasMsg() first ...
Definition: subscribe_handler.h:106
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
virtual void start()
Enables the callbacks for the handled topic.
Definition: subscribe_handler.h:170
The main class for ROS topic subscription, message timeout handling etc.
Definition: subscribe_handler.h:80
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
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
typename SubscribeHandler::message_type message_type
Helper alias for convenient extraction of handled message type from a SubscribeHandlerPtr.
Definition: subscribe_handler.h:441
SubscribeHandler()
Default constructor to avoid having to use pointers.
Definition: subscribe_handler.h:187
std::string node_name
Name of the ROS node, using this handle (used for messages printed to console).
Definition: subscribe_handler.h:36
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
All mrs_lib functions, classes, variables and definitions are contained in this namespace.
Definition: attitude_converter.h:29
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
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
TODO.
Definition: timeout_manager.h:19
SubscribeHandler(const SubscribeHandlerOptions &options, const message_callback_t &message_callback={})
Convenience constructor overload.
Definition: subscribe_handler.h:223
virtual std::string topicName() const
Returns the resolved (full) name of the topic, handled by this SubscribeHandler.
Definition: subscribe_handler.h:155
std::string topic_name
Name of the ROS topic to be handled.
Definition: subscribe_handler.h:38
std::function< void(typename MessageType::ConstPtr)> message_callback_t
Convenience type for the message callback function.
Definition: subscribe_handler.h:96
virtual std::string subscribedTopicName() const
Returns the subscribed (unresolved) name of the topic, handled by this SubscribeHandler.
Definition: subscribe_handler.h:162
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
bool threadsafe
If true, all methods of the SubscribeHandler will be mutexed (using a recursive mutex) to avoid data ...
Definition: subscribe_handler.h:46
ros::NodeHandle nh
The ROS NodeHandle to be used for subscription.
Definition: subscribe_handler.h:34
SubscribeHandler(const SubscribeHandlerOptions &options, mrs_lib::TimeoutManager &timeout_manager, Types ... args)
Convenience constructor overload.
Definition: subscribe_handler.h:399
SubscribeHandler(const SubscribeHandlerOptions &options, const ros::Duration &no_message_timeout, Types ... args)
Convenience constructor overload.
Definition: subscribe_handler.h:372
virtual ros::Time lastMsgTime() const
Returns time of the last received message on the topic, handled by this SubscribeHandler.
Definition: subscribe_handler.h:148
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
bool autostart
If true, the SubscribeHandler will be started after construction. Otherwise it has to be started usin...
Definition: subscribe_handler.h:48