00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00037 #include <diagnostic_aggregator/aggregator.h>
00038
00039 using namespace std;
00040 using namespace diagnostic_aggregator;
00041
00042 Aggregator::Aggregator() :
00043 pub_rate_(1.0),
00044 analyzer_group_(NULL),
00045 other_analyzer_(NULL),
00046 base_path_("")
00047 {
00048 ros::NodeHandle nh = ros::NodeHandle("~");
00049 nh.param(string("base_path"), base_path_, string(""));
00050 if (base_path_.size() > 0 && base_path_.find("/") != 0)
00051 base_path_ = "/" + base_path_;
00052
00053 nh.param("pub_rate", pub_rate_, pub_rate_);
00054
00055 analyzer_group_ = new AnalyzerGroup();
00056
00057 if (!analyzer_group_->init(base_path_, nh))
00058 {
00059 ROS_ERROR("Analyzer group for diagnostic aggregator failed to initialize!");
00060 }
00061
00062
00063
00064 other_analyzer_ = new OtherAnalyzer();
00065 other_analyzer_->init(base_path_);
00066
00067 diag_sub_ = n_.subscribe("/diagnostics", 1000, &Aggregator::diagCallback, this);
00068 agg_pub_ = n_.advertise<diagnostic_msgs::DiagnosticArray>("/diagnostics_agg", 1);
00069 }
00070
00071 void Aggregator::checkTimestamp(const diagnostic_msgs::DiagnosticArray::ConstPtr& diag_msg)
00072 {
00073 if (diag_msg->header.stamp.toSec() != 0)
00074 return;
00075
00076 string stamp_warn = "No timestamp set for diagnostic message. Message names: ";
00077 vector<diagnostic_msgs::DiagnosticStatus>::const_iterator it;
00078 for (it = diag_msg->status.begin(); it != diag_msg->status.end(); ++it)
00079 {
00080 if (it != diag_msg->status.begin())
00081 stamp_warn += ", ";
00082 stamp_warn += it->name;
00083 }
00084
00085 if (!ros_warnings_.count(stamp_warn))
00086 {
00087 ROS_WARN("%s", stamp_warn.c_str());
00088 ros_warnings_.insert(stamp_warn);
00089 }
00090 }
00091
00092 void Aggregator::diagCallback(const diagnostic_msgs::DiagnosticArray::ConstPtr& diag_msg)
00093 {
00094 checkTimestamp(diag_msg);
00095
00096 bool analyzed = false;
00097 for (unsigned int j = 0; j < diag_msg->status.size(); ++j)
00098 {
00099 analyzed = false;
00100 boost::shared_ptr<StatusItem> item(new StatusItem(&diag_msg->status[j]));
00101 if (analyzer_group_->match(item->getName()))
00102 analyzed = analyzer_group_->analyze(item);
00103
00104 if (!analyzed)
00105 other_analyzer_->analyze(item);
00106 }
00107 }
00108
00109 Aggregator::~Aggregator()
00110 {
00111 if (analyzer_group_) delete analyzer_group_;
00112
00113 if (other_analyzer_) delete other_analyzer_;
00114 }
00115
00116 void Aggregator::publishData()
00117 {
00118 diagnostic_msgs::DiagnosticArray diag_array;
00119
00120 vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> > processed = analyzer_group_->report();
00121 for (unsigned int i = 0; i < processed.size(); ++i)
00122 diag_array.status.push_back(*processed[i]);
00123
00124 vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> > processed_other = other_analyzer_->report();
00125 for (unsigned int i = 0; i < processed_other.size(); ++i)
00126 diag_array.status.push_back(*processed_other[i]);
00127
00128 diag_array.header.stamp = ros::Time::now();
00129
00130 agg_pub_.publish(diag_array);
00131 }
00132
00133
00134
00135
00136
00137
00138
00139