22 #include "../tools/from_any_value.hpp"
32 #include <boost/foreach.hpp>
33 #define for_each BOOST_FOREACH
39 if (status.level == diagnostic_msgs::DiagnosticStatus::OK) {
40 status.message =
"OK";
41 }
else if (status.level == diagnostic_msgs::DiagnosticStatus::WARN) {
42 status.message =
"WARN";
44 status.message =
"ERROR";
56 p_memory_(
session->service(
"ALMemory").value()),
57 temperature_warn_level_(68),
58 temperature_error_level_(74)
71 std::vector<std::vector<float> > joint_limits;
72 qi::AnyValue qi_joint_limits;
75 this->
p_motion_ = session->service(
"ALMotion").value();
79 all_keys_.push_back(std::string(
"Device/SubDeviceList/") + (*it) + std::string(
"/Temperature/Sensor/Value"));
80 all_keys_.push_back(std::string(
"Device/SubDeviceList/") + (*it) + std::string(
"/Hardness/Actuator/Value"));
86 qi_joint_limits = this->
p_motion_.call<qi::AnyValue>(
90 }
catch (
const std::exception &e) {
91 std::cerr <<
"Exception caught in DiagnosticsConverter: "
100 }
catch (std::exception &e) {
101 std::cerr <<
"Error while converting the qi value corresponding to "
102 <<
"the joint's limits : "
109 static_cast<double>(joint_limits[0][0]));
111 static_cast<double>(joint_limits[0][1]));
113 static_cast<double>(joint_limits[0][2]));
115 static_cast<double>(joint_limits[0][3]));
119 all_keys_.push_back(std::string(
"BatteryChargeChanged"));
120 all_keys_.push_back(std::string(
"BatteryPowerPluggedChanged"));
121 all_keys_.push_back(std::string(
"BatteryFullChargedFlagChanged"));
122 all_keys_.push_back(std::string(
"Device/SubDeviceList/Battery/Current/Sensor/Value"));
124 std::string battery_status_keys[] = {
"Charging",
"Fully Charged"};
136 diagnostic_msgs::DiagnosticArray
msg;
141 std::vector<float>
values;
145 }
catch (
const std::exception& e) {
146 std::cerr <<
"Exception caught in DiagnosticsConverter: " << e.what() << std::endl;
151 double maxTemperature = 0.0;
152 double maxStiffness = 0.0;
153 double minStiffness = 1.0;
154 double minStiffnessWoHands = 1.0;
155 std::stringstream hotJointsSS;
158 diagnostic_msgs::DiagnosticStatus::_level_type max_level = diagnostic_msgs::DiagnosticStatus::OK;
162 status.name = std::string(
"naoqi_driver_joints:") +
joint_names_[i];
164 double temperature =
static_cast<double>(
values[val++]);
165 double stiffness =
static_cast<double>(
values[val++]);
169 status.
add(
"Temperature", temperature);
170 status.
add(
"Stiffness", stiffness);
179 status.level = diagnostic_msgs::DiagnosticStatus::OK;
180 status.message =
"OK";
184 status.level = diagnostic_msgs::DiagnosticStatus::WARN;
185 status.message =
"Hot";
189 status.level = diagnostic_msgs::DiagnosticStatus::ERROR;
190 status.message =
"Too hot";
193 msg.status.push_back(status);
196 max_level = std::max(max_level, status.level);
197 maxTemperature = std::max(maxTemperature, temperature);
198 maxStiffness = std::max(maxStiffness, stiffness);
199 minStiffness = std::min(minStiffness, stiffness);
201 minStiffnessWoHands = std::min(minStiffnessWoHands, stiffness);
202 if(status.level >= (
int) diagnostic_msgs::DiagnosticStatus::WARN) {
203 hotJointsSS << std::endl <<
joint_names_[i] <<
": " << temperature <<
"°C";
210 status.name = std::string(
"naoqi_driver_joints:Status");
211 status.hardware_id =
"joints";
212 status.level = max_level;
213 setMessageFromStatus(status);
215 status.
add(
"Highest Temperature", maxTemperature);
216 status.
add(
"Highest Stiffness", maxStiffness);
217 status.
add(
"Lowest Stiffness", minStiffness);
218 status.
add(
"Lowest Stiffness without Hands", minStiffnessWoHands);
219 status.
add(
"Hot Joints", hotJointsSS.str());
221 msg.status.push_back(status);
226 int battery_percentage =
static_cast<int>(
values[val++]);
229 status.name = std::string(
"naoqi_driver_battery:Status");
230 status.hardware_id =
"battery";
231 status.
add(
"Percentage", battery_percentage);
233 std::stringstream ss;
235 bool value = bool(
values[val++]);
242 status.level = diagnostic_msgs::DiagnosticStatus::OK;
243 ss <<
"Charging (" << std::setw(4) << battery_percentage <<
"%)";
247 if (battery_percentage > 60)
249 status.level = diagnostic_msgs::DiagnosticStatus::OK;
250 ss <<
"Battery OK (" << std::setw(4) << battery_percentage <<
"% left)";
252 else if (battery_percentage > 30)
254 status.level = diagnostic_msgs::DiagnosticStatus::WARN;
255 ss <<
"Battery discharging (" << std::setw(4) << battery_percentage <<
"% left)";
259 status.level = diagnostic_msgs::DiagnosticStatus::ERROR;
260 ss <<
"Battery almost empty (" << std::setw(4) << battery_percentage <<
"% left)";
264 else if ((i == 1) && value)
266 status.level = diagnostic_msgs::DiagnosticStatus::OK;
267 status.message =
"Battery fully charged";
270 if (!ss.str().empty())
271 status.message = ss.str();
273 max_level = status.level;
274 msg.status.push_back(status);
279 float current = float(
values[val++]);
281 status.name = std::string(
"naoqi_driver_battery:Current");
282 status.hardware_id =
"battery";
283 status.
add(
"Current", current);
284 status.level = max_level;
285 std::ostringstream ss;
287 ss <<
"Total Current: " << std::setw(5) << current <<
" Ampere (charging)";
289 ss <<
"Total Current: " << std::setw(5) << current <<
" Ampere (discharging)";
290 status.message = ss.str();
291 msg.status.push_back(status);
298 status.name = std::string(
"naoqi_driver_computer:CPU");
299 status.level = diagnostic_msgs::DiagnosticStatus::OK;
302 status.
add(
"Temperature",
static_cast<float>(-1));
304 msg.status.push_back(status);