Diagnostic updater that automatically sets its Hardware ID to hostname of the machine. More...
#include <updater.h>
Public Member Functions | |
DiagnosticUpdater (const ::ros::NodeHandle &h=::ros::NodeHandle(), const ::ros::NodeHandle &ph=::ros::NodeHandle("~"), const ::std::string &node_name=::ros::this_node::getName()) | |
Create the updater. More... | |
Public Member Functions inherited from diagnostic_updater::Updater | |
void | broadcast (int lvl, const std::string msg) |
void | force_update () |
double | getPeriod () |
void | setHardwareID (const std::string &hwid) |
void | setHardwareIDf (const char *format,...) |
void | update () |
Updater (ros::NodeHandle h=ros::NodeHandle(), ros::NodeHandle ph=ros::NodeHandle("~"), std::string node_name=ros::this_node::getName()) | |
Public Member Functions inherited from diagnostic_updater::DiagnosticTaskVector | |
void | add (const std::string &name, TaskFunction f) |
void | add (DiagnosticTask &task) |
void | add (const std::string name, T *c, void(T::*f)(diagnostic_updater::DiagnosticStatusWrapper &)) |
bool | removeByName (const std::string name) |
Additional Inherited Members | |
Public Attributes inherited from diagnostic_updater::Updater | |
bool | verbose_ |
Protected Member Functions inherited from diagnostic_updater::DiagnosticTaskVector | |
void | addInternal (DiagnosticTaskInternal &task) |
const std::vector< DiagnosticTaskInternal > & | getTasks () |
Protected Attributes inherited from diagnostic_updater::DiagnosticTaskVector | |
boost::mutex | lock_ |
Diagnostic updater that automatically sets its Hardware ID to hostname of the machine.
|
explicit |
Create the updater.
[in] | h | Node handle to use for publishing to "/diagnostics" topic. |
[in] | ph | Node handle from which "~diagnostic_period" parameter is read. |
[in] | node_name | This name is prepended to all status messages. |