Public Member Functions | Private Attributes | List of all members
diagnostic_aggregator::OtherAnalyzer Class Reference

#include <other_analyzer.h>

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

Public Member Functions

bool init (const std::string base_path, const ros::NodeHandle &n)
 Analyzer is initialized with base path and namespace. More...
 
bool init (std::string path)
 
bool match (std::string name)
 Match function isn't implemented by GenericAnalyzerBase. More...
 
 OtherAnalyzer (bool other_as_errors=false)
 Default constructor. OtherAnalyzer isn't loaded by pluginlib. More...
 
std::vector< boost::shared_ptr< diagnostic_msgs::DiagnosticStatus > > report ()
 Reports current state, returns vector of formatted status messages. More...
 
 ~OtherAnalyzer ()
 
- Public Member Functions inherited from diagnostic_aggregator::GenericAnalyzerBase
virtual bool analyze (const boost::shared_ptr< StatusItem > item)
 Update state with new StatusItem. More...
 
 GenericAnalyzerBase ()
 
virtual std::string getName () const
 Returns nice name (ex: "Power System") More...
 
virtual std::string getPath () const
 Returns full prefix (ex: "/Robot/Power System") More...
 
bool init (const std::string path, const std::string nice_name, double timeout=-1.0, int num_items_expected=-1, bool discard_stale=false)
 
virtual ~GenericAnalyzerBase ()
 
- Public Member Functions inherited from diagnostic_aggregator::Analyzer
 Analyzer ()
 Default constructor, called by pluginlib. More...
 
virtual ~Analyzer ()
 

Private Attributes

bool other_as_errors_
 

Additional Inherited Members

- Protected Member Functions inherited from diagnostic_aggregator::GenericAnalyzerBase
void addItem (std::string name, boost::shared_ptr< StatusItem > item)
 Subclasses can add items to analyze. More...
 
- Protected Attributes inherited from diagnostic_aggregator::GenericAnalyzerBase
std::string nice_name_
 
int num_items_expected_
 
std::string path_
 
double timeout_
 

Detailed Description

Definition at line 92 of file other_analyzer.h.

Constructor & Destructor Documentation

◆ OtherAnalyzer()

diagnostic_aggregator::OtherAnalyzer::OtherAnalyzer ( bool  other_as_errors = false)
inlineexplicit

Default constructor. OtherAnalyzer isn't loaded by pluginlib.

Definition at line 130 of file other_analyzer.h.

◆ ~OtherAnalyzer()

diagnostic_aggregator::OtherAnalyzer::~OtherAnalyzer ( )
inline

Definition at line 134 of file other_analyzer.h.

Member Function Documentation

◆ init() [1/2]

bool diagnostic_aggregator::OtherAnalyzer::init ( const std::string  base_path,
const ros::NodeHandle n 
)
inlinevirtual

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.

Implements diagnostic_aggregator::GenericAnalyzerBase.

Definition at line 151 of file other_analyzer.h.

◆ init() [2/2]

bool diagnostic_aggregator::OtherAnalyzer::init ( std::string  path)
inline

Definition at line 141 of file other_analyzer.h.

◆ match()

bool diagnostic_aggregator::OtherAnalyzer::match ( std::string  name)
inlinevirtual

Match function isn't implemented by GenericAnalyzerBase.

Implements diagnostic_aggregator::GenericAnalyzerBase.

Definition at line 162 of file other_analyzer.h.

◆ report()

std::vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> > diagnostic_aggregator::OtherAnalyzer::report ( )
inlinevirtual

Reports current state, returns vector of formatted status messages.

Returns
Vector of DiagnosticStatus messages. They must have the correct prefix for all names.

Reimplemented from diagnostic_aggregator::GenericAnalyzerBase.

Definition at line 168 of file other_analyzer.h.

Member Data Documentation

◆ other_as_errors_

bool diagnostic_aggregator::OtherAnalyzer::other_as_errors_
private

Definition at line 196 of file other_analyzer.h.


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


diagnostic_aggregator
Author(s): Kevin Watts, Brice Rebsamen
autogenerated on Tue Nov 15 2022 03:17:13