Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | List of all members
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]

Public Member Functions

void broadcast (int lvl, const std::string msg)
 Output a message on all the known DiagnosticStatus. More...
 
void force_update ()
 Forces the diagnostics to update. More...
 
double getPeriod ()
 Returns the interval between updates. More...
 
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. More...
 
 Updater (ros::NodeHandle h=ros::NodeHandle(), ros::NodeHandle ph=ros::NodeHandle("~"), std::string node_name=ros::this_node::getName())
 Constructs an updater class. More...
 
- Public Member Functions inherited from diagnostic_updater::DiagnosticTaskVector
void add (const std::string &name, TaskFunction f)
 Add a DiagnosticTask embodied by a name and function to the DiagnosticTaskVector. More...
 
void add (DiagnosticTask &task)
 Add a DiagnosticTask to the DiagnosticTaskVector. More...
 
template<class T >
void add (const std::string name, T *c, void(T::*f)(diagnostic_updater::DiagnosticStatusWrapper &))
 Add a DiagnosticTask embodied by a name and method to the DiagnosticTaskVector. More...
 
bool removeByName (const std::string name)
 Remove a task based on its name. More...
 

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_
 
std::string node_name_
 
double period_
 
ros::NodeHandle private_node_handle_
 
ros::Publisher publisher_
 
bool warn_nohwid_done_
 

Additional Inherited Members

- Protected Member Functions inherited from diagnostic_updater::DiagnosticTaskVector
void addInternal (DiagnosticTaskInternal &task)
 
const std::vector< DiagnosticTaskInternal > & getTasks ()
 Returns the vector of tasks. More...
 
- Protected Attributes inherited from diagnostic_updater::DiagnosticTaskVector
boost::mutex lock_
 

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

diagnostic_updater::Updater::Updater ( ros::NodeHandle  h = ros::NodeHandle(),
ros::NodeHandle  ph = ros::NodeHandle("~"),
std::string  node_name = ros::this_node::getName() 
)
inline

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)
inlineprivatevirtual

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 569 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.

void diagnostic_updater::Updater::force_update ( )
inline

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.

double diagnostic_updater::Updater::getPeriod ( )
inline

Returns the interval between updates.

Definition at line 448 of file diagnostic_updater.h.

void diagnostic_updater::Updater::publish ( diagnostic_msgs::DiagnosticStatus &  stat)
inlineprivate

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)
inlineprivate

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 ( )
inlineprivate

Publishes on /diagnostics and reads the diagnostic_period parameter.

Definition at line 553 of file diagnostic_updater.h.

void diagnostic_updater::Updater::update ( )
inline

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

Definition at line 382 of file diagnostic_updater.h.

void diagnostic_updater::Updater::update_diagnostic_period ( )
inlineprivate

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 584 of file diagnostic_updater.h.

ros::Time diagnostic_updater::Updater::next_time_
private

Definition at line 581 of file diagnostic_updater.h.

ros::NodeHandle diagnostic_updater::Updater::node_handle_
private

Definition at line 578 of file diagnostic_updater.h.

std::string diagnostic_updater::Updater::node_name_
private

Definition at line 585 of file diagnostic_updater.h.

double diagnostic_updater::Updater::period_
private

Definition at line 583 of file diagnostic_updater.h.

ros::NodeHandle diagnostic_updater::Updater::private_node_handle_
private

Definition at line 577 of file diagnostic_updater.h.

ros::Publisher diagnostic_updater::Updater::publisher_
private

Definition at line 579 of file diagnostic_updater.h.

bool diagnostic_updater::Updater::verbose_

Definition at line 365 of file diagnostic_updater.h.

bool diagnostic_updater::Updater::warn_nohwid_done_
private

Definition at line 586 of file diagnostic_updater.h.


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


diagnostic_updater
Author(s): Kevin Watts, Brice Rebsamen , Jeremy Leibs, Blaise Gassend
autogenerated on Wed Mar 27 2019 03:02:22