45 AnalyzerGroup::AnalyzerGroup() :
48 analyzer_loader_(
"diagnostic_aggregator",
"diagnostic_aggregator::Analyzer")
55 if (base_path.size() > 0 && base_path !=
"/")
64 if (
path_.find(
"/") != 0)
70 analyzers_nh.
getParam(
"", analyzer_params);
71 ROS_DEBUG(
"Analyzer params: %s.", analyzer_params.
toXml().c_str());
76 for (xml_it = analyzer_params.
begin(); xml_it != analyzer_params.
end(); ++xml_it)
82 string ns = analyzer_name;
84 if (!analyzer_value.hasMember(
"type"))
86 ROS_ERROR(
"Namespace %s has no member 'type', unable to initialize analyzer for this namespace.", analyzers_nh.
getNamespace().c_str());
94 string an_type = analyzer_type;
102 bool have_class =
false;
104 for(
unsigned int i = 0; i < classes.size(); ++i)
109 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.",
110 an_type.c_str(), classes[i].c_str());
111 an_type = classes[i];
118 ROS_ERROR(
"Unable to find Analyzer class %s. Check that Analyzer is fully declared.", an_type.c_str());
127 ROS_ERROR(
"Failed to load analyzer %s, type %s. Caught exception. %s", ns.c_str(), an_type.c_str(), e.what());
136 ROS_ERROR(
"Pluginlib returned a null analyzer for %s, namespace %s.", an_type.c_str(), analyzers_nh.
getNamespace().c_str());
145 ROS_ERROR(
"Unable to initialize analyzer NS: %s, type: %s", analyzers_nh.
getNamespace().c_str(), an_type.c_str());
177 vector<boost::shared_ptr<Analyzer> >::iterator it = find(
analyzers_.begin(),
analyzers_.end(), analyzer);
191 bool match_name =
false;
194 vector<bool> &mtch_vec =
matched_[name];
195 for (
unsigned int i = 0; i < mtch_vec.size(); ++i)
204 for (
unsigned int i = 0; i <
analyzers_.size(); ++i)
207 match_name = mtch || match_name;
222 ROS_ASSERT_MSG(
matched_.count(item->getName()),
"AnalyzerGroup was asked to analyze an item it hadn't matched.");
224 bool analyzed =
false;
225 vector<bool> &mtch_vec =
matched_[item->getName()];
226 for (
unsigned int i = 0; i < mtch_vec.size(); ++i)
229 analyzed =
analyzers_[i]->analyze(item) || analyzed;
237 vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> > output;
240 header_status->name =
path_;
241 header_status->level = 0;
242 header_status->message =
"OK";
246 header_status->level = 2;
247 header_status->message =
"No analyzers";
248 output.push_back(header_status);
250 if (header_status->name ==
"" || header_status->name ==
"/")
251 header_status->name =
"/AnalyzerGroup";
256 bool all_stale =
true;
258 for (
unsigned int j = 0; j <
analyzers_.size(); ++j)
263 vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> > processed =
analyzers_[j]->report();
266 if (processed.size() == 0)
271 for (
unsigned int i = 0; i < processed.size(); ++i)
273 output.push_back(processed[i]);
276 if (processed[i]->name == path)
278 diagnostic_msgs::KeyValue kv;
280 kv.value = processed[i]->message;
282 all_stale = all_stale && (processed[i]->level == 3);
283 header_status->level = max(header_status->level, processed[i]->level);
284 header_status->values.push_back(kv);
290 if (header_status->level == 3 && !all_stale)
291 header_status->level = 2;
293 header_status->message =
valToMsg(header_status->level);
297 output.push_back(header_status);
300 for (
unsigned int i = 0; i <
aux_items_.size(); ++i)
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.
ValueStruct::iterator iterator
pluginlib::ClassLoader< Analyzer > analyzer_loader_
Loads Analyzer plugins in "analyzers" namespace.
std::string valToMsg(const int val)
Converts int to message {0: 'OK', 1: 'Warning', 2: 'Error', 3: 'Stale' }.
std::map< const std::string, std::vector< bool > > matched_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
bool getParam(const std::string &key, std::string &s) const
#define ROS_ASSERT_MSG(cond,...)
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.
const std::string & getNamespace() const
std::string toXml() const
void resetMatches()
Clear match arrays. Used when analyzers are added or removed.
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.
Helper class to hold, store DiagnosticStatus messages.
PLUGINLIB_EXPORT_CLASS(diagnostic_aggregator::AnalyzerGroup, diagnostic_aggregator::Analyzer) AnalyzerGroup
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.