Base for ROS publisher and subscriber with automatic message rate and delay diagnostics. More...
#include <diagnosed_pub_sub.hpp>
Public Member Functions | |
virtual void | attach (::diagnostic_updater::Updater &updater) |
Add the diagnostic task to the given updater. More... | |
DiagnosedPubSub (const ::cras::BoundParamHelperPtr ¶ms) | |
Configure the diagnostic task from the given ROS parameter helper. More... | |
DiagnosedPubSub (const ::cras::BoundParamHelperPtr ¶ms, const ::cras::SimpleTopicStatusParam< Message > &defaultParams) | |
Configure the diagnostic task from the given ROS parameter helper. 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... | |
virtual ::std::shared_ptr<::cras::TopicStatus< Message > > | getDiagnosticTask () const |
Get the topic diagnostic task. More... | |
virtual | ~DiagnosedPubSub ()=default |
Protected Member Functions | |
template<class M = Message, ::std::enable_if_t<::ros::message_traits::HasHeader< M >::value, bool > EnableM = true> | |
void | addDelayParams (::cras::SimpleTopicStatusParam< Message > &topicStatusParam, const ::cras::BoundParamHelperPtr ¶ms) |
When configuring from ROS params, load the delay configuration. More... | |
template<class M = Message, ::std::enable_if_t<!::ros::message_traits::HasHeader< M >::value, bool > EnableM = true> | |
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 | |
::std::shared_ptr<::cras::TopicStatus< Message > > | diag {nullptr} |
The diagnostic task. More... | |
Base for ROS publisher and subscriber with automatic message rate and delay diagnostics.
This class offers an option to configure the diagnostic task from a set of ROS parameters. The following parameters are read:
rate/desired
(double, Hz, no default): If set, this value will be used as the default of min/max rates.rate/min
(double, Hz, default 0.0 or desired): Minimum acceptable rate.rate/max
(double, Hz, default +inf or desired): Maximum acceptable rate.rate/tolerance
(double, default 0.1): Tolerance of the min/max rate (0.0 means that the min/max rate limits are strict).rate/window_size
(uint, default 5): Over how many diagnostics updates should the rate be computed.delay/min
(double, s, default -1.0): Minimum acceptable delay (only computed for messages with a header).delay/max
(double, s, default 5.0): Maximum acceptable delay (only computed for messages with a header).Message | Type of the published/subscribed message. |
Enable | SFINAE only. Do not explicitly set. |
Definition at line 57 of file diagnosed_pub_sub.hpp.
|
explicit |
Use the given diagnostic task to diagnose the publisher/subscriber.
[in] | diag |
|
explicit |
Create the diagnostic task from the given params.
[in] | name | Name of the task. |
[in] | diagParams | Parameters of the task. |
cras::DiagnosedPubSub< Message, Enable >::DiagnosedPubSub | ( | const ::cras::BoundParamHelperPtr & | params, |
const ::cras::SimpleTopicStatusParam< Message > & | defaultParams | ||
) |
Configure the diagnostic task from the given ROS parameter helper.
[in] | params | The ROS parameters to load configuration from. |
[in] | defaultParams | Defaults used in case a ROS parameter doesn' exist. |
|
explicit |
Configure the diagnostic task from the given ROS parameter helper.
[in] | params | The ROS parameters to load configuration from. |
|
virtualdefault |
|
protected |
When configuring from ROS params, load the delay configuration.
M | SFINAE only. Do not set explicitly. |
EnableM | SFINAE only. Do not set explicitly. |
[in] | topicStatusParam | Some pre-loaded param struct. |
[in] | params | Parameters to load from? |
|
protected |
When configuring from ROS params for a headerless message type, this function does nothing.
M | SFINAE only. Do not set explicitly. |
EnableM | SFINAE only. Do not set explicitly. |
[in] | topicStatusParam | Some pre-loaded param struct. |
[in] | params | Parameters to load from? |
|
virtual |
Add the diagnostic task to the given updater.
[in] | updater | The updater to add to. |
virtual ::std::shared_ptr<::cras::TopicStatus<Message> > cras::DiagnosedPubSub< Message, Enable >::getDiagnosticTask | ( | ) | const |
Get the topic diagnostic task.
|
protected |
The diagnostic task.
Definition at line 125 of file diagnosed_pub_sub.hpp.