analyzer_group.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_ANALYZER_GROUP_H
40 #define DIAGNOSTIC_ANALYZER_GROUP_H
41 
42 #include <map>
43 #include <vector>
44 #include <string>
45 #include <algorithm>
46 #include <ros/ros.h>
47 #include <diagnostic_msgs/DiagnosticStatus.h>
48 #include <diagnostic_msgs/KeyValue.h>
50 #include <boost/shared_ptr.hpp>
51 #include "XmlRpcValue.h"
56 
57 namespace diagnostic_aggregator {
58 
110 class AnalyzerGroup : public Analyzer
111 {
112 public:
113  AnalyzerGroup();
114 
115  virtual ~AnalyzerGroup();
116 
122  virtual bool init(const std::string base_path, const ros::NodeHandle &n);
123 
127  virtual bool addAnalyzer(boost::shared_ptr<Analyzer>& analyzer);
128 
132  virtual bool removeAnalyzer(boost::shared_ptr<Analyzer>& analyzer);
133 
137  virtual bool match(const std::string name);
138 
142  void resetMatches();
143 
147  virtual bool analyze(const boost::shared_ptr<StatusItem> item);
148 
152  virtual std::vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> > report();
153 
154  virtual std::string getPath() const { return path_; }
155 
156  virtual std::string getName() const { return nice_name_; }
157 
158 private:
160 
165 
169  std::vector<boost::shared_ptr<StatusItem> > aux_items_;
170 
171  std::vector<boost::shared_ptr<Analyzer> > analyzers_;
172 
173  /*
174  *\brief The map of names to matchings is stored internally.
175  */
176  std::map<const std::string, std::vector<bool> > matched_;
177 
178 };
179 
180 }
181 
182 #endif //DIAGNOSTIC_ANALYZER_GROUP_H
diagnostic_aggregator
Definition: aggregator.h:61
diagnostic_aggregator::AnalyzerGroup::matched_
std::map< const std::string, std::vector< bool > > matched_
Definition: analyzer_group.h:240
boost::shared_ptr
analyzer.h
ros.h
diagnostic_aggregator::AnalyzerGroup::analyzers_
std::vector< boost::shared_ptr< Analyzer > > analyzers_
Definition: analyzer_group.h:235
status_item.h
diagnostic_aggregator::AnalyzerGroup::path_
std::string path_
Definition: analyzer_group.h:223
diagnostic_aggregator::AnalyzerGroup::getName
virtual std::string getName() const
Returns nice name for display. (ex: 'Sensors')
Definition: analyzer_group.h:220
testing::internal::string
::std::string string
Definition: gtest.h:1979
diagnostic_aggregator::AnalyzerGroup::removeAnalyzer
virtual bool removeAnalyzer(boost::shared_ptr< Analyzer > &analyzer)
Remove an analyzer from this analyzerGroup.
Definition: analyzer_group.cpp:175
diagnostic_aggregator::AnalyzerGroup::nice_name_
std::string nice_name_
Definition: analyzer_group.h:223
diagnostic_aggregator::AnalyzerGroup::report
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.
Definition: analyzer_group.cpp:235
diagnostic_aggregator::AnalyzerGroup::~AnalyzerGroup
virtual ~AnalyzerGroup()
Definition: analyzer_group.cpp:164
diagnostic_aggregator::AnalyzerGroup::getPath
virtual std::string getPath() const
Returns full prefix of analyzer. (ex: '/Robot/Sensors')
Definition: analyzer_group.h:218
diagnostic_aggregator::AnalyzerGroup::addAnalyzer
virtual bool addAnalyzer(boost::shared_ptr< Analyzer > &analyzer)
Add an analyzer to this analyzerGroup.
Definition: analyzer_group.cpp:169
XmlRpcValue.h
pluginlib::ClassLoader
class_loader.hpp
diagnostic_aggregator::AnalyzerGroup::analyzer_loader_
pluginlib::ClassLoader< Analyzer > analyzer_loader_
Loads Analyzer plugins in "analyzers" namespace.
Definition: analyzer_group.h:228
diagnostic_aggregator::AnalyzerGroup::analyze
virtual bool analyze(const boost::shared_ptr< StatusItem > item)
Analyze returns true if any sub-analyzers will analyze an item.
Definition: analyzer_group.cpp:220
diagnostic_aggregator::AnalyzerGroup::init
virtual bool init(const std::string base_path, const ros::NodeHandle &n)
Initialized with base path and namespace.
Definition: analyzer_group.cpp:51
diagnostic_aggregator::AnalyzerGroup::aux_items_
std::vector< boost::shared_ptr< StatusItem > > aux_items_
These items store errors, if any, for analyzers that failed to initialize or load.
Definition: analyzer_group.h:233
diagnostic_aggregator::AnalyzerGroup::resetMatches
void resetMatches()
Clear match arrays. Used when analyzers are added or removed.
Definition: analyzer_group.cpp:214
class_list_macros.hpp
diagnostic_aggregator::AnalyzerGroup::match
virtual bool match(const std::string name)
Match returns true if any sub-analyzers match an item.
Definition: analyzer_group.cpp:186
diagnostic_aggregator::AnalyzerGroup::AnalyzerGroup
AnalyzerGroup()
ros::NodeHandle


diagnostic_aggregator
Author(s): Kevin Watts, Brice Rebsamen
autogenerated on Tue Nov 15 2022 03:17:12