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


mavros
Author(s): Vladimir Ermakov
autogenerated on Tue Jun 1 2021 02:36:26