aggregator.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_H
40 #define DIAGNOSTIC_AGGREGATOR_H
41 
42 #include <ros/ros.h>
43 #include <string>
44 #include <map>
45 #include <vector>
46 #include <set>
47 #include <boost/shared_ptr.hpp>
48 #include <boost/thread/mutex.hpp>
49 #include <bondcpp/bond.h>
50 #include <diagnostic_msgs/DiagnosticArray.h>
51 #include <diagnostic_msgs/DiagnosticStatus.h>
52 #include <diagnostic_msgs/KeyValue.h>
53 #include <diagnostic_msgs/AddDiagnostics.h>
54 #include "XmlRpcValue.h"
59 
60 
62 
105 class Aggregator
106 {
107 public:
111  Aggregator();
112 
113  ~Aggregator();
114 
118  void publishData();
119 
123  bool ok() const { return n_.ok(); }
124 
128  double getPubRate() const { return pub_rate_; }
129 
130 private:
136  boost::mutex mutex_;
137  double pub_rate_;
138 
142  void diagCallback(const diagnostic_msgs::DiagnosticArray::ConstPtr& diag_msg);
143 
150  bool addDiagnostics(diagnostic_msgs::AddDiagnostics::Request &req,
151  diagnostic_msgs::AddDiagnostics::Response &res);
152 
154 
156 
157  std::vector<boost::shared_ptr<bond::Bond> > bonds_;
159  /*
160  *!\brief called when a bond between the aggregator and a node is broken
161  *
162  * Modifies the contents of added_analyzers_ and analyzer_group, removing the
163  * diagnostics that had been brought up by that bond.
164  *!\param bond_id The bond id (namespace) from which the analyzer was created
165  *!\param analyzer Shared pointer to the analyzer group that was added
166  */
167  void bondBroken(std::string bond_id,
168  boost::shared_ptr<Analyzer> analyzer);
169 
170  /*
171  *!\brief called when a bond is formed between the aggregator and a node.
172  * Actually adds the analyzergroup to the main analyzer group. Before this
173  * function is called, the added diagnostics will not be analyzed by the
174  * aggregator.
175  *!\param group Shared pointer to the analyzer group that is to be added,
176  * which was created in the addDiagnostics function
177  */
179 
182  std::set<std::string> ros_warnings_;
184  /*
185  *!\brief Checks timestamp of message, and warns if timestamp is 0 (not set)
186  */
187  void checkTimestamp(const diagnostic_msgs::DiagnosticArray::ConstPtr& diag_msg);
188 
189 };
190 
191 /*
192  *!\brief Functor for checking whether a bond has the same ID as the given string
193  */
194 struct BondIDMatch
195 {
196  BondIDMatch(const std::string s) : s(s) {}
197  bool operator()(const boost::shared_ptr<bond::Bond>& b){ return s == b->getId(); }
198  const std::string s;
199 };
200 
201 }
202 
203 #endif // DIAGNOSTIC_AGGREGATOR_H
diagnostic_aggregator::Aggregator::toplevel_state_pub_
ros::Publisher toplevel_state_pub_
Definition: aggregator.h:199
diagnostic_aggregator
Definition: aggregator.h:61
diagnostic_aggregator::Aggregator::bondBroken
void bondBroken(std::string bond_id, boost::shared_ptr< Analyzer > analyzer)
Definition: aggregator.cpp:125
ros::Publisher
diagnostic_aggregator::Aggregator::ros_warnings_
std::set< std::string > ros_warnings_
Records all ROS warnings. No warnings are repeated.
Definition: aggregator.h:246
diagnostic_aggregator::AnalyzerGroup
Allows analyzers to be grouped together, or used as sub-analyzers.
Definition: analyzer_group.h:142
boost::shared_ptr
analyzer.h
diagnostic_aggregator::Aggregator::base_path_
std::string base_path_
Prepended to all status names of aggregator.
Definition: aggregator.h:244
ros.h
diagnostic_aggregator::Aggregator::addDiagnostics
bool addDiagnostics(diagnostic_msgs::AddDiagnostics::Request &req, diagnostic_msgs::AddDiagnostics::Response &res)
Service request callback for addition of diagnostics. Creates a bond between the calling node and the...
Definition: aggregator.cpp:151
diagnostic_aggregator::Aggregator::agg_pub_
ros::Publisher agg_pub_
Definition: aggregator.h:198
status_item.h
diagnostic_aggregator::Aggregator::bonds_
std::vector< boost::shared_ptr< bond::Bond > > bonds_
Contains all bonds for additional diagnostics.
Definition: aggregator.h:221
diagnostic_aggregator::Aggregator::getPubRate
double getPubRate() const
Publish rate defaults to 1Hz, but can be set with ~pub_rate param.
Definition: aggregator.h:192
diagnostic_aggregator::BondIDMatch::BondIDMatch
BondIDMatch(const std::string s)
Definition: aggregator.h:228
diagnostic_aggregator::Aggregator::analyzer_group_
AnalyzerGroup * analyzer_group_
Definition: aggregator.h:217
diagnostic_aggregator::Aggregator::checkTimestamp
void checkTimestamp(const diagnostic_msgs::DiagnosticArray::ConstPtr &diag_msg)
Definition: aggregator.cpp:74
diagnostic_aggregator::Aggregator::n_
ros::NodeHandle n_
Definition: aggregator.h:195
diagnostic_aggregator::Aggregator::ok
bool ok() const
True if the NodeHandle reports OK.
Definition: aggregator.h:187
diagnostic_aggregator::Aggregator::other_analyzer_
OtherAnalyzer * other_analyzer_
Definition: aggregator.h:219
diagnostic_aggregator::BondIDMatch
Definition: aggregator.h:226
diagnostic_aggregator::Aggregator::diag_sub_
ros::Subscriber diag_sub_
Definition: aggregator.h:197
ros::ServiceServer
testing::internal::string
::std::string string
Definition: gtest.h:1979
bond.h
diagnostic_aggregator::Aggregator::publishData
void publishData()
Processes, publishes data. Should be called at pub_rate.
Definition: aggregator.cpp:202
diagnostic_aggregator::OtherAnalyzer
Definition: other_analyzer.h:92
other_analyzer.h
diagnostic_aggregator::Aggregator::diagCallback
void diagCallback(const diagnostic_msgs::DiagnosticArray::ConstPtr &diag_msg)
Callback for incoming "/diagnostics".
Definition: aggregator.cpp:95
diagnostic_aggregator::Aggregator
Aggregator processes /diagnostics, republishes on /diagnostics_agg.
Definition: aggregator.h:137
diagnostic_aggregator::BondIDMatch::s
const std::string s
Definition: aggregator.h:230
XmlRpcValue.h
diagnostic_aggregator::Aggregator::add_srv_
ros::ServiceServer add_srv_
Definition: aggregator.h:196
diagnostic_aggregator::Aggregator::Aggregator
Aggregator()
Constructor initializes with main prefix (ex: '/Robot')
Definition: aggregator.cpp:42
ros::NodeHandle::ok
bool ok() const
diagnostic_aggregator::Aggregator::pub_rate_
double pub_rate_
Definition: aggregator.h:201
diagnostic_aggregator::BondIDMatch::operator()
bool operator()(const boost::shared_ptr< bond::Bond > &b)
Definition: aggregator.h:229
diagnostic_aggregator::Aggregator::~Aggregator
~Aggregator()
Definition: aggregator.cpp:117
diagnostic_aggregator::Aggregator::mutex_
boost::mutex mutex_
Definition: aggregator.h:200
diagnostic_aggregator::Aggregator::bondFormed
void bondFormed(boost::shared_ptr< Analyzer > group)
Definition: aggregator.cpp:144
ros::NodeHandle
ros::Subscriber
analyzer_group.h


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