#include <other_analyzer.h>
Public Member Functions | |
bool | init (std::string path) |
bool | init (const std::string base_path, const ros::NodeHandle &n) |
Analyzer is initialized with base path and namespace. | |
bool | match (std::string name) |
Match function isn't implemented by GenericAnalyzerBase. | |
OtherAnalyzer (bool other_as_errors=false) | |
Default constructor. OtherAnalyzer isn't loaded by pluginlib. | |
std::vector< boost::shared_ptr < diagnostic_msgs::DiagnosticStatus > > | report () |
Reports current state, returns vector of formatted status messages. | |
~OtherAnalyzer () | |
Private Attributes | |
bool | other_as_errors_ |
Definition at line 60 of file other_analyzer.h.
diagnostic_aggregator::OtherAnalyzer::OtherAnalyzer | ( | bool | other_as_errors = false | ) | [inline, explicit] |
Default constructor. OtherAnalyzer isn't loaded by pluginlib.
Definition at line 66 of file other_analyzer.h.
diagnostic_aggregator::OtherAnalyzer::~OtherAnalyzer | ( | ) | [inline] |
Definition at line 70 of file other_analyzer.h.
bool diagnostic_aggregator::OtherAnalyzer::init | ( | std::string | path | ) | [inline] |
Definition at line 77 of file other_analyzer.h.
bool diagnostic_aggregator::OtherAnalyzer::init | ( | const std::string | base_path, |
const ros::NodeHandle & | n | ||
) | [inline, 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.
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 87 of file other_analyzer.h.
bool diagnostic_aggregator::OtherAnalyzer::match | ( | std::string | name | ) | [inline, virtual] |
Match function isn't implemented by GenericAnalyzerBase.
Implements diagnostic_aggregator::GenericAnalyzerBase.
Definition at line 98 of file other_analyzer.h.
std::vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> > diagnostic_aggregator::OtherAnalyzer::report | ( | ) | [inline, virtual] |
Reports current state, returns vector of formatted status messages.
Reimplemented from diagnostic_aggregator::GenericAnalyzerBase.
Definition at line 104 of file other_analyzer.h.
bool diagnostic_aggregator::OtherAnalyzer::other_as_errors_ [private] |
Definition at line 132 of file other_analyzer.h.