mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
|
The main class for ROS topic subscription, message timeout handling etc. More...
#include <subscribe_handler.h>
Classes | |
class | Impl |
class | ImplThreadsafe |
Public Types | |
using | message_type = MessageType |
Convenience type for the template parameter to enable nice aliasing. | |
using | timeout_callback_t = std::function< void(const std::string &topic_name, const ros::Time &last_msg)> |
Type for the timeout callback function. | |
using | message_callback_t = std::function< void(typename MessageType::ConstPtr)> |
Convenience type for the message callback function. | |
Public Member Functions | |
virtual MessageType::ConstPtr | getMsg () |
Returns the last received message on the topic, handled by this SubscribeHandler. Use hasMsg() first to check if at least one message is available or newMsg() to check if a new message since the last call to getMsg() is available. More... | |
virtual MessageType::ConstPtr | peekMsg () const |
Returns the last received message on the topic without modifying the newMsg() or usedMsg() flags. More... | |
virtual bool | hasMsg () const |
Used to check whether at least one message has been received on the handled topic. More... | |
virtual bool | newMsg () const |
Used to check whether at least one message has been received on the handled topic since the last call to getMsg(). More... | |
virtual bool | usedMsg () const |
Used to check whether getMsg() was called at least once on this SubscribeHandler. More... | |
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. More... | |
virtual ros::Time | lastMsgTime () const |
Returns time of the last received message on the topic, handled by this SubscribeHandler. More... | |
virtual std::string | topicName () const |
Returns the resolved (full) name of the topic, handled by this SubscribeHandler. More... | |
virtual std::string | subscribedTopicName () const |
Returns the subscribed (unresolved) name of the topic, handled by this SubscribeHandler. More... | |
virtual uint32_t | getNumPublishers () const |
Returns number of publishers registered at the topic. More... | |
virtual void | setNoMessageTimeout (const ros::Duration &timeout) |
Sets the timeout for no received message. More... | |
virtual void | start () |
Enables the callbacks for the handled topic. More... | |
virtual void | stop () |
Disables the callbacks for the handled topic. More... | |
SubscribeHandler () | |
Default constructor to avoid having to use pointers. More... | |
template<class ... Types> | |
SubscribeHandler (const SubscribeHandlerOptions &options, const std::string &topic_name, Types ... args) | |
Main constructor. More... | |
SubscribeHandler (const SubscribeHandlerOptions &options, const message_callback_t &message_callback={}) | |
Convenience constructor overload. More... | |
template<class ... Types> | |
SubscribeHandler (const SubscribeHandlerOptions &options, const timeout_callback_t &timeout_callback, Types ... args) | |
Convenience constructor overload. More... | |
template<class ObjectType1 , class ... Types> | |
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. More... | |
template<class ObjectType2 , class ... Types> | |
SubscribeHandler (const SubscribeHandlerOptions &options, void(ObjectType2::*const message_callback)(typename MessageType::ConstPtr), ObjectType2 *const obj2, Types ... args) | |
Convenience constructor overload. More... | |
template<class ObjectType1 , class ObjectType2 , class ... Types> | |
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. More... | |
template<class ... Types> | |
SubscribeHandler (const SubscribeHandlerOptions &options, const ros::Duration &no_message_timeout, Types ... args) | |
Convenience constructor overload. More... | |
template<class ... Types> | |
SubscribeHandler (const SubscribeHandlerOptions &options, mrs_lib::TimeoutManager &timeout_manager, Types ... args) | |
Convenience constructor overload. More... | |
SubscribeHandler (const SubscribeHandler &)=delete | |
SubscribeHandler & | operator= (const SubscribeHandler &)=delete |
SubscribeHandler (SubscribeHandler &&other) | |
SubscribeHandler & | operator= (SubscribeHandler &&other) |
The main class for ROS topic subscription, message timeout handling etc.
This class handles the raw ROS Subscriber for a specified topic. The last message received on the topic is remembered and may be retrieved by calling the getMsg() method. To check whether at least one message was received, use hasMsg() (if no message was received and you call getMsg(), a nullptr is returned and an error message is printed). To check whether a new message has arrived since the last call to getMsg(), use newMsg() (useful to check whether a new message needs to be processed in a loop or ROS Timer callback).
A timeout callback function may be specified, which is called if no message is received on the topic for a specified timeout (use the timeout_callback
and no_message_timeout
parameters). If the timeout callback is not set by the user, an error message is printed to the console after the timeout by default.
A message callback function may be specified, which is called whenever a new message is received (use the message_callback
parameter).
The callbacks and timeouts may be stopped and started using the stop() and start() methods.
For more details, see the example below (I recommend starting with the simple_example which covers most use-cases).
|
inline |
Default constructor to avoid having to use pointers.
It does nothing and the SubscribeHandler it constructs will also do nothing. Use some of the other constructors for actual construction of a usable SubscribeHandler.
|
inline |
Main constructor.
options | The common options struct (see documentation of SubscribeHandlerOptions). |
topic_name | Name of the topic to be handled by this subscribed. |
args | Remaining arguments to be parsed (see other constructors). |
|
inline |
Convenience constructor overload.
options | The common options struct (see documentation of SubscribeHandlerOptions). |
message_callback | The callback function to call when a new message is received (you can leave this argument empty and just use the newMsg()/hasMsg() and getMsg() interface). |
|
inline |
Convenience constructor overload.
options | The common options struct (see documentation of SubscribeHandlerOptions). |
timeout_callback | The callback function to call when a new message is not received for the duration, specified in options or in the no_message_timeout parameter. |
args | Remaining arguments to be parsed (see other constructors). |
|
inline |
Convenience constructor overload.
options | The common options struct (see documentation of SubscribeHandlerOptions). |
timeout_callback | The callback method to call when a new message is not received for the duration, specified in options or in the no_message_timeout parameter. |
obj1 | The object on which the callback method timeout_callback will be called. |
args | Remaining arguments to be parsed (see other constructors). |
|
inline |
Convenience constructor overload.
options | The common options struct (see documentation of SubscribeHandlerOptions). |
message_callback | The callback method to call when a new message is received. |
obj2 | The object on which the callback method timeout_callback will be called. |
args | Remaining arguments to be parsed (see other constructors). |
|
inline |
Convenience constructor overload.
options | The common options struct (see documentation of SubscribeHandlerOptions). |
message_callback | The callback method to call when a new message is received. |
obj2 | The object on which the callback method timeout_callback will be called. |
timeout_callback | The callback method to call when a new message is not received for the duration, specified in options or in the no_message_timeout parameter. |
obj1 | The object on which the callback method timeout_callback will be called. |
args | Remaining arguments to be parsed (see other constructors). |
|
inline |
Convenience constructor overload.
options | The common options struct (see documentation of SubscribeHandlerOptions). |
no_message_timeout | If no message is received for this duration, the timeout callback function is called. If no timeout callback is specified, an error message is printed to the console. |
args | Remaining arguments to be parsed (see other constructors). |
|
inline |
Convenience constructor overload.
options | The common options struct (see documentation of SubscribeHandlerOptions). |
timeout_manager | The manager for timeout callbacks. |
args | Remaining arguments to be parsed (see other constructors). |
|
inlinevirtual |
Returns the last received message on the topic, handled by this SubscribeHandler. Use hasMsg() first to check if at least one message is available or newMsg() to check if a new message since the last call to getMsg() is available.
|
inlinevirtual |
Returns number of publishers registered at the topic.
|
inlinevirtual |
Used to check whether at least one message has been received on the handled topic.
|
inlinevirtual |
Returns time of the last received message on the topic, handled by this SubscribeHandler.
|
inlinevirtual |
Used to check whether at least one message has been received on the handled topic since the last call to getMsg().
|
inlinevirtual |
|
inlinevirtual |
Sets the timeout for no received message.
timeout | The new timeout for no received messages. |
|
inlinevirtual |
Enables the callbacks for the handled topic.
If the SubscribeHandler object is stopped using the stop() method, no callbacks will be called until the start() method is called.
|
inlinevirtual |
Disables the callbacks for the handled topic.
All messages after this method is called will be ignored until start() is called again. Timeout checking will also be disabled.
|
inlinevirtual |
Returns the subscribed (unresolved) name of the topic, handled by this SubscribeHandler.
|
inlinevirtual |
Returns the resolved (full) name of the topic, handled by this SubscribeHandler.
|
inlinevirtual |
Used to check whether getMsg() was called at least once on this SubscribeHandler.
|
inlinevirtual |
Blocks until new data becomes available or until the timeout runs out or until a spurious wake-up.
timeout | after this duration, this method will return a nullptr if no new data becomes available. |
nullptr
otherwise.