Go to the documentation of this file.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
00037 #include "diagnostic_aggregator/generic_analyzer.h"
00038
00039 using namespace diagnostic_aggregator;
00040 using namespace std;
00041
00042 PLUGINLIB_EXPORT_CLASS(diagnostic_aggregator::GenericAnalyzer,
00043 diagnostic_aggregator::Analyzer)
00044
00045
00046 GenericAnalyzer::GenericAnalyzer() { }
00047
00048 bool GenericAnalyzer::init(const string base_path, const ros::NodeHandle &n)
00049 {
00050 string nice_name;
00051 if (!n.getParam("path", nice_name))
00052 {
00053 ROS_ERROR("GenericAnalyzer was not given parameter \"path\". Namepspace: %s",
00054 n.getNamespace().c_str());
00055 return false;
00056 }
00057
00058 XmlRpc::XmlRpcValue find_remove;
00059 if (n.getParam("find_and_remove_prefix", find_remove))
00060 {
00061 vector<string> output;
00062 getParamVals(find_remove, output);
00063 chaff_ = output;
00064 startswith_ = output;
00065 }
00066
00067 XmlRpc::XmlRpcValue removes;
00068 if (n.getParam("remove_prefix", removes))
00069 getParamVals(removes, chaff_);
00070
00071 XmlRpc::XmlRpcValue startswith;
00072 if (n.getParam("startswith", startswith))
00073 getParamVals(startswith, startswith_);
00074
00075 XmlRpc::XmlRpcValue name_val;
00076 if (n.getParam("name", name_val))
00077 getParamVals(name_val, name_);
00078
00079 XmlRpc::XmlRpcValue contains;
00080 if (n.getParam("contains", contains))
00081 getParamVals(contains, contains_);
00082
00083 XmlRpc::XmlRpcValue expected;
00084 if (n.getParam("expected", expected))
00085 {
00086 getParamVals(expected, expected_);
00087 for (unsigned int i = 0; i < expected_.size(); ++i)
00088 {
00089 boost::shared_ptr<StatusItem> item(new StatusItem(expected_[i]));
00090 addItem(expected_[i], item);
00091 }
00092 }
00093
00094 XmlRpc::XmlRpcValue regexes;
00095 if (n.getParam("regex", regexes))
00096 {
00097 vector<string> regex_strs;
00098 getParamVals(regexes, regex_strs);
00099
00100 for (unsigned int i = 0; i < regex_strs.size(); ++i)
00101 {
00102 try
00103 {
00104 boost::regex re(regex_strs[i]);
00105 regex_.push_back(re);
00106 }
00107 catch (boost::regex_error& e)
00108 {
00109 ROS_ERROR("Attempted to make regex from %s. Caught exception, ignoring value. Exception: %s",
00110 regex_strs[i].c_str(), e.what());
00111 }
00112 }
00113 }
00114
00115 if (startswith_.size() == 0 && name_.size() == 0 &&
00116 contains_.size() == 0 && expected_.size() == 0 && regex_.size() == 0)
00117 {
00118 ROS_ERROR("GenericAnalyzer was not initialized with any way of checking diagnostics. Name: %s, namespace: %s", nice_name.c_str(), n.getNamespace().c_str());
00119 return false;
00120 }
00121
00122
00123 for(size_t i=0; i<chaff_.size(); i++) {
00124 chaff_[i] = getOutputName(chaff_[i]);
00125 }
00126
00127 double timeout;
00128 int num_items_expected;
00129 bool discard_stale;
00130 n.param("timeout", timeout, 5.0);
00131 n.param("num_items", num_items_expected, -1);
00132 n.param("discard_stale", discard_stale, false);
00133
00134 string my_path;
00135 if (base_path == "/")
00136 my_path = nice_name;
00137 else
00138 my_path = base_path + "/" + nice_name;
00139
00140 if (my_path.find("/") != 0)
00141 my_path = "/" + my_path;
00142
00143 return GenericAnalyzerBase::init(my_path, nice_name,
00144 timeout, num_items_expected, discard_stale);
00145 }
00146
00147 GenericAnalyzer::~GenericAnalyzer() { }
00148
00149
00150 bool GenericAnalyzer::match(const string name)
00151 {
00152 boost::cmatch what;
00153 for (unsigned int i = 0; i < regex_.size(); ++i)
00154 {
00155 if (boost::regex_match(name.c_str(), what, regex_[i]))
00156 return true;
00157 }
00158
00159 for (unsigned int i = 0; i < expected_.size(); ++i)
00160 {
00161 if (name == expected_[i])
00162 return true;
00163 }
00164
00165 for (unsigned int i = 0; i < name_.size(); ++i)
00166 {
00167 if (name == name_[i])
00168 return true;
00169 }
00170
00171 for (unsigned int i = 0; i < startswith_.size(); ++i)
00172 {
00173 if (name.find(startswith_[i]) == 0)
00174 return true;
00175 }
00176
00177 for (unsigned int i = 0; i < contains_.size(); ++i)
00178 {
00179 if (name.find(contains_[i]) != string::npos)
00180 return true;
00181 }
00182
00183 return false;
00184 }
00185
00186 vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> > GenericAnalyzer::report()
00187 {
00188 vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> > processed = GenericAnalyzerBase::report();
00189
00190
00191 vector<string> expected_names_missing;
00192 bool has_name = false;
00193
00194 for (unsigned int i = 0; i < expected_.size(); ++i)
00195 {
00196 has_name = false;
00197 for (unsigned int j = 0; j < processed.size(); ++j)
00198 {
00199 size_t last_slash = processed[j]->name.rfind("/");
00200 string nice_name = processed[j]->name.substr(last_slash + 1);
00201 if (nice_name == expected_[i] || nice_name == getOutputName(expected_[i]))
00202 {
00203 has_name = true;
00204 break;
00205 }
00206
00207
00208 for (unsigned int k = 0; k < chaff_.size(); ++k)
00209 {
00210 if (nice_name == removeLeadingNameChaff(expected_[i], chaff_[k]))
00211 {
00212 has_name = true;
00213 break;
00214 }
00215 }
00216
00217 }
00218 if (!has_name)
00219 expected_names_missing.push_back(expected_[i]);
00220 }
00221
00222
00223 bool all_stale = true;
00224 for (unsigned int j = 0; j < processed.size(); ++j)
00225 {
00226 if (processed[j]->level != 3)
00227 all_stale = false;
00228 }
00229
00230
00231 for (unsigned int i = 0; i < expected_names_missing.size(); ++i)
00232 {
00233 boost::shared_ptr<StatusItem> item(new StatusItem(expected_names_missing[i]));
00234 processed.push_back(item->toStatusMsg(path_, true));
00235 }
00236
00237 for (unsigned int j = 0; j < processed.size(); ++j)
00238 {
00239
00240 for (unsigned int i = 0; i < chaff_.size(); ++i)
00241 processed[j]->name = removeLeadingNameChaff(processed[j]->name, chaff_[i]);
00242
00243
00244 if (expected_names_missing.size() > 0 && processed[j]->name == path_)
00245 {
00246 if (!all_stale)
00247 {
00248 processed[j]->level = 2;
00249 processed[j]->message = "Error";
00250 }
00251 else
00252 {
00253 processed[j]->level = 3;
00254 processed[j]->message = "All Stale";
00255 }
00256
00257
00258 for (unsigned int k = 0; k < expected_names_missing.size(); ++k)
00259 {
00260 diagnostic_msgs::KeyValue kv;
00261 kv.key = expected_names_missing[k];
00262 kv.value = "Missing";
00263 processed[j]->values.push_back(kv);
00264 }
00265 }
00266 }
00267
00268 return processed;
00269 }