GenericAnalyzerBase is the base class for GenericAnalyzer and OtherAnalyzer. More...
#include <generic_analyzer_base.h>
Public Member Functions | |
virtual bool | analyze (const boost::shared_ptr< StatusItem > item) |
Update state with new StatusItem. | |
GenericAnalyzerBase () | |
virtual std::string | getName () const |
Returns nice name (ex: "Power System") | |
virtual std::string | getPath () const |
Returns full prefix (ex: "/Robot/Power System") | |
bool | init (const std::string path, const ros::NodeHandle &n)=0 |
Analyzer is initialized with base path and namespace. | |
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 bool | match (const std::string name)=0 |
Match function isn't implemented by GenericAnalyzerBase. | |
virtual std::vector < boost::shared_ptr < diagnostic_msgs::DiagnosticStatus > > | report () |
Reports current state, returns vector of formatted status messages. | |
virtual | ~GenericAnalyzerBase () |
Protected Member Functions | |
void | addItem (std::string name, boost::shared_ptr< StatusItem > item) |
Subclasses can add items to analyze. | |
Protected Attributes | |
std::string | nice_name_ |
int | num_items_expected_ |
std::string | path_ |
double | timeout_ |
Private Attributes | |
bool | discard_stale_ |
bool | has_initialized_ |
bool | has_warned_ |
std::map< std::string, boost::shared_ptr< StatusItem > > | items_ |
Stores items by name. State of analyzer. |
GenericAnalyzerBase is the base class for GenericAnalyzer and OtherAnalyzer.
GenericAnalyzerBase contains the getPath(), getName(), analyze() and report() functions of the Generic and Other Analyzers. It is a virtual class, and cannot be instantiated or loaded as a plugin. Subclasses are responsible for implementing the init() and match() functions.
The GenericAnalyzerBase holds the state of the analyzer, and tracks if items are stale, and if the user has the correct number of items.
Definition at line 65 of file generic_analyzer_base.h.
Definition at line 68 of file generic_analyzer_base.h.
virtual diagnostic_aggregator::GenericAnalyzerBase::~GenericAnalyzerBase | ( | ) | [inline, virtual] |
Definition at line 73 of file generic_analyzer_base.h.
void diagnostic_aggregator::GenericAnalyzerBase::addItem | ( | std::string | name, |
boost::shared_ptr< StatusItem > | item | ||
) | [inline, protected] |
Subclasses can add items to analyze.
Definition at line 247 of file generic_analyzer_base.h.
virtual bool diagnostic_aggregator::GenericAnalyzerBase::analyze | ( | const boost::shared_ptr< StatusItem > | item | ) | [inline, virtual] |
Update state with new StatusItem.
Implements diagnostic_aggregator::Analyzer.
Definition at line 108 of file generic_analyzer_base.h.
virtual std::string diagnostic_aggregator::GenericAnalyzerBase::getName | ( | ) | const [inline, virtual] |
Returns nice name (ex: "Power System")
Implements diagnostic_aggregator::Analyzer.
Definition at line 235 of file generic_analyzer_base.h.
virtual std::string diagnostic_aggregator::GenericAnalyzerBase::getPath | ( | ) | const [inline, virtual] |
Returns full prefix (ex: "/Robot/Power System")
Implements diagnostic_aggregator::Analyzer.
Definition at line 230 of file generic_analyzer_base.h.
bool diagnostic_aggregator::GenericAnalyzerBase::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.
base_path | : Common to all analyzers, prepended to all processed names. Starts with "/". |
n | : NodeHandle with proper private namespace for analyzer. |
Implements diagnostic_aggregator::Analyzer.
Implemented in diagnostic_aggregator::GenericAnalyzer, and diagnostic_aggregator::OtherAnalyzer.
bool diagnostic_aggregator::GenericAnalyzerBase::init | ( | const std::string | path, |
const std::string | nice_name, | ||
double | timeout = -1.0 , |
||
int | num_items_expected = -1 , |
||
bool | discard_stale = false |
||
) | [inline] |
Definition at line 85 of file generic_analyzer_base.h.
virtual bool diagnostic_aggregator::GenericAnalyzerBase::match | ( | const std::string | name | ) | [pure virtual] |
Match function isn't implemented by GenericAnalyzerBase.
Implements diagnostic_aggregator::Analyzer.
Implemented in diagnostic_aggregator::GenericAnalyzer, and diagnostic_aggregator::OtherAnalyzer.
virtual std::vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> > diagnostic_aggregator::GenericAnalyzerBase::report | ( | ) | [inline, virtual] |
Reports current state, returns vector of formatted status messages.
Implements diagnostic_aggregator::Analyzer.
Reimplemented in diagnostic_aggregator::GenericAnalyzer, diagnostic_aggregator::OtherAnalyzer, and diagnostic_aggregator::DiscardAnalyzer.
Definition at line 129 of file generic_analyzer_base.h.
bool diagnostic_aggregator::GenericAnalyzerBase::discard_stale_ [private] |
Definition at line 255 of file generic_analyzer_base.h.
bool diagnostic_aggregator::GenericAnalyzerBase::has_initialized_ [private] |
Definition at line 255 of file generic_analyzer_base.h.
bool diagnostic_aggregator::GenericAnalyzerBase::has_warned_ [private] |
Definition at line 255 of file generic_analyzer_base.h.
std::map<std::string, boost::shared_ptr<StatusItem> > diagnostic_aggregator::GenericAnalyzerBase::items_ [private] |
Stores items by name. State of analyzer.
Definition at line 253 of file generic_analyzer_base.h.
std::string diagnostic_aggregator::GenericAnalyzerBase::nice_name_ [protected] |
Definition at line 238 of file generic_analyzer_base.h.
int diagnostic_aggregator::GenericAnalyzerBase::num_items_expected_ [protected] |
Definition at line 242 of file generic_analyzer_base.h.
std::string diagnostic_aggregator::GenericAnalyzerBase::path_ [protected] |
Definition at line 239 of file generic_analyzer_base.h.
double diagnostic_aggregator::GenericAnalyzerBase::timeout_ [protected] |
Definition at line 241 of file generic_analyzer_base.h.