Public Member Functions
diagnostic_aggregator::Analyzer Class Reference

Base class of all Analyzers. Loaded by aggregator. More...

#include <analyzer.h>

Inheritance diagram for diagnostic_aggregator::Analyzer:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual bool analyze (const boost::shared_ptr< StatusItem > item)=0
 Returns true if analyzer will analyze this name.
 Analyzer ()
 Default constructor, called by pluginlib.
virtual std::string getName () const =0
 Returns nice name for display. (ex: 'Sensors')
virtual std::string getPath () const =0
 Returns full prefix of analyzer. (ex: '/Robot/Sensors')
virtual bool init (const std::string base_path, const ros::NodeHandle &n)=0
 Analyzer is initialized with base path and namespace.
virtual bool match (const std::string name)=0
 Returns true if analyzer will handle this item.
virtual std::vector
< boost::shared_ptr
< diagnostic_msgs::DiagnosticStatus > > 
report ()=0
 Analysis function, output processed data.
virtual ~Analyzer ()

Detailed Description

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.

Definition at line 85 of file analyzer.h.


Constructor & Destructor Documentation

Default constructor, called by pluginlib.

Definition at line 91 of file analyzer.h.

virtual diagnostic_aggregator::Analyzer::~Analyzer ( ) [inline, virtual]

Definition at line 93 of file analyzer.h.


Member Function Documentation

virtual bool diagnostic_aggregator::Analyzer::analyze ( const boost::shared_ptr< StatusItem item) [pure virtual]

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.

Implemented in diagnostic_aggregator::AnalyzerGroup, diagnostic_aggregator::GenericAnalyzerBase, and diagnostic_aggregator::IgnoreAnalyzer.

virtual std::string diagnostic_aggregator::Analyzer::getName ( ) const [pure virtual]
virtual std::string diagnostic_aggregator::Analyzer::getPath ( ) const [pure virtual]

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

Implemented in diagnostic_aggregator::GenericAnalyzerBase, diagnostic_aggregator::AnalyzerGroup, and diagnostic_aggregator::IgnoreAnalyzer.

virtual bool diagnostic_aggregator::Analyzer::init ( const std::string  base_path,
const ros::NodeHandle n 
) [pure virtual]

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 "/".
n: NodeHandle with proper private namespace for analyzer.

Implemented in diagnostic_aggregator::GenericAnalyzer, diagnostic_aggregator::AnalyzerGroup, diagnostic_aggregator::OtherAnalyzer, diagnostic_aggregator::GenericAnalyzerBase, and diagnostic_aggregator::IgnoreAnalyzer.

virtual bool diagnostic_aggregator::Analyzer::match ( const std::string  name) [pure virtual]

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.

Implemented in diagnostic_aggregator::GenericAnalyzer, diagnostic_aggregator::GenericAnalyzerBase, diagnostic_aggregator::AnalyzerGroup, diagnostic_aggregator::OtherAnalyzer, and diagnostic_aggregator::IgnoreAnalyzer.

virtual std::vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> > diagnostic_aggregator::Analyzer::report ( ) [pure virtual]

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

Implemented in diagnostic_aggregator::GenericAnalyzer, diagnostic_aggregator::AnalyzerGroup, diagnostic_aggregator::GenericAnalyzerBase, diagnostic_aggregator::OtherAnalyzer, diagnostic_aggregator::IgnoreAnalyzer, and diagnostic_aggregator::DiscardAnalyzer.


The documentation for this class was generated from the following file:


diagnostic_aggregator
Author(s): Kevin Watts, Brice Rebsamen
autogenerated on Mon Aug 14 2017 02:51:54