39 #ifndef DIAGNOSTIC_AGGREGATOR_GENERIC_ANALYZER_H 40 #define DIAGNOSTIC_AGGREGATOR_GENERIC_ANALYZER_H 47 #include <boost/shared_ptr.hpp> 48 #include <boost/regex.hpp> 50 #include "diagnostic_msgs/DiagnosticStatus.h" 51 #include "diagnostic_msgs/KeyValue.h" 71 output.push_back(find);
76 for (
int i = 0; i < param.
size(); ++i)
80 ROS_ERROR(
"Parameter is not a list of strings, found non-string value. XmlRpcValue: %s", param.
toXml().c_str());
86 output.push_back(find);
91 ROS_ERROR(
"Parameter not a list or string, unable to return values. XmlRpcValue:s %s", param.
toXml().c_str());
223 virtual std::vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> >
report();
242 #endif //DIAGNOSTIC_AGGREGATOR_GENERIC_ANALYZER_H
std::vector< std::string > contains_
virtual std::vector< boost::shared_ptr< diagnostic_msgs::DiagnosticStatus > > report()
Reports current state, returns vector of formatted status messages.
GenericAnalyzer is most basic diagnostic Analyzer.
virtual ~GenericAnalyzer()
Type const & getType() const
std::vector< boost::regex > regex_
std::vector< std::string > chaff_
std::vector< std::string > startswith_
std::string toXml() const
virtual bool match(const std::string name)
Returns true if item matches any of the given criteria.
bool init(const std::string base_path, const ros::NodeHandle &n)
Initializes GenericAnalyzer from namespace. Returns true if s.
bool getParamVals(XmlRpc::XmlRpcValue param, std::vector< std::string > &output)
Returns list of strings from a parameter.
std::vector< std::string > expected_
GenericAnalyzerBase is the base class for GenericAnalyzer and OtherAnalyzer.
GenericAnalyzer()
Default constructor loaded by pluginlib.
std::vector< std::string > name_