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_AGGREGATOR_GENERIC_ANALYZER_H
00040 #define DIAGNOSTIC_AGGREGATOR_GENERIC_ANALYZER_H
00041
00042 #include <map>
00043 #include <ros/ros.h>
00044 #include <vector>
00045 #include <string>
00046 #include <sstream>
00047 #include <boost/shared_ptr.hpp>
00048 #include <boost/regex.hpp>
00049 #include <pluginlib/class_list_macros.h>
00050 #include "diagnostic_msgs/DiagnosticStatus.h"
00051 #include "diagnostic_msgs/KeyValue.h"
00052 #include "diagnostic_aggregator/analyzer.h"
00053 #include "diagnostic_aggregator/status_item.h"
00054 #include "diagnostic_aggregator/generic_analyzer_base.h"
00055 #include "XmlRpcValue.h"
00056
00057 namespace diagnostic_aggregator {
00058
00065 inline bool getParamVals(XmlRpc::XmlRpcValue param, std::vector<std::string> &output)
00066 {
00067 XmlRpc::XmlRpcValue::Type type = param.getType();
00068 if (type == XmlRpc::XmlRpcValue::TypeString)
00069 {
00070 std::string find = param;
00071 output.push_back(find);
00072 return true;
00073 }
00074 else if (type == XmlRpc::XmlRpcValue::TypeArray)
00075 {
00076 for (int i = 0; i < param.size(); ++i)
00077 {
00078 if (param[i].getType() != XmlRpc::XmlRpcValue::TypeString)
00079 {
00080 ROS_ERROR("Parameter is not a list of strings, found non-string value. XmlRpcValue: %s", param.toXml().c_str());
00081 output.clear();
00082 return false;
00083 }
00084
00085 std::string find = param[i];
00086 output.push_back(find);
00087 }
00088 return true;
00089 }
00090
00091 ROS_ERROR("Parameter not a list or string, unable to return values. XmlRpcValue:s %s", param.toXml().c_str());
00092 output.clear();
00093 return false;
00094 }
00095
00096
00198 class GenericAnalyzer : public GenericAnalyzerBase
00199 {
00200 public:
00204 GenericAnalyzer();
00205
00206 virtual ~GenericAnalyzer();
00207
00208
00216 bool init(const std::string base_path, const ros::NodeHandle &n);
00217
00223 virtual std::vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> > report();
00224
00229 virtual bool match(const std::string name);
00230
00231 private:
00232 std::vector<std::string> chaff_;
00233 std::vector<std::string> expected_;
00234 std::vector<std::string> startswith_;
00235 std::vector<std::string> contains_;
00236 std::vector<std::string> name_;
00237 std::vector<boost::regex> regex_;
00239 };
00240
00241 }
00242 #endif //DIAGNOSTIC_AGGREGATOR_GENERIC_ANALYZER_H