sys_status.cpp
Go to the documentation of this file.
1 
9 /*
10  * Copyright 2013,2014,2015,2016 Vladimir Ermakov.
11  * Copyright 2022 Dr.-Ing. Amilcar do Carmo Lucas, IAV GmbH.
12  *
13  * This file is part of the mavros package and subject to the license terms
14  * in the top-level LICENSE file of the mavros repository.
15  * https://github.com/mavlink/mavros/tree/master/LICENSE.md
16  */
17 
18 #include <mavros/mavros_plugin.h>
19 
20 #include <mavros_msgs/State.h>
21 #include <mavros_msgs/EstimatorStatus.h>
22 #include <mavros_msgs/ExtendedState.h>
23 #include <mavros_msgs/StreamRate.h>
24 #include <mavros_msgs/SetMode.h>
25 #include <mavros_msgs/CommandLong.h>
26 #include <mavros_msgs/StatusText.h>
27 #include <mavros_msgs/VehicleInfo.h>
28 #include <mavros_msgs/VehicleInfoGet.h>
29 #include <mavros_msgs/MessageInterval.h>
30 
31 
32 #ifdef HAVE_SENSOR_MSGS_BATTERYSTATE_MSG
33 #include <sensor_msgs/BatteryState.h>
34 using BatteryMsg = sensor_msgs::BatteryState;
35 #else
36 #include <mavros_msgs/BatteryStatus.h>
37 using BatteryMsg = mavros_msgs::BatteryStatus;
38 #endif
39 
40 namespace mavros {
41 namespace std_plugins {
42 using mavlink::minimal::MAV_TYPE;
43 using mavlink::minimal::MAV_AUTOPILOT;
44 using mavlink::minimal::MAV_STATE;
45 using utils::enum_value;
46 
47 #define MAX_NR_BATTERY_STATUS 10
48 
55 {
56 public:
57  HeartbeatStatus(const std::string &name, size_t win_size) :
59  times_(win_size),
60  seq_nums_(win_size),
61  window_size_(win_size),
62  min_freq_(0.2),
63  max_freq_(100),
64  tolerance_(0.1),
65  autopilot(MAV_AUTOPILOT::GENERIC),
66  type(MAV_TYPE::GENERIC),
67  system_status(MAV_STATE::UNINIT)
68  {
69  clear();
70  }
71 
72  void clear()
73  {
74  std::lock_guard<std::mutex> lock(mutex);
75  ros::Time curtime = ros::Time::now();
76  count_ = 0;
77 
78  for (size_t i = 0; i < window_size_; i++) {
79  times_[i] = curtime;
80  seq_nums_[i] = count_;
81  }
82 
83  hist_indx_ = 0;
84  }
85 
86  void tick(uint8_t type_, uint8_t autopilot_,
87  std::string &mode_, uint8_t system_status_)
88  {
89  std::lock_guard<std::mutex> lock(mutex);
90  count_++;
91 
92  type = static_cast<MAV_TYPE>(type_);
93  autopilot = static_cast<MAV_AUTOPILOT>(autopilot_);
94  mode = mode_;
95  system_status = static_cast<MAV_STATE>(system_status_);
96  }
97 
99  {
100  std::lock_guard<std::mutex> lock(mutex);
101 
102  ros::Time curtime = ros::Time::now();
103  int curseq = count_;
104  int events = curseq - seq_nums_[hist_indx_];
105  double window = (curtime - times_[hist_indx_]).toSec();
106  double freq = events / window;
107  seq_nums_[hist_indx_] = curseq;
108  times_[hist_indx_] = curtime;
110 
111  if (events == 0) {
112  stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "No events recorded.");
113  }
114  else if (freq < min_freq_ * (1 - tolerance_)) {
115  stat.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Frequency too low.");
116  }
117  else if (freq > max_freq_ * (1 + tolerance_)) {
118  stat.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Frequency too high.");
119  }
120  else {
121  stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Normal");
122  }
123 
124  stat.addf("Heartbeats since startup", "%d", count_);
125  stat.addf("Frequency (Hz)", "%f", freq);
126  stat.add("Vehicle type", utils::to_string(type));
127  stat.add("Autopilot type", utils::to_string(autopilot));
128  stat.add("Mode", mode);
129  stat.add("System status", utils::to_string(system_status));
130  }
131 
132 private:
133  int count_;
134  std::vector<ros::Time> times_;
135  std::vector<int> seq_nums_;
138  const size_t window_size_;
139  const double min_freq_;
140  const double max_freq_;
141  const double tolerance_;
142 
143  MAV_AUTOPILOT autopilot;
145  std::string mode;
147 };
148 
149 
154 {
155 public:
156  SystemStatusDiag(const std::string &name) :
158  last_st {}
159  { }
160 
161  void set(mavlink::common::msg::SYS_STATUS &st)
162  {
163  std::lock_guard<std::mutex> lock(mutex);
164  last_st = st;
165  }
166 
168  std::lock_guard<std::mutex> lock(mutex);
169 
170  if ((last_st.onboard_control_sensors_health & last_st.onboard_control_sensors_enabled)
171  != last_st.onboard_control_sensors_enabled)
172  stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Sensor health");
173  else
174  stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Normal");
175 
176  stat.addf("Sensor present", "0x%08X", last_st.onboard_control_sensors_present);
177  stat.addf("Sensor enabled", "0x%08X", last_st.onboard_control_sensors_enabled);
178  stat.addf("Sensor health", "0x%08X", last_st.onboard_control_sensors_health);
179 
180  using STS = mavlink::common::MAV_SYS_STATUS_SENSOR;
181 
182  // [[[cog:
183  // import pymavlink.dialects.v20.common as common
184  // ename = 'MAV_SYS_STATUS_SENSOR'
185  // ename_pfx2 = 'MAV_SYS_STATUS_'
186  //
187  // enum = sorted(common.enums[ename].items())
188  // enum.pop() # -> remove ENUM_END
189  //
190  // for k, e in enum:
191  // desc = e.description.split(' ', 1)[1] if e.description.startswith('0x') else e.description
192  // sts = e.name
193  //
194  // if sts.startswith(ename + '_'):
195  // sts = sts[len(ename) + 1:]
196  // if sts.startswith(ename_pfx2):
197  // sts = sts[len(ename_pfx2):]
198  // if sts[0].isdigit():
199  // sts = 'SENSOR_' + sts
200  //
201  // cog.outl(f"""\
202  // if (last_st.onboard_control_sensors_enabled & enum_value(STS::{sts}))
203  // \tstat.add("{desc.strip()}", (last_st.onboard_control_sensors_health & enum_value(STS::{sts})) ? "Ok" : "Fail");""")
204  // ]]]
205  if (last_st.onboard_control_sensors_enabled & enum_value(STS::SENSOR_3D_GYRO))
206  stat.add("3D gyro", (last_st.onboard_control_sensors_health & enum_value(STS::SENSOR_3D_GYRO)) ? "Ok" : "Fail");
207  if (last_st.onboard_control_sensors_enabled & enum_value(STS::SENSOR_3D_ACCEL))
208  stat.add("3D accelerometer", (last_st.onboard_control_sensors_health & enum_value(STS::SENSOR_3D_ACCEL)) ? "Ok" : "Fail");
209  if (last_st.onboard_control_sensors_enabled & enum_value(STS::SENSOR_3D_MAG))
210  stat.add("3D magnetometer", (last_st.onboard_control_sensors_health & enum_value(STS::SENSOR_3D_MAG)) ? "Ok" : "Fail");
211  if (last_st.onboard_control_sensors_enabled & enum_value(STS::ABSOLUTE_PRESSURE))
212  stat.add("absolute pressure", (last_st.onboard_control_sensors_health & enum_value(STS::ABSOLUTE_PRESSURE)) ? "Ok" : "Fail");
213  if (last_st.onboard_control_sensors_enabled & enum_value(STS::DIFFERENTIAL_PRESSURE))
214  stat.add("differential pressure", (last_st.onboard_control_sensors_health & enum_value(STS::DIFFERENTIAL_PRESSURE)) ? "Ok" : "Fail");
215  if (last_st.onboard_control_sensors_enabled & enum_value(STS::GPS))
216  stat.add("GPS", (last_st.onboard_control_sensors_health & enum_value(STS::GPS)) ? "Ok" : "Fail");
217  if (last_st.onboard_control_sensors_enabled & enum_value(STS::OPTICAL_FLOW))
218  stat.add("optical flow", (last_st.onboard_control_sensors_health & enum_value(STS::OPTICAL_FLOW)) ? "Ok" : "Fail");
219  if (last_st.onboard_control_sensors_enabled & enum_value(STS::VISION_POSITION))
220  stat.add("computer vision position", (last_st.onboard_control_sensors_health & enum_value(STS::VISION_POSITION)) ? "Ok" : "Fail");
221  if (last_st.onboard_control_sensors_enabled & enum_value(STS::LASER_POSITION))
222  stat.add("laser based position", (last_st.onboard_control_sensors_health & enum_value(STS::LASER_POSITION)) ? "Ok" : "Fail");
223  if (last_st.onboard_control_sensors_enabled & enum_value(STS::EXTERNAL_GROUND_TRUTH))
224  stat.add("external ground truth (Vicon or Leica)", (last_st.onboard_control_sensors_health & enum_value(STS::EXTERNAL_GROUND_TRUTH)) ? "Ok" : "Fail");
225  if (last_st.onboard_control_sensors_enabled & enum_value(STS::ANGULAR_RATE_CONTROL))
226  stat.add("3D angular rate control", (last_st.onboard_control_sensors_health & enum_value(STS::ANGULAR_RATE_CONTROL)) ? "Ok" : "Fail");
227  if (last_st.onboard_control_sensors_enabled & enum_value(STS::ATTITUDE_STABILIZATION))
228  stat.add("attitude stabilization", (last_st.onboard_control_sensors_health & enum_value(STS::ATTITUDE_STABILIZATION)) ? "Ok" : "Fail");
229  if (last_st.onboard_control_sensors_enabled & enum_value(STS::YAW_POSITION))
230  stat.add("yaw position", (last_st.onboard_control_sensors_health & enum_value(STS::YAW_POSITION)) ? "Ok" : "Fail");
231  if (last_st.onboard_control_sensors_enabled & enum_value(STS::Z_ALTITUDE_CONTROL))
232  stat.add("z/altitude control", (last_st.onboard_control_sensors_health & enum_value(STS::Z_ALTITUDE_CONTROL)) ? "Ok" : "Fail");
233  if (last_st.onboard_control_sensors_enabled & enum_value(STS::XY_POSITION_CONTROL))
234  stat.add("x/y position control", (last_st.onboard_control_sensors_health & enum_value(STS::XY_POSITION_CONTROL)) ? "Ok" : "Fail");
235  if (last_st.onboard_control_sensors_enabled & enum_value(STS::MOTOR_OUTPUTS))
236  stat.add("motor outputs / control", (last_st.onboard_control_sensors_health & enum_value(STS::MOTOR_OUTPUTS)) ? "Ok" : "Fail");
237  if (last_st.onboard_control_sensors_enabled & enum_value(STS::RC_RECEIVER))
238  stat.add("rc receiver", (last_st.onboard_control_sensors_health & enum_value(STS::RC_RECEIVER)) ? "Ok" : "Fail");
239  if (last_st.onboard_control_sensors_enabled & enum_value(STS::SENSOR_3D_GYRO2))
240  stat.add("2nd 3D gyro", (last_st.onboard_control_sensors_health & enum_value(STS::SENSOR_3D_GYRO2)) ? "Ok" : "Fail");
241  if (last_st.onboard_control_sensors_enabled & enum_value(STS::SENSOR_3D_ACCEL2))
242  stat.add("2nd 3D accelerometer", (last_st.onboard_control_sensors_health & enum_value(STS::SENSOR_3D_ACCEL2)) ? "Ok" : "Fail");
243  if (last_st.onboard_control_sensors_enabled & enum_value(STS::SENSOR_3D_MAG2))
244  stat.add("2nd 3D magnetometer", (last_st.onboard_control_sensors_health & enum_value(STS::SENSOR_3D_MAG2)) ? "Ok" : "Fail");
245  if (last_st.onboard_control_sensors_enabled & enum_value(STS::GEOFENCE))
246  stat.add("geofence", (last_st.onboard_control_sensors_health & enum_value(STS::GEOFENCE)) ? "Ok" : "Fail");
247  if (last_st.onboard_control_sensors_enabled & enum_value(STS::AHRS))
248  stat.add("AHRS subsystem health", (last_st.onboard_control_sensors_health & enum_value(STS::AHRS)) ? "Ok" : "Fail");
249  if (last_st.onboard_control_sensors_enabled & enum_value(STS::TERRAIN))
250  stat.add("Terrain subsystem health", (last_st.onboard_control_sensors_health & enum_value(STS::TERRAIN)) ? "Ok" : "Fail");
251  if (last_st.onboard_control_sensors_enabled & enum_value(STS::REVERSE_MOTOR))
252  stat.add("Motors are reversed", (last_st.onboard_control_sensors_health & enum_value(STS::REVERSE_MOTOR)) ? "Ok" : "Fail");
253  if (last_st.onboard_control_sensors_enabled & enum_value(STS::LOGGING))
254  stat.add("Logging", (last_st.onboard_control_sensors_health & enum_value(STS::LOGGING)) ? "Ok" : "Fail");
255  if (last_st.onboard_control_sensors_enabled & enum_value(STS::BATTERY))
256  stat.add("Battery", (last_st.onboard_control_sensors_health & enum_value(STS::BATTERY)) ? "Ok" : "Fail");
257  if (last_st.onboard_control_sensors_enabled & enum_value(STS::PROXIMITY))
258  stat.add("Proximity", (last_st.onboard_control_sensors_health & enum_value(STS::PROXIMITY)) ? "Ok" : "Fail");
259  if (last_st.onboard_control_sensors_enabled & enum_value(STS::SATCOM))
260  stat.add("Satellite Communication", (last_st.onboard_control_sensors_health & enum_value(STS::SATCOM)) ? "Ok" : "Fail");
261  if (last_st.onboard_control_sensors_enabled & enum_value(STS::PREARM_CHECK))
262  stat.add("pre-arm check status. Always healthy when armed", (last_st.onboard_control_sensors_health & enum_value(STS::PREARM_CHECK)) ? "Ok" : "Fail");
263  if (last_st.onboard_control_sensors_enabled & enum_value(STS::OBSTACLE_AVOIDANCE))
264  stat.add("Avoidance/collision prevention", (last_st.onboard_control_sensors_health & enum_value(STS::OBSTACLE_AVOIDANCE)) ? "Ok" : "Fail");
265  if (last_st.onboard_control_sensors_enabled & enum_value(STS::PROPULSION))
266  stat.add("propulsion (actuator, esc, motor or propellor)", (last_st.onboard_control_sensors_health & enum_value(STS::PROPULSION)) ? "Ok" : "Fail");
267  // [[[end]]] (checksum: 24471e5532db5c99f411475509d41f72)
268 
269  stat.addf("CPU Load (%)", "%.1f", last_st.load / 10.0);
270  stat.addf("Drop rate (%)", "%.1f", last_st.drop_rate_comm / 10.0);
271  stat.addf("Errors comm", "%d", last_st.errors_comm);
272  stat.addf("Errors count #1", "%d", last_st.errors_count1);
273  stat.addf("Errors count #2", "%d", last_st.errors_count2);
274  stat.addf("Errors count #3", "%d", last_st.errors_count3);
275  stat.addf("Errors count #4", "%d", last_st.errors_count4);
276  }
277 
278 private:
280  mavlink::common::msg::SYS_STATUS last_st;
281 };
282 
283 
288 {
289 public:
290  explicit BatteryStatusDiag(const std::string &name) :
292  voltage(-1.0f),
293  current(0.0f),
294  remaining(0.0f),
295  min_voltage(6.0f)
296  { }
297 
298  // Move constructor, required to dynamically create an array of instances of this class
299  // because it contains an unique mutex object
302  voltage(-1.0f),
303  current(0.0f),
304  remaining(0.0f),
305  min_voltage(6.0f)
306  {
307  *this = std::move(other);
308  }
309 
310  // Move assignment operator, required to dynamically create an array of instances of this class
311  // because it contains an unique mutex object
313  if (this != &other)
314  {
315  *this = std::move(other);
316  }
317  return *this;
318  }
319 
320  void set_min_voltage(float volt) {
321  std::lock_guard<std::mutex> lock(mutex);
322  min_voltage = volt;
323  }
324 
325  void set(float volt, float curr, float rem) {
326  std::lock_guard<std::mutex> lock(mutex);
327  voltage = volt;
328  current = curr;
329  remaining = rem;
330  }
331 
332  void setcell_v(const std::vector<float> voltages) {
333  std::lock_guard<std::mutex> lock(mutex);
334  cell_voltage = voltages;
335  }
336 
338  {
339  std::lock_guard<std::mutex> lock(mutex);
340 
341  if (voltage < 0.0f)
342  stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "No data");
343  else if (voltage < min_voltage)
344  stat.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Low voltage");
345  else
346  stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Normal");
347 
348  stat.addf("Voltage", "%.2f", voltage);
349  stat.addf("Current", "%.1f", current);
350  stat.addf("Remaining", "%.1f", remaining * 100.0f);
351  const int nr_cells = cell_voltage.size();
352  if (nr_cells > 1)
353  {
354  for (int i = 1; i <= nr_cells ; ++i) {
355  stat.addf(utils::format("Cell %u", i), "%.2f", cell_voltage[i-1]);
356  }
357  }
358  }
359 
360 private:
362  float voltage;
363  float current;
364  float remaining;
365  float min_voltage;
366  std::vector<float> cell_voltage;
367 };
368 
369 
374 {
375 public:
376  MemInfo(const std::string &name) :
378  freemem(UINT32_MAX),
379  brkval(0),
380  last_rcd(0)
381  { }
382 
383  void set(uint32_t f, uint16_t b) {
384  freemem = f;
385  brkval = b;
386  last_rcd = ros::Time::now().toNSec();
387  }
388 
390  {
391  // access atomic variables just once
392  size_t freemem_ = freemem;
393  uint16_t brkval_ = brkval;
394  ros::Time last_rcd_;
395  last_rcd_.fromNSec(last_rcd.load());
396  constexpr int timeout = 10.0; // seconds
397 
398  // summarize the results
399  if (last_rcd_.isZero()) {
400  stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Not initialised");
401  } else if (ros::Time::now().toSec() - last_rcd_.toSec() > timeout) {
402  stat.summary(diagnostic_msgs::DiagnosticStatus::STALE, "Not received for more than " + std::to_string(timeout) + "s");
403  } else {
404  if (freemem == UINT32_MAX)
405  stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "No data");
406  else if (freemem < 200)
407  stat.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Low mem");
408  else
409  stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Normal");
410  }
411  stat.addf("Free memory (B)", "%zd", freemem_);
412  stat.addf("Heap top", "0x%04X", brkval_);
413  }
414 
415 private:
416  std::atomic<size_t> freemem;
417  std::atomic<uint16_t> brkval;
418  std::atomic<uint64_t> last_rcd;
419 };
420 
421 
426 {
427 public:
428  HwStatus(const std::string &name) :
430  vcc(-1.0),
431  i2cerr(0),
432  i2cerr_last(0),
433  last_rcd(0)
434  { }
435 
436  void set(uint16_t v, uint8_t e) {
437  std::lock_guard<std::mutex> lock(mutex);
438  vcc = v * 0.001f;
439  i2cerr = e;
440  last_rcd = ros::Time::now();
441  }
442 
444  {
445  std::lock_guard<std::mutex> lock(mutex);
446  constexpr int timeout = 10.0; // seconds
447  if (last_rcd.isZero()) {
448  stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Not initialised");
449  } else if (ros::Time::now().toSec() - last_rcd.toSec() > timeout) {
450  stat.summary(diagnostic_msgs::DiagnosticStatus::STALE, "Not received for more than " + std::to_string(timeout) + "s");
451  } else {
452  if (vcc < 0)
453  stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "No data");
454  else if (vcc < 4.5)
455  stat.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Low voltage");
456  else if (i2cerr != i2cerr_last) {
457  i2cerr_last = i2cerr;
458  stat.summary(diagnostic_msgs::DiagnosticStatus::WARN, "New I2C error");
459  }
460  else
461  stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Normal");
462  }
463  stat.addf("Core voltage", "%f", vcc);
464  stat.addf("I2C errors", "%zu", i2cerr);
465  }
466 
467 private:
469  float vcc;
470  size_t i2cerr;
471  size_t i2cerr_last;
473 };
474 
475 
482 {
483 public:
484  SystemStatusPlugin() : PluginBase(),
485  nh("~"),
486  hb_diag("Heartbeat", 10),
487  mem_diag("APM Memory"),
488  hwst_diag("APM Hardware"),
489  sys_diag("System"),
490  conn_heartbeat_mav_type(MAV_TYPE::ONBOARD_CONTROLLER),
491  version_retries(RETRIES_COUNT),
492  disable_diag(false),
493  has_battery_status0(false)
494  {
495  batt_diag.reserve(MAX_NR_BATTERY_STATUS);
496  batt_diag.emplace_back("Battery");
497  for (int i = 2; i <= MAX_NR_BATTERY_STATUS ; ++i) {
498  batt_diag.emplace_back(utils::format("Battery %u", i));
499  }
500  }
501 
502  void initialize(UAS &uas_) override
503  {
504  PluginBase::initialize(uas_);
505 
506  ros::WallDuration conn_heartbeat;
507 
508  double conn_timeout_d;
509  double conn_heartbeat_d;
510  std::vector<double> min_voltage;
511  std::string conn_heartbeat_mav_type_str;
512 
513  nh.param("conn/timeout", conn_timeout_d, 10.0);
514  nh.param("sys/min_voltage", min_voltage, {10.0});
515  nh.param("sys/disable_diag", disable_diag, false);
516 
517  // heartbeat rate parameter
518  if (nh.getParam("conn/heartbeat_rate", conn_heartbeat_d) && conn_heartbeat_d != 0.0) {
519  conn_heartbeat = ros::WallDuration(ros::Rate(conn_heartbeat_d));
520  }
521 
522  // heartbeat mav type parameter
523  if (nh.getParam("conn/heartbeat_mav_type", conn_heartbeat_mav_type_str)) {
524  conn_heartbeat_mav_type = utils::mav_type_from_str(conn_heartbeat_mav_type_str);
525  }
526 
527  // heartbeat diag always enabled
528  UAS_DIAG(m_uas).add(hb_diag);
529  if (!disable_diag) {
530  UAS_DIAG(m_uas).add(sys_diag);
531  for (size_t i = 0; i < MAX_NR_BATTERY_STATUS && i < min_voltage.size(); ++i) {
532  batt_diag[i].set_min_voltage(min_voltage[i]);
533  UAS_DIAG(m_uas).add(batt_diag[i]);
534  }
535  }
536 
537 
538  // one-shot timeout timer
539  timeout_timer = nh.createWallTimer(ros::WallDuration(conn_timeout_d),
540  &SystemStatusPlugin::timeout_cb, this, true);
541  //timeout_timer.start();
542 
543  if (!conn_heartbeat.isZero()) {
544  heartbeat_timer = nh.createWallTimer(conn_heartbeat,
546  //heartbeat_timer.start();
547  }
548 
549  // version request timer
550  autopilot_version_timer = nh.createWallTimer(ros::WallDuration(1.0),
552  autopilot_version_timer.stop();
553 
554  state_pub = nh.advertise<mavros_msgs::State>("state", 10, true);
555  extended_state_pub = nh.advertise<mavros_msgs::ExtendedState>("extended_state", 10);
556  batt_pub = nh.advertise<BatteryMsg>("battery", 10);
557  estimator_status_pub = nh.advertise<mavros_msgs::EstimatorStatus>("estimator_status", 10);
558  statustext_pub = nh.advertise<mavros_msgs::StatusText>("statustext/recv", 10);
559  statustext_sub = nh.subscribe("statustext/send", 10, &SystemStatusPlugin::statustext_cb, this);
560  rate_srv = nh.advertiseService("set_stream_rate", &SystemStatusPlugin::set_rate_cb, this);
561  mode_srv = nh.advertiseService("set_mode", &SystemStatusPlugin::set_mode_cb, this);
562  vehicle_info_get_srv = nh.advertiseService("vehicle_info_get", &SystemStatusPlugin::vehicle_info_get_cb, this);
563  message_interval_srv = nh.advertiseService("set_message_interval", &SystemStatusPlugin::set_message_interval_cb, this);
564 
565  // init state topic
566  publish_disconnection();
567  enable_connection_cb();
568  }
569 
571  return {
575  make_handler(&SystemStatusPlugin::handle_meminfo),
581  };
582  }
583 
584 private:
586 
591  std::vector<BatteryStatusDiag> batt_diag;
595 
606 
608  static constexpr int RETRIES_COUNT = 6;
612 
613  using M_VehicleInfo = std::unordered_map<uint16_t, mavros_msgs::VehicleInfo>;
615 
616  /* -*- mid-level helpers -*- */
617 
618  // Get vehicle key for the unordered map containing all vehicles
619  inline uint16_t get_vehicle_key(uint8_t sysid,uint8_t compid) {
620  return sysid << 8 | compid;
621  }
622 
623  // Find or create vehicle info
624  inline M_VehicleInfo::iterator find_or_create_vehicle_info(uint8_t sysid, uint8_t compid) {
625  auto key = get_vehicle_key(sysid, compid);
626  M_VehicleInfo::iterator ret = vehicles.find(key);
627 
628  if (ret == vehicles.end()) {
629  // Not found
630  mavros_msgs::VehicleInfo v;
631  v.sysid = sysid;
632  v.compid = compid;
633  v.available_info = 0;
634 
635  auto res = vehicles.emplace(key, v); //-> pair<iterator, bool>
636  ret = res.first;
637  }
638 
639  ROS_ASSERT(ret != vehicles.end());
640  return ret;
641  }
642 
648  void process_statustext_normal(uint8_t severity, std::string &text)
649  {
650  using mavlink::common::MAV_SEVERITY;
651 
652  switch (severity) {
653  // [[[cog:
654  // for l1, l2 in (
655  // (('EMERGENCY', 'ALERT', 'CRITICAL', 'ERROR'), 'ERROR'),
656  // (('WARNING', 'NOTICE'), 'WARN'),
657  // (('INFO', ), 'INFO'),
658  // (('DEBUG', ), 'DEBUG')
659  // ):
660  // for v in l1:
661  // cog.outl("case enum_value(MAV_SEVERITY::%s):" % v)
662  // cog.outl("\tROS_%s_STREAM_NAMED(\"fcu\", \"FCU: \" << text);" % l2)
663  // cog.outl("\tbreak;")
664  // ]]]
665  case enum_value(MAV_SEVERITY::EMERGENCY):
666  case enum_value(MAV_SEVERITY::ALERT):
667  case enum_value(MAV_SEVERITY::CRITICAL):
668  case enum_value(MAV_SEVERITY::ERROR):
669  ROS_ERROR_STREAM_NAMED("fcu", "FCU: " << text);
670  break;
671  case enum_value(MAV_SEVERITY::WARNING):
672  case enum_value(MAV_SEVERITY::NOTICE):
673  ROS_WARN_STREAM_NAMED("fcu", "FCU: " << text);
674  break;
675  case enum_value(MAV_SEVERITY::INFO):
676  ROS_INFO_STREAM_NAMED("fcu", "FCU: " << text);
677  break;
678  case enum_value(MAV_SEVERITY::DEBUG):
679  ROS_DEBUG_STREAM_NAMED("fcu", "FCU: " << text);
680  break;
681  // [[[end]]] (checksum: 315aa363b5ecb4dda66cc8e1e3d3aa48)
682  default:
683  ROS_WARN_STREAM_NAMED("fcu", "FCU: UNK(" << +severity << "): " << text);
684  break;
685  };
686  }
687 
688  static std::string custom_version_to_hex_string(std::array<uint8_t, 8> &array)
689  {
690  // should be little-endian
691  uint64_t b;
692  memcpy(&b, array.data(), sizeof(uint64_t));
693  b = le64toh(b);
694 
695  return utils::format("%016llx", b);
696  }
697 
698  void process_autopilot_version_normal(mavlink::common::msg::AUTOPILOT_VERSION &apv, uint8_t sysid, uint8_t compid)
699  {
700  char prefix[16];
701  std::snprintf(prefix, sizeof(prefix), "VER: %d.%d", sysid, compid);
702 
703  ROS_INFO_NAMED("sys", "%s: Capabilities 0x%016llx", prefix, (long long int)apv.capabilities);
704  ROS_INFO_NAMED("sys", "%s: Flight software: %08x (%s)",
705  prefix,
706  apv.flight_sw_version,
707  custom_version_to_hex_string(apv.flight_custom_version).c_str());
708  ROS_INFO_NAMED("sys", "%s: Middleware software: %08x (%s)",
709  prefix,
710  apv.middleware_sw_version,
711  custom_version_to_hex_string(apv.middleware_custom_version).c_str());
712  ROS_INFO_NAMED("sys", "%s: OS software: %08x (%s)",
713  prefix,
714  apv.os_sw_version,
715  custom_version_to_hex_string(apv.os_custom_version).c_str());
716  ROS_INFO_NAMED("sys", "%s: Board hardware: %08x", prefix, apv.board_version);
717  ROS_INFO_NAMED("sys", "%s: VID/PID: %04x:%04x", prefix, apv.vendor_id, apv.product_id);
718  ROS_INFO_NAMED("sys", "%s: UID: %016llx", prefix, (long long int)apv.uid);
719  }
720 
721  void process_autopilot_version_apm_quirk(mavlink::common::msg::AUTOPILOT_VERSION &apv, uint8_t sysid, uint8_t compid)
722  {
723  char prefix[16];
724  std::snprintf(prefix, sizeof(prefix), "VER: %d.%d", sysid, compid);
725 
726  // Note based on current APM's impl.
727  // APM uses custom version array[8] as a string
728  ROS_INFO_NAMED("sys", "%s: Capabilities 0x%016llx", prefix, (long long int)apv.capabilities);
729  ROS_INFO_NAMED("sys", "%s: Flight software: %08x (%*s)",
730  prefix,
731  apv.flight_sw_version,
732  8, apv.flight_custom_version.data());
733  ROS_INFO_NAMED("sys", "%s: Middleware software: %08x (%*s)",
734  prefix,
735  apv.middleware_sw_version,
736  8, apv.middleware_custom_version.data());
737  ROS_INFO_NAMED("sys", "%s: OS software: %08x (%*s)",
738  prefix,
739  apv.os_sw_version,
740  8, apv.os_custom_version.data());
741  ROS_INFO_NAMED("sys", "%s: Board hardware: %08x", prefix, apv.board_version);
742  ROS_INFO_NAMED("sys", "%s: VID/PID: %04x:%04x", prefix, apv.vendor_id, apv.product_id);
743  ROS_INFO_NAMED("sys", "%s: UID: %016llx", prefix, (long long int)apv.uid);
744  }
745 
747  auto state_msg = boost::make_shared<mavros_msgs::State>();
748  state_msg->header.stamp = ros::Time::now();
749  state_msg->connected = false;
750  state_msg->armed = false;
751  state_msg->guided = false;
752  state_msg->mode = "";
753  state_msg->system_status = enum_value(MAV_STATE::UNINIT);
754 
755  state_pub.publish(state_msg);
756  }
757 
758  /* -*- message handlers -*- */
759 
760  void handle_heartbeat(const mavlink::mavlink_message_t *msg, mavlink::minimal::msg::HEARTBEAT &hb)
761  {
762  using mavlink::minimal::MAV_MODE_FLAG;
763 
764  // Store generic info of all heartbeats seen
765  auto it = find_or_create_vehicle_info(msg->sysid, msg->compid);
766 
767  auto vehicle_mode = m_uas->str_mode_v10(hb.base_mode, hb.custom_mode);
768  auto stamp = ros::Time::now();
769 
770  // Update vehicle data
771  it->second.header.stamp = stamp;
772  it->second.available_info |= mavros_msgs::VehicleInfo::HAVE_INFO_HEARTBEAT;
773  it->second.autopilot = hb.autopilot;
774  it->second.type = hb.type;
775  it->second.system_status = hb.system_status;
776  it->second.base_mode = hb.base_mode;
777  it->second.custom_mode = hb.custom_mode;
778  it->second.mode = vehicle_mode;
779 
780  if (!(hb.base_mode & enum_value(MAV_MODE_FLAG::CUSTOM_MODE_ENABLED))) {
781  it->second.mode_id = hb.base_mode;
782  } else {
783  it->second.mode_id = hb.custom_mode;
784  }
785 
786  // Continue from here only if vehicle is my target
787  if (!m_uas->is_my_target(msg->sysid, msg->compid)) {
788  ROS_DEBUG_NAMED("sys", "HEARTBEAT from [%d, %d] dropped.", msg->sysid, msg->compid);
789  return;
790  }
791 
792  // update context && setup connection timeout
793  m_uas->update_heartbeat(hb.type, hb.autopilot, hb.base_mode);
794  m_uas->update_connection_status(true);
795  timeout_timer.stop();
796  timeout_timer.start();
797 
798  // build state message after updating uas
799  auto state_msg = boost::make_shared<mavros_msgs::State>();
800  state_msg->header.stamp = stamp;
801  state_msg->connected = true;
802  state_msg->armed = !!(hb.base_mode & enum_value(MAV_MODE_FLAG::SAFETY_ARMED));
803  state_msg->guided = !!(hb.base_mode & enum_value(MAV_MODE_FLAG::GUIDED_ENABLED));
804  state_msg->manual_input = !!(hb.base_mode & enum_value(MAV_MODE_FLAG::MANUAL_INPUT_ENABLED));
805  state_msg->mode = vehicle_mode;
806  state_msg->system_status = hb.system_status;
807 
808  state_pub.publish(state_msg);
809  hb_diag.tick(hb.type, hb.autopilot, state_msg->mode, hb.system_status);
810  }
811 
812  void handle_extended_sys_state(const mavlink::mavlink_message_t *msg, mavlink::common::msg::EXTENDED_SYS_STATE &state)
813  {
814  auto state_msg = boost::make_shared<mavros_msgs::ExtendedState>();
815  state_msg->header.stamp = ros::Time::now();
816  state_msg->vtol_state = state.vtol_state;
817  state_msg->landed_state = state.landed_state;
818 
819  extended_state_pub.publish(state_msg);
820  }
821 
822  void handle_sys_status(const mavlink::mavlink_message_t *msg, mavlink::common::msg::SYS_STATUS &stat)
823  {
824  using MC = mavlink::minimal::MAV_COMPONENT;
825  if (static_cast<MC>(msg->compid) == MC::COMP_ID_GIMBAL) {
826  return;
827  }
828 
829  float volt = stat.voltage_battery * 0.001f; // mV
830  float curr = stat.current_battery * 0.01f; // 10 mA or -1
831  float rem = stat.battery_remaining * 0.01f; // or -1
832 
833  sys_diag.set(stat);
834 
835  if (has_battery_status0)
836  return;
837 
838  batt_diag[0].set(volt, curr, rem);
839  auto batt_msg = boost::make_shared<BatteryMsg>();
840  batt_msg->header.stamp = ros::Time::now();
841 
842 #ifdef HAVE_SENSOR_MSGS_BATTERYSTATE_MSG
843  batt_msg->voltage = volt;
844  batt_msg->current = -curr;
845  batt_msg->charge = NAN;
846  batt_msg->capacity = NAN;
847  batt_msg->design_capacity = NAN;
848  batt_msg->percentage = rem;
849  batt_msg->power_supply_status = BatteryMsg::POWER_SUPPLY_STATUS_DISCHARGING;
850  batt_msg->power_supply_health = BatteryMsg::POWER_SUPPLY_HEALTH_UNKNOWN;
851  batt_msg->power_supply_technology = BatteryMsg::POWER_SUPPLY_TECHNOLOGY_UNKNOWN;
852  batt_msg->present = true;
853  batt_msg->cell_voltage.clear(); // not necessary. Cell count and Voltage unknown.
854  batt_msg->location = "";
855  batt_msg->serial_number = "";
856 #else // mavros_msgs::BatteryStatus
857  batt_msg->voltage = volt;
858  batt_msg->current = curr;
859  batt_msg->remaining = rem;
860 #endif
861 
862  batt_pub.publish(batt_msg);
863  }
864 
865  void handle_statustext(const mavlink::mavlink_message_t *msg, mavlink::common::msg::STATUSTEXT &textm)
866  {
867  auto text = mavlink::to_string(textm.text);
868  process_statustext_normal(textm.severity, text);
869 
870  auto st_msg = boost::make_shared<mavros_msgs::StatusText>();
871  st_msg->header.stamp = ros::Time::now();
872  st_msg->severity = textm.severity;
873  st_msg->text = text;
874  statustext_pub.publish(st_msg);
875  }
876 
877  void handle_meminfo(const mavlink::mavlink_message_t *msg, mavlink::ardupilotmega::msg::MEMINFO &mem)
878  {
879  mem_diag.set(std::max(static_cast<uint32_t>(mem.freemem), mem.freemem32), mem.brkval);
880  }
881 
882  void handle_hwstatus(const mavlink::mavlink_message_t *msg, mavlink::ardupilotmega::msg::HWSTATUS &hwst)
883  {
884  hwst_diag.set(hwst.Vcc, hwst.I2Cerr);
885  }
886 
887  void handle_autopilot_version(const mavlink::mavlink_message_t *msg, mavlink::common::msg::AUTOPILOT_VERSION &apv)
888  {
889  // we want to store only FCU caps
890  if (m_uas->is_my_target(msg->sysid, msg->compid)) {
891  autopilot_version_timer.stop();
892  m_uas->update_capabilities(true, apv.capabilities);
893  }
894 
895  // but print all version responses
896  if (m_uas->is_ardupilotmega())
897  process_autopilot_version_apm_quirk(apv, msg->sysid, msg->compid);
898  else
899  process_autopilot_version_normal(apv, msg->sysid, msg->compid);
900 
901  // Store generic info of all autopilot seen
902  auto it = find_or_create_vehicle_info(msg->sysid, msg->compid);
903 
904  // Update vehicle data
905  it->second.header.stamp = ros::Time::now();
906  it->second.available_info |= mavros_msgs::VehicleInfo::HAVE_INFO_AUTOPILOT_VERSION;
907  it->second.capabilities = apv.capabilities;
908  it->second.flight_sw_version = apv.flight_sw_version;
909  it->second.middleware_sw_version = apv.middleware_sw_version;
910  it->second.os_sw_version = apv.os_sw_version;
911  it->second.board_version = apv.board_version;
912  it->second.flight_custom_version = custom_version_to_hex_string(apv.flight_custom_version);
913  it->second.vendor_id = apv.vendor_id;
914  it->second.product_id = apv.product_id;
915  it->second.uid = apv.uid;
916  }
917 
918  void handle_battery_status(const mavlink::mavlink_message_t *msg, mavlink::common::msg::BATTERY_STATUS &bs)
919  {
920 #ifdef HAVE_SENSOR_MSGS_BATTERYSTATE_MSG
921  using BT = mavlink::common::MAV_BATTERY_TYPE;
922  auto batt_msg = boost::make_shared<BatteryMsg>();
923  batt_msg->header.stamp = ros::Time::now();
924 
925  batt_msg->current = bs.current_battery==-1?NAN:-(bs.current_battery * 0.01f); // 10 mA
926  batt_msg->charge = NAN;
927  batt_msg->capacity = NAN;
928  batt_msg->design_capacity = NAN;
929  batt_msg->percentage = bs.battery_remaining * 0.01f;
930  batt_msg->power_supply_status = BatteryMsg::POWER_SUPPLY_STATUS_DISCHARGING;
931  batt_msg->power_supply_health = BatteryMsg::POWER_SUPPLY_HEALTH_UNKNOWN;
932 
933  switch (bs.type) {
934  // [[[cog:
935  // for f in (
936  // 'LIPO',
937  // 'LIFE',
938  // 'LION',
939  // 'NIMH',
940  // 'UNKNOWN'):
941  // cog.outl("case enum_value(BT::%s):" % f)
942  // if f == 'UNKNOWN':
943  // cog.outl("default:")
944  // cog.outl("\tbatt_msg->power_supply_technology = BatteryMsg::POWER_SUPPLY_TECHNOLOGY_%s;" % f)
945  // cog.outl("\tbreak;")
946  // ]]]
947  case enum_value(BT::LIPO):
948  batt_msg->power_supply_technology = BatteryMsg::POWER_SUPPLY_TECHNOLOGY_LIPO;
949  break;
950  case enum_value(BT::LIFE):
951  batt_msg->power_supply_technology = BatteryMsg::POWER_SUPPLY_TECHNOLOGY_LIFE;
952  break;
953  case enum_value(BT::LION):
954  batt_msg->power_supply_technology = BatteryMsg::POWER_SUPPLY_TECHNOLOGY_LION;
955  break;
956  case enum_value(BT::NIMH):
957  batt_msg->power_supply_technology = BatteryMsg::POWER_SUPPLY_TECHNOLOGY_NIMH;
958  break;
959  case enum_value(BT::UNKNOWN):
960  default:
961  batt_msg->power_supply_technology = BatteryMsg::POWER_SUPPLY_TECHNOLOGY_UNKNOWN;
962  break;
963  // [[[end]]] (checksum: 2bf14a81b3027f14ba1dd9b4c086a41d)
964  }
965 
966  batt_msg->present = true;
967 
968  batt_msg->cell_voltage.clear();
969  batt_msg->cell_voltage.reserve(bs.voltages.size() + bs.voltages_ext.size());
970  float cell_voltage;
971  float voltage_acc = 0.0f;
972  float total_voltage = 0.0f;
973  constexpr float coalesce_voltage = (UINT16_MAX-1) * 0.001f; // 65,534V cell voltage means that the next element in the array must be added to this one
974  for (auto v : bs.voltages) {
975  if (v == UINT16_MAX)
976  break;
977 
978  if (v == UINT16_MAX-1) // cell voltage is above 65,534V
979  {
980  voltage_acc += coalesce_voltage;
981  continue; // add to the next array element to get the correct voltage
982  }
983  cell_voltage = voltage_acc + (v * 0.001f); // 1 mV
984  voltage_acc = 0.0f;
985  batt_msg->cell_voltage.push_back(cell_voltage);
986  total_voltage += cell_voltage;
987  }
988  for (auto v : bs.voltages_ext) {
989  if (v == UINT16_MAX || v == 0) // this one is different from the for loop above to support mavlink2 message truncation
990  break;
991 
992  if (v == UINT16_MAX-1) // cell voltage is above 65,534V
993  {
994  voltage_acc += coalesce_voltage;
995  continue; // add to the next array element to get the correct voltage
996  }
997  cell_voltage = voltage_acc + (v * 0.001f); // 1 mV
998  voltage_acc = 0.0f;
999  batt_msg->cell_voltage.push_back(cell_voltage);
1000  total_voltage += cell_voltage;
1001  }
1002  batt_msg->voltage = total_voltage;
1003 
1004  batt_msg->location = utils::format("id%u", bs.id);
1005  batt_msg->serial_number = "";
1006  batt_pub.publish(batt_msg);
1007 
1008  if (bs.id == 0) {
1009  has_battery_status0 = true;
1010  }
1011 
1012  if (!disable_diag && bs.id >= 0 && bs.id < MAX_NR_BATTERY_STATUS) {
1013  batt_diag[bs.id].set(total_voltage, batt_msg->current, batt_msg->percentage);
1014  batt_diag[bs.id].setcell_v(batt_msg->cell_voltage);
1015  }
1016 #endif
1017  }
1018 
1019  void handle_estimator_status(const mavlink::mavlink_message_t *msg, mavlink::common::msg::ESTIMATOR_STATUS &status)
1020  {
1021  using ESF = mavlink::common::ESTIMATOR_STATUS_FLAGS;
1022 
1023  auto est_status_msg = boost::make_shared<mavros_msgs::EstimatorStatus>();
1024  est_status_msg->header.stamp = ros::Time::now();
1025 
1026  // [[[cog:
1027  // import pymavlink.dialects.v20.common as common
1028  // ename = 'ESTIMATOR_STATUS_FLAGS'
1029  // ename_pfx2 = 'ESTIMATOR_'
1030  //
1031  // enum = sorted(common.enums[ename].items())
1032  // enum.pop() # -> remove ENUM_END
1033  //
1034  // for k, e in enum:
1035  // desc = e.description.split(' ', 1)[1] if e.description.startswith('0x') else e.description
1036  // esf = e.name
1037  //
1038  // if esf.startswith(ename + '_'):
1039  // esf = esf[len(ename) + 1:]
1040  // if esf.startswith(ename_pfx2):
1041  // esf = esf[len(ename_pfx2):]
1042  // if esf[0].isdigit():
1043  // esf = 'SENSOR_' + esf
1044  // cog.outl("est_status_msg->%s_status_flag = !!(status.flags & enum_value(ESF::%s));" % (esf.lower(), esf))
1045  // ]]]
1046  est_status_msg->attitude_status_flag = !!(status.flags & enum_value(ESF::ATTITUDE));
1047  est_status_msg->velocity_horiz_status_flag = !!(status.flags & enum_value(ESF::VELOCITY_HORIZ));
1048  est_status_msg->velocity_vert_status_flag = !!(status.flags & enum_value(ESF::VELOCITY_VERT));
1049  est_status_msg->pos_horiz_rel_status_flag = !!(status.flags & enum_value(ESF::POS_HORIZ_REL));
1050  est_status_msg->pos_horiz_abs_status_flag = !!(status.flags & enum_value(ESF::POS_HORIZ_ABS));
1051  est_status_msg->pos_vert_abs_status_flag = !!(status.flags & enum_value(ESF::POS_VERT_ABS));
1052  est_status_msg->pos_vert_agl_status_flag = !!(status.flags & enum_value(ESF::POS_VERT_AGL));
1053  est_status_msg->const_pos_mode_status_flag = !!(status.flags & enum_value(ESF::CONST_POS_MODE));
1054  est_status_msg->pred_pos_horiz_rel_status_flag = !!(status.flags & enum_value(ESF::PRED_POS_HORIZ_REL));
1055  est_status_msg->pred_pos_horiz_abs_status_flag = !!(status.flags & enum_value(ESF::PRED_POS_HORIZ_ABS));
1056  est_status_msg->gps_glitch_status_flag = !!(status.flags & enum_value(ESF::GPS_GLITCH));
1057  est_status_msg->accel_error_status_flag = !!(status.flags & enum_value(ESF::ACCEL_ERROR));
1058  // [[[end]]] (checksum: da59238f4d4337aeb395f7205db08237)
1059 
1060  estimator_status_pub.publish(est_status_msg);
1061  }
1062 
1063  /* -*- timer callbacks -*- */
1064 
1065  void timeout_cb(const ros::WallTimerEvent &event)
1066  {
1067  m_uas->update_connection_status(false);
1068  }
1069 
1071  {
1072  using mavlink::common::MAV_MODE;
1073 
1074  mavlink::minimal::msg::HEARTBEAT hb {};
1075 
1076  hb.type = enum_value(conn_heartbeat_mav_type);
1077  hb.autopilot = enum_value(MAV_AUTOPILOT::INVALID);
1078  hb.base_mode = enum_value(MAV_MODE::MANUAL_ARMED);
1079  hb.custom_mode = 0;
1080  hb.system_status = enum_value(MAV_STATE::ACTIVE);
1081 
1082  UAS_FCU(m_uas)->send_message_ignore_drop(hb);
1083  }
1084 
1086  {
1087  using mavlink::common::MAV_CMD;
1088 
1089  bool ret = false;
1090 
1091  // Request from all first 3 times, then fallback to unicast
1092  bool do_broadcast = version_retries > RETRIES_COUNT / 2;
1093 
1094  try {
1095  auto client = nh.serviceClient<mavros_msgs::CommandLong>("cmd/command");
1096 
1097  mavros_msgs::CommandLong cmd{};
1098 
1099  cmd.request.broadcast = do_broadcast;
1100  cmd.request.command = enum_value(MAV_CMD::REQUEST_AUTOPILOT_CAPABILITIES);
1101  cmd.request.confirmation = false;
1102  cmd.request.param1 = 1.0;
1103 
1104  ROS_DEBUG_NAMED("sys", "VER: Sending %s request.",
1105  (do_broadcast) ? "broadcast" : "unicast");
1106  ret = client.call(cmd);
1107  }
1108  catch (ros::InvalidNameException &ex) {
1109  ROS_ERROR_NAMED("sys", "VER: %s", ex.what());
1110  }
1111 
1112  ROS_ERROR_COND_NAMED(!ret, "sys", "VER: command plugin service call failed!");
1113 
1114  if (version_retries > 0) {
1115  version_retries--;
1116  ROS_WARN_COND_NAMED(version_retries != RETRIES_COUNT - 1, "sys",
1117  "VER: %s request timeout, retries left %d",
1118  (do_broadcast) ? "broadcast" : "unicast",
1119  version_retries);
1120  }
1121  else {
1122  m_uas->update_capabilities(false);
1123  autopilot_version_timer.stop();
1124  ROS_WARN_NAMED("sys", "VER: your FCU don't support AUTOPILOT_VERSION, "
1125  "switched to default capabilities");
1126  }
1127  }
1128 
1129  void connection_cb(bool connected) override
1130  {
1131  has_battery_status0 = false;
1132 
1133  // if connection changes, start delayed version request
1134  version_retries = RETRIES_COUNT;
1135  if (connected)
1136  autopilot_version_timer.start();
1137  else
1138  autopilot_version_timer.stop();
1139 
1140  // add/remove APM diag tasks
1141  if (connected && !disable_diag && m_uas->is_ardupilotmega()) {
1142  UAS_DIAG(m_uas).add(mem_diag);
1143  UAS_DIAG(m_uas).add(hwst_diag);
1144  }
1145  else {
1146  UAS_DIAG(m_uas).removeByName(mem_diag.getName());
1147  UAS_DIAG(m_uas).removeByName(hwst_diag.getName());
1148  }
1149 
1150  if (!connected) {
1151  // publish connection change
1152  publish_disconnection();
1153 
1154  // Clear known vehicles
1155  vehicles.clear();
1156  }
1157  }
1158 
1159  /* -*- subscription callbacks -*- */
1160 
1162  mavlink::common::msg::STATUSTEXT statustext {};
1163  statustext.severity = req->severity;
1164 
1165  // Limit the length of the string by null-terminating at the 50-th character
1166  ROS_WARN_COND_NAMED(req->text.length() >= statustext.text.size(), "sys",
1167  "Status text too long: truncating...");
1168  mavlink::set_string_z(statustext.text, req->text);
1169 
1170  UAS_FCU(m_uas)->send_message_ignore_drop(statustext);
1171  }
1172 
1173  /* -*- ros callbacks -*- */
1174 
1175  bool set_rate_cb(mavros_msgs::StreamRate::Request &req,
1176  mavros_msgs::StreamRate::Response &res)
1177  {
1178  mavlink::common::msg::REQUEST_DATA_STREAM rq = {};
1179 
1180  rq.target_system = m_uas->get_tgt_system();
1181  rq.target_component = m_uas->get_tgt_component();
1182  rq.req_stream_id = req.stream_id;
1183  rq.req_message_rate = req.message_rate;
1184  rq.start_stop = (req.on_off) ? 1 : 0;
1185 
1186  UAS_FCU(m_uas)->send_message_ignore_drop(rq);
1187  return true;
1188  }
1189 
1190  bool set_mode_cb(mavros_msgs::SetMode::Request &req,
1191  mavros_msgs::SetMode::Response &res)
1192  {
1193  using mavlink::minimal::MAV_MODE_FLAG;
1194 
1195  uint8_t base_mode = req.base_mode;
1196  uint32_t custom_mode = 0;
1197 
1198  if (req.custom_mode != "") {
1199  if (!m_uas->cmode_from_str(req.custom_mode, custom_mode)) {
1200  res.mode_sent = false;
1201  return true;
1202  }
1203 
1209  base_mode |= (m_uas->get_armed()) ? enum_value(MAV_MODE_FLAG::SAFETY_ARMED) : 0;
1210  base_mode |= (m_uas->get_hil_state()) ? enum_value(MAV_MODE_FLAG::HIL_ENABLED) : 0;
1211  base_mode |= enum_value(MAV_MODE_FLAG::CUSTOM_MODE_ENABLED);
1212  }
1213 
1214  mavlink::common::msg::SET_MODE sm = {};
1215  sm.target_system = m_uas->get_tgt_system();
1216  sm.base_mode = base_mode;
1217  sm.custom_mode = custom_mode;
1218 
1219  UAS_FCU(m_uas)->send_message_ignore_drop(sm);
1220  res.mode_sent = true;
1221  return true;
1222  }
1223 
1224  bool vehicle_info_get_cb(mavros_msgs::VehicleInfoGet::Request &req,
1225  mavros_msgs::VehicleInfoGet::Response &res)
1226  {
1227  if (req.get_all) {
1228  // Send all vehicles
1229  for (const auto &got : vehicles) {
1230  res.vehicles.emplace_back(got.second);
1231  }
1232 
1233  res.success = true;
1234  return res.success;
1235  }
1236 
1237  uint8_t req_sysid = req.sysid;
1238  uint8_t req_compid = req.compid;
1239 
1240  if (req.sysid == 0 && req.compid == 0) {
1241  // use target
1242  req_sysid = m_uas->get_tgt_system();
1243  req_compid = m_uas->get_tgt_component();
1244  }
1245 
1246  uint16_t key = get_vehicle_key(req_sysid, req_compid);
1247  auto it = vehicles.find(key);
1248 
1249  if (it == vehicles.end()) {
1250  // Vehicle not found
1251  res.success = false;
1252  return res.success;
1253  }
1254 
1255  res.vehicles.emplace_back(it->second);
1256  res.success = true;
1257  return res.success;
1258  }
1259 
1260  bool set_message_interval_cb(mavros_msgs::MessageInterval::Request &req,
1261  mavros_msgs::MessageInterval::Response &res)
1262  {
1263  using mavlink::common::MAV_CMD;
1264 
1265  try {
1266  auto client = nh.serviceClient<mavros_msgs::CommandLong>("cmd/command");
1267 
1268  // calculate interval
1269  float interval_us;
1270  if (req.message_rate < 0) {
1271  interval_us = -1.0f;
1272  } else if (req.message_rate == 0) {
1273  interval_us = 0.0f;
1274  } else {
1275  interval_us = 1000000.0f / req.message_rate;
1276  }
1277 
1278  mavros_msgs::CommandLong cmd{};
1279 
1280  cmd.request.broadcast = false;
1281  cmd.request.command = enum_value(MAV_CMD::SET_MESSAGE_INTERVAL);
1282  cmd.request.confirmation = false;
1283  cmd.request.param1 = req.message_id;
1284  cmd.request.param2 = interval_us;
1285 
1286  ROS_DEBUG_NAMED("sys", "SetMessageInterval: Request msgid %u at %f hz",
1287  req.message_id, req.message_rate);
1288  res.success = client.call(cmd);
1289  }
1290  catch (ros::InvalidNameException &ex) {
1291  ROS_ERROR_NAMED("sys", "SetMessageInterval: %s", ex.what());
1292  }
1293 
1294  ROS_ERROR_COND_NAMED(!res.success, "sys", "SetMessageInterval: command plugin service call failed!");
1295 
1296  return res.success;
1297  }
1298 };
1299 } // namespace std_plugins
1300 } // namespace mavros
1301 
MemInfo(const std::string &name)
Definition: sys_status.cpp:376
MAVROS Plugin base class.
Definition: mavros_plugin.h:36
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
#define ROS_ERROR_COND_NAMED(cond, name,...)
#define ROS_WARN_COND_NAMED(cond, name,...)
std::shared_ptr< MAVConnInterface const > ConstPtr
std::string format(const std::string &fmt, Args ... args)
BatteryStatusDiag & operator=(BatteryStatusDiag &&other) noexcept
Definition: sys_status.cpp:312
bool set_mode_cb(mavros_msgs::SetMode::Request &req, mavros_msgs::SetMode::Response &res)
#define ROS_INFO_NAMED(name,...)
void run(diagnostic_updater::DiagnosticStatusWrapper &stat)
Definition: sys_status.cpp:167
std::atomic< uint16_t > brkval
Definition: sys_status.cpp:417
#define ROS_DEBUG_STREAM_NAMED(name, args)
std::vector< ros::Time > times_
Definition: sys_status.cpp:134
mavros_msgs::BatteryStatus BatteryMsg
Definition: sys_status.cpp:37
bool vehicle_info_get_cb(mavros_msgs::VehicleInfoGet::Request &req, mavros_msgs::VehicleInfoGet::Response &res)
#define ROS_ERROR_STREAM_NAMED(name, args)
#define ROS_WARN_NAMED(name,...)
System status diagnostic updater.
Definition: sys_status.cpp:153
void handle_heartbeat(const mavlink::mavlink_message_t *msg, mavlink::minimal::msg::HEARTBEAT &hb)
Definition: sys_status.cpp:760
Time & fromNSec(uint64_t t)
void summary(unsigned char lvl, const std::string s)
MAVROS Plugin base.
string cmd
std::unordered_map< uint16_t, mavros_msgs::VehicleInfo > M_VehicleInfo
Definition: sys_status.cpp:613
void statustext_cb(const mavros_msgs::StatusText::ConstPtr &req)
void process_autopilot_version_apm_quirk(mavlink::common::msg::AUTOPILOT_VERSION &apv, uint8_t sysid, uint8_t compid)
Definition: sys_status.cpp:721
uint64_t toNSec() const
void handle_autopilot_version(const mavlink::mavlink_message_t *msg, mavlink::common::msg::AUTOPILOT_VERSION &apv)
Definition: sys_status.cpp:887
void handle_sys_status(const mavlink::mavlink_message_t *msg, mavlink::common::msg::SYS_STATUS &stat)
Definition: sys_status.cpp:822
void tick(uint8_t type_, uint8_t autopilot_, std::string &mode_, uint8_t system_status_)
Definition: sys_status.cpp:86
void setcell_v(const std::vector< float > voltages)
Definition: sys_status.cpp:332
void initialize(UAS &uas_) override
Plugin initializer.
Definition: sys_status.cpp:502
void handle_battery_status(const mavlink::mavlink_message_t *msg, mavlink::common::msg::BATTERY_STATUS &bs)
Definition: sys_status.cpp:918
void timeout_cb(const ros::WallTimerEvent &event)
#define UAS_DIAG(uasobjptr)
helper accessor to diagnostic updater
Definition: mavros_uas.h:48
#define ROS_INFO_STREAM_NAMED(name, args)
std::vector< BatteryStatusDiag > batt_diag
Definition: sys_status.cpp:591
void process_autopilot_version_normal(mavlink::common::msg::AUTOPILOT_VERSION &apv, uint8_t sysid, uint8_t compid)
Definition: sys_status.cpp:698
void addf(const std::string &key, const char *format,...)
Memory usage diag (APM-only)
Definition: sys_status.cpp:373
void run(diagnostic_updater::DiagnosticStatusWrapper &stat)
Definition: sys_status.cpp:337
#define MAX_NR_BATTERY_STATUS
Definition: sys_status.cpp:47
mavlink::common::msg::SYS_STATUS last_st
Definition: sys_status.cpp:280
bool set_message_interval_cb(mavros_msgs::MessageInterval::Request &req, mavros_msgs::MessageInterval::Response &res)
bool set_rate_cb(mavros_msgs::StreamRate::Request &req, mavros_msgs::StreamRate::Response &res)
uint16_t get_vehicle_key(uint8_t sysid, uint8_t compid)
Definition: sys_status.cpp:619
BatteryStatusDiag(BatteryStatusDiag &&other) noexcept
Definition: sys_status.cpp:300
#define ROS_DEBUG_NAMED(name,...)
void handle_extended_sys_state(const mavlink::mavlink_message_t *msg, mavlink::common::msg::EXTENDED_SYS_STATE &state)
Definition: sys_status.cpp:812
std::atomic< size_t > freemem
Definition: sys_status.cpp:416
void publish(const boost::shared_ptr< M > &message) const
void run(diagnostic_updater::DiagnosticStatusWrapper &stat)
Definition: sys_status.cpp:389
void handle_hwstatus(const mavlink::mavlink_message_t *msg, mavlink::ardupilotmega::msg::HWSTATUS &hwst)
Definition: sys_status.cpp:882
UAS for plugins.
Definition: mavros_uas.h:67
void handle_statustext(const mavlink::mavlink_message_t *msg, mavlink::common::msg::STATUSTEXT &textm)
Definition: sys_status.cpp:865
mavlink::minimal::MAV_TYPE mav_type_from_str(const std::string &mav_type)
Retreive MAV_TYPE from name.
void handle_meminfo(const mavlink::mavlink_message_t *msg, mavlink::ardupilotmega::msg::MEMINFO &mem)
Definition: sys_status.cpp:877
#define UAS_FCU(uasobjptr)
helper accessor to FCU link interface
Definition: mavros_uas.h:42
Subscriptions get_subscriptions() override
Return vector of MAVLink message subscriptions (handlers)
Definition: sys_status.cpp:570
HeartbeatStatus(const std::string &name, size_t win_size)
Definition: sys_status.cpp:57
std::string to_string(timesync_mode e)
SystemStatusDiag(const std::string &name)
Definition: sys_status.cpp:156
HwStatus(const std::string &name)
Definition: sys_status.cpp:428
Battery diagnostic updater.
Definition: sys_status.cpp:287
void run(diagnostic_updater::DiagnosticStatusWrapper &stat)
Definition: sys_status.cpp:98
void set(uint32_t f, uint16_t b)
Definition: sys_status.cpp:383
const std::string & getName()
DiagnosticTask(const std::string name)
BatteryStatusDiag(const std::string &name)
Definition: sys_status.cpp:290
std::vector< HandlerInfo > Subscriptions
Subscriptions vector.
Definition: mavros_plugin.h:47
void autopilot_version_cb(const ros::WallTimerEvent &event)
#define ROS_ERROR_NAMED(name,...)
void connection_cb(bool connected) override
static Time now()
M_VehicleInfo::iterator find_or_create_vehicle_info(uint8_t sysid, uint8_t compid)
Definition: sys_status.cpp:624
std::atomic< uint64_t > last_rcd
Definition: sys_status.cpp:418
static std::string custom_version_to_hex_string(std::array< uint8_t, 8 > &array)
Definition: sys_status.cpp:688
void add(const std::string &key, const T &val)
res
#define ROS_ASSERT(cond)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void set(uint16_t v, uint8_t e)
Definition: sys_status.cpp:436
void run(diagnostic_updater::DiagnosticStatusWrapper &stat)
Definition: sys_status.cpp:443
Hardware status (APM-only)
Definition: sys_status.cpp:425
void set(mavlink::common::msg::SYS_STATUS &st)
Definition: sys_status.cpp:161
void process_statustext_normal(uint8_t severity, std::string &text)
Definition: sys_status.cpp:648
constexpr std::underlying_type< _T >::type enum_value(_T e)
Definition: utils.h:55
std::recursive_mutex mutex
#define ROS_WARN_STREAM_NAMED(name, args)
void heartbeat_cb(const ros::WallTimerEvent &event)
void handle_estimator_status(const mavlink::mavlink_message_t *msg, mavlink::common::msg::ESTIMATOR_STATUS &status)


mavros
Author(s): Vladimir Ermakov
autogenerated on Tue Jun 13 2023 02:17:50