39 #ifndef DIAGNOSTIC_ANALYZER_GROUP_H 40 #define DIAGNOSTIC_ANALYZER_GROUP_H 47 #include <diagnostic_msgs/DiagnosticStatus.h> 48 #include <diagnostic_msgs/KeyValue.h> 50 #include <boost/shared_ptr.hpp> 152 virtual std::vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> >
report();
176 std::map<const std::string, std::vector<bool> >
matched_;
182 #endif //DIAGNOSTIC_ANALYZER_GROUP_H virtual std::vector< boost::shared_ptr< diagnostic_msgs::DiagnosticStatus > > report()
The processed output is the combined output of the sub-analyzers, and the top level status...
virtual bool addAnalyzer(boost::shared_ptr< Analyzer > &analyzer)
Add an analyzer to this analyzerGroup.
pluginlib::ClassLoader< Analyzer > analyzer_loader_
Loads Analyzer plugins in "analyzers" namespace.
virtual std::string getPath() const
Returns full prefix of analyzer. (ex: '/Robot/Sensors')
std::map< const std::string, std::vector< bool > > matched_
Base class of all Analyzers. Loaded by aggregator.
virtual bool analyze(const boost::shared_ptr< StatusItem > item)
Analyze returns true if any sub-analyzers will analyze an item.
Allows analyzers to be grouped together, or used as sub-analyzers.
virtual bool init(const std::string base_path, const ros::NodeHandle &n)
Initialized with base path and namespace.
void resetMatches()
Clear match arrays. Used when analyzers are added or removed.
virtual std::string getName() const
Returns nice name for display. (ex: 'Sensors')
virtual bool removeAnalyzer(boost::shared_ptr< Analyzer > &analyzer)
Remove an analyzer from this analyzerGroup.
virtual bool match(const std::string name)
Match returns true if any sub-analyzers match an item.
std::vector< boost::shared_ptr< Analyzer > > analyzers_
std::vector< boost::shared_ptr< StatusItem > > aux_items_
These items store errors, if any, for analyzers that failed to initialize or load.