37 #ifndef GENERIC_ANALYZER_BASE_H 38 #define GENERIC_ANALYZER_BASE_H 45 #include <boost/shared_ptr.hpp> 46 #include <boost/regex.hpp> 48 #include "diagnostic_msgs/DiagnosticStatus.h" 49 #include "diagnostic_msgs/KeyValue.h" 86 double timeout = -1.0,
int num_items_expected = -1,
bool discard_stale =
false)
96 ROS_WARN(
"Cannot discard stale items if no timeout specified. No items will be discarded");
113 ROS_ERROR(
"GenericAnalyzerBase is asked to analyze diagnostics without being initialized. init() must be called in order to correctly use this class.");
119 items_[item->getName()] = item;
129 virtual std::vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> >
report()
134 ROS_ERROR(
"GenericAnalyzerBase is asked to report diagnostics without being initialized. init() must be called in order to correctly use this class.");
138 std::vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> > vec;
143 header_status->name =
path_;
144 header_status->level = 0;
145 header_status->message =
"OK";
147 std::vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> > processed;
148 processed.push_back(header_status);
150 bool all_stale =
true;
152 std::map<std::string, boost::shared_ptr<StatusItem> >::iterator it =
items_.begin();
169 int8_t level = item->getLevel();
170 header_status->level = std::max(header_status->level, level);
172 diagnostic_msgs::KeyValue kv;
174 kv.value = item->getMessage();
176 header_status->values.push_back(kv);
178 all_stale = all_stale && ((level == 3) || stale);
182 processed.push_back(item->toStatusMsg(
path_, stale));
185 header_status->level = 3;
192 header_status->level = 3;
193 else if (header_status->level == 3)
194 header_status->level = 2;
196 header_status->message =
valToMsg(header_status->level);
201 header_status->level = 0;
202 header_status->message =
"OK";
207 header_status->level = std::max(lvl, header_status->level);
209 std::stringstream expec, item;
214 header_status->message =
"Expected " + expec.str() +
", found " + item.str();
216 header_status->message =
"No items found, expected " + expec.str();
253 std::map<std::string, boost::shared_ptr<StatusItem> >
items_;
259 #endif //GENERIC_ANALYZER_BASE_H
virtual bool analyze(const boost::shared_ptr< StatusItem > item)
Update state with new StatusItem.
virtual ~GenericAnalyzerBase()
std::string valToMsg(const int val)
Converts int to message {0: 'OK', 1: 'Warning', 2: 'Error', 3: 'Stale' }.
virtual std::vector< boost::shared_ptr< diagnostic_msgs::DiagnosticStatus > > report()
Reports current state, returns vector of formatted status messages.
bool init(const std::string path, const std::string nice_name, double timeout=-1.0, int num_items_expected=-1, bool discard_stale=false)
virtual bool match(const std::string name)=0
Match function isn't implemented by GenericAnalyzerBase.
bool init(const std::string path, const ros::NodeHandle &n)=0
Analyzer is initialized with base path and namespace.
virtual std::string getPath() const
Returns full prefix (ex: "/Robot/Power System")
Base class of all Analyzers. Loaded by aggregator.
virtual std::string getName() const
Returns nice name (ex: "Power System")
GenericAnalyzerBase is the base class for GenericAnalyzer and OtherAnalyzer.
void addItem(std::string name, boost::shared_ptr< StatusItem > item)
Subclasses can add items to analyze.
std::map< std::string, boost::shared_ptr< StatusItem > > items_
Stores items by name. State of analyzer.