generic_analyzer.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 
39 #ifndef DIAGNOSTIC_AGGREGATOR_GENERIC_ANALYZER_H
40 #define DIAGNOSTIC_AGGREGATOR_GENERIC_ANALYZER_H
41 
42 #include <map>
43 #include <ros/ros.h>
44 #include <vector>
45 #include <string>
46 #include <sstream>
47 #include <boost/shared_ptr.hpp>
48 #include <boost/regex.hpp>
50 #include "diagnostic_msgs/DiagnosticStatus.h"
51 #include "diagnostic_msgs/KeyValue.h"
55 #include "XmlRpcValue.h"
56 
57 namespace diagnostic_aggregator {
58 
65 inline bool getParamVals(XmlRpc::XmlRpcValue param, std::vector<std::string> &output)
66 {
67  XmlRpc::XmlRpcValue::Type type = param.getType();
69  {
70  std::string find = param;
71  output.push_back(find);
72  return true;
73  }
74  else if (type == XmlRpc::XmlRpcValue::TypeArray)
75  {
76  for (int i = 0; i < param.size(); ++i)
77  {
78  if (param[i].getType() != XmlRpc::XmlRpcValue::TypeString)
79  {
80  ROS_ERROR("Parameter is not a list of strings, found non-string value. XmlRpcValue: %s", param.toXml().c_str());
81  output.clear();
82  return false;
83  }
84 
85  std::string find = param[i];
86  output.push_back(find);
87  }
88  return true;
89  }
90 
91  ROS_ERROR("Parameter not a list or string, unable to return values. XmlRpcValue:s %s", param.toXml().c_str());
92  output.clear();
93  return false;
94 }
95 
96 
199 {
200 public:
204  GenericAnalyzer();
205 
206  virtual ~GenericAnalyzer();
207 
208  // Move to class description above
216  bool init(const std::string base_path, const ros::NodeHandle &n);
217 
223  virtual std::vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> > report();
224 
229  virtual bool match(const std::string name);
230 
231 private:
232  std::vector<std::string> chaff_;
233  std::vector<std::string> expected_;
234  std::vector<std::string> startswith_;
235  std::vector<std::string> contains_;
236  std::vector<std::string> name_;
237  std::vector<boost::regex> regex_;
239 };
240 
241 }
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.
int size() const
::std::string string
Definition: gtest.h:1979
GenericAnalyzer is most basic diagnostic Analyzer.
Type const & getType() const
std::vector< boost::regex > regex_
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.
#define ROS_ERROR(...)


diagnostic_aggregator
Author(s): Kevin Watts, Brice Rebsamen
autogenerated on Wed Mar 27 2019 03:00:18