Go to the documentation of this file.
37 #ifndef __DIAGNOSTIC_UPDATER__DRIVER_H__
38 #define __DIAGNOSTIC_UPDATER__DRIVER_H__
40 #include <ros/publisher.h>
41 #include <ros/subscription.h>
42 #include <diagnostic_updater/update_functions.h>
56 class HeaderlessTopicDiagnostic :
public CompositeDiagnosticTask
112 class TopicDiagnostic :
public HeaderlessTopicDiagnostic
149 virtual void tick() {
ROS_FATAL(
"tick(void) has been called on a TopicDiagnostic. This is never correct. Use tick(ros::Time &) instead."); }
175 class DiagnosedPublisher :
public TopicDiagnostic
void addTask(DiagnosticTask *t)
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)
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)
void publish(const boost::shared_ptr< M > &message) const
def message(msg, *args, **kwargs)
virtual void publish(const boost::shared_ptr< T > &message)
void tick(const ros::Time t)
virtual ~TopicDiagnostic()
ros::Publisher getPublisher() const
std::string getTopic() const
CompositeDiagnosticTask(const std::string name)
void setPublisher(ros::Publisher pub)
void add(const std::string &name, TaskFunction f)
ros::Publisher publisher_
A structure that holds the constructor parameters for the FrequencyStatus class.
sick_scan_xd
Author(s): Michael Lehning
, Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:10