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").value()),
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").value();
63 
64  // Only call setEnableNotifications if NAOqi < 2.9
66  {
67  p_body_temperature_.call<void>("setEnableNotifications", true);
68  }
69  }
70 
71  std::vector<std::vector<float> > joint_limits;
72  qi::AnyValue qi_joint_limits;
73 
74  // Get all the joint names
75  this->p_motion_ = session->service("ALMotion").value();
76  joint_names_ = this->p_motion_.call<std::vector<std::string> >("getBodyNames", "JointActuators");
77 
78  for(std::vector<std::string>::const_iterator it = joint_names_.begin(); it != joint_names_.end(); ++it) {
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"));
81 
82  // Get the joint limits
83  joint_limits.clear();
84 
85  try {
86  qi_joint_limits = this->p_motion_.call<qi::AnyValue>(
87  "getLimits",
88  (*it));
89 
90  } catch (const std::exception &e) {
91  std::cerr << "Exception caught in DiagnosticsConverter: "
92  << e.what()
93  << std::endl;
94  continue;
95  }
96 
97  try {
98  tools::fromAnyValueToFloatVectorVector(qi_joint_limits, joint_limits);
99 
100  } catch (std::exception &e) {
101  std::cerr << "Error while converting the qi value corresponding to "
102  << "the joint's limits : "
103  << e.what()
104  << std::endl;
105  continue;
106  }
107 
108  this->joint_limit_map_[(*it)].push_back(
109  static_cast<double>(joint_limits[0][0]));
110  this->joint_limit_map_[(*it)].push_back(
111  static_cast<double>(joint_limits[0][1]));
112  this->joint_limit_map_[(*it)].push_back(
113  static_cast<double>(joint_limits[0][2]));
114  this->joint_limit_map_[(*it)].push_back(
115  static_cast<double>(joint_limits[0][3]));
116  }
117 
118  // Get all the battery keys
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"));
123 
124  std::string battery_status_keys[] = {"Charging", "Fully Charged"};
125  battery_status_keys_ = std::vector<std::string>(battery_status_keys, battery_status_keys+2);
126 
127  // Get the CPU keys
128  // TODO check that: it is apparently always -1 ...
129  //all_keys_.push_back(std::string("HeadProcessorIsHot"));
130 
131  // TODO get ID from Device/DeviceList/ChestBoard/BodyId
132 }
133 
134 void DiagnosticsConverter::callAll( const std::vector<message_actions::MessageAction>& actions )
135 {
136  diagnostic_msgs::DiagnosticArray msg;
137  msg.header.stamp = ros::Time::now();
138 
139  // Get all the keys
140  //qi::details::printMetaObject(std::cout, p_memory_.metaObject());
141  std::vector<float> values;
142  try {
143  qi::AnyValue anyvalues = p_memory_.call<qi::AnyValue>("getListData", all_keys_);
145  } catch (const std::exception& e) {
146  std::cerr << "Exception caught in DiagnosticsConverter: " << e.what() << std::endl;
147  return;
148  }
149 
150  // Fill the temperature / stiffness message for the joints
151  double maxTemperature = 0.0;
152  double maxStiffness = 0.0;
153  double minStiffness = 1.0;
154  double minStiffnessWoHands = 1.0;
155  std::stringstream hotJointsSS;
156 
157  size_t val = 0;
158  diagnostic_msgs::DiagnosticStatus::_level_type max_level = diagnostic_msgs::DiagnosticStatus::OK;
159  for(size_t i = 0; i < joint_names_.size(); ++i)
160  {
162  status.name = std::string("naoqi_driver_joints:") + joint_names_[i];
163 
164  double temperature = static_cast<double>(values[val++]);
165  double stiffness = static_cast<double>(values[val++]);
166 
167  // Fill the status data
168  status.hardware_id = joint_names_[i];
169  status.add("Temperature", temperature);
170  status.add("Stiffness", stiffness);
171  status.add("minAngle", this->joint_limit_map_[joint_names_[i]][0]);
172  status.add("maxAngle", this->joint_limit_map_[joint_names_[i]][1]);
173  status.add("maxVelocity", this->joint_limit_map_[joint_names_[i]][2]);
174  status.add("maxTorque", this->joint_limit_map_[joint_names_[i]][3]);
175 
176  // Define the level
177  if (temperature < temperature_warn_level_)
178  {
179  status.level = diagnostic_msgs::DiagnosticStatus::OK;
180  status.message = "OK";
181  }
182  else if (temperature < temperature_error_level_)
183  {
184  status.level = diagnostic_msgs::DiagnosticStatus::WARN;
185  status.message = "Hot";
186  }
187  else
188  {
189  status.level = diagnostic_msgs::DiagnosticStatus::ERROR;
190  status.message = "Too hot";
191  }
192 
193  msg.status.push_back(status);
194 
195  // Fill the joint data for later processing
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);
200  if(joint_names_[i].find("Hand") == std::string::npos)
201  minStiffnessWoHands = std::min(minStiffnessWoHands, stiffness);
202  if(status.level >= (int) diagnostic_msgs::DiagnosticStatus::WARN) {
203  hotJointsSS << std::endl << joint_names_[i] << ": " << temperature << "°C";
204  }
205  }
206 
207  // Get the aggregated joints status
208  {
210  status.name = std::string("naoqi_driver_joints:Status");
211  status.hardware_id = "joints";
212  status.level = max_level;
213  setMessageFromStatus(status);
214 
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());
220 
221  msg.status.push_back(status);
222  }
223 
224  // Fill the message for the battery
225  {
226  int battery_percentage = static_cast<int>(values[val++]);
227 
229  status.name = std::string("naoqi_driver_battery:Status");
230  status.hardware_id = "battery";
231  status.add("Percentage", battery_percentage);
232  // Add the semantic info
233  std::stringstream ss;
234  for( size_t i = 0; i < battery_status_keys_.size(); ++i) {
235  bool value = bool(values[val++]);
236  status.add(battery_status_keys_[i], value);
237 
238  if (i == 0)
239  {
240  if (value)
241  {
242  status.level = diagnostic_msgs::DiagnosticStatus::OK;
243  ss << "Charging (" << std::setw(4) << battery_percentage << "%)";
244  }
245  else
246  {
247  if (battery_percentage > 60)
248  {
249  status.level = diagnostic_msgs::DiagnosticStatus::OK;
250  ss << "Battery OK (" << std::setw(4) << battery_percentage << "% left)";
251  }
252  else if (battery_percentage > 30)
253  {
254  status.level = diagnostic_msgs::DiagnosticStatus::WARN;
255  ss << "Battery discharging (" << std::setw(4) << battery_percentage << "% left)";
256  }
257  else
258  {
259  status.level = diagnostic_msgs::DiagnosticStatus::ERROR;
260  ss << "Battery almost empty (" << std::setw(4) << battery_percentage << "% left)";
261  }
262  }
263  }
264  else if ((i == 1) && value)
265  {
266  status.level = diagnostic_msgs::DiagnosticStatus::OK;
267  status.message = "Battery fully charged";
268  }
269  }
270  if (!ss.str().empty())
271  status.message = ss.str();
272 
273  max_level = status.level;
274  msg.status.push_back(status);
275  }
276 
277  // Process the current battery information
278  {
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;
286  if (current > 0)
287  ss << "Total Current: " << std::setw(5) << current << " Ampere (charging)";
288  else
289  ss << "Total Current: " << std::setw(5) << current << " Ampere (discharging)";
290  status.message = ss.str();
291  msg.status.push_back(status);
292  }
293 
294  // TODO: CPU information should be obtained from system files like done in Python
295  // We can still get the temperature
296  {
298  status.name = std::string("naoqi_driver_computer:CPU");
299  status.level = diagnostic_msgs::DiagnosticStatus::OK;
300  //status.add("Temperature", static_cast<float>(values[val++]));
301  // setting to -1 until we find the right key
302  status.add("Temperature", static_cast<float>(-1));
303 
304  msg.status.push_back(status);
305  }
306 
307  // TODO: wifi and ethernet statuses should be obtained from DBUS
308 
309  for_each( message_actions::MessageAction action, actions )
310  {
311  callbacks_[action]( msg);
312  }
313 
314 }
315 
317 {
318 }
319 
321 {
322  callbacks_[action] = cb;
323 }
324 
325 } //converter
326 } // naoqi
naoqi::converter::DiagnosticsConverter::DiagnosticsConverter
DiagnosticsConverter(const std::string &name, float frequency, const qi::SessionPtr &session)
Definition: converters/diagnostics.cpp:54
msg
msg
diagnostic_updater::DiagnosticStatusWrapper::add
void add(const std::string &key, const bool &b)
converter
naoqi::converter::DiagnosticsConverter::callbacks_
std::map< message_actions::MessageAction, Callback_t > callbacks_
Definition: converters/diagnostics.hpp:76
session
session
naoqi::message_actions::MessageAction
MessageAction
Definition: message_actions.h:9
diagnostics.hpp
naoqi::converter::DiagnosticsConverter::Callback_t
boost::function< void(diagnostic_msgs::DiagnosticArray &) > Callback_t
Definition: converters/diagnostics.hpp:45
naoqi::converter::DiagnosticsConverter::battery_status_keys_
std::vector< std::string > battery_status_keys_
Definition: converters/diagnostics.hpp:62
naoqi::tools::fromAnyValueToFloatVectorVector
void fromAnyValueToFloatVectorVector(qi::AnyValue &value, std::vector< std::vector< float > > &result)
Definition: from_any_value.cpp:222
naoqi::converter::DiagnosticsConverter::p_body_temperature_
qi::AnyObject p_body_temperature_
Definition: converters/diagnostics.hpp:70
naoqi::converter::DiagnosticsConverter::joint_names_
std::vector< std::string > joint_names_
Definition: converters/diagnostics.hpp:58
naoqi::tools::fromAnyValueToFloatVector
std::vector< float > fromAnyValueToFloatVector(qi::AnyValue &value, std::vector< float > &result)
Definition: from_any_value.cpp:185
naoqi
Definition: converter.hpp:29
naoqi::converter::BaseConverter< DiagnosticsConverter >::naoqi_version_
const robot::NaoqiVersion & naoqi_version_
Definition: converter_base.hpp:73
naoqi::converter::DiagnosticsConverter::reset
void reset()
Definition: converters/diagnostics.cpp:316
for_each
#define for_each
Definition: converters/diagnostics.cpp:33
naoqi::converter::DiagnosticsConverter::temperature_warn_level_
float temperature_warn_level_
Definition: converters/diagnostics.hpp:72
naoqi::converter::DiagnosticsConverter::registerCallback
void registerCallback(const message_actions::MessageAction action, Callback_t cb)
Definition: converters/diagnostics.cpp:320
DiagnosticStatusWrapper.h
naoqi::converter::DiagnosticsConverter::p_motion_
qi::AnyObject p_motion_
Definition: converters/diagnostics.hpp:68
naoqi::helpers::driver::isNaoqiVersionLesser
bool isNaoqiVersionLesser(const robot::NaoqiVersion &naoqi_version, const int &major, const int &minor, const int &patch, const int &build)
Function that returns true if the provided naoqi_version is (strictly) lesser than the specified one ...
Definition: driver_helpers.cpp:408
name
name
naoqi::converter::BaseConverter
Definition: converter_base.hpp:40
naoqi::converter::DiagnosticsConverter::all_keys_
std::vector< std::string > all_keys_
Definition: converters/diagnostics.hpp:60
naoqi::robot::PEPPER
@ PEPPER
Definition: tools.hpp:41
naoqi::converter::DiagnosticsConverter::callAll
void callAll(const std::vector< message_actions::MessageAction > &actions)
Definition: converters/diagnostics.cpp:134
values
std::vector< double > values
naoqi::converter::DiagnosticsConverter::p_memory_
qi::AnyObject p_memory_
Definition: converters/diagnostics.hpp:66
naoqi::robot::NAO
@ NAO
Definition: tools.hpp:40
naoqi::converter::DiagnosticsConverter::temperature_error_level_
float temperature_error_level_
Definition: converters/diagnostics.hpp:73
diagnostic_updater::DiagnosticStatusWrapper
naoqi::converter::DiagnosticsConverter::joint_limit_map_
std::map< std::string, std::vector< double > > joint_limit_map_
Definition: converters/diagnostics.hpp:64
ros::Time::now
static Time now()
naoqi::converter::BaseConverter< DiagnosticsConverter >::robot_
const robot::Robot & robot_
Definition: converter_base.hpp:71


naoqi_driver
Author(s): Karsten Knese
autogenerated on Sat Feb 3 2024 03:50:06