39 #ifndef DIAGNOSTIC_AGGREGATOR_H 40 #define DIAGNOSTIC_AGGREGATOR_H 47 #include <boost/shared_ptr.hpp> 48 #include <boost/thread/mutex.hpp> 50 #include <diagnostic_msgs/DiagnosticArray.h> 51 #include <diagnostic_msgs/DiagnosticStatus.h> 52 #include <diagnostic_msgs/KeyValue.h> 53 #include <diagnostic_msgs/AddDiagnostics.h> 142 void diagCallback(
const diagnostic_msgs::DiagnosticArray::ConstPtr& diag_msg);
150 bool addDiagnostics(diagnostic_msgs::AddDiagnostics::Request &req,
151 diagnostic_msgs::AddDiagnostics::Response &res);
157 std::vector<boost::shared_ptr<bond::Bond> >
bonds_;
187 void checkTimestamp(
const diagnostic_msgs::DiagnosticArray::ConstPtr& diag_msg);
203 #endif // DIAGNOSTIC_AGGREGATOR_H AnalyzerGroup * analyzer_group_
void diagCallback(const diagnostic_msgs::DiagnosticArray::ConstPtr &diag_msg)
Callback for incoming "/diagnostics".
ros::ServiceServer add_srv_
std::string base_path_
Prepended to all status names of aggregator.
bool operator()(const boost::shared_ptr< bond::Bond > &b)
void bondFormed(boost::shared_ptr< Analyzer > group)
BondIDMatch(const std::string s)
Aggregator()
Constructor initializes with main prefix (ex: '/Robot')
void checkTimestamp(const diagnostic_msgs::DiagnosticArray::ConstPtr &diag_msg)
void bondBroken(std::string bond_id, boost::shared_ptr< Analyzer > analyzer)
std::set< std::string > ros_warnings_
Records all ROS warnings. No warnings are repeated.
ros::Subscriber diag_sub_
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...
double getPubRate() const
Publish rate defaults to 1Hz, but can be set with ~pub_rate param.
std::vector< boost::shared_ptr< bond::Bond > > bonds_
Contains all bonds for additional diagnostics.
Allows analyzers to be grouped together, or used as sub-analyzers.
OtherAnalyzer * other_analyzer_
bool ok() const
True if the NodeHandle reports OK.
Aggregator processes /diagnostics, republishes on /diagnostics_agg.
void publishData()
Processes, publishes data. Should be called at pub_rate.
ros::Publisher toplevel_state_pub_