foxy/include/diagnostic_updater/diagnostic_updater.hpp
Go to the documentation of this file.
1 #include "sick_scan/sick_scan_base.h" /* Base definitions included in all header files, added by add_sick_scan_base_header.py. Do not edit this line. */
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the Willow Garage nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 #ifndef DIAGNOSTIC_UPDATER__DIAGNOSTIC_UPDATER_HPP_
37 #define DIAGNOSTIC_UPDATER__DIAGNOSTIC_UPDATER_HPP_
38 
39 #include <functional> // for bind()
40 #include <memory>
41 #include <stdexcept>
42 #include <string>
43 #include <vector>
44 
45 #include "builtin_interfaces/msg/time.hpp"
46 
47 #include "diagnostic_msgs/msg/diagnostic_array.hpp"
48 #include "diagnostic_msgs/msg/diagnostic_status.hpp"
49 
50 #include "diagnostic_updater/diagnostic_status_wrapper.hpp"
51 
52 #include "rcl/time.h"
53 
54 #include "rclcpp/create_timer.hpp"
55 #include "rclcpp/rclcpp.hpp"
56 
57 namespace diagnostic_updater
58 {
59 
60 typedef std::function<void (DiagnosticStatusWrapper &)> TaskFunction;
61 typedef std::function<void (diagnostic_msgs::msg::DiagnosticStatus &)>
63 
73 class DiagnosticTask
74 {
75 public:
79  explicit DiagnosticTask(const std::string name)
80  : name_(name) {}
81 
85  const std::string & getName() {return name_;}
86 
90  virtual void run(diagnostic_updater::DiagnosticStatusWrapper & stat) = 0;
91 
95  virtual ~DiagnosticTask() {}
96 
97 private:
98  const std::string name_;
99 };
100 
112 template<class T>
113 class GenericFunctionDiagnosticTask : public DiagnosticTask
114 {
115 public:
125  const std::string & name,
126  std::function<void(T &)> fn)
127  : DiagnosticTask(name), fn_(fn) {}
128 
129  virtual void run(DiagnosticStatusWrapper & stat) {fn_(stat);}
130 
131 private:
132  const std::string name_;
133  const TaskFunction fn_;
134 };
135 
136 typedef GenericFunctionDiagnosticTask<diagnostic_msgs::msg::DiagnosticStatus>
138 typedef GenericFunctionDiagnosticTask<DiagnosticStatusWrapper>
140 
153 class CompositeDiagnosticTask : public DiagnosticTask
154 {
155 public:
159  explicit CompositeDiagnosticTask(const std::string name)
160  : DiagnosticTask(name) {}
161 
165  virtual void run(DiagnosticStatusWrapper & stat)
166  {
167  DiagnosticStatusWrapper combined_summary;
168  DiagnosticStatusWrapper original_summary;
169 
170  original_summary.summary(stat);
171 
172  for (std::vector<DiagnosticTask *>::iterator i = tasks_.begin();
173  i != tasks_.end(); i++)
174  {
175  // Put the summary that was passed in.
176  stat.summary(original_summary);
177  // Let the next task add entries and put its summary.
178  (*i)->run(stat);
179  // Merge the new summary into the combined summary.
180  combined_summary.mergeSummary(stat);
181  }
182 
183  // Copy the combined summary into the output.
184  stat.summary(combined_summary);
185  }
186 
193  void addTask(DiagnosticTask * t) {tasks_.push_back(t);}
194 
195 private:
196  std::vector<DiagnosticTask *> tasks_;
197 };
198 
207 class DiagnosticTaskVector
208 {
209 protected:
214  class DiagnosticTaskInternal
215  {
216 public:
217  DiagnosticTaskInternal(const std::string name, TaskFunction f)
218  : name_(name), fn_(f) {}
219 
221  {
222  stat.name = name_;
223  fn_(stat);
224  }
225 
226  const std::string & getName() const {return name_;}
227 
228 private:
229  std::string name_;
231  };
232 
233  std::mutex lock_;
234 
238  const std::vector<DiagnosticTaskInternal> & getTasks() {return tasks_;}
239 
240 public:
241  virtual ~DiagnosticTaskVector() {}
242 
254  void add(const std::string & name, TaskFunction f)
255  {
256  DiagnosticTaskInternal int_task(name, f);
257  addInternal(int_task);
258  }
259 
267  void add(DiagnosticTask & task)
268  {
269  TaskFunction f = std::bind(&DiagnosticTask::run, &task, std::placeholders::_1);
270  add(task.getName(), f);
271  }
272 
286  template<class T>
287  void add(
288  const std::string name, T * c,
290  {
291  DiagnosticTaskInternal int_task(name, std::bind(f, c, std::placeholders::_1));
292  addInternal(int_task);
293  }
294 
305  bool removeByName(const std::string name)
306  {
307  std::unique_lock<std::mutex> lock(lock_);
308  for (std::vector<DiagnosticTaskInternal>::iterator iter = tasks_.begin();
309  iter != tasks_.end(); iter++)
310  {
311  if (iter->getName() == name) {
312  tasks_.erase(iter);
313  return true;
314  }
315 
317  }
318  return false;
319  }
320 
321 private:
327  virtual void addedTaskCallback(DiagnosticTaskInternal &) {}
328  std::vector<DiagnosticTaskInternal> tasks_;
329 
330 protected:
334  void addInternal(DiagnosticTaskInternal & task)
335  {
336  std::unique_lock<std::mutex> lock(lock_);
337  tasks_.push_back(task);
338  addedTaskCallback(task);
339  }
340 };
341 
353 class Updater : public DiagnosticTaskVector
354 {
355 public:
356  bool verbose_;
357 
366  template<class NodeT>
367  explicit Updater(NodeT node, double period = 1.0)
368  : Updater(
369  node->get_node_base_interface(),
370  node->get_node_logging_interface(),
371  node->get_node_parameters_interface(),
372  node->get_node_timers_interface(),
373  node->get_node_topics_interface(),
374  period)
375  {}
376 
377  Updater(
378  std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface> base_interface,
379  std::shared_ptr<rclcpp::node_interfaces::NodeLoggingInterface> logging_interface,
380  std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface> parameters_interface,
381  std::shared_ptr<rclcpp::node_interfaces::NodeTimersInterface> timers_interface,
382  std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface> topics_interface,
383  double period = 1.0)
384  : verbose_(false),
385  base_interface_(base_interface),
386  timers_interface_(timers_interface),
387  clock_(std::make_shared<rclcpp::Clock>(RCL_ROS_TIME)),
388  period_(static_cast<rcl_duration_value_t>(period * 1e9)),
389  publisher_(
390  rclcpp::create_publisher<diagnostic_msgs::msg::DiagnosticArray>(
391  topics_interface, "/diagnostics", 1)),
392  logger_(logging_interface->get_logger()),
393  node_name_(base_interface->get_name()),
394  warn_nohwid_done_(false)
395  {
396  period = parameters_interface->declare_parameter(
397  "diagnostic_updater.period", rclcpp::ParameterValue(period)).get<double>();
398  period_ = rclcpp::Duration(static_cast<rcl_duration_value_t>(period * 1e9));
399 
400  reset_timer();
401  }
402 
406  auto getPeriod() const {return period_;}
407 
411  void setPeriod(rclcpp::Duration period)
412  {
413  period_ = period;
414  reset_timer();
415  }
416 
420  void setPeriod(rcl_duration_value_t period)
421  {
422  setPeriod(rclcpp::Duration(period));
423  }
424 
428  void setPeriod(double period)
429  {
430  setPeriod(static_cast<rcl_duration_value_t>(period * 1e9));
431  }
432 
436  void force_update()
437  {
438  update();
439  }
440 
451  void broadcast(int lvl, const std::string msg)
452  {
453  std::vector<diagnostic_msgs::msg::DiagnosticStatus> status_vec;
454 
455  const std::vector<DiagnosticTaskInternal> & tasks = getTasks();
456  for (std::vector<DiagnosticTaskInternal>::const_iterator iter =
457  tasks.begin();
458  iter != tasks.end(); iter++)
459  {
461 
462  status.name = iter->getName();
463  status.summary(lvl, msg);
464 
465  status_vec.push_back(status);
466  }
467 
468  publish(status_vec);
469  }
470 
471  void setHardwareIDf(const char * format, ...)
472  {
473  va_list va;
474  const int kBufferSize = 1000;
475  char buff[kBufferSize]; // @todo This could be done more elegantly.
476  va_start(va, format);
477  if (vsnprintf(buff, kBufferSize, format, va) >= kBufferSize) {
478  RCLCPP_DEBUG(logger_, "Really long string in diagnostic_updater::setHardwareIDf.");
479  }
480  hwid_ = std::string(buff);
481  va_end(va);
482  }
483 
484  void setHardwareID(const std::string & hwid) {hwid_ = hwid;}
485 
486 private:
487  void reset_timer()
488  {
489  update_timer_ = rclcpp::create_timer(
490  base_interface_,
491  timers_interface_,
492  clock_,
493  period_,
494  std::bind(&Updater::update, this));
495  }
496 
501  void update()
502  {
503  if (rclcpp::ok()) {
504  bool warn_nohwid = hwid_.empty();
505 
506  std::vector<diagnostic_msgs::msg::DiagnosticStatus> status_vec;
507 
508  std::unique_lock<std::mutex> lock(
509  lock_); // Make sure no adds happen while we are processing here.
510  const std::vector<DiagnosticTaskInternal> & tasks = getTasks();
511  for (std::vector<DiagnosticTaskInternal>::const_iterator iter =
512  tasks.begin();
513  iter != tasks.end(); iter++)
514  {
516 
517  status.name = iter->getName();
518  status.level = 2;
519  status.message = "No message was set";
520  status.hardware_id = hwid_;
521 
522  iter->run(status);
523 
524  status_vec.push_back(status);
525 
526  if (status.level) {
527  warn_nohwid = false;
528  }
529 
530  if (verbose_ && status.level) {
531  RCLCPP_WARN(
532  logger_, "Non-zero diagnostic status. Name: '%s', status %i: '%s'",
533  status.name.c_str(), status.level, status.message.c_str());
534  }
535  }
536 
537  if (warn_nohwid && !warn_nohwid_done_) {
538  std::string error_msg = "diagnostic_updater: No HW_ID was set.";
539  error_msg += " This is probably a bug. Please report it.";
540  error_msg += " For devices that do not have a HW_ID, set this value to 'none'.";
541  error_msg += " This warning only occurs once all diagnostics are OK.";
542  error_msg += " It is okay to wait until the device is open before calling setHardwareID.";
543  RCLCPP_WARN(logger_, error_msg);
544  warn_nohwid_done_ = true;
545  }
546 
547  publish(status_vec);
548  }
549  }
550 
555  // TODO(Karsten1987) Follow up PR for eloquent
556  // void update_diagnostic_period()
557  // {
558  // // rcl_duration_value_t old_period = period_;
559  // // next_time_ = next_time_ +
560  // // rclcpp::Duration(period_ - old_period); // Update next_time_
561  // }
562 
567  {
568  std::vector<diagnostic_msgs::msg::DiagnosticStatus> status_vec;
569  status_vec.push_back(stat);
570  publish(status_vec);
571  }
572 
576  void publish(std::vector<diagnostic_msgs::msg::DiagnosticStatus> & status_vec)
577  {
578  for (std::vector<diagnostic_msgs::msg::DiagnosticStatus>::iterator iter =
579  status_vec.begin();
580  iter != status_vec.end(); iter++)
581  {
582  iter->name = node_name_ + std::string(": ") + iter->name;
583  }
585  msg.status = status_vec;
586  msg.header.stamp = rclcpp::Clock().now();
588  }
589 
594  virtual void addedTaskCallback(DiagnosticTaskInternal & task)
595  {
596  DiagnosticStatusWrapper stat;
597  stat.name = task.getName();
598  stat.summary(0, "Node starting up");
599  publish(stat);
600  }
601 
602  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr base_interface_;
603  rclcpp::node_interfaces::NodeTimersInterface::SharedPtr timers_interface_;
604  rclcpp::Clock::SharedPtr clock_;
606  rclcpp::TimerBase::SharedPtr update_timer_;
607  rclcpp::Publisher<diagnostic_msgs::msg::DiagnosticArray>::SharedPtr publisher_;
608  rclcpp::Logger logger_;
609 
610  std::string hwid_;
611  std::string node_name_;
612  bool warn_nohwid_done_;
613 };
614 } // namespace diagnostic_updater
615 
616 #endif // DIAGNOSTIC_UPDATER__DIAGNOSTIC_UPDATER_HPP_
diagnostic_updater::CompositeDiagnosticTask::addTask
void addTask(DiagnosticTask *t)
diagnostic_updater::Updater::addedTaskCallback
virtual void addedTaskCallback(DiagnosticTaskInternal &task)
diagnostic_updater::DiagnosticTask::name_
const std::string name_
Definition: eloquent/include/diagnostic_updater/diagnostic_updater.hpp:98
diagnostic_updater::CompositeDiagnosticTask::tasks_
std::vector< DiagnosticTask * > tasks_
Definition: eloquent/include/diagnostic_updater/diagnostic_updater.hpp:196
diagnostic_updater::DiagnosticTaskVector::DiagnosticTaskInternal::name_
std::string name_
Definition: eloquent/include/diagnostic_updater/diagnostic_updater.hpp:229
msg
msg
diagnostic_updater::DiagnosticTaskVector::lock_
boost::mutex lock_
Definition: foxy/include/diagnostic_updater/diagnostic_updater.hpp:233
diagnostic_updater::Updater::setHardwareIDf
void setHardwareIDf(const char *format,...)
diagnostic_updater::Updater::force_update
void force_update()
diagnostic_updater::DiagnosticTask::DiagnosticTask
DiagnosticTask(const std::string name)
diagnostic_updater::UnwrappedTaskFunction
boost::function< void(diagnostic_msgs::DiagnosticStatus &)> UnwrappedTaskFunction
Definition: foxy/include/diagnostic_updater/diagnostic_updater.hpp:62
diagnostic_updater::DiagnosticTaskVector::DiagnosticTaskInternal::getName
const std::string & getName() const
diagnostic_updater::Updater::node_name_
std::string node_name_
Definition: eloquent/include/diagnostic_updater/diagnostic_updater.hpp:612
diagnostic_updater::GenericFunctionDiagnosticTask::fn_
const TaskFunction fn_
Definition: eloquent/include/diagnostic_updater/diagnostic_updater.hpp:133
diagnostic_msgs::DiagnosticStatus
::diagnostic_msgs::DiagnosticStatus_< std::allocator< void > > DiagnosticStatus
Definition: DiagnosticStatus.h:73
diagnostic_updater::DiagnosticTask::~DiagnosticTask
virtual ~DiagnosticTask()
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
diagnostic_updater::Updater::broadcast
void broadcast(int lvl, const std::string msg)
f
f
diagnostic_updater::GenericFunctionDiagnosticTask::GenericFunctionDiagnosticTask
GenericFunctionDiagnosticTask(const std::string &name, boost::function< void(T &)> fn)
std_msgs::Duration
::std_msgs::Duration_< std::allocator< void > > Duration
Definition: Duration.h:48
diagnostic_updater::Updater::verbose_
bool verbose_
Definition: eloquent/include/diagnostic_updater/diagnostic_updater.hpp:356
diagnostic_updater::UnwrappedFunctionDiagnosticTask
GenericFunctionDiagnosticTask< diagnostic_msgs::DiagnosticStatus > UnwrappedFunctionDiagnosticTask
Definition: foxy/include/diagnostic_updater/diagnostic_updater.hpp:137
api.setup.name
name
Definition: python/api/setup.py:12
diagnostic_updater::DiagnosticTask::run
virtual void run(diagnostic_updater::DiagnosticStatusWrapper &stat)=0
polar_to_cartesian_pointcloud_ros1.node
node
Definition: polar_to_cartesian_pointcloud_ros1.py:81
diagnostic_updater::Updater::Updater
Updater(ros::NodeHandle h=ros::NodeHandle(), ros::NodeHandle ph=ros::NodeHandle("~"), std::string node_name=ros::this_node::getName())
diagnostic_updater
Author: Blaise Gassend.
diagnostic_updater::Updater::publisher_
ros::Publisher publisher_
Definition: diagnostic_updater.h:583
diagnostic_updater::Updater::period_
double period_
Definition: diagnostic_updater.h:587
diagnostic_updater::Updater::hwid_
std::string hwid_
Definition: eloquent/include/diagnostic_updater/diagnostic_updater.hpp:611
diagnostic_updater::DiagnosticTaskVector::DiagnosticTaskInternal::fn_
TaskFunction fn_
Definition: eloquent/include/diagnostic_updater/diagnostic_updater.hpp:230
diagnostic_updater::TaskFunction
boost::function< void(DiagnosticStatusWrapper &)> TaskFunction
Definition: foxy/include/diagnostic_updater/diagnostic_updater.hpp:60
diagnostic_updater::Updater::setHardwareID
void setHardwareID(const std::string &hwid)
diagnostic_updater::DiagnosticTaskVector::addedTaskCallback
virtual void addedTaskCallback(DiagnosticTaskInternal &)
diagnostic_updater::DiagnosticTaskVector::DiagnosticTaskInternal::DiagnosticTaskInternal
DiagnosticTaskInternal(const std::string name, TaskFunction f)
diagnostic_updater::Updater::update
void update()
diagnostic_updater::FunctionDiagnosticTask
GenericFunctionDiagnosticTask< DiagnosticStatusWrapper > FunctionDiagnosticTask
Definition: foxy/include/diagnostic_updater/diagnostic_updater.hpp:139
diagnostic_updater::Updater::warn_nohwid_done_
bool warn_nohwid_done_
Definition: eloquent/include/diagnostic_updater/diagnostic_updater.hpp:613
sick_scan_xd_api_test.c
c
Definition: sick_scan_xd_api_test.py:445
diagnostic_updater::DiagnosticTaskVector::DiagnosticTaskInternal::run
void run(diagnostic_updater::DiagnosticStatusWrapper &stat) const
diagnostic_updater::DiagnosticTask::getName
const std::string & getName()
diagnostic_updater::Updater::publish
void publish(diagnostic_msgs::DiagnosticStatus &stat)
diagnostic_updater::GenericFunctionDiagnosticTask::name_
const std::string name_
Definition: eloquent/include/diagnostic_updater/diagnostic_updater.hpp:132
diagnostic_updater::CompositeDiagnosticTask::CompositeDiagnosticTask
CompositeDiagnosticTask(const std::string name)
sick_scan_base.h
diagnostic_updater::DiagnosticStatusWrapper
Wrapper for the diagnostic_msgs::msg::DiagnosticStatus message that makes it easier to update.
Definition: eloquent/include/diagnostic_updater/diagnostic_status_wrapper.hpp:68
diagnostic_updater::DiagnosticTaskVector::removeByName
bool removeByName(const std::string name)
diagnostic_updater::DiagnosticTaskVector::addInternal
void addInternal(DiagnosticTaskInternal &task)
diagnostic_updater::DiagnosticTaskVector::tasks_
std::vector< DiagnosticTaskInternal > tasks_
Definition: eloquent/include/diagnostic_updater/diagnostic_updater.hpp:328
diagnostic_updater::GenericFunctionDiagnosticTask::run
virtual void run(DiagnosticStatusWrapper &stat)
diagnostic_updater::CompositeDiagnosticTask::run
virtual void run(DiagnosticStatusWrapper &stat)
roswrap::ok
ROSCPP_DECL bool ok()
Check whether it's time to exit.
Definition: rossimu.cpp:273
diagnostic_updater::DiagnosticTaskVector::getTasks
const std::vector< DiagnosticTaskInternal > & getTasks()
diagnostic_updater::Updater::getPeriod
double getPeriod()
diagnostic_updater::DiagnosticTaskVector::add
void add(const std::string &name, TaskFunction f)
diagnostic_msgs::DiagnosticArray
::diagnostic_msgs::DiagnosticArray_< std::allocator< void > > DiagnosticArray
Definition: DiagnosticArray.h:55
sick_scan_xd_simu.status
def status
Definition: sick_scan_xd_simu.py:139
t
geometry_msgs::TransformStamped t


sick_scan_xd
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:08