Wrapper for ROS subscriber that automatically diagnoses the rate and delay of received messages. More...
#include <diagnosed_pub_sub.hpp>
Public Member Functions | |
template<typename M , typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>> | |
DiagnosedSubscriber (::ros::NodeHandle nh, const ::cras::BoundParamHelperPtr ¶ms, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultParams, const ::std::string &topic, uint32_t queue_size, void(*cb)(M), ::ros::TransportHints hints={}) | |
Subscribe to the given topic reading diagnostic task configuration from ROS parameters. More... | |
DiagnosedSubscriber (::ros::NodeHandle nh, const ::cras::BoundParamHelperPtr ¶ms, const ::cras::SimpleTopicStatusParam< Message > &defaultParams, const ::std::string &topic, uint32_t queue_size, const ::boost::function< void(const ::boost::shared_ptr< Message > &)> &cb, ::ros::TransportHints hints={}) | |
Subscribe to the given topic reading diagnostic task configuration from ROS parameters. More... | |
template<typename C , typename EnableC = ::std::enable_if_t<::cras::IsMessageParam<C>::value>> | |
DiagnosedSubscriber (::ros::NodeHandle nh, const ::cras::BoundParamHelperPtr ¶ms, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< C >> &defaultParams, const ::std::string &topic, uint32_t queue_size, const ::boost::function< void(C)> &cb, ::ros::VoidConstPtr obj={}, ::ros::TransportHints hints={}) | |
Subscribe to the given topic reading diagnostic task configuration from ROS parameters. More... | |
template<typename M , class T , typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>> | |
DiagnosedSubscriber (::ros::NodeHandle nh, const ::cras::BoundParamHelperPtr ¶ms, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultParams, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M), T *obj, ::ros::TransportHints hints={}) | |
Subscribe to the given topic reading diagnostic task configuration from ROS parameters. More... | |
template<typename M , class T , typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>> | |
DiagnosedSubscriber (::ros::NodeHandle nh, const ::cras::BoundParamHelperPtr ¶ms, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultParams, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M) const, T *obj, ::ros::TransportHints hints={}) | |
Subscribe to the given topic reading diagnostic task configuration from ROS parameters. More... | |
template<typename M , class T , typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>> | |
DiagnosedSubscriber (::ros::NodeHandle nh, const ::cras::BoundParamHelperPtr ¶ms, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultParams, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M), const ::boost::shared_ptr< T > &obj, ::ros::TransportHints hints={}) | |
Subscribe to the given topic reading diagnostic task configuration from ROS parameters. More... | |
template<typename M , class T , typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>> | |
DiagnosedSubscriber (::ros::NodeHandle nh, const ::cras::BoundParamHelperPtr ¶ms, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultParams, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M) const, const ::boost::shared_ptr< T > &obj, ::ros::TransportHints hints={}) | |
Subscribe to the given topic reading diagnostic task configuration from ROS parameters. More... | |
DiagnosedSubscriber (::ros::NodeHandle nh, const ::cras::BoundParamHelperPtr ¶ms, const ::cras::SimpleTopicStatusParam< Message > &defaultParams, ::ros::SubscribeOptions &options) | |
Subscribe to the given topic reading diagnostic task configuration from ROS parameters. More... | |
const ::ros::Subscriber & | getSubscriber () const |
Get the created ROS subscriber. More... | |
::ros::Subscriber & | getSubscriber () |
Get the created ROS subscriber. More... | |
Public Member Functions inherited from cras::DiagnosedPubSub< Message > | |
virtual void | attach (::diagnostic_updater::Updater &updater) |
Add the diagnostic task to the given updater. More... | |
DiagnosedPubSub (const ::std::shared_ptr<::cras::TopicStatus< Message >> &diag) | |
Use the given diagnostic task to diagnose the publisher/subscriber. More... | |
DiagnosedPubSub (const ::std::string &name, const ::cras::TopicStatusParam< Message > &diagParams) | |
Create the diagnostic task from the given params. More... | |
DiagnosedPubSub (const ::cras::BoundParamHelperPtr ¶ms, const ::cras::SimpleTopicStatusParam< Message > &defaultParams) | |
Configure the diagnostic task from the given ROS parameter helper. More... | |
DiagnosedPubSub (const ::cras::BoundParamHelperPtr ¶ms) | |
Configure the diagnostic task from the given ROS parameter helper. More... | |
virtual ::std::shared_ptr<::cras::TopicStatus< Message > > | getDiagnosticTask () const |
Get the topic diagnostic task. More... | |
virtual | ~DiagnosedPubSub ()=default |
Protected Member Functions | |
::boost::function< void(const Message &)> | addTick (const ::std::function< void(const Message &)> &fn) |
Wrap fn in a function that first calls tick() on the diagnostic task and then calls fn() . More... | |
::boost::function< void(const typename Message::Ptr &)> | addTick (const ::std::function< void(const typename Message::Ptr &)> &fn) |
Wrap fn in a function that first calls tick() on the diagnostic task and then calls fn() . More... | |
::boost::function< void(const ::ros::MessageEvent< Message > &)> | addTick (const ::std::function< void(const ::ros::MessageEvent< Message > &)> &fn) |
Wrap fn in a function that first calls tick() on the diagnostic task and then calls fn() . More... | |
template<typename T , typename M , typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>> | |
::boost::function< void(M)> | addTick (const ::std::function< void(M)> &fn, T) |
Wrap fn in a function that first calls tick() on the diagnostic task and then calls fn() . More... | |
template<typename T , typename M , typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>> | |
::boost::function< void(M)> | addTick (void(T::*fn)(M), T *obj) |
Wrap fn in a function that first calls tick() on the diagnostic task and then calls fn() . More... | |
template<typename T , typename M , typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>> | |
::boost::function< void(M)> | addTick (void(T::*fn)(M), const ::boost::shared_ptr< T > &obj) |
Wrap fn in a function that first calls tick() on the diagnostic task and then calls fn() . More... | |
template<typename T , typename M , typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>> | |
::boost::function< void(M)> | addTick (void(T::*fn)(M) const, T *obj) |
Wrap fn in a function that first calls tick() on the diagnostic task and then calls fn() . More... | |
template<typename T , typename M , typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>> | |
::boost::function< void(M)> | addTick (void(T::*fn)(M) const, const ::boost::shared_ptr< T > &obj) |
Wrap fn in a function that first calls tick() on the diagnostic task and then calls fn() . More... | |
Protected Member Functions inherited from cras::DiagnosedPubSub< Message > | |
void | addDelayParams (::cras::SimpleTopicStatusParam< Message > &topicStatusParam, const ::cras::BoundParamHelperPtr ¶ms) |
When configuring from ROS params, load the delay configuration. More... | |
void | addDelayParams (::cras::SimpleTopicStatusParam< Message > &topicStatusParam, const ::cras::BoundParamHelperPtr ¶ms) |
When configuring from ROS params for a headerless message type, this function does nothing. More... | |
Protected Attributes | |
::ros::Subscriber | subscriber |
The ROS subscriber. More... | |
Protected Attributes inherited from cras::DiagnosedPubSub< Message > | |
::std::shared_ptr<::cras::TopicStatus< Message > > | diag |
The diagnostic task. More... | |
Wrapper for ROS subscriber that automatically diagnoses the rate and delay of received messages.
Message | Type of the subscribed message. |
Enable | SFINAE only. Do not set explicitly. |
Definition at line 230 of file diagnosed_pub_sub.hpp.
cras::DiagnosedSubscriber< Message, Enable >::DiagnosedSubscriber | ( | ::ros::NodeHandle | nh, |
const ::cras::BoundParamHelperPtr & | params, | ||
const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> & | defaultParams, | ||
const ::std::string & | topic, | ||
uint32_t | queue_size, | ||
void(*)(M) | cb, | ||
::ros::TransportHints | hints = {} |
||
) |
Subscribe to the given topic reading diagnostic task configuration from ROS parameters.
M | SFINAE only. Do not set explicitly. |
EnableM | SFINAE only. Do not set explicitly. |
[in] | nh | Node handle used for subscribing. |
[in] | params | ROS parameters from which the configuration of the diagnostic task is taken. |
[in] | defaultParams | Default parameters used when no ROS parameter exists. |
[in] | topic | Name of the topic to subscribe. |
[in] | queue_size | Queue size of the subscriber. |
[in] | cb | The message callback. |
[in] | hints | Connection hints. |
cras::DiagnosedSubscriber< Message, Enable >::DiagnosedSubscriber | ( | ::ros::NodeHandle | nh, |
const ::cras::BoundParamHelperPtr & | params, | ||
const ::cras::SimpleTopicStatusParam< Message > & | defaultParams, | ||
const ::std::string & | topic, | ||
uint32_t | queue_size, | ||
const ::boost::function< void(const ::boost::shared_ptr< Message > &)> & | cb, | ||
::ros::TransportHints | hints = {} |
||
) |
Subscribe to the given topic reading diagnostic task configuration from ROS parameters.
[in] | nh | Node handle used for subscribing. |
[in] | params | ROS parameters from which the configuration of the diagnostic task is taken. |
[in] | defaultParams | Default parameters used when no ROS parameter exists. |
[in] | topic | Name of the topic to subscribe. |
[in] | queue_size | Queue size of the subscriber. |
[in] | cb | The message callback. |
[in] | hints | Connection hints. |
cras::DiagnosedSubscriber< Message, Enable >::DiagnosedSubscriber | ( | ::ros::NodeHandle | nh, |
const ::cras::BoundParamHelperPtr & | params, | ||
const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< C >> & | defaultParams, | ||
const ::std::string & | topic, | ||
uint32_t | queue_size, | ||
const ::boost::function< void(C)> & | cb, | ||
::ros::VoidConstPtr | obj = {} , |
||
::ros::TransportHints | hints = {} |
||
) |
Subscribe to the given topic reading diagnostic task configuration from ROS parameters.
C | SFINAE only. Do not set explicitly. |
EnableC | SFINAE only. Do not set explicitly. |
[in] | nh | Node handle used for subscribing. |
[in] | params | ROS parameters from which the configuration of the diagnostic task is taken. |
[in] | defaultParams | Default parameters used when no ROS parameter exists. |
[in] | topic | Name of the topic to subscribe. |
[in] | queue_size | Queue size of the subscriber. |
[in] | cb | The message callback. |
[in] | obj | Tracked object for the subscriber. |
[in] | hints | Connection hints. |
cras::DiagnosedSubscriber< Message, Enable >::DiagnosedSubscriber | ( | ::ros::NodeHandle | nh, |
const ::cras::BoundParamHelperPtr & | params, | ||
const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> & | defaultParams, | ||
const ::std::string & | topic, | ||
uint32_t | queue_size, | ||
void(T::*)(M) | cb, | ||
T * | obj, | ||
::ros::TransportHints | hints = {} |
||
) |
Subscribe to the given topic reading diagnostic task configuration from ROS parameters.
M | SFINAE only. Do not set explicitly. |
EnableM | SFINAE only. Do not set explicitly. |
[in] | nh | Node handle used for subscribing. |
[in] | params | ROS parameters from which the configuration of the diagnostic task is taken. |
[in] | defaultParams | Default parameters used when no ROS parameter exists. |
[in] | topic | Name of the topic to subscribe. |
[in] | queue_size | Queue size of the subscriber. |
[in] | cb | The message callback. |
[in] | obj | Tracked object for the subscriber and on which the callback will be called. |
[in] | hints | Connection hints. |
cras::DiagnosedSubscriber< Message, Enable >::DiagnosedSubscriber | ( | ::ros::NodeHandle | nh, |
const ::cras::BoundParamHelperPtr & | params, | ||
const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> & | defaultParams, | ||
const ::std::string & | topic, | ||
uint32_t | queue_size, | ||
void(T::*)(M) const | cb, | ||
T * | obj, | ||
::ros::TransportHints | hints = {} |
||
) |
Subscribe to the given topic reading diagnostic task configuration from ROS parameters.
M | SFINAE only. Do not set explicitly. |
EnableM | SFINAE only. Do not set explicitly. |
[in] | nh | Node handle used for subscribing. |
[in] | params | ROS parameters from which the configuration of the diagnostic task is taken. |
[in] | defaultParams | Default parameters used when no ROS parameter exists. |
[in] | topic | Name of the topic to subscribe. |
[in] | queue_size | Queue size of the subscriber. |
[in] | cb | The message callback. |
[in] | obj | Tracked object for the subscriber and on which the callback will be called. |
[in] | hints | Connection hints. |
cras::DiagnosedSubscriber< Message, Enable >::DiagnosedSubscriber | ( | ::ros::NodeHandle | nh, |
const ::cras::BoundParamHelperPtr & | params, | ||
const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> & | defaultParams, | ||
const ::std::string & | topic, | ||
uint32_t | queue_size, | ||
void(T::*)(M) | cb, | ||
const ::boost::shared_ptr< T > & | obj, | ||
::ros::TransportHints | hints = {} |
||
) |
Subscribe to the given topic reading diagnostic task configuration from ROS parameters.
M | SFINAE only. Do not set explicitly. |
EnableM | SFINAE only. Do not set explicitly. |
[in] | nh | Node handle used for subscribing. |
[in] | params | ROS parameters from which the configuration of the diagnostic task is taken. |
[in] | defaultParams | Default parameters used when no ROS parameter exists. |
[in] | topic | Name of the topic to subscribe. |
[in] | queue_size | Queue size of the subscriber. |
[in] | cb | The message callback. |
[in] | obj | Tracked object for the subscriber and on which the callback will be called. |
[in] | hints | Connection hints. |
cras::DiagnosedSubscriber< Message, Enable >::DiagnosedSubscriber | ( | ::ros::NodeHandle | nh, |
const ::cras::BoundParamHelperPtr & | params, | ||
const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> & | defaultParams, | ||
const ::std::string & | topic, | ||
uint32_t | queue_size, | ||
void(T::*)(M) const | cb, | ||
const ::boost::shared_ptr< T > & | obj, | ||
::ros::TransportHints | hints = {} |
||
) |
Subscribe to the given topic reading diagnostic task configuration from ROS parameters.
M | SFINAE only. Do not set explicitly. |
EnableM | SFINAE only. Do not set explicitly. |
[in] | nh | Node handle used for subscribing. |
[in] | params | ROS parameters from which the configuration of the diagnostic task is taken. |
[in] | defaultParams | Default parameters used when no ROS parameter exists. |
[in] | topic | Name of the topic to subscribe. |
[in] | queue_size | Queue size of the subscriber. |
[in] | cb | The message callback. |
[in] | obj | Tracked object for the subscriber and on which the callback will be called. |
[in] | hints | Connection hints. |
cras::DiagnosedSubscriber< Message, Enable >::DiagnosedSubscriber | ( | ::ros::NodeHandle | nh, |
const ::cras::BoundParamHelperPtr & | params, | ||
const ::cras::SimpleTopicStatusParam< Message > & | defaultParams, | ||
::ros::SubscribeOptions & | options | ||
) |
Subscribe to the given topic reading diagnostic task configuration from ROS parameters.
[in] | nh | Node handle used for subscribing. |
[in] | params | ROS parameters from which the configuration of the diagnostic task is taken. |
[in] | defaultParams | Default parameters used when no ROS parameter exists. |
[in] | options | Subscribe options. |
options
to automatically trigger the diagnostic task when a message is received.
|
protected |
Wrap fn
in a function that first calls tick()
on the diagnostic task and then calls fn()
.
[in] | fn | The function to wrap. |
|
protected |
Wrap fn
in a function that first calls tick()
on the diagnostic task and then calls fn()
.
[in] | fn | The function to wrap. |
|
protected |
Wrap fn
in a function that first calls tick()
on the diagnostic task and then calls fn()
.
[in] | fn | The function to wrap. |
|
protected |
Wrap fn
in a function that first calls tick()
on the diagnostic task and then calls fn()
.
T | Ignored. |
M | SFINAE only. Do not set explicitly. |
EnableM | SFINAE only. Do not set explicitly. |
[in] | fn | The function to wrap. |
|
protected |
Wrap fn
in a function that first calls tick()
on the diagnostic task and then calls fn()
.
T | Ignored. |
M | SFINAE only. Do not set explicitly. |
EnableM | SFINAE only. Do not set explicitly. |
[in] | fn | The function to wrap. |
[in] | obj | Tracked object for the subscriber and on which the callback will be called. |
|
protected |
Wrap fn
in a function that first calls tick()
on the diagnostic task and then calls fn()
.
T | Ignored. |
M | SFINAE only. Do not set explicitly. |
EnableM | SFINAE only. Do not set explicitly. |
[in] | fn | The function to wrap. |
[in] | obj | Tracked object for the subscriber and on which the callback will be called. |
|
protected |
Wrap fn
in a function that first calls tick()
on the diagnostic task and then calls fn()
.
T | Ignored. |
M | SFINAE only. Do not set explicitly. |
EnableM | SFINAE only. Do not set explicitly. |
[in] | fn | The function to wrap. |
[in] | obj | Tracked object for the subscriber and on which the callback will be called. |
|
protected |
Wrap fn
in a function that first calls tick()
on the diagnostic task and then calls fn()
.
T | Ignored. |
M | SFINAE only. Do not set explicitly. |
EnableM | SFINAE only. Do not set explicitly. |
[in] | fn | The function to wrap. |
[in] | obj | Tracked object for the subscriber and on which the callback will be called. |
const ::ros::Subscriber& cras::DiagnosedSubscriber< Message, Enable >::getSubscriber | ( | ) | const |
Get the created ROS subscriber.
::ros::Subscriber& cras::DiagnosedSubscriber< Message, Enable >::getSubscriber | ( | ) |
Get the created ROS subscriber.
|
protected |
The ROS subscriber.
Definition at line 466 of file diagnosed_pub_sub.hpp.