|
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
18 static const ros::Duration no_timeout = ros::Duration(0);
81 template <
typename MessageType>
93 using timeout_callback_t = std::function<void(
const std::string& topic_name,
const ros::Time& last_msg)>;
108 virtual typename MessageType::ConstPtr
getMsg() {assert(m_pimpl);
return m_pimpl->getMsg();};
115 virtual typename MessageType::ConstPtr
peekMsg()
const {assert(m_pimpl);
return m_pimpl->peekMsg();};
122 virtual bool hasMsg()
const {assert(m_pimpl);
return m_pimpl->hasMsg();};
129 virtual bool newMsg()
const {assert(m_pimpl);
return m_pimpl->newMsg();};
136 virtual bool usedMsg()
const {assert(m_pimpl);
return m_pimpl->usedMsg();};
144 virtual typename MessageType::ConstPtr
waitForNew(
const ros::WallDuration& timeout) {assert(m_pimpl);
return m_pimpl->waitForNew(timeout);};
151 virtual ros::Time
lastMsgTime()
const {assert(m_pimpl);
return m_pimpl->lastMsgTime();};
158 virtual std::string
topicName()
const {assert(m_pimpl);
return m_pimpl->topicName();};
172 virtual uint32_t
getNumPublishers()
const {assert(m_pimpl);
return m_pimpl->getNumPublishers();};
179 virtual void setNoMessageTimeout(
const ros::Duration& timeout) {assert(m_pimpl);
return m_pimpl->setNoMessageTimeout(timeout);};
187 virtual void start() {assert(m_pimpl);
return m_pimpl->start();};
195 virtual void stop() {assert(m_pimpl);
return m_pimpl->stop();};
214 template<
class ... Types>
217 const std::string& topic_name,
222 [options, topic_name]()
247 m_pimpl = std::make_unique<ImplThreadsafe>
255 m_pimpl = std::make_unique<Impl>
273 template <
class ... Types>
281 [options, timeout_callback]()
301 template <
class ObjectType1,
class ... Types>
304 void (ObjectType1::*
const timeout_callback) (
const std::string& topic_name,
const ros::Time& last_msg),
305 ObjectType1*
const obj1,
310 [options, timeout_callback, obj1]()
330 template <
class ObjectType2,
class ... Types>
333 void (ObjectType2::*
const message_callback) (
typename MessageType::ConstPtr),
334 ObjectType2*
const obj2,
340 message_callback == nullptr ?
message_callback_t() : std::bind(message_callback, obj2, std::placeholders::_1),
357 template <
class ObjectType1,
class ObjectType2,
class ... Types>
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,
368 [options, timeout_callback, obj1]()
374 message_callback ==
nullptr ?
message_callback_t() : std::bind(message_callback, obj2, std::placeholders::_1),
388 template<
class ... Types>
391 const ros::Duration& no_message_timeout,
396 [options, no_message_timeout]()
415 template <
class ... Types>
424 timeout_manager = timeout_manager,
437 this->m_pimpl = std::move(other.m_pimpl);
438 other.m_pimpl =
nullptr;
442 this->m_pimpl = std::move(other.m_pimpl);
443 other.m_pimpl =
nullptr;
449 class ImplThreadsafe;
450 std::unique_ptr<Impl> m_pimpl;
457 template<
typename SubscribeHandler>
469 template<
typename Class,
class ... Types>
475 object = Class(args...);
479 #include <mrs_lib/impl/subscribe_handler.hpp>
481 #endif // SUBRSCRIBE_HANDLER_H
uint32_t queue_size
This parameter is passed to the NodeHandle when subscribing to the topic.
Definition: subscribe_handler.h:52
virtual bool hasMsg() const
Used to check whether at least one message has been received on the handled topic.
Definition: subscribe_handler.h:122
SubscribeHandler(const SubscribeHandlerOptions &options, const timeout_callback_t &timeout_callback, Types ... args)
Convenience constructor overload.
Definition: subscribe_handler.h:274
virtual void setNoMessageTimeout(const ros::Duration &timeout)
Sets the timeout for no received message.
Definition: subscribe_handler.h:179
MessageType message_type
Convenience type for the template parameter to enable nice aliasing.
Definition: subscribe_handler.h:88
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
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
virtual bool usedMsg() const
Used to check whether getMsg() was called at least once on this SubscribeHandler.
Definition: subscribe_handler.h:136
ros::TransportHints transport_hints
This parameter is passed to the NodeHandle when subscribing to the topic.
Definition: subscribe_handler.h:54
A helper class to simplify setup of SubscribeHandler construction. This class is passed to the Subscr...
Definition: subscribe_handler.h:31
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
virtual void stop()
Disables the callbacks for the handled topic.
Definition: subscribe_handler.h:195
SubscribeHandler(const SubscribeHandlerOptions &options, const std::string &topic_name, Types ... args)
Main constructor.
Definition: subscribe_handler.h:215
virtual MessageType::ConstPtr getMsg()
Returns the last received message on the topic, handled by this SubscribeHandler. Use hasMsg() first ...
Definition: subscribe_handler.h:108
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
virtual void start()
Enables the callbacks for the handled topic.
Definition: subscribe_handler.h:187
The main class for ROS topic subscription, message timeout handling etc.
Definition: subscribe_handler.h:82
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
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
typename SubscribeHandler::message_type message_type
Helper alias for convenient extraction of handled message type from a SubscribeHandlerPtr.
Definition: subscribe_handler.h:458
SubscribeHandler()
Default constructor to avoid having to use pointers.
Definition: subscribe_handler.h:204
std::string node_name
Name of the ROS node, using this handle (used for messages printed to console).
Definition: subscribe_handler.h:38
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
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:115
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
TODO.
Definition: timeout_manager.h:19
SubscribeHandler(const SubscribeHandlerOptions &options, const message_callback_t &message_callback={})
Convenience constructor overload.
Definition: subscribe_handler.h:240
virtual std::string topicName() const
Returns the resolved (full) name of the topic, handled by this SubscribeHandler.
Definition: subscribe_handler.h:158
std::string topic_name
Name of the ROS topic to be handled.
Definition: subscribe_handler.h:40
std::function< void(typename MessageType::ConstPtr)> message_callback_t
Convenience type for the message callback function.
Definition: subscribe_handler.h:98
virtual std::string subscribedTopicName() const
Returns the subscribed (unresolved) name of the topic, handled by this SubscribeHandler.
Definition: subscribe_handler.h:165
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
bool threadsafe
If true, all methods of the SubscribeHandler will be mutexed (using a recursive mutex) to avoid data ...
Definition: subscribe_handler.h:48
ros::NodeHandle nh
The ROS NodeHandle to be used for subscription.
Definition: subscribe_handler.h:36
virtual uint32_t getNumPublishers() const
Returns number of publishers registered at the topic.
Definition: subscribe_handler.h:172
SubscribeHandler(const SubscribeHandlerOptions &options, mrs_lib::TimeoutManager &timeout_manager, Types ... args)
Convenience constructor overload.
Definition: subscribe_handler.h:416
SubscribeHandler(const SubscribeHandlerOptions &options, const ros::Duration &no_message_timeout, Types ... args)
Convenience constructor overload.
Definition: subscribe_handler.h:389
virtual ros::Time lastMsgTime() const
Returns time of the last received message on the topic, handled by this SubscribeHandler.
Definition: subscribe_handler.h:151
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
bool autostart
If true, the SubscribeHandler will be started after construction. Otherwise it has to be started usin...
Definition: subscribe_handler.h:50