36 #ifndef DIAGNOSTIC_UPDATER__DIAGNOSTIC_UPDATER_HPP_
37 #define DIAGNOSTIC_UPDATER__DIAGNOSTIC_UPDATER_HPP_
45 #include "builtin_interfaces/msg/time.hpp"
47 #include "diagnostic_msgs/msg/diagnostic_array.hpp"
48 #include "diagnostic_msgs/msg/diagnostic_status.hpp"
50 #include "diagnostic_updater/diagnostic_status_wrapper.hpp"
54 #include "rclcpp/create_timer.hpp"
55 #include "rclcpp/rclcpp.hpp"
60 typedef std::function<void (DiagnosticStatusWrapper &)>
TaskFunction;
98 const std::string
name_;
113 class GenericFunctionDiagnosticTask :
public DiagnosticTask
125 const std::string &
name,
126 std::function<
void(T &)> fn)
129 virtual void run(DiagnosticStatusWrapper & stat) {
fn_(stat);}
132 const std::string
name_;
136 typedef GenericFunctionDiagnosticTask<diagnostic_msgs::msg::DiagnosticStatus>
138 typedef GenericFunctionDiagnosticTask<DiagnosticStatusWrapper>
153 class CompositeDiagnosticTask :
public DiagnosticTask
165 virtual void run(DiagnosticStatusWrapper & stat)
167 DiagnosticStatusWrapper combined_summary;
168 DiagnosticStatusWrapper original_summary;
170 original_summary.summary(stat);
172 for (std::vector<DiagnosticTask *>::iterator i =
tasks_.begin();
176 stat.summary(original_summary);
180 combined_summary.mergeSummary(stat);
184 stat.summary(combined_summary);
196 std::vector<DiagnosticTask *>
tasks_;
207 class DiagnosticTaskVector
214 class DiagnosticTaskInternal
238 const std::vector<DiagnosticTaskInternal> &
getTasks() {
return tasks_;}
241 virtual ~DiagnosticTaskVector() {}
256 DiagnosticTaskInternal int_task(
name,
f);
267 void add(DiagnosticTask & task)
270 add(task.getName(),
f);
288 const std::string
name, T *
c,
291 DiagnosticTaskInternal int_task(
name, std::bind(
f,
c, std::placeholders::_1));
307 std::unique_lock<std::mutex> lock(
lock_);
308 for (std::vector<DiagnosticTaskInternal>::iterator iter =
tasks_.begin();
309 iter !=
tasks_.end(); iter++)
311 if (iter->getName() ==
name) {
328 std::vector<DiagnosticTaskInternal>
tasks_;
336 std::unique_lock<std::mutex> lock(
lock_);
353 class Updater :
public DiagnosticTaskVector
366 template<
class NodeT>
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(),
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,
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)),
390 rclcpp::create_publisher<diagnostic_msgs::msg::DiagnosticArray>(
391 topics_interface,
"/diagnostics", 1)),
392 logger_(logging_interface->get_logger()),
396 period = parameters_interface->declare_parameter(
397 "diagnostic_updater.period", rclcpp::ParameterValue(period)).get<
double>();
420 void setPeriod(rcl_duration_value_t period)
428 void setPeriod(
double period)
430 setPeriod(
static_cast<rcl_duration_value_t
>(period * 1e9));
453 std::vector<diagnostic_msgs::msg::DiagnosticStatus> status_vec;
455 const std::vector<DiagnosticTaskInternal> & tasks =
getTasks();
456 for (std::vector<DiagnosticTaskInternal>::const_iterator iter =
458 iter != tasks.end(); iter++)
462 status.name = iter->getName();
465 status_vec.push_back(
status);
474 const int kBufferSize = 1000;
475 char buff[kBufferSize];
476 va_start(va, format);
477 if (vsnprintf(buff, kBufferSize, format, va) >= kBufferSize) {
478 RCLCPP_DEBUG(logger_,
"Really long string in diagnostic_updater::setHardwareIDf.");
480 hwid_ = std::string(buff);
489 update_timer_ = rclcpp::create_timer(
504 bool warn_nohwid =
hwid_.empty();
506 std::vector<diagnostic_msgs::msg::DiagnosticStatus> status_vec;
508 std::unique_lock<std::mutex> lock(
510 const std::vector<DiagnosticTaskInternal> & tasks =
getTasks();
511 for (std::vector<DiagnosticTaskInternal>::const_iterator iter =
513 iter != tasks.end(); iter++)
517 status.name = iter->getName();
519 status.message =
"No message was set";
524 status_vec.push_back(
status);
532 logger_,
"Non-zero diagnostic status. Name: '%s', status %i: '%s'",
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);
568 std::vector<diagnostic_msgs::msg::DiagnosticStatus> status_vec;
569 status_vec.push_back(stat);
576 void publish(std::vector<diagnostic_msgs::msg::DiagnosticStatus> & status_vec)
578 for (std::vector<diagnostic_msgs::msg::DiagnosticStatus>::iterator iter =
580 iter != status_vec.end(); iter++)
582 iter->name =
node_name_ + std::string(
": ") + iter->name;
585 msg.status = status_vec;
586 msg.header.stamp = rclcpp::Clock().now();
596 DiagnosticStatusWrapper stat;
597 stat.name = task.getName();
598 stat.summary(0,
"Node starting up");
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_;
616 #endif // DIAGNOSTIC_UPDATER__DIAGNOSTIC_UPDATER_HPP_