Template Class DiagnosedPubSub
Defined in File diagnosed_pub_sub.hpp
Inheritance Relationships
Derived Types
public cras::DiagnosedPublisher< Message, Enable >(Template Class DiagnosedPublisher)public cras::DiagnosedSubscriber< Message, Enable >(Template Class DiagnosedSubscriber)
Class Documentation
-
template<class Message, typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
class DiagnosedPubSub 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).
- Template Parameters:
Message – Type of the published/subscribed message.
Enable – SFINAE only. Do not explicitly set.
Subclassed by cras::DiagnosedPublisher< Message, Enable >, cras::DiagnosedSubscriber< Message, Enable >
Public Functions
Use the given diagnostic task to diagnose the publisher/subscriber.
- Parameters:
diag – [in]
-
explicit DiagnosedPubSub(const ::std::string &name, const ::cras::TopicStatusParam<Message> &diagParams)
Create the diagnostic task from the given params.
- Parameters:
name – [in] Name of the task.
diagParams – [in] Parameters of the task.
-
DiagnosedPubSub(const ::cras::BoundParamHelperPtr ¶ms, const ::cras::SimpleTopicStatusParam<Message> &defaultParams)
Configure the diagnostic task from the given ROS parameter helper.
- Parameters:
params – [in] The ROS parameters to load configuration from.
defaultParams – [in] Defaults used in case a ROS parameter doesn’ exist.
-
explicit DiagnosedPubSub(const ::cras::BoundParamHelperPtr ¶ms)
Configure the diagnostic task from the given ROS parameter helper.
- Parameters:
params – [in] The ROS parameters to load configuration from.
-
virtual ~DiagnosedPubSub() = default
-
virtual void attach(::diagnostic_updater::Updater &updater)
Add the diagnostic task to the given updater.
- Parameters:
updater – [in] The updater to add to.
-
::std::shared_ptr<::cras::TopicStatus<Message>> getDiagnosticTask() const
Get the topic diagnostic task.
- Returns:
The task.
Protected 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.
- Template Parameters:
M – SFINAE only. Do not set explicitly.
EnableM – SFINAE only. Do not set explicitly.
- Parameters:
topicStatusParam – [in] Some pre-loaded param struct.
params – [in] Parameters to load from?
-
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.
- Template Parameters:
M – SFINAE only. Do not set explicitly.
EnableM – SFINAE only. Do not set explicitly.
- Parameters:
topicStatusParam – [in] Some pre-loaded param struct.
params – [in] Parameters to load from?
Protected Attributes
-
::std::shared_ptr<::cras::TopicStatus<Message>> diag = {nullptr}
The diagnostic task.