generic_analyzer_base.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2009, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
37 #ifndef GENERIC_ANALYZER_BASE_H
38 #define GENERIC_ANALYZER_BASE_H
39 
40 #include <map>
41 #include <ros/ros.h>
42 #include <vector>
43 #include <string>
44 #include <sstream>
45 #include <boost/shared_ptr.hpp>
46 #include <boost/regex.hpp>
48 #include "diagnostic_msgs/DiagnosticStatus.h"
49 #include "diagnostic_msgs/KeyValue.h"
52 
53 namespace diagnostic_aggregator {
54 
66 {
67 public:
69  nice_name_(""), path_(""), timeout_(-1.0), num_items_expected_(-1),
70  discard_stale_(false), has_initialized_(false), has_warned_(false)
71  { }
72 
73  virtual ~GenericAnalyzerBase() { items_.clear(); }
74 
75  /*
76  *\brief Cannot be initialized from (string, NodeHandle) like defined Analyzers
77  */
78  bool init(const std::string path, const ros::NodeHandle &n) = 0;
79 
80  /*
81  *\brief Must be initialized with path, and a "nice name"
82  *
83  * Must be initialized in order to prepend the path to all outgoing status messages.
84  */
85  bool init(const std::string path, const std::string nice_name,
86  double timeout = -1.0, int num_items_expected = -1, bool discard_stale = false)
87  {
88  num_items_expected_ = num_items_expected;
89  timeout_ = timeout;
90  nice_name_ = nice_name;
91  path_ = path;
92  discard_stale_ = discard_stale;
93 
94  if (discard_stale_ && timeout <= 0)
95  {
96  ROS_WARN("Cannot discard stale items if no timeout specified. No items will be discarded");
97  discard_stale_ = false;
98  }
99 
100  has_initialized_ = true;
101 
102  return true;
103  }
104 
108  virtual bool analyze(const boost::shared_ptr<StatusItem> item)
109  {
110  if (!has_initialized_ && !has_warned_)
111  {
112  has_warned_ = true;
113  ROS_ERROR("GenericAnalyzerBase is asked to analyze diagnostics without being initialized. init() must be called in order to correctly use this class.");
114  }
115 
116  if (!has_initialized_)
117  return false;
118 
119  items_[item->getName()] = item;
120 
121  return has_initialized_;
122  }
123 
129  virtual std::vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> > report()
130  {
131  if (!has_initialized_ && !has_warned_)
132  {
133  has_warned_ = true;
134  ROS_ERROR("GenericAnalyzerBase is asked to report diagnostics without being initialized. init() must be called in order to correctly use this class.");
135  }
136  if (!has_initialized_)
137  {
138  std::vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> > vec;
139  return vec;
140  }
141 
142  boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> header_status(new diagnostic_msgs::DiagnosticStatus());
143  header_status->name = path_;
144  header_status->level = 0;
145  header_status->message = "OK";
146 
147  std::vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> > processed;
148  processed.push_back(header_status);
149 
150  bool all_stale = true;
151 
152  std::map<std::string, boost::shared_ptr<StatusItem> >::iterator it = items_.begin();
153  while(it != items_.end())
154  {
155  std::string name = it->first;
156  boost::shared_ptr<StatusItem> item = it->second;
157 
158  bool stale = false;
159  if (timeout_ > 0)
160  stale = (ros::Time::now() - item->getLastUpdateTime()).toSec() > timeout_;
161 
162  // Erase item if its stale and we're discarding items
163  if (discard_stale_ && stale)
164  {
165  items_.erase(it++);
166  continue;
167  }
168 
169  int8_t level = item->getLevel();
170  header_status->level = std::max(header_status->level, level);
171 
172  diagnostic_msgs::KeyValue kv;
173  kv.key = name;
174  kv.value = item->getMessage();
175 
176  header_status->values.push_back(kv);
177 
178  all_stale = all_stale && ((level == 3) || stale);
179 
180  //boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> stat = item->toStatusMsg(path_, stale);
181 
182  processed.push_back(item->toStatusMsg(path_, stale));
183 
184  if (stale)
185  header_status->level = 3;
186 
187  ++it;
188  }
189 
190  // Header is not stale unless all subs are
191  if (all_stale)
192  header_status->level = 3;
193  else if (header_status->level == 3)
194  header_status->level = 2;
195 
196  header_status->message = valToMsg(header_status->level);
197 
198  // If we expect a given number of items, check that we have this number
199  if (num_items_expected_ == 0 && items_.size() == 0)
200  {
201  header_status->level = 0;
202  header_status->message = "OK";
203  }
204  else if (num_items_expected_ > 0 && int(items_.size()) != num_items_expected_)
205  {
206  int8_t lvl = 2;
207  header_status->level = std::max(lvl, header_status->level);
208 
209  std::stringstream expec, item;
210  expec << num_items_expected_;
211  item << items_.size();
212 
213  if (items_.size() > 0)
214  header_status->message = "Expected " + expec.str() + ", found " + item.str();
215  else
216  header_status->message = "No items found, expected " + expec.str();
217  }
218 
219  return processed;
220  }
221 
225  virtual bool match(const std::string name) = 0;
226 
230  virtual std::string getPath() const { return path_; }
231 
235  virtual std::string getName() const { return nice_name_; }
236 
237 protected:
240 
241  double timeout_;
243 
247  void addItem(std::string name, boost::shared_ptr<StatusItem> item) { items_[name] = item; }
248 
249 private:
253  std::map<std::string, boost::shared_ptr<StatusItem> > items_;
254 
256 };
257 
258 }
259 #endif //GENERIC_ANALYZER_BASE_H
virtual bool analyze(const boost::shared_ptr< StatusItem > item)
Update state with new StatusItem.
::std::string string
Definition: gtest.h:1979
std::string valToMsg(const int val)
Converts int to message {0: &#39;OK&#39;, 1: &#39;Warning&#39;, 2: &#39;Error&#39;, 3: &#39;Stale&#39; }.
Definition: status_item.h:101
#define ROS_WARN(...)
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&#39;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.
Definition: analyzer.h:85
virtual std::string getName() const
Returns nice name (ex: "Power System")
static Time now()
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.
#define ROS_ERROR(...)
std::map< std::string, boost::shared_ptr< StatusItem > > items_
Stores items by name. State of analyzer.


diagnostic_aggregator
Author(s): Kevin Watts, Brice Rebsamen
autogenerated on Thu Oct 8 2020 03:17:16