00001 00006 #ifndef NAO_JOINTS_ANALYZER_H 00007 #define NAO_JOINTS_ANALYZER_H 00008 00009 #include <ros/ros.h> 00010 #include <diagnostic_aggregator/analyzer.h> 00011 #include <diagnostic_aggregator/status_item.h> 00012 #include <diagnostic_msgs/DiagnosticStatus.h> 00013 #include <pluginlib/class_list_macros.h> 00014 #include <string> 00015 #include <map> 00016 00017 namespace diagnostic_aggregator { 00018 00022 class NaoJointsAnalyzer: public Analyzer { 00023 public: 00024 NaoJointsAnalyzer(); 00025 ~NaoJointsAnalyzer(); 00026 bool init(const std::string base_name, const ros::NodeHandle &n); 00027 bool match(const std::string name); 00028 bool analyze(const boost::shared_ptr<StatusItem> item); 00029 std::vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> > report(); 00030 std::string getPath() const { 00031 return m_path; 00032 } 00033 std::string getName() const { 00034 return m_niceName; 00035 } 00036 00037 private: 00038 std::string m_path, m_niceName; 00039 boost::shared_ptr<StatusItem> m_jointsMasterItem; 00040 boost::shared_ptr<StatusItem> m_statusItems; 00041 ros::Time m_lastSeen; 00042 00043 struct JointData { 00044 std::string name; 00045 double temperature, stiffness; 00046 boost::shared_ptr<diagnostic_aggregator::StatusItem> status; 00047 }; 00048 typedef std::map<std::string, JointData> JointsMapType; 00049 JointsMapType m_joints; 00050 00051 template<typename T> void addValue(boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> joint_stat, const std::string& key, const T& value) const; 00052 static bool compareByTemperature(const NaoJointsAnalyzer::JointData& a, const NaoJointsAnalyzer::JointData& b); 00053 }; 00054 00055 } 00056 #endif //NAO_JOINTS_ANALYZER_H