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/analyzer_group.h>
00038
00039 using namespace std;
00040 using namespace diagnostic_aggregator;
00041
00042 PLUGINLIB_EXPORT_CLASS(diagnostic_aggregator::AnalyzerGroup,
00043 diagnostic_aggregator::Analyzer)
00044
00045 AnalyzerGroup::AnalyzerGroup() :
00046 path_(""),
00047 nice_name_(""),
00048 analyzer_loader_("diagnostic_aggregator", "diagnostic_aggregator::Analyzer")
00049 { }
00050
00051 bool AnalyzerGroup::init(const string base_path, const ros::NodeHandle &n)
00052 {
00053 n.param("path", nice_name_, string(""));
00054
00055 if (base_path.size() > 0 && base_path != "/")
00056 if (nice_name_.size() > 0)
00057 path_ = base_path + "/" + nice_name_;
00058 else
00059 path_ = base_path;
00060 else
00061 path_ = nice_name_;
00062
00063
00064 if (path_.find("/") != 0)
00065 path_ = "/" + path_;
00066
00067 ros::NodeHandle analyzers_nh = ros::NodeHandle(n, "analyzers");
00068
00069 XmlRpc::XmlRpcValue analyzer_params;
00070 analyzers_nh.getParam("", analyzer_params);
00071 ROS_DEBUG("Analyzer params: %s.", analyzer_params.toXml().c_str());
00072
00073 bool init_ok = true;
00074
00075 XmlRpc::XmlRpcValue::iterator xml_it;
00076 for (xml_it = analyzer_params.begin(); xml_it != analyzer_params.end(); ++xml_it)
00077 {
00078 XmlRpc::XmlRpcValue analyzer_name = xml_it->first;
00079 ROS_DEBUG("Got analyzer name: %s", analyzer_name.toXml().c_str());
00080 XmlRpc::XmlRpcValue analyzer_value = xml_it->second;
00081
00082 string ns = analyzer_name;
00083
00084 if (!analyzer_value.hasMember("type"))
00085 {
00086 ROS_ERROR("Namespace %s has no member 'type', unable to initialize analyzer for this namespace.", analyzers_nh.getNamespace().c_str());
00087 boost::shared_ptr<StatusItem> item(new StatusItem(ns, "No Analyzer type given"));
00088 aux_items_.push_back(item);
00089 init_ok = false;
00090 continue;
00091 }
00092
00093 XmlRpc::XmlRpcValue analyzer_type = analyzer_value["type"];
00094 string an_type = analyzer_type;
00095
00096 boost::shared_ptr<Analyzer> analyzer;
00097 try
00098 {
00099
00100 if (!analyzer_loader_.isClassAvailable(an_type))
00101 {
00102 bool have_class = false;
00103 vector<string> classes = analyzer_loader_.getDeclaredClasses();
00104 for(unsigned int i = 0; i < classes.size(); ++i)
00105 {
00106 if(an_type == analyzer_loader_.getName(classes[i]))
00107 {
00108
00109 ROS_WARN("Analyzer specification should now include the package name. You are using a deprecated API. Please switch from %s to %s in your Analyzer specification.",
00110 an_type.c_str(), classes[i].c_str());
00111 an_type = classes[i];
00112 have_class = true;
00113 break;
00114 }
00115 }
00116 if (!have_class)
00117 {
00118 ROS_ERROR("Unable to find Analyzer class %s. Check that Analyzer is fully declared.", an_type.c_str());
00119 continue;
00120 }
00121 }
00122
00123 analyzer = analyzer_loader_.createInstance(an_type);
00124 }
00125 catch (pluginlib::LibraryLoadException& e)
00126 {
00127 ROS_ERROR("Failed to load analyzer %s, type %s. Caught exception. %s", ns.c_str(), an_type.c_str(), e.what());
00128 boost::shared_ptr<StatusItem> item(new StatusItem(ns, "Pluginlib exception loading analyzer"));
00129 aux_items_.push_back(item);
00130 init_ok = false;
00131 continue;
00132 }
00133
00134 if (!analyzer)
00135 {
00136 ROS_ERROR("Pluginlib returned a null analyzer for %s, namespace %s.", an_type.c_str(), analyzers_nh.getNamespace().c_str());
00137 boost::shared_ptr<StatusItem> item(new StatusItem(ns, "Pluginlib return NULL Analyzer for " + an_type));
00138 aux_items_.push_back(item);
00139 init_ok = false;
00140 continue;
00141 }
00142
00143 if (!analyzer->init(path_, ros::NodeHandle(analyzers_nh, ns)))
00144 {
00145 ROS_ERROR("Unable to initialize analyzer NS: %s, type: %s", analyzers_nh.getNamespace().c_str(), an_type.c_str());
00146 boost::shared_ptr<StatusItem> item(new StatusItem(ns, "Analyzer init failed"));
00147 aux_items_.push_back(item);
00148 init_ok = false;
00149 continue;
00150 }
00151
00152 analyzers_.push_back(analyzer);
00153 }
00154
00155 if (analyzers_.size() == 0)
00156 {
00157 init_ok = false;
00158 ROS_ERROR("No analyzers initialized in AnalyzerGroup %s", analyzers_nh.getNamespace().c_str());
00159 }
00160
00161 return init_ok;
00162 }
00163
00164 AnalyzerGroup::~AnalyzerGroup()
00165 {
00166 analyzers_.clear();
00167 }
00168
00169 bool AnalyzerGroup::addAnalyzer(boost::shared_ptr<Analyzer>& analyzer)
00170 {
00171 analyzers_.push_back(analyzer);
00172 return true;
00173 }
00174
00175 bool AnalyzerGroup::removeAnalyzer(boost::shared_ptr<Analyzer>& analyzer)
00176 {
00177 vector<boost::shared_ptr<Analyzer> >::iterator it = find(analyzers_.begin(), analyzers_.end(), analyzer);
00178 if (it != analyzers_.end())
00179 {
00180 analyzers_.erase(it);
00181 return true;
00182 }
00183 return false;
00184 }
00185
00186 bool AnalyzerGroup::match(const string name)
00187 {
00188 if (analyzers_.size() == 0)
00189 return false;
00190
00191 bool match_name = false;
00192 if (matched_.count(name))
00193 {
00194 vector<bool> &mtch_vec = matched_[name];
00195 for (unsigned int i = 0; i < mtch_vec.size(); ++i)
00196 {
00197 if (mtch_vec[i])
00198 return true;
00199 }
00200 return false;
00201 }
00202
00203 matched_[name].resize(analyzers_.size());
00204 for (unsigned int i = 0; i < analyzers_.size(); ++i)
00205 {
00206 bool mtch = analyzers_[i]->match(name);
00207 match_name = mtch || match_name;
00208 matched_[name].at(i) = mtch;
00209 }
00210
00211 return match_name;
00212 }
00213
00214 void AnalyzerGroup::resetMatches()
00215 {
00216 matched_.clear();
00217 }
00218
00219
00220 bool AnalyzerGroup::analyze(const boost::shared_ptr<StatusItem> item)
00221 {
00222 ROS_ASSERT_MSG(matched_.count(item->getName()), "AnalyzerGroup was asked to analyze an item it hadn't matched.");
00223
00224 bool analyzed = false;
00225 vector<bool> &mtch_vec = matched_[item->getName()];
00226 for (unsigned int i = 0; i < mtch_vec.size(); ++i)
00227 {
00228 if (mtch_vec[i])
00229 analyzed = analyzers_[i]->analyze(item) || analyzed;
00230 }
00231
00232 return analyzed;
00233 }
00234
00235 vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> > AnalyzerGroup::report()
00236 {
00237 vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> > output;
00238
00239 boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> header_status(new diagnostic_msgs::DiagnosticStatus);
00240 header_status->name = path_;
00241 header_status->level = 0;
00242 header_status->message = "OK";
00243
00244 if (analyzers_.size() == 0)
00245 {
00246 header_status->level = 2;
00247 header_status->message = "No analyzers";
00248 output.push_back(header_status);
00249
00250 if (header_status->name == "" || header_status->name == "/")
00251 header_status->name = "/AnalyzerGroup";
00252
00253 return output;
00254 }
00255
00256 bool all_stale = true;
00257
00258 for (unsigned int j = 0; j < analyzers_.size(); ++j)
00259 {
00260 string path = analyzers_[j]->getPath();
00261 string nice_name = analyzers_[j]->getName();
00262
00263 vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> > processed = analyzers_[j]->report();
00264
00265
00266 if (processed.size() == 0)
00267 continue;
00268
00269
00270
00271 for (unsigned int i = 0; i < processed.size(); ++i)
00272 {
00273 output.push_back(processed[i]);
00274
00275
00276 if (processed[i]->name == path)
00277 {
00278 diagnostic_msgs::KeyValue kv;
00279 kv.key = nice_name;
00280 kv.value = processed[i]->message;
00281
00282 all_stale = all_stale && (processed[i]->level == 3);
00283 header_status->level = max(header_status->level, processed[i]->level);
00284 header_status->values.push_back(kv);
00285 }
00286 }
00287 }
00288
00289
00290 if (header_status->level == 3 && !all_stale)
00291 header_status->level = 2;
00292
00293 header_status->message = valToMsg(header_status->level);
00294
00295 if (path_ != "" && path_ != "/")
00296 {
00297 output.push_back(header_status);
00298 }
00299
00300 for (unsigned int i = 0; i < aux_items_.size(); ++i)
00301 {
00302 output.push_back(aux_items_[i]->toStatusMsg(path_, true));
00303 }
00304
00305 return output;
00306 }