converters/diagnostics.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2015 Aldebaran
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16  */
17 
18 /*
19 * LOCAL includes
20 */
21 #include "diagnostics.hpp"
22 #include "../tools/from_any_value.hpp"
23 
24 /*
25 * ROS includes
26 */
28 
29 /*
30 * BOOST includes
31 */
32 #include <boost/foreach.hpp>
33 #define for_each BOOST_FOREACH
34 
35 namespace
36 {
37 void setMessageFromStatus(diagnostic_updater::DiagnosticStatusWrapper &status)
38 {
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";
43  } else {
44  status.message = "ERROR";
45  }
46 }
47 }
48 
49 namespace naoqi
50 {
51 namespace converter
52 {
53 
54 DiagnosticsConverter::DiagnosticsConverter( const std::string& name, float frequency, const qi::SessionPtr& session ):
55  BaseConverter( name, frequency, session ),
56  p_memory_(session->service("ALMemory")),
57  temperature_warn_level_(68),
58  temperature_error_level_(74)
59 {
60  // Allow for temperature reporting (for CPU)
61  if ((robot_ == robot::PEPPER) || (robot_ == robot::NAO)) {
62  p_body_temperature_ = session->service("ALBodyTemperature");
63  p_body_temperature_.call<void>("setEnableNotifications", true);
64  }
65 
66  std::vector<std::vector<float> > joint_limits;
67  qi::AnyValue qi_joint_limits;
68 
69  // Get all the joint names
70  this->p_motion_ = session->service("ALMotion");
71  joint_names_ = this->p_motion_.call<std::vector<std::string> >("getBodyNames", "JointActuators");
72 
73  for(std::vector<std::string>::const_iterator it = joint_names_.begin(); it != joint_names_.end(); ++it) {
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"));
76 
77  // Get the joint limits
78  joint_limits.clear();
79 
80  try {
81  qi_joint_limits = this->p_motion_.call<qi::AnyValue>(
82  "getLimits",
83  (*it));
84 
85  } catch (const std::exception &e) {
86  std::cerr << "Exception caught in DiagnosticsConverter: "
87  << e.what()
88  << std::endl;
89  continue;
90  }
91 
92  try {
93  tools::fromAnyValueToFloatVectorVector(qi_joint_limits, joint_limits);
94 
95  } catch (std::exception &e) {
96  std::cerr << "Error while converting the qi value corresponding to "
97  << "the joint's limits : "
98  << e.what()
99  << std::endl;
100  continue;
101  }
102 
103  this->joint_limit_map_[(*it)].push_back(
104  static_cast<double>(joint_limits[0][0]));
105  this->joint_limit_map_[(*it)].push_back(
106  static_cast<double>(joint_limits[0][1]));
107  this->joint_limit_map_[(*it)].push_back(
108  static_cast<double>(joint_limits[0][2]));
109  this->joint_limit_map_[(*it)].push_back(
110  static_cast<double>(joint_limits[0][3]));
111  }
112 
113  // Get all the battery keys
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"));
118 
119  std::string battery_status_keys[] = {"Charging", "Fully Charged"};
120  battery_status_keys_ = std::vector<std::string>(battery_status_keys, battery_status_keys+2);
121 
122  // Get the CPU keys
123  // TODO check that: it is apparently always -1 ...
124  //all_keys_.push_back(std::string("HeadProcessorIsHot"));
125 
126  // TODO get ID from Device/DeviceList/ChestBoard/BodyId
127 }
128 
129 void DiagnosticsConverter::callAll( const std::vector<message_actions::MessageAction>& actions )
130 {
131  diagnostic_msgs::DiagnosticArray msg;
132  msg.header.stamp = ros::Time::now();
133 
134  // Get all the keys
135  //qi::details::printMetaObject(std::cout, p_memory_.metaObject());
136  std::vector<float> values;
137  try {
138  qi::AnyValue anyvalues = p_memory_.call<qi::AnyValue>("getListData", all_keys_);
139  tools::fromAnyValueToFloatVector(anyvalues, values);
140  } catch (const std::exception& e) {
141  std::cerr << "Exception caught in DiagnosticsConverter: " << e.what() << std::endl;
142  return;
143  }
144 
145  // Fill the temperature / stiffness message for the joints
146  double maxTemperature = 0.0;
147  double maxStiffness = 0.0;
148  double minStiffness = 1.0;
149  double minStiffnessWoHands = 1.0;
150  std::stringstream hotJointsSS;
151 
152  size_t val = 0;
153  diagnostic_msgs::DiagnosticStatus::_level_type max_level = diagnostic_msgs::DiagnosticStatus::OK;
154  for(size_t i = 0; i < joint_names_.size(); ++i)
155  {
157  status.name = std::string("naoqi_driver_joints:") + joint_names_[i];
158 
159  double temperature = static_cast<double>(values[val++]);
160  double stiffness = static_cast<double>(values[val++]);
161 
162  // Fill the status data
163  status.hardware_id = joint_names_[i];
164  status.add("Temperature", temperature);
165  status.add("Stiffness", stiffness);
166  status.add("minAngle", this->joint_limit_map_[joint_names_[i]][0]);
167  status.add("maxAngle", this->joint_limit_map_[joint_names_[i]][1]);
168  status.add("maxVelocity", this->joint_limit_map_[joint_names_[i]][2]);
169  status.add("maxTorque", this->joint_limit_map_[joint_names_[i]][3]);
170 
171  // Define the level
172  if (temperature < temperature_warn_level_)
173  {
174  status.level = diagnostic_msgs::DiagnosticStatus::OK;
175  status.message = "OK";
176  }
177  else if (temperature < temperature_error_level_)
178  {
179  status.level = diagnostic_msgs::DiagnosticStatus::WARN;
180  status.message = "Hot";
181  }
182  else
183  {
184  status.level = diagnostic_msgs::DiagnosticStatus::ERROR;
185  status.message = "Too hot";
186  }
187 
188  msg.status.push_back(status);
189 
190  // Fill the joint data for later processing
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);
195  if(joint_names_[i].find("Hand") == std::string::npos)
196  minStiffnessWoHands = std::min(minStiffnessWoHands, stiffness);
197  if(status.level >= (int) diagnostic_msgs::DiagnosticStatus::WARN) {
198  hotJointsSS << std::endl << joint_names_[i] << ": " << temperature << "°C";
199  }
200  }
201 
202  // Get the aggregated joints status
203  {
205  status.name = std::string("naoqi_driver_joints:Status");
206  status.hardware_id = "joints";
207  status.level = max_level;
208  setMessageFromStatus(status);
209 
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());
215 
216  msg.status.push_back(status);
217  }
218 
219  // Fill the message for the battery
220  {
221  int battery_percentage = static_cast<int>(values[val++]);
222 
224  status.name = std::string("naoqi_driver_battery:Status");
225  status.hardware_id = "battery";
226  status.add("Percentage", battery_percentage);
227  // Add the semantic info
228  std::stringstream ss;
229  for( size_t i = 0; i < battery_status_keys_.size(); ++i) {
230  bool value = bool(values[val++]);
231  status.add(battery_status_keys_[i], value);
232 
233  if (i == 0)
234  {
235  if (value)
236  {
237  status.level = diagnostic_msgs::DiagnosticStatus::OK;
238  ss << "Charging (" << std::setw(4) << battery_percentage << "%)";
239  }
240  else
241  {
242  if (battery_percentage > 60)
243  {
244  status.level = diagnostic_msgs::DiagnosticStatus::OK;
245  ss << "Battery OK (" << std::setw(4) << battery_percentage << "% left)";
246  }
247  else if (battery_percentage > 30)
248  {
249  status.level = diagnostic_msgs::DiagnosticStatus::WARN;
250  ss << "Battery discharging (" << std::setw(4) << battery_percentage << "% left)";
251  }
252  else
253  {
254  status.level = diagnostic_msgs::DiagnosticStatus::ERROR;
255  ss << "Battery almost empty (" << std::setw(4) << battery_percentage << "% left)";
256  }
257  }
258  }
259  else if ((i == 1) && value)
260  {
261  status.level = diagnostic_msgs::DiagnosticStatus::OK;
262  status.message = "Battery fully charged";
263  }
264  }
265  if (!ss.str().empty())
266  status.message = ss.str();
267 
268  max_level = status.level;
269  msg.status.push_back(status);
270  }
271 
272  // Process the current battery information
273  {
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;
281  if (current > 0)
282  ss << "Total Current: " << std::setw(5) << current << " Ampere (charging)";
283  else
284  ss << "Total Current: " << std::setw(5) << current << " Ampere (discharging)";
285  status.message = ss.str();
286  msg.status.push_back(status);
287  }
288 
289  // TODO: CPU information should be obtained from system files like done in Python
290  // We can still get the temperature
291  {
293  status.name = std::string("naoqi_driver_computer:CPU");
294  status.level = diagnostic_msgs::DiagnosticStatus::OK;
295  //status.add("Temperature", static_cast<float>(values[val++]));
296  // setting to -1 until we find the right key
297  status.add("Temperature", static_cast<float>(-1));
298 
299  msg.status.push_back(status);
300  }
301 
302  // TODO: wifi and ethernet statuses should be obtained from DBUS
303 
305  {
306  callbacks_[action]( msg);
307  }
308 
309 }
310 
312 {
313 }
314 
316 {
317  callbacks_[action] = cb;
318 }
319 
320 } //converter
321 } // naoqi
msg
std::vector< double > values
std::map< message_actions::MessageAction, Callback_t > callbacks_
void registerCallback(const message_actions::MessageAction action, Callback_t cb)
#define for_each
DiagnosticsConverter(const std::string &name, float frequency, const qi::SessionPtr &session)
boost::function< void(diagnostic_msgs::DiagnosticArray &) > Callback_t
action
std::map< std::string, std::vector< double > > joint_limit_map_
void callAll(const std::vector< message_actions::MessageAction > &actions)
std::vector< float > fromAnyValueToFloatVector(qi::AnyValue &value, std::vector< float > &result)
static Time now()
void add(const std::string &key, const T &val)
void fromAnyValueToFloatVectorVector(qi::AnyValue &value, std::vector< std::vector< float > > &result)


naoqi_driver
Author(s): Karsten Knese
autogenerated on Sat Feb 15 2020 03:24:26