Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021 #include "diagnostics.hpp"
00022 #include "../tools/from_any_value.hpp"
00023
00024
00025
00026
00027 #include <diagnostic_updater/DiagnosticStatusWrapper.h>
00028
00029
00030
00031
00032 #include <boost/foreach.hpp>
00033 #define for_each BOOST_FOREACH
00034
00035 namespace
00036 {
00037 void setMessageFromStatus(diagnostic_updater::DiagnosticStatusWrapper &status)
00038 {
00039 if (status.level == diagnostic_msgs::DiagnosticStatus::OK) {
00040 status.message = "OK";
00041 } else if (status.level == diagnostic_msgs::DiagnosticStatus::WARN) {
00042 status.message = "WARN";
00043 } else {
00044 status.message = "ERROR";
00045 }
00046 }
00047 }
00048
00049 namespace naoqi
00050 {
00051 namespace converter
00052 {
00053
00054 DiagnosticsConverter::DiagnosticsConverter( const std::string& name, float frequency, const qi::SessionPtr& session ):
00055 BaseConverter( name, frequency, session ),
00056 p_memory_(session->service("ALMemory")),
00057 temperature_warn_level_(68),
00058 temperature_error_level_(74)
00059 {
00060
00061 if ((robot_ == robot::PEPPER) || (robot_ == robot::NAO)) {
00062 p_body_temperature_ = session->service("ALBodyTemperature");
00063 p_body_temperature_.call<void>("setEnableNotifications", true);
00064 }
00065
00066
00067 qi::AnyObject p_motion = session->service("ALMotion");
00068 joint_names_ = p_motion.call<std::vector<std::string> >("getBodyNames", "JointActuators" );
00069
00070 for(std::vector<std::string>::const_iterator it = joint_names_.begin(); it != joint_names_.end(); ++it) {
00071 all_keys_.push_back(std::string("Device/SubDeviceList/") + (*it) + std::string("/Temperature/Sensor/Value"));
00072 all_keys_.push_back(std::string("Device/SubDeviceList/") + (*it) + std::string("/Hardness/Actuator/Value"));
00073 }
00074
00075
00076 all_keys_.push_back(std::string("BatteryChargeChanged"));
00077 all_keys_.push_back(std::string("BatteryPowerPluggedChanged"));
00078 all_keys_.push_back(std::string("BatteryFullChargedFlagChanged"));
00079 all_keys_.push_back(std::string("Device/SubDeviceList/Battery/Current/Sensor/Value"));
00080
00081 std::string battery_status_keys[] = {"Charging", "Fully Charged"};
00082 battery_status_keys_ = std::vector<std::string>(battery_status_keys, battery_status_keys+2);
00083
00084
00085
00086
00087
00088
00089 }
00090
00091 void DiagnosticsConverter::callAll( const std::vector<message_actions::MessageAction>& actions )
00092 {
00093 diagnostic_msgs::DiagnosticArray msg;
00094 msg.header.stamp = ros::Time::now();
00095
00096
00097
00098 std::vector<float> values;
00099 try {
00100 qi::AnyValue anyvalues = p_memory_.call<qi::AnyValue>("getListData", all_keys_);
00101 tools::fromAnyValueToFloatVector(anyvalues, values);
00102 } catch (const std::exception& e) {
00103 std::cerr << "Exception caught in DiagnosticsConverter: " << e.what() << std::endl;
00104 return;
00105 }
00106
00107
00108 double maxTemperature = 0.0;
00109 double maxStiffness = 0.0;
00110 double minStiffness = 1.0;
00111 double minStiffnessWoHands = 1.0;
00112 std::stringstream hotJointsSS;
00113
00114 size_t val = 0;
00115 diagnostic_msgs::DiagnosticStatus::_level_type max_level = diagnostic_msgs::DiagnosticStatus::OK;
00116 for(size_t i = 0; i < joint_names_.size(); ++i)
00117 {
00118 diagnostic_updater::DiagnosticStatusWrapper status;
00119 status.name = std::string("naoqi_driver_joints:") + joint_names_[i];
00120
00121 double temperature = static_cast<double>(values[val++]);
00122 double stiffness = static_cast<double>(values[val++]);
00123
00124
00125 status.hardware_id = joint_names_[i];
00126 status.add("Temperature", temperature);
00127 status.add("Stiffness", stiffness);
00128
00129
00130 if (temperature < temperature_warn_level_)
00131 {
00132 status.level = diagnostic_msgs::DiagnosticStatus::OK;
00133 status.message = "OK";
00134 }
00135 else if (temperature < temperature_error_level_)
00136 {
00137 status.level = diagnostic_msgs::DiagnosticStatus::WARN;
00138 status.message = "Hot";
00139 }
00140 else
00141 {
00142 status.level = diagnostic_msgs::DiagnosticStatus::ERROR;
00143 status.message = "Too hot";
00144 }
00145
00146 msg.status.push_back(status);
00147
00148
00149 max_level = std::max(max_level, status.level);
00150 maxTemperature = std::max(maxTemperature, temperature);
00151 maxStiffness = std::max(maxStiffness, stiffness);
00152 minStiffness = std::min(minStiffness, stiffness);
00153 if(joint_names_[i].find("Hand") == std::string::npos)
00154 minStiffnessWoHands = std::min(minStiffnessWoHands, stiffness);
00155 if(status.level >= (int) diagnostic_msgs::DiagnosticStatus::WARN) {
00156 hotJointsSS << std::endl << joint_names_[i] << ": " << temperature << "°C";
00157 }
00158 }
00159
00160
00161 {
00162 diagnostic_updater::DiagnosticStatusWrapper status;
00163 status.name = std::string("naoqi_driver_joints:Status");
00164 status.hardware_id = "joints";
00165 status.level = max_level;
00166 setMessageFromStatus(status);
00167
00168 status.add("Highest Temperature", maxTemperature);
00169 status.add("Highest Stiffness", maxStiffness);
00170 status.add("Lowest Stiffness", minStiffness);
00171 status.add("Lowest Stiffness without Hands", minStiffnessWoHands);
00172 status.add("Hot Joints", hotJointsSS.str());
00173
00174 msg.status.push_back(status);
00175 }
00176
00177
00178 {
00179 int battery_percentage = static_cast<int>(values[val++]);
00180
00181 diagnostic_updater::DiagnosticStatusWrapper status;
00182 status.name = std::string("naoqi_driver_battery:Status");
00183 status.hardware_id = "battery";
00184 status.add("Percentage", battery_percentage);
00185
00186 std::stringstream ss;
00187 for( size_t i = 0; i < battery_status_keys_.size(); ++i) {
00188 bool value = bool(values[val++]);
00189 status.add(battery_status_keys_[i], value);
00190
00191 if (i == 0)
00192 {
00193 if (value)
00194 {
00195 status.level = diagnostic_msgs::DiagnosticStatus::OK;
00196 ss << "Charging (" << std::setw(4) << battery_percentage << "%)";
00197 }
00198 else
00199 {
00200 if (battery_percentage > 60)
00201 {
00202 status.level = diagnostic_msgs::DiagnosticStatus::OK;
00203 ss << "Battery OK (" << std::setw(4) << battery_percentage << "% left)";
00204 }
00205 else if (battery_percentage > 30)
00206 {
00207 status.level = diagnostic_msgs::DiagnosticStatus::WARN;
00208 ss << "Battery discharging (" << std::setw(4) << battery_percentage << "% left)";
00209 }
00210 else
00211 {
00212 status.level = diagnostic_msgs::DiagnosticStatus::ERROR;
00213 ss << "Battery almost empty (" << std::setw(4) << battery_percentage << "% left)";
00214 }
00215 }
00216 }
00217 else if ((i == 1) && value)
00218 {
00219 status.level = diagnostic_msgs::DiagnosticStatus::OK;
00220 status.message = "Battery fully charged";
00221 }
00222 }
00223 if (!ss.str().empty())
00224 status.message = ss.str();
00225
00226 max_level = status.level;
00227 msg.status.push_back(status);
00228 }
00229
00230
00231 {
00232 float current = float(values[val++]);
00233 diagnostic_updater::DiagnosticStatusWrapper status;
00234 status.name = std::string("naoqi_driver_battery:Current");
00235 status.hardware_id = "battery";
00236 status.add("Current", current);
00237 status.level = max_level;
00238 std::ostringstream ss;
00239 if (current > 0)
00240 ss << "Total Current: " << std::setw(5) << current << " Ampere (charging)";
00241 else
00242 ss << "Total Current: " << std::setw(5) << current << " Ampere (discharging)";
00243 status.message = ss.str();
00244
00245 msg.status.push_back(status);
00246 }
00247
00248
00249
00250 {
00251 diagnostic_updater::DiagnosticStatusWrapper status;
00252 status.name = std::string("naoqi_driver_computer:CPU");
00253 status.level = diagnostic_msgs::DiagnosticStatus::OK;
00254
00255
00256 status.add("Temperature", static_cast<float>(-1));
00257
00258 msg.status.push_back(status);
00259 }
00260
00261
00262
00263 for_each( message_actions::MessageAction action, actions )
00264 {
00265 callbacks_[action]( msg);
00266 }
00267
00268 }
00269
00270 void DiagnosticsConverter::reset()
00271 {
00272 }
00273
00274 void DiagnosticsConverter::registerCallback( const message_actions::MessageAction action, Callback_t cb )
00275 {
00276 callbacks_[action] = cb;
00277 }
00278
00279 }
00280 }