35 #ifndef DIAGNOSTICUPDATER_HH 36 #define DIAGNOSTICUPDATER_HH 45 #include "diagnostic_msgs/DiagnosticArray.h" 46 #include "diagnostic_msgs/DiagnosticStatus.h" 49 #include <boost/thread.hpp> 54 typedef boost::function<void(DiagnosticStatusWrapper&)>
TaskFunction;
164 original_summary.
summary(stat);
166 for (std::vector<DiagnosticTask *>::iterator i = tasks_.begin();
167 i != tasks_.end(); i++)
170 stat.
summary(original_summary);
178 stat.
summary(combined_summary);
239 const std::vector<DiagnosticTaskInternal> &
getTasks()
257 void add(
const std::string &name, TaskFunction f)
260 addInternal(int_task);
294 addInternal(int_task);
311 boost::mutex::scoped_lock 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 boost::mutex::scoped_lock lock(lock_);
343 tasks_.push_back(task);
344 addedTaskCallback(task);
386 if (now_time < next_time_) {
402 update_diagnostic_period();
406 if (node_handle_.ok())
408 bool warn_nohwid = hwid_.empty();
410 std::vector<diagnostic_msgs::DiagnosticStatus> status_vec;
412 boost::mutex::scoped_lock lock(lock_);
413 const std::vector<DiagnosticTaskInternal> &tasks = getTasks();
414 for (std::vector<DiagnosticTaskInternal>::const_iterator iter = tasks.begin();
415 iter != tasks.end(); iter++)
419 status.name = iter->getName();
421 status.message =
"No message was set";
422 status.hardware_id = hwid_;
426 status_vec.push_back(status);
431 if (verbose_ && status.level)
432 ROS_WARN(
"Non-zero diagnostic status. Name: '%s', status %i: '%s'", status.name.c_str(), status.level, status.message.c_str());
435 if (warn_nohwid && !warn_nohwid_done_)
437 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.");
438 warn_nohwid_done_ =
true;
479 std::vector<diagnostic_msgs::DiagnosticStatus> status_vec;
481 const std::vector<DiagnosticTaskInternal> &tasks = getTasks();
482 for (std::vector<DiagnosticTaskInternal>::const_iterator iter = tasks.begin();
483 iter != tasks.end(); iter++)
487 status.name = iter->getName();
490 status_vec.push_back(status);
500 va_start(va, format);
501 if (vsnprintf(buff, 1000, format, va) >= 1000)
502 ROS_DEBUG(
"Really long string in diagnostic_updater::setHardwareIDf.");
503 hwid_ = std::string(buff);
519 double old_period = period_;
520 private_node_handle_.getParamCached(
"diagnostic_period", period_);
527 void publish(diagnostic_msgs::DiagnosticStatus &stat)
529 std::vector<diagnostic_msgs::DiagnosticStatus> status_vec;
530 status_vec.push_back(stat);
537 void publish(std::vector<diagnostic_msgs::DiagnosticStatus> &status_vec)
539 for (std::vector<diagnostic_msgs::DiagnosticStatus>::iterator
540 iter = status_vec.begin(); iter != status_vec.end(); iter++)
543 node_name_.substr(1) + std::string(
": ") + iter->name;
545 diagnostic_msgs::DiagnosticArray
msg;
546 msg.status = status_vec;
548 publisher_.publish(msg);
556 publisher_ = node_handle_.advertise<diagnostic_msgs::DiagnosticArray>(
"/diagnostics", 1);
560 update_diagnostic_period();
563 warn_nohwid_done_ =
false;
574 stat.
summary(0,
"Node starting up");
void addInternal(DiagnosticTaskInternal &task)
Updater(ros::NodeHandle h=ros::NodeHandle(), ros::NodeHandle ph=ros::NodeHandle("~"), std::string node_name=ros::this_node::getName())
Constructs an updater class.
ros::Publisher publisher_
std::vector< DiagnosticTaskInternal > tasks_
void summary(unsigned char lvl, const std::string s)
Fills out the level and message fields of the DiagnosticStatus.
void update_diagnostic_period()
void setHardwareID(const std::string &hwid)
virtual void run(diagnostic_updater::DiagnosticStatusWrapper &stat)=0
Fills out this Task's DiagnosticStatusWrapper.
virtual ~DiagnosticTask()
void add(const std::string &name, TaskFunction f)
Add a DiagnosticTask embodied by a name and function to the DiagnosticTaskVector. ...
ROSCPP_DECL const std::string & getName()
boost::function< void(diagnostic_msgs::DiagnosticStatus &)> UnwrappedTaskFunction
const std::string & getName() const
Manages a list of diagnostic tasks, and calls them in a rate-limited manner.
virtual void addedTaskCallback(DiagnosticTaskInternal &task)
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.
std::vector< DiagnosticTask * > tasks_
double getPeriod()
Returns the interval between updates.
DiagnosticTaskInternal(const std::string name, TaskFunction f)
virtual void addedTaskCallback(DiagnosticTaskInternal &)
void add(DiagnosticTask &task)
Add a DiagnosticTask to the DiagnosticTaskVector.
void run(diagnostic_updater::DiagnosticStatusWrapper &stat) const
Duration & fromSec(double t)
void update()
Causes the diagnostics to update if the inter-update interval has been exceeded.
GenericFunctionDiagnosticTask< diagnostic_msgs::DiagnosticStatus > UnwrappedFunctionDiagnosticTask
bool removeByName(const std::string name)
Remove a task based on its name.
GenericFunctionDiagnosticTask(const std::string &name, boost::function< void(T &)> fn)
a DiagnosticTask based on a boost::function.
ros::NodeHandle node_handle_
void mergeSummary(unsigned char lvl, const std::string s)
Merges a level and message with the existing ones.
const std::string & getName()
Returns the name of the DiagnosticTask.
DiagnosticTask(const std::string name)
Constructs a DiagnosticTask setting its name in the process.
void force_update()
Forces the diagnostics to update.
Class used to represent a diagnostic task internally in DiagnosticTaskVector.
boost::function< void(DiagnosticStatusWrapper &)> TaskFunction
CompositeDiagnosticTask(const std::string name)
Constructs a CompositeDiagnosticTask with the given name.
virtual void run(DiagnosticStatusWrapper &stat)
Fills out this Task's DiagnosticStatusWrapper.
ros::NodeHandle private_node_handle_
DiagnosticTask is an abstract base class for collecting diagnostic data.
virtual void run(DiagnosticStatusWrapper &stat)
Runs each child and merges their outputs.
void broadcast(int lvl, const std::string msg)
Output a message on all the known DiagnosticStatus.
const std::vector< DiagnosticTaskInternal > & getTasks()
Returns the vector of tasks.
void setHardwareIDf(const char *format,...)
void publish(std::vector< diagnostic_msgs::DiagnosticStatus > &status_vec)
GenericFunctionDiagnosticTask< DiagnosticStatusWrapper > FunctionDiagnosticTask
void publish(diagnostic_msgs::DiagnosticStatus &stat)
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.