Public Member Functions | Public Attributes | Private Member Functions | Private Attributes
diagnostic_updater::Updater Class Reference

Manages a list of diagnostic tasks, and calls them in a rate-limited manner. More...

#include <diagnostic_updater.h>

Inheritance diagram for diagnostic_updater::Updater:
Inheritance graph
[legend]

List of all members.

Public Member Functions

void broadcast (int lvl, const std::string msg)
 Output a message on all the known DiagnosticStatus.
void force_update ()
 Forces the diagnostics to update.
double getPeriod ()
 Returns the interval between updates.
void setHardwareID (const std::string &hwid)
void setHardwareIDf (const char *format,...)
void update ()
 Causes the diagnostics to update if the inter-update interval has been exceeded.
 Updater ()
 Constructs an updater class.

Public Attributes

bool verbose_

Private Member Functions

virtual void addedTaskCallback (DiagnosticTaskInternal &task)
void publish (diagnostic_msgs::DiagnosticStatus &stat)
void publish (std::vector< diagnostic_msgs::DiagnosticStatus > &status_vec)
void setup ()
void update_diagnostic_period ()

Private Attributes

std::string hwid_
ros::Time next_time_
ros::NodeHandle node_handle_
double period_
ros::NodeHandle private_node_handle_
ros::Publisher publisher_
bool warn_nohwid_done_

Detailed Description

Manages a list of diagnostic tasks, and calls them in a rate-limited manner.

This class manages a list of diagnostic tasks. Its update function should be called frequently. At some predetermined rate, the update function will cause all the diagnostic tasks to run, and will collate and publish the resulting diagnostics. The publication rate is determined by the "~diagnostic_period" ros parameter.

The class also allows an update to be forced when something significant has happened, and allows a single message to be broadcast on all the diagnostics if normal operation of the node is suspended for some reason.

Definition at line 362 of file diagnostic_updater.h.


Constructor & Destructor Documentation

Constructs an updater class.

Parameters:
hNode handle from which to get the diagnostic_period parameter.

Definition at line 373 of file diagnostic_updater.h.


Member Function Documentation

virtual void diagnostic_updater::Updater::addedTaskCallback ( DiagnosticTaskInternal task) [inline, private, virtual]

Causes a placeholder DiagnosticStatus to be published as soon as a diagnostic task is added to the Updater.

Reimplemented from diagnostic_updater::DiagnosticTaskVector.

Definition at line 570 of file diagnostic_updater.h.

void diagnostic_updater::Updater::broadcast ( int  lvl,
const std::string  msg 
) [inline]

Output a message on all the known DiagnosticStatus.

Useful if something drastic is happening such as shutdown or a self-test.

Parameters:
lvlLevel of the diagnostic being output.
msgStatus message to output.

Definition at line 476 of file diagnostic_updater.h.

Forces the diagnostics to update.

Useful if the node has undergone a drastic state change that should be published immediately.

Definition at line 399 of file diagnostic_updater.h.

Returns the interval between updates.

Definition at line 448 of file diagnostic_updater.h.

void diagnostic_updater::Updater::publish ( diagnostic_msgs::DiagnosticStatus &  stat) [inline, private]

Publishes a single diagnostic status.

Definition at line 526 of file diagnostic_updater.h.

void diagnostic_updater::Updater::publish ( std::vector< diagnostic_msgs::DiagnosticStatus > &  status_vec) [inline, private]

Publishes a vector of diagnostic statuses.

Definition at line 536 of file diagnostic_updater.h.

void diagnostic_updater::Updater::setHardwareID ( const std::string &  hwid) [inline]

Definition at line 506 of file diagnostic_updater.h.

void diagnostic_updater::Updater::setHardwareIDf ( const char *  format,
  ... 
) [inline]

Definition at line 495 of file diagnostic_updater.h.

void diagnostic_updater::Updater::setup ( ) [inline, private]

Publishes on /diagnostics and reads the diagnostic_period parameter.

Definition at line 553 of file diagnostic_updater.h.

Causes the diagnostics to update if the inter-update interval has been exceeded.

Definition at line 382 of file diagnostic_updater.h.

Recheck the diagnostic_period on the parameter server. (Cached)

Definition at line 516 of file diagnostic_updater.h.


Member Data Documentation

std::string diagnostic_updater::Updater::hwid_ [private]

Definition at line 585 of file diagnostic_updater.h.

Definition at line 582 of file diagnostic_updater.h.

Definition at line 579 of file diagnostic_updater.h.

Definition at line 584 of file diagnostic_updater.h.

Definition at line 578 of file diagnostic_updater.h.

Definition at line 580 of file diagnostic_updater.h.

Definition at line 365 of file diagnostic_updater.h.

Definition at line 586 of file diagnostic_updater.h.


The documentation for this class was generated from the following file:


diagnostic_updater
Author(s): Jeremy Leibs, Blaise Gassend, Brice Rebsamen
autogenerated on Fri Jan 3 2014 11:18:57