Class Updater

Inheritance Relationships

Base Type

Class Documentation

class Updater : public diagnostic_updater::DiagnosticTaskVector

Manages a list of diagnostic tasks, and calls them in a rate-limited manner.

This class manages a list of diagnostic tasks. Its update function should be called frequently. At some predetermined rate, the update function will cause all the diagnostic tasks to run, and will collate and publish the resulting diagnostics. The publication rate is determined by the “~/diagnostic_updater.period” ros2 parameter. The force_update function can always be triggered async to the period interval.

Public Functions

template<class NodeT>
inline explicit Updater(NodeT node, double period = 1.0)

Constructs an updater class.

Note

The given period value not being used if the diagnostic_updater.period ros2 parameter was set previously.

Parameters:
  • node – Node pointer to set up diagnostics

  • period – Value in seconds to set the update period

inline Updater(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface> base_interface, std::shared_ptr<rclcpp::node_interfaces::NodeClockInterface> clock_interface, std::shared_ptr<rclcpp::node_interfaces::NodeLoggingInterface> logging_interface, std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface> parameters_interface, std::shared_ptr<rclcpp::node_interfaces::NodeTimersInterface> timers_interface, std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface> topics_interface, double period = 1.0)
inline auto getPeriod() const

Returns the interval between updates.

inline void setPeriod(rclcpp::Duration period)

Sets the period as a rclcpp::Duration.

inline void setPeriod(double period)

Sets the period given a value in seconds.

inline void force_update()

Forces to send out an update for all known DiagnosticStatus.

inline void broadcast(unsigned char lvl, const std::string msg)

Output a message on all the known DiagnosticStatus.

Useful if something drastic is happening such as shutdown or a self-test.

Parameters:
  • lvl – Level of the diagnostic being output.

  • msg – Status message to output.

inline void setHardwareIDf(const char *format, ...)
inline void setHardwareID(const std::string &hwid)

Public Members

bool verbose_