Manages a list of diagnostic tasks, and calls them in a rate-limited manner. More...
#include <diagnostic_updater.h>
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_ |
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 363 of file diagnostic_updater.h.
|
inline |
Constructs an updater class.
h | Node handle from which to get the diagnostic_period parameter. |
Definition at line 374 of file diagnostic_updater.h.
|
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 570 of file diagnostic_updater.h.
|
inline |
Output a message on all the known DiagnosticStatus.
Useful if something drastic is happening such as shutdown or a self-test.
lvl | Level of the diagnostic being output. |
msg | Status message to output. |
Definition at line 477 of file diagnostic_updater.h.
|
inline |
Forces the diagnostics to update.
Useful if the node has undergone a drastic state change that should be published immediately.
Definition at line 400 of file diagnostic_updater.h.
|
inline |
Returns the interval between updates.
Definition at line 449 of file diagnostic_updater.h.
|
inlineprivate |
Publishes a single diagnostic status.
Definition at line 527 of file diagnostic_updater.h.
|
inlineprivate |
Publishes a vector of diagnostic statuses.
Definition at line 537 of file diagnostic_updater.h.
|
inline |
Definition at line 507 of file diagnostic_updater.h.
|
inline |
Definition at line 496 of file diagnostic_updater.h.
|
inlineprivate |
Publishes on /diagnostics and reads the diagnostic_period parameter.
Definition at line 554 of file diagnostic_updater.h.
|
inline |
Causes the diagnostics to update if the inter-update interval has been exceeded.
Definition at line 383 of file diagnostic_updater.h.
|
inlineprivate |
Recheck the diagnostic_period on the parameter server. (Cached)
Definition at line 517 of file diagnostic_updater.h.
|
private |
Definition at line 585 of file diagnostic_updater.h.
|
private |
Definition at line 582 of file diagnostic_updater.h.
|
private |
Definition at line 579 of file diagnostic_updater.h.
|
private |
Definition at line 586 of file diagnostic_updater.h.
|
private |
Definition at line 584 of file diagnostic_updater.h.
|
private |
Definition at line 578 of file diagnostic_updater.h.
|
private |
Definition at line 580 of file diagnostic_updater.h.
bool diagnostic_updater::Updater::verbose_ |
Definition at line 366 of file diagnostic_updater.h.
|
private |
Definition at line 587 of file diagnostic_updater.h.