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 std::vector<std::vector<float> > joint_limits;
00067 qi::AnyValue qi_joint_limits;
00068
00069
00070 this->p_motion_ = session->service("ALMotion");
00071 joint_names_ = this->p_motion_.call<std::vector<std::string> >("getBodyNames", "JointActuators");
00072
00073 for(std::vector<std::string>::const_iterator it = joint_names_.begin(); it != joint_names_.end(); ++it) {
00074 all_keys_.push_back(std::string("Device/SubDeviceList/") + (*it) + std::string("/Temperature/Sensor/Value"));
00075 all_keys_.push_back(std::string("Device/SubDeviceList/") + (*it) + std::string("/Hardness/Actuator/Value"));
00076
00077
00078 joint_limits.clear();
00079
00080 try {
00081 qi_joint_limits = this->p_motion_.call<qi::AnyValue>(
00082 "getLimits",
00083 (*it));
00084
00085 } catch (const std::exception &e) {
00086 std::cerr << "Exception caught in DiagnosticsConverter: "
00087 << e.what()
00088 << std::endl;
00089 continue;
00090 }
00091
00092 try {
00093 tools::fromAnyValueToFloatVectorVector(qi_joint_limits, joint_limits);
00094
00095 } catch (std::exception &e) {
00096 std::cerr << "Error while converting the qi value corresponding to "
00097 << "the joint's limits : "
00098 << e.what()
00099 << std::endl;
00100 continue;
00101 }
00102
00103 this->joint_limit_map_[(*it)].push_back(
00104 static_cast<double>(joint_limits[0][0]));
00105 this->joint_limit_map_[(*it)].push_back(
00106 static_cast<double>(joint_limits[0][1]));
00107 this->joint_limit_map_[(*it)].push_back(
00108 static_cast<double>(joint_limits[0][2]));
00109 this->joint_limit_map_[(*it)].push_back(
00110 static_cast<double>(joint_limits[0][3]));
00111 }
00112
00113
00114 all_keys_.push_back(std::string("BatteryChargeChanged"));
00115 all_keys_.push_back(std::string("BatteryPowerPluggedChanged"));
00116 all_keys_.push_back(std::string("BatteryFullChargedFlagChanged"));
00117 all_keys_.push_back(std::string("Device/SubDeviceList/Battery/Current/Sensor/Value"));
00118
00119 std::string battery_status_keys[] = {"Charging", "Fully Charged"};
00120 battery_status_keys_ = std::vector<std::string>(battery_status_keys, battery_status_keys+2);
00121
00122
00123
00124
00125
00126
00127 }
00128
00129 void DiagnosticsConverter::callAll( const std::vector<message_actions::MessageAction>& actions )
00130 {
00131 diagnostic_msgs::DiagnosticArray msg;
00132 msg.header.stamp = ros::Time::now();
00133
00134
00135
00136 std::vector<float> values;
00137 try {
00138 qi::AnyValue anyvalues = p_memory_.call<qi::AnyValue>("getListData", all_keys_);
00139 tools::fromAnyValueToFloatVector(anyvalues, values);
00140 } catch (const std::exception& e) {
00141 std::cerr << "Exception caught in DiagnosticsConverter: " << e.what() << std::endl;
00142 return;
00143 }
00144
00145
00146 double maxTemperature = 0.0;
00147 double maxStiffness = 0.0;
00148 double minStiffness = 1.0;
00149 double minStiffnessWoHands = 1.0;
00150 std::stringstream hotJointsSS;
00151
00152 size_t val = 0;
00153 diagnostic_msgs::DiagnosticStatus::_level_type max_level = diagnostic_msgs::DiagnosticStatus::OK;
00154 for(size_t i = 0; i < joint_names_.size(); ++i)
00155 {
00156 diagnostic_updater::DiagnosticStatusWrapper status;
00157 status.name = std::string("naoqi_driver_joints:") + joint_names_[i];
00158
00159 double temperature = static_cast<double>(values[val++]);
00160 double stiffness = static_cast<double>(values[val++]);
00161
00162
00163 status.hardware_id = joint_names_[i];
00164 status.add("Temperature", temperature);
00165 status.add("Stiffness", stiffness);
00166 status.add("minAngle", this->joint_limit_map_[joint_names_[i]][0]);
00167 status.add("maxAngle", this->joint_limit_map_[joint_names_[i]][1]);
00168 status.add("maxVelocity", this->joint_limit_map_[joint_names_[i]][2]);
00169 status.add("maxTorque", this->joint_limit_map_[joint_names_[i]][3]);
00170
00171
00172 if (temperature < temperature_warn_level_)
00173 {
00174 status.level = diagnostic_msgs::DiagnosticStatus::OK;
00175 status.message = "OK";
00176 }
00177 else if (temperature < temperature_error_level_)
00178 {
00179 status.level = diagnostic_msgs::DiagnosticStatus::WARN;
00180 status.message = "Hot";
00181 }
00182 else
00183 {
00184 status.level = diagnostic_msgs::DiagnosticStatus::ERROR;
00185 status.message = "Too hot";
00186 }
00187
00188 msg.status.push_back(status);
00189
00190
00191 max_level = std::max(max_level, status.level);
00192 maxTemperature = std::max(maxTemperature, temperature);
00193 maxStiffness = std::max(maxStiffness, stiffness);
00194 minStiffness = std::min(minStiffness, stiffness);
00195 if(joint_names_[i].find("Hand") == std::string::npos)
00196 minStiffnessWoHands = std::min(minStiffnessWoHands, stiffness);
00197 if(status.level >= (int) diagnostic_msgs::DiagnosticStatus::WARN) {
00198 hotJointsSS << std::endl << joint_names_[i] << ": " << temperature << "°C";
00199 }
00200 }
00201
00202
00203 {
00204 diagnostic_updater::DiagnosticStatusWrapper status;
00205 status.name = std::string("naoqi_driver_joints:Status");
00206 status.hardware_id = "joints";
00207 status.level = max_level;
00208 setMessageFromStatus(status);
00209
00210 status.add("Highest Temperature", maxTemperature);
00211 status.add("Highest Stiffness", maxStiffness);
00212 status.add("Lowest Stiffness", minStiffness);
00213 status.add("Lowest Stiffness without Hands", minStiffnessWoHands);
00214 status.add("Hot Joints", hotJointsSS.str());
00215
00216 msg.status.push_back(status);
00217 }
00218
00219
00220 {
00221 int battery_percentage = static_cast<int>(values[val++]);
00222
00223 diagnostic_updater::DiagnosticStatusWrapper status;
00224 status.name = std::string("naoqi_driver_battery:Status");
00225 status.hardware_id = "battery";
00226 status.add("Percentage", battery_percentage);
00227
00228 std::stringstream ss;
00229 for( size_t i = 0; i < battery_status_keys_.size(); ++i) {
00230 bool value = bool(values[val++]);
00231 status.add(battery_status_keys_[i], value);
00232
00233 if (i == 0)
00234 {
00235 if (value)
00236 {
00237 status.level = diagnostic_msgs::DiagnosticStatus::OK;
00238 ss << "Charging (" << std::setw(4) << battery_percentage << "%)";
00239 }
00240 else
00241 {
00242 if (battery_percentage > 60)
00243 {
00244 status.level = diagnostic_msgs::DiagnosticStatus::OK;
00245 ss << "Battery OK (" << std::setw(4) << battery_percentage << "% left)";
00246 }
00247 else if (battery_percentage > 30)
00248 {
00249 status.level = diagnostic_msgs::DiagnosticStatus::WARN;
00250 ss << "Battery discharging (" << std::setw(4) << battery_percentage << "% left)";
00251 }
00252 else
00253 {
00254 status.level = diagnostic_msgs::DiagnosticStatus::ERROR;
00255 ss << "Battery almost empty (" << std::setw(4) << battery_percentage << "% left)";
00256 }
00257 }
00258 }
00259 else if ((i == 1) && value)
00260 {
00261 status.level = diagnostic_msgs::DiagnosticStatus::OK;
00262 status.message = "Battery fully charged";
00263 }
00264 }
00265 if (!ss.str().empty())
00266 status.message = ss.str();
00267
00268 max_level = status.level;
00269 msg.status.push_back(status);
00270 }
00271
00272
00273 {
00274 float current = float(values[val++]);
00275 diagnostic_updater::DiagnosticStatusWrapper status;
00276 status.name = std::string("naoqi_driver_battery:Current");
00277 status.hardware_id = "battery";
00278 status.add("Current", current);
00279 status.level = max_level;
00280 std::ostringstream ss;
00281 if (current > 0)
00282 ss << "Total Current: " << std::setw(5) << current << " Ampere (charging)";
00283 else
00284 ss << "Total Current: " << std::setw(5) << current << " Ampere (discharging)";
00285 status.message = ss.str();
00286 msg.status.push_back(status);
00287 }
00288
00289
00290
00291 {
00292 diagnostic_updater::DiagnosticStatusWrapper status;
00293 status.name = std::string("naoqi_driver_computer:CPU");
00294 status.level = diagnostic_msgs::DiagnosticStatus::OK;
00295
00296
00297 status.add("Temperature", static_cast<float>(-1));
00298
00299 msg.status.push_back(status);
00300 }
00301
00302
00303
00304 for_each( message_actions::MessageAction action, actions )
00305 {
00306 callbacks_[action]( msg);
00307 }
00308
00309 }
00310
00311 void DiagnosticsConverter::reset()
00312 {
00313 }
00314
00315 void DiagnosticsConverter::registerCallback( const message_actions::MessageAction action, Callback_t cb )
00316 {
00317 callbacks_[action] = cb;
00318 }
00319
00320 }
00321 }