Go to the documentation of this file.
36 #ifndef __DIAGNOSTIC_UPDATER__DRIVER_H__
37 #define __DIAGNOSTIC_UPDATER__DRIVER_H__
55 class HeaderlessTopicDiagnostic :
public CompositeDiagnosticTask
111 class TopicDiagnostic :
public HeaderlessTopicDiagnostic
148 virtual void tick() {
ROS_FATAL(
"tick(void) has been called on a TopicDiagnostic. This is never correct. Use tick(ros::Time &) instead."); }
218 virtual void publish(
const T& message) {
tick(message.header.stamp);
void addTask(DiagnosticTask *t)
Adds a child CompositeDiagnosticTask.
A diagnostic task that monitors the frequency of an event.
virtual ~DiagnosedPublisher()
A structure that holds the constructor parameters for the TimeStampStatus class.
DiagnosedPublisher(const ros::Publisher &pub, diagnostic_updater::Updater &diag, const diagnostic_updater::FrequencyStatusParam &freq, const diagnostic_updater::TimeStampStatusParam &stamp)
Constructs a DiagnosedPublisher.
Diagnostic task to monitor the interval between events.
Manages a list of diagnostic tasks, and calls them in a rate-limited manner.
TopicDiagnostic(std::string name, diagnostic_updater::Updater &diag, const diagnostic_updater::FrequencyStatusParam &freq, const diagnostic_updater::TimeStampStatusParam &stamp)
Constructs a TopicDiagnostic.
void publish(const boost::shared_ptr< M > &message) const
void tick()
Signals that an event has occurred.
virtual void publish(const boost::shared_ptr< T > &message)
Collects statistics and publishes the message.
A TopicDiagnostic combined with a ros::Publisher.
virtual ~TopicDiagnostic()
A class to facilitate making diagnostics for a topic using a FrequencyStatus and TimeStampStatus.
ros::Publisher getPublisher() const
Returns the publisher.
CompositeDiagnosticTask(const std::string name)
Constructs a CompositeDiagnosticTask with the given name.
void clear()
Resets the statistics.
void setPublisher(ros::Publisher pub)
Changes the publisher.
void tick(double stamp)
Signals an event. Timestamp stored as a double.
void add(const std::string &name, TaskFunction f)
Add a DiagnosticTask embodied by a name and function to the DiagnosticTaskVector.
ros::Publisher publisher_
A structure that holds the constructor parameters for the FrequencyStatus class.
diagnostic_updater
Author(s): Kevin Watts, Brice Rebsamen
, Jeremy Leibs, Blaise Gassend
autogenerated on Tue Nov 15 2022 03:17:19