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


mavros
Author(s): Vladimir Ermakov
autogenerated on Tue May 6 2025 02:34:03