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")),
57 temperature_warn_level_(68),
58 temperature_error_level_(74)
66 std::vector<std::vector<float> > joint_limits;
67 qi::AnyValue qi_joint_limits;
70 this->
p_motion_ = session->service(
"ALMotion");
74 all_keys_.push_back(std::string(
"Device/SubDeviceList/") + (*it) + std::string(
"/Temperature/Sensor/Value"));
75 all_keys_.push_back(std::string(
"Device/SubDeviceList/") + (*it) + std::string(
"/Hardness/Actuator/Value"));
81 qi_joint_limits = this->
p_motion_.call<qi::AnyValue>(
85 }
catch (
const std::exception &e) {
86 std::cerr <<
"Exception caught in DiagnosticsConverter: " 95 }
catch (std::exception &e) {
96 std::cerr <<
"Error while converting the qi value corresponding to " 97 <<
"the joint's limits : " 104 static_cast<double>(joint_limits[0][0]));
106 static_cast<double>(joint_limits[0][1]));
108 static_cast<double>(joint_limits[0][2]));
110 static_cast<double>(joint_limits[0][3]));
114 all_keys_.push_back(std::string(
"BatteryChargeChanged"));
115 all_keys_.push_back(std::string(
"BatteryPowerPluggedChanged"));
116 all_keys_.push_back(std::string(
"BatteryFullChargedFlagChanged"));
117 all_keys_.push_back(std::string(
"Device/SubDeviceList/Battery/Current/Sensor/Value"));
119 std::string battery_status_keys[] = {
"Charging",
"Fully Charged"};
131 diagnostic_msgs::DiagnosticArray
msg;
136 std::vector<float>
values;
140 }
catch (
const std::exception& e) {
141 std::cerr <<
"Exception caught in DiagnosticsConverter: " << e.what() << std::endl;
146 double maxTemperature = 0.0;
147 double maxStiffness = 0.0;
148 double minStiffness = 1.0;
149 double minStiffnessWoHands = 1.0;
150 std::stringstream hotJointsSS;
153 diagnostic_msgs::DiagnosticStatus::_level_type max_level = diagnostic_msgs::DiagnosticStatus::OK;
157 status.name = std::string(
"naoqi_driver_joints:") +
joint_names_[i];
159 double temperature =
static_cast<double>(values[val++]);
160 double stiffness =
static_cast<double>(values[val++]);
164 status.
add(
"Temperature", temperature);
165 status.
add(
"Stiffness", stiffness);
174 status.level = diagnostic_msgs::DiagnosticStatus::OK;
175 status.message =
"OK";
179 status.level = diagnostic_msgs::DiagnosticStatus::WARN;
180 status.message =
"Hot";
184 status.level = diagnostic_msgs::DiagnosticStatus::ERROR;
185 status.message =
"Too hot";
188 msg.status.push_back(status);
191 max_level = std::max(max_level, status.level);
192 maxTemperature = std::max(maxTemperature, temperature);
193 maxStiffness = std::max(maxStiffness, stiffness);
194 minStiffness = std::min(minStiffness, stiffness);
196 minStiffnessWoHands = std::min(minStiffnessWoHands, stiffness);
197 if(status.level >= (
int) diagnostic_msgs::DiagnosticStatus::WARN) {
198 hotJointsSS << std::endl <<
joint_names_[i] <<
": " << temperature <<
"°C";
205 status.name = std::string(
"naoqi_driver_joints:Status");
206 status.hardware_id =
"joints";
207 status.level = max_level;
208 setMessageFromStatus(status);
210 status.
add(
"Highest Temperature", maxTemperature);
211 status.
add(
"Highest Stiffness", maxStiffness);
212 status.
add(
"Lowest Stiffness", minStiffness);
213 status.
add(
"Lowest Stiffness without Hands", minStiffnessWoHands);
214 status.
add(
"Hot Joints", hotJointsSS.str());
216 msg.status.push_back(status);
221 int battery_percentage =
static_cast<int>(values[val++]);
224 status.name = std::string(
"naoqi_driver_battery:Status");
225 status.hardware_id =
"battery";
226 status.
add(
"Percentage", battery_percentage);
228 std::stringstream ss;
230 bool value = bool(values[val++]);
237 status.level = diagnostic_msgs::DiagnosticStatus::OK;
238 ss <<
"Charging (" << std::setw(4) << battery_percentage <<
"%)";
242 if (battery_percentage > 60)
244 status.level = diagnostic_msgs::DiagnosticStatus::OK;
245 ss <<
"Battery OK (" << std::setw(4) << battery_percentage <<
"% left)";
247 else if (battery_percentage > 30)
249 status.level = diagnostic_msgs::DiagnosticStatus::WARN;
250 ss <<
"Battery discharging (" << std::setw(4) << battery_percentage <<
"% left)";
254 status.level = diagnostic_msgs::DiagnosticStatus::ERROR;
255 ss <<
"Battery almost empty (" << std::setw(4) << battery_percentage <<
"% left)";
259 else if ((i == 1) && value)
261 status.level = diagnostic_msgs::DiagnosticStatus::OK;
262 status.message =
"Battery fully charged";
265 if (!ss.str().empty())
266 status.message = ss.str();
268 max_level = status.level;
269 msg.status.push_back(status);
274 float current = float(values[val++]);
276 status.name = std::string(
"naoqi_driver_battery:Current");
277 status.hardware_id =
"battery";
278 status.
add(
"Current", current);
279 status.level = max_level;
280 std::ostringstream ss;
282 ss <<
"Total Current: " << std::setw(5) << current <<
" Ampere (charging)";
284 ss <<
"Total Current: " << std::setw(5) << current <<
" Ampere (discharging)";
285 status.message = ss.str();
286 msg.status.push_back(status);
293 status.name = std::string(
"naoqi_driver_computer:CPU");
294 status.level = diagnostic_msgs::DiagnosticStatus::OK;
297 status.
add(
"Temperature", static_cast<float>(-1));
299 msg.status.push_back(status);
float temperature_warn_level_
std::vector< double > values
std::map< message_actions::MessageAction, Callback_t > callbacks_
std::vector< std::string > joint_names_
void registerCallback(const message_actions::MessageAction action, Callback_t cb)
const robot::Robot & robot_
float temperature_error_level_
std::vector< std::string > all_keys_
DiagnosticsConverter(const std::string &name, float frequency, const qi::SessionPtr &session)
boost::function< void(diagnostic_msgs::DiagnosticArray &) > Callback_t
std::map< std::string, std::vector< double > > joint_limit_map_
void callAll(const std::vector< message_actions::MessageAction > &actions)
std::vector< std::string > battery_status_keys_
void add(const std::string &key, const T &val)
qi::AnyObject p_body_temperature_