#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. More... | |
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_ |
Definition at line 60 of file other_analyzer.h.
|
inlineexplicit |
Default constructor. OtherAnalyzer isn't loaded by pluginlib.
Definition at line 66 of file other_analyzer.h.
|
inline |
Definition at line 70 of file other_analyzer.h.
|
inline |
Definition at line 77 of file other_analyzer.h.
|
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.
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.
|
inlinevirtual |
Match function isn't implemented by GenericAnalyzerBase.
Implements diagnostic_aggregator::GenericAnalyzerBase.
Definition at line 98 of file other_analyzer.h.
|
inlinevirtual |
Reports current state, returns vector of formatted status messages.
Reimplemented from diagnostic_aggregator::GenericAnalyzerBase.
Definition at line 104 of file other_analyzer.h.
|
private |
Definition at line 132 of file other_analyzer.h.