Class Analyzer

Inheritance Relationships

Derived Types

Class Documentation

class Analyzer

Base class of all Analyzers. Loaded by aggregator.

Base class, for all Analyzers loaded by pluginlib. All analyzers must implement these functions: init, match, analyze, report, getPath and getName.

Analyzers must output their data in a vector of DiagnosticStatus messages when the report() function is called. Each DiagnosticStatus message name should be prepended by the path of the Analyzer. The path is “BASE_PATH/MY_PATH” for each analyzer. For example:

EtherCAT Device (head_pan_motor)
EtherCAT Device (head_tilt_motor)
---
PATH/EtherCAT Device (head_pan_motor)
PATH/EtherCAT Device (head_tilt_motor)
PATH/EtherCAT Devices
 *
Analyzers generally also output another DiagnosticStatus message for the “header”, with the name BASE_PATH/MY_PATH, as in the example above (“PATH/EtherCAT Devices”).

For each new DiagnosticStatus name recieved, the analyzer will be asked whether it wants view the message using “match(string name)”. If the analyzer wants to view the message, all future messages with that name will be given to the analyzer, using “analyze(item)”.

If an analyzer is given a message to analyze, it should return true only if it will report that status value. For example, an Analyzer may look at all the messages for robots motors and power, but will only report messages on motors. This allows Analyzers to use data from other sections of the robot in reporting data.

Since the match() function is called only when new DiagnosticStatus names arrive, the analyzers are not allowed to change which messages they want to look at.

Subclassed by diagnostic_aggregator::AnalyzerGroup, diagnostic_aggregator::IgnoreAnalyzer

Public Functions

inline Analyzer()

Default constructor, called by pluginlib.

inline virtual ~Analyzer()
virtual DIAGNOSTIC_AGGREGATOR_PUBLIC bool init (const std::string &base_path, const std::string &breadcrumb, const rclcpp::Node::SharedPtr node)=0

Analyzer is initialized with base path and namespace.

The Analyzer initialized with parameters in its given namespace. The “base_path” is common to all analyzers, and needs to be prepended to all DiagnosticStatus names.

Parameters:
  • base_path – : Common to all analyzers, prepended to all processed names. Starts with “/”.

  • breadcrumb – : Prefix for parameter getter.

  • n – : NodeHandle with proper private namespace for analyzer.

virtual DIAGNOSTIC_AGGREGATOR_PUBLIC bool match (const std::string &name)=0

Returns true if analyzer will handle this item.

Match is called once for each new status name, so this return value cannot change with time.

virtual DIAGNOSTIC_AGGREGATOR_PUBLIC bool analyze (const std::shared_ptr< StatusItem > item)=0

Returns true if analyzer will analyze this name.

This is called with every new item that an analyzer matches. Analyzers should only return “true” if they will report the value of this item. If it is only looking at an item, it should return false.

virtual DIAGNOSTIC_AGGREGATOR_PUBLIC std::vector< std::shared_ptr< diagnostic_msgs::msg::DiagnosticStatus > > report ()=0

Analysis function, output processed data.

report is called at 1Hz intervals. Analyzers should return a vector of processed DiagnosticStatus messages.

Returns:

The array of DiagnosticStatus messages must have proper names, with prefixes prepended

virtual DIAGNOSTIC_AGGREGATOR_PUBLIC std::string getPath () const =0

Returns full prefix of analyzer. (ex: ‘/Robot/Sensors’)

virtual DIAGNOSTIC_AGGREGATOR_PUBLIC std::string getName () const =0

Returns nice name for display. (ex: ‘Sensors’)

Protected Attributes

rclcpp::Clock::SharedPtr clock_