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
00038 #ifndef _PR2_MECHANISM_DIAGNOSTICS_H_MECH_DIAG_
00039 #define _PR2_MECHANISM_DIAGNOSTICS_H_MECH_DIAG_
00040
00041 #include <ros/ros.h>
00042 #include <pr2_mechanism_msgs/MechanismStatistics.h>
00043 #include <diagnostic_msgs/DiagnosticArray.h>
00044 #include <diagnostic_updater/DiagnosticStatusWrapper.h>
00045 #include <vector>
00046 #include <float.h>
00047 #include <boost/shared_ptr.hpp>
00048 #include <boost/math/special_functions/fpclassify.hpp>
00049 #include "pr2_mechanism_model/robot.h"
00050 #include "pr2_mechanism_diagnostics/joint_diagnostics.h"
00051 #include "pr2_mechanism_diagnostics/controller_diagnostics.h"
00052 #include "std_srvs/Empty.h"
00053 #include "std_msgs/Bool.h"
00054
00055 namespace pr2_mechanism_diagnostics
00056 {
00057
00062 class CtrlJntDiagnosticPublisher
00063 {
00064 private:
00065 std::map<std::string, boost::shared_ptr<JointStats> > joint_stats;
00066 std::map<std::string, boost::shared_ptr<ControllerStats> > controller_stats;
00067
00068 ros::NodeHandle n_, pnh_;
00069 ros::Subscriber mech_st_sub_;
00070 ros::Publisher diag_pub_;
00071
00072 bool use_sim_time_;
00073 bool disable_controller_warnings_;
00074
00075 void mechCallback(const pr2_mechanism_msgs::MechanismStatistics::ConstPtr& mechMsg);
00076
00077 public:
00078 CtrlJntDiagnosticPublisher();
00079
00080 ~CtrlJntDiagnosticPublisher() { }
00081
00082 void publishDiag();
00084 bool ok() const { return n_.ok(); }
00085 };
00086
00087 }
00088
00089 #endif // _PR2_MECHANISM_DIAGNOSTICS_H_MECH_DIAG_