36 #ifndef DIAGNOSTICUPDATER_HH
37 #define DIAGNOSTICUPDATER_HH
43 #include "ros/node_handle.h"
44 #include "ros/this_node.h"
47 #include "diagnostic_updater/DiagnosticStatusWrapper.h"
54 typedef std::function<void(DiagnosticStatusWrapper&)>
TaskFunction;
95 const std::string
name_;
108 class GenericFunctionDiagnosticTask :
public DiagnosticTask
123 virtual void run(DiagnosticStatusWrapper &stat)
129 const std::string
name_;
147 class CompositeDiagnosticTask :
public DiagnosticTask
159 virtual void run(DiagnosticStatusWrapper &stat)
161 DiagnosticStatusWrapper combined_summary;
162 DiagnosticStatusWrapper original_summary;
164 original_summary.summary(stat);
166 for (std::vector<DiagnosticTask *>::iterator i =
tasks_.begin();
170 stat.summary(original_summary);
174 combined_summary.mergeSummary(stat);
178 stat.summary(combined_summary);
193 std::vector<DiagnosticTask *>
tasks_;
204 class DiagnosticTaskVector
211 class DiagnosticTaskInternal
224 const std::string &
getName()
const
239 const std::vector<DiagnosticTaskInternal> &
getTasks()
259 DiagnosticTaskInternal int_task(
name,
f);
271 void add(DiagnosticTask &task)
274 add(task.getName(),
f);
293 DiagnosticTaskInternal int_task(
name, std::bind(
f,
c, std::placeholders::_1));
311 std::lock_guard<std::mutex> lock(
lock_);
312 for (std::vector<DiagnosticTaskInternal>::iterator iter =
tasks_.begin();
313 iter !=
tasks_.end(); iter++)
315 if (iter->getName() ==
name)
334 std::vector<DiagnosticTaskInternal>
tasks_;
342 std::lock_guard<std::mutex> lock(
lock_);
363 class Updater :
public DiagnosticTaskVector
409 bool warn_nohwid =
hwid_.empty();
411 std::vector<diagnostic_msgs::DiagnosticStatus> status_vec;
413 std::lock_guard<std::mutex> lock(
lock_);
414 const std::vector<DiagnosticTaskInternal> &tasks =
getTasks();
415 for (std::vector<DiagnosticTaskInternal>::const_iterator iter = tasks.begin();
416 iter != tasks.end(); iter++)
420 status.name = iter->getName();
422 status.message =
"No message was set";
427 status_vec.push_back(
status);
433 ROS_WARN(
"Non-zero diagnostic status. Name: '%s', status %i: '%s'",
status.name.c_str(),
status.level,
status.message.c_str());
438 ROS_WARN(
"diagnostic_updater: No HW_ID was set. This is probably a bug. Please report it. For devices that do not have a HW_ID, set this value to 'none'. This warning only occurs once all diagnostics are OK so it is okay to wait until the device is open before calling setHardwareID.");
480 std::vector<diagnostic_msgs::DiagnosticStatus> status_vec;
482 const std::vector<DiagnosticTaskInternal> &tasks =
getTasks();
483 for (std::vector<DiagnosticTaskInternal>::const_iterator iter = tasks.begin();
484 iter != tasks.end(); iter++)
488 status.name = iter->getName();
491 status_vec.push_back(
status);
501 va_start(va, format);
502 if (vsnprintf(buff, 1000, format, va) >= 1000)
503 ROS_DEBUG(
"Really long string in diagnostic_updater::setHardwareIDf.");
504 hwid_ = std::string(buff);
530 std::vector<diagnostic_msgs::DiagnosticStatus> status_vec;
531 status_vec.push_back(stat);
538 void publish(std::vector<diagnostic_msgs::DiagnosticStatus> &status_vec)
540 for (std::vector<diagnostic_msgs::DiagnosticStatus>::iterator
541 iter = status_vec.begin(); iter != status_vec.end(); iter++)
544 node_name_.substr(1) + std::string(
": ") + iter->name;
547 msg.status = status_vec;
575 DiagnosticStatusWrapper stat;
576 stat.
name = task.getName();
577 stat.summary(0,
"Node starting up");