$search
00001 00006 #include "NaoJointsAnalyzer.h" 00007 00008 #include <sstream> 00009 #include <fstream> 00010 00011 PLUGINLIB_DECLARE_CLASS(nao_dashboard, NaoJointsAnalyzer, 00012 diagnostic_aggregator::NaoJointsAnalyzer, 00013 diagnostic_aggregator::Analyzer) 00014 00015 namespace diagnostic_aggregator { 00016 00020 NaoJointsAnalyzer::NaoJointsAnalyzer() : 00021 m_path(""), m_niceName("Joints"), m_lastSeen(0) { 00022 } 00023 00027 NaoJointsAnalyzer::~NaoJointsAnalyzer() { 00028 } 00029 00030 bool NaoJointsAnalyzer::init(const std::string base_name, const ros::NodeHandle &n) { 00031 if (!n.getParam("path", m_niceName)) 00032 { 00033 ROS_ERROR("NaoJointsAnalyzer was not given parameter \"path\". Namespace: %s", 00034 n.getNamespace().c_str()); 00035 return false; 00036 } 00037 00038 m_path = base_name; 00039 00040 boost::shared_ptr<StatusItem> item(new StatusItem(m_niceName)); 00041 m_jointsMasterItem = item; 00042 00043 return true; 00044 } 00045 00046 bool NaoJointsAnalyzer::match(const std::string name) { 00047 return name.find("nao_joint") == 0; 00048 } 00049 00050 bool NaoJointsAnalyzer::analyze(const boost::shared_ptr<StatusItem> item) { 00051 if(item->getName().find("nao_joint") != 0) 00052 return false; 00053 00054 JointData data; 00055 00056 std::stringstream ssStiffness(item->getValue("Stiffness")); 00057 ssStiffness >> data.stiffness; 00058 00059 std::stringstream ssTemperature(item->getValue("Temperature")); 00060 ssTemperature >> data.temperature; 00061 00062 data.status = item; 00063 00064 if(m_joints.find(item->getName()) == m_joints.end()) 00065 m_joints.insert(make_pair(item->getName(), data)); 00066 else 00067 m_joints.at(item->getName()) = data; 00068 00069 m_lastSeen = ros::Time::now(); 00070 00071 return true; 00072 } 00073 00074 bool NaoJointsAnalyzer::compareByTemperature(const NaoJointsAnalyzer::JointData& a, const NaoJointsAnalyzer::JointData& b) { 00075 return (a.temperature > b.temperature); 00076 } 00077 00085 template<typename T> 00086 void NaoJointsAnalyzer::addValue(boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> joint_stat, const std::string& key, const T& value) const { 00087 std::stringstream ss; 00088 ss << value; 00089 diagnostic_msgs::KeyValue kv; 00090 kv.key = key; 00091 kv.value = ss.str(); 00092 joint_stat->values.push_back(kv); 00093 } 00094 00095 std::vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> > NaoJointsAnalyzer::report() { 00096 bool stale = (ros::Time::now()-m_lastSeen).toSec() > 5.0; 00097 boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> joint_stat = 00098 m_jointsMasterItem->toStatusMsg(m_path, stale); 00099 00100 std::vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> > output; 00101 if(stale) { 00102 output.push_back(joint_stat); 00103 return output; 00104 } 00105 00106 double maxTemperature = 0.0; 00107 double maxStiffness = 0.0; 00108 double minStiffness = 1.0; 00109 double minStiffnessWoHands = 1.0; 00110 00111 std::vector<JointData> hotJoints; 00112 joint_stat->level = diagnostic_msgs::DiagnosticStatus::OK; 00113 00114 for(JointsMapType::const_iterator it = m_joints.begin(); it != m_joints.end(); it++) { 00115 if(it->first.find("RHipYawPitch") == std::string::npos) { 00116 maxTemperature = std::max(maxTemperature, it->second.temperature); 00117 maxStiffness = std::max(maxStiffness, it->second.stiffness); 00118 minStiffness = std::min(minStiffness, it->second.stiffness); 00119 if(it->first.find("Hand") == std::string::npos) 00120 minStiffnessWoHands = std::min(minStiffnessWoHands, it->second.stiffness); 00121 if((int) it->second.status->getLevel() >= (int) diagnostic_msgs::DiagnosticStatus::WARN) { 00122 hotJoints.push_back(it->second); 00123 } 00124 if(it->second.status->getLevel() > joint_stat->level) 00125 joint_stat->level = it->second.status->getLevel(); 00126 } 00127 } 00128 00129 addValue(joint_stat, "Highest Temperature", maxTemperature); 00130 addValue(joint_stat, "Highest Stiffness", maxStiffness); 00131 addValue(joint_stat, "Lowest Stiffness", minStiffness); 00132 addValue(joint_stat, "Lowest Stiffness without Hands", minStiffnessWoHands); 00133 00134 std::sort(hotJoints.begin(), hotJoints.end(), NaoJointsAnalyzer::compareByTemperature); 00135 std::stringstream hotJointsSS; 00136 for(size_t i = 0; i < hotJoints.size(); i++) { 00137 hotJointsSS << std::endl << removeLeadingNameChaff(hotJoints[i].status->getName(), "nao_joint") << ": " << hotJoints[i].temperature << "°C"; 00138 } 00139 addValue(joint_stat, "Hot Joints", hotJointsSS.str()); 00140 00141 if (joint_stat->level == diagnostic_msgs::DiagnosticStatus::OK) { 00142 joint_stat->message = "OK"; 00143 } else if (joint_stat->level == diagnostic_msgs::DiagnosticStatus::WARN) { 00144 joint_stat->message = "WARN"; 00145 } else { 00146 joint_stat->message = "ERROR"; 00147 } 00148 00149 output.push_back(joint_stat); 00150 00151 for(JointsMapType::const_iterator it = m_joints.begin(); it != m_joints.end(); it++) { 00152 boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> msg(it->second.status->toStatusMsg(m_path + "/" + m_niceName, 00153 (ros::Time::now() - it->second.status->getLastUpdateTime()).toSec() > 3.0)); 00154 msg->name = m_path + "/" + m_niceName + "/" + removeLeadingNameChaff(it->second.status->getName(), "nao_joint"); 00155 output.push_back(msg); 00156 } 00157 00158 return output; 00159 } 00160 }