36 #include <std_msgs/Bool.h> 68 stat.
add(
"Diagnostic Name",
"dummy");
72 stat.
addf(
"Geeky thing to say",
"The square of the time to launch %f is %f",
83 stat.
add(
"Stupidicity of this updater", 1000.);
90 DummyTask() : DiagnosticTask(
"Updater Derived from DiagnosticTask")
96 stat.
add(
"Stupidicity of this updater", 2000.);
120 int main(
int argc,
char **argv)
122 ros::init(argc, argv,
"diagnostic_updater_example");
185 updater.
broadcast(0,
"Doing important initialization stuff.");
208 double min_freq = 0.5;
228 ROS_ERROR(
"The Bound check task was not found when trying to remove it.");
void publish(const boost::shared_ptr< M > &message) const
void summary(unsigned char lvl, const std::string s)
Fills out the level and message fields of the DiagnosticStatus.
A structure that holds the constructor parameters for the FrequencyStatus class.
void setHardwareID(const std::string &hwid)
void run(diagnostic_updater::DiagnosticStatusWrapper &stat)
Fills out this Task's DiagnosticStatusWrapper.
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void add(const std::string &name, TaskFunction f)
Add a DiagnosticTask embodied by a name and function to the DiagnosticTaskVector. ...
void addf(const std::string &key, const char *format,...)
Add a key-value pair using a format string.
void check_upper_bound(diagnostic_updater::DiagnosticStatusWrapper &stat)
Manages a list of diagnostic tasks, and calls them in a rate-limited manner.
void summaryf(unsigned char lvl, const char *format,...)
Formatted version of summary.
int main(int argc, char **argv)
void update()
Causes the diagnostics to update if the inter-update interval has been exceeded.
void dummy_diagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool removeByName(const std::string name)
Remove a task based on its name.
void produce_diagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
void force_update()
Forces the diagnostics to update.
DiagnosticTask is an abstract base class for collecting diagnostic data.
void check_lower_bound(diagnostic_updater::DiagnosticStatusWrapper &stat)
void add(const std::string &key, const T &val)
Add a key-value pair.
void broadcast(int lvl, const std::string msg)
Output a message on all the known DiagnosticStatus.
void setHardwareIDf(const char *format,...)
Merges CompositeDiagnosticTask into a single DiagnosticTask.
Wrapper for the diagnostic_msgs::DiagnosticStatus message that makes it easier to update...
void addTask(DiagnosticTask *t)
Adds a child CompositeDiagnosticTask.