|
|
@ -171,7 +171,8 @@ void AP_OpenDroneID::send_static_out() |
|
|
|
const uint32_t now_ms = AP_HAL::millis(); |
|
|
|
const uint32_t now_ms = AP_HAL::millis(); |
|
|
|
|
|
|
|
|
|
|
|
// we need to notify user if we lost the transmitter
|
|
|
|
// we need to notify user if we lost the transmitter
|
|
|
|
if (now_ms - last_arm_status_ms > 5000) { |
|
|
|
if (now_ms - last_arm_status_ms > 5000 && now_ms - last_lost_tx_ms > 5000) { |
|
|
|
|
|
|
|
last_lost_tx_ms = now_ms; |
|
|
|
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "ODID: lost transmitter"); |
|
|
|
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "ODID: lost transmitter"); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|