Browse Source

AP_OpenDroneID: report if we lose operator location

release-4.2.3
Andrew Tridgell 3 years ago committed by Randy Mackay
parent
commit
bfb8cb08fd
  1. 6
      libraries/AP_OpenDroneID/AP_OpenDroneID.cpp
  2. 3
      libraries/AP_OpenDroneID/AP_OpenDroneID.h

6
libraries/AP_OpenDroneID/AP_OpenDroneID.cpp

@ -176,6 +176,12 @@ void AP_OpenDroneID::send_static_out() @@ -176,6 +176,12 @@ void AP_OpenDroneID::send_static_out()
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "ODID: lost transmitter");
}
// we need to notify user if we lost system msg with operator location
if (now_ms - last_system_ms > 5000 && now_ms - last_lost_operator_msg_ms > 5000) {
last_lost_operator_msg_ms = now_ms;
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "ODID: lost operator location");
}
const uint32_t msg_spacing_ms = _mavlink_dynamic_period_ms / 4;
if (now_ms - last_msg_send_ms >= msg_spacing_ms) {
// allow update of channel during setup, this makes it easy to debug with a GCS

3
libraries/AP_OpenDroneID/AP_OpenDroneID.h

@ -145,6 +145,9 @@ private: @@ -145,6 +145,9 @@ private:
// last time we sent a lost transmitter message
uint32_t last_lost_tx_ms;
// last time we sent a lost operator location notice
uint32_t last_lost_operator_msg_ms;
// transmit functions to manually send a static MAVLink message
void send_dynamic_out();
void send_static_out();

Loading…
Cancel
Save