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_TRANSMISSION_CHECK_TRANS_CHECK_NODE_H_
00039 #define _PR2_TRANSMISSION_CHECK_TRANS_CHECK_NODE_H_
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 "std_srvs/Empty.h"
00051 #include "std_msgs/Bool.h"
00052 #include "pr2_transmission_check/transmission_check.h"
00053 #include <exception>
00054
00055 namespace pr2_transmission_check
00056 {
00057
00058 class PR2TransmissionCheckException: public std::runtime_error
00059 {
00060 public:
00061 PR2TransmissionCheckException(const std::string &errorDesc) : std::runtime_error(errorDesc) { ; };
00062 };
00063
00068 class PR2TransmissionCheckNode
00069 {
00070 private:
00071 ros::NodeHandle n_, pnh_;
00072 ros::Subscriber mech_st_sub_;
00073 ros::Publisher diag_pub_;
00074 ros::Publisher trans_status_pub_;
00075 ros::ServiceServer reset_srv_;
00076
00077 bool use_sim_time_;
00078 bool disable_controller_warnings_;
00079
00080 std::vector<boost::shared_ptr<TransmissionListener> > trans_listeners_;
00081 bool trans_status_;
00082
00083 void loadTransCheckers(urdf::Model &robot, std::map<std::string, std::string> &joints_to_actuators);
00084
00085 void loadTransmissions(TiXmlElement *robot, std::map<std::string, std::string> &joints_to_actuators);
00086
00087 void mechCallback(const pr2_mechanism_msgs::MechanismStatistics::ConstPtr& mechMsg);
00088
00089 bool reset_cb(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response)
00090 {
00091 for (uint i = 0; i < trans_listeners_.size(); ++i)
00092 trans_listeners_[i]->reset();
00093
00094 trans_status_ = true;
00095 return true;
00096 }
00097
00098 public:
00099 PR2TransmissionCheckNode();
00100
00101 ~PR2TransmissionCheckNode() { }
00102
00103
00104
00105 void publishDiag();
00107 bool ok() const { return n_.ok(); }
00108 };
00109
00110 }
00111
00112 #endif