other_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 OTHER_ANALYZER_H
40 #define OTHER_ANALYZER_H
41 
42 #include <string>
43 #include <ros/ros.h>
45 
46 namespace diagnostic_aggregator {
47 
48 /*
49  *\brief OtherAnalyzer analyzes any messages that haven't been analyzed by other Analyzers
50  *
51  * OtherAnalyzer is not loaded as a plugin. It is created by the Aggregator, and called
52  * seperately. The aggregator will call analyze() on any message not handled by other
53  * analyzers.
54  *
55  * Stale items will be discarded after 5 seconds of no updates.
56  *
57  * OtherAnalyzer is designed to be used internally by the Aggregator only.
58  *
59  */
60 class OtherAnalyzer : public GenericAnalyzerBase
61 {
62 public:
66  explicit OtherAnalyzer(bool other_as_errors = false)
67  : other_as_errors_(other_as_errors)
68  { }
69 
70  ~OtherAnalyzer() { }
71 
72  /*
73  *\brief Initialized with the base path only.
74  *
75  *\param path Base path of Aggregator
76  */
77  bool init(std::string path)
78  {
79  return GenericAnalyzerBase::init(path + "/Other", "Other", 5.0, -1, true);
80  }
81 
82  /*
83  *\brief OtherAnalyzer cannot be initialized with a NodeHandle
84  *
85  *\return False, since NodeHandle initialization isn't valid
86  */
87  bool init(const std::string base_path, const ros::NodeHandle &n)
88  {
89  ROS_ERROR("OtherAnalyzer was attempted to initialize with a NodeHandle. This analyzer cannot be used as a plugin.");
90  return false;
91  }
92 
93  /*
94  *\brief match() isn't called by aggregator for OtherAnalyzer
95  *
96  *\return True, since match() will never by called by Aggregator
97  */
98  bool match(std::string name) { return true; }
99 
100  /*
101  *\brief Reports diagnostics, but doesn't report anything if it doesn't have data
102  *
103  */
104  std::vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> > report()
105  {
106  std::vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> > processed = GenericAnalyzerBase::report();
107 
108  // We don't report anything if there's no "Other" items
109  if (processed.size() == 1)
110  {
111  processed.clear();
112  }
113  // "Other" items are considered an error.
114  else if (other_as_errors_ && processed.size() > 1)
115  {
116  std::vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> >::iterator it = processed.begin();
117  for (; it != processed.end(); ++it)
118  {
119  if ((*it)->name == path_)
120  {
121  (*it)->level = DiagnosticLevel::Level_Error;
122  (*it)->message = "Unanalyzed items found in \"Other\"";
123  break;
124  }
125  }
126  }
127 
128  return processed;
129  }
130 
131 private:
132  bool other_as_errors_;
133 };
134 
135 }
136 
137 
138 #endif // OTHER_ANALYZER_H
diagnostic_aggregator::OtherAnalyzer::match
bool match(std::string name)
Match function isn't implemented by GenericAnalyzerBase.
Definition: other_analyzer.h:162
diagnostic_aggregator
Definition: aggregator.h:61
diagnostic_aggregator::GenericAnalyzerBase::init
bool init(const std::string path, const ros::NodeHandle &n)=0
Analyzer is initialized with base path and namespace.
diagnostic_aggregator::OtherAnalyzer::init
bool init(std::string path)
Definition: other_analyzer.h:141
ros.h
diagnostic_aggregator::Level_Error
@ Level_Error
Definition: status_item.h:108
diagnostic_aggregator::GenericAnalyzerBase::path_
std::string path_
Definition: generic_analyzer_base.h:321
diagnostic_aggregator::OtherAnalyzer::report
std::vector< boost::shared_ptr< diagnostic_msgs::DiagnosticStatus > > report()
Reports current state, returns vector of formatted status messages.
Definition: other_analyzer.h:168
testing::internal::string
::std::string string
Definition: gtest.h:1979
diagnostic_aggregator::OtherAnalyzer::~OtherAnalyzer
~OtherAnalyzer()
Definition: other_analyzer.h:134
diagnostic_aggregator::OtherAnalyzer::OtherAnalyzer
OtherAnalyzer(bool other_as_errors=false)
Default constructor. OtherAnalyzer isn't loaded by pluginlib.
Definition: other_analyzer.h:130
diagnostic_aggregator::GenericAnalyzerBase::report
virtual std::vector< boost::shared_ptr< diagnostic_msgs::DiagnosticStatus > > report()
Reports current state, returns vector of formatted status messages.
Definition: generic_analyzer_base.h:195
ROS_ERROR
#define ROS_ERROR(...)
generic_analyzer_base.h
diagnostic_aggregator::OtherAnalyzer::other_as_errors_
bool other_as_errors_
Definition: other_analyzer.h:196
ros::NodeHandle


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