00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00039 #ifndef DIAGNOSTIC_ANALYZER_GROUP_H
00040 #define DIAGNOSTIC_ANALYZER_GROUP_H
00041
00042 #include <map>
00043 #include <vector>
00044 #include <string>
00045 #include <ros/ros.h>
00046 #include <diagnostic_msgs/DiagnosticStatus.h>
00047 #include <diagnostic_msgs/KeyValue.h>
00048 #include "diagnostic_aggregator/status_item.h"
00049 #include <boost/shared_ptr.hpp>
00050 #include "XmlRpcValue.h"
00051 #include "diagnostic_aggregator/analyzer.h"
00052 #include "diagnostic_aggregator/status_item.h"
00053 #include "pluginlib/class_loader.h"
00054 #include "pluginlib/class_list_macros.h"
00055
00056 namespace diagnostic_aggregator {
00057
00109 class AnalyzerGroup : public Analyzer
00110 {
00111 public:
00112 AnalyzerGroup();
00113
00114 virtual ~AnalyzerGroup();
00115
00121 virtual bool init(const std::string base_path, const ros::NodeHandle &n);
00122
00126 virtual bool match(const std::string name);
00127
00131 virtual bool analyze(const boost::shared_ptr<StatusItem> item);
00132
00136 virtual std::vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> > report();
00137
00138 virtual std::string getPath() const { return path_; }
00139
00140 virtual std::string getName() const { return nice_name_; }
00141
00142 private:
00143 std::string path_, nice_name_;
00144
00148 pluginlib::ClassLoader<Analyzer> analyzer_loader_;
00149
00153 std::vector<boost::shared_ptr<StatusItem> > aux_items_;
00154
00155 std::vector<Analyzer*> analyzers_;
00156
00157
00158
00159
00160 std::map<const std::string, std::vector<bool> > matched_;
00161
00162 };
00163
00164 }
00165
00166 #endif //DIAGNOSTIC_ANALYZER_GROUP_H