mirror of https://github.com/ArduPilot/ardupilot
AP_OpenDroneID: prevent sending of lost transmitter msg too fast
This commit is contained in:
parent
0e037c99f3
commit
74a66ede95
|
@ -171,7 +171,8 @@ void AP_OpenDroneID::send_static_out()
|
|||
const uint32_t now_ms = AP_HAL::millis();
|
||||
|
||||
// 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");
|
||||
}
|
||||
|
||||
|
|
|
@ -142,6 +142,9 @@ private:
|
|||
mavlink_open_drone_id_arm_status_t arm_status;
|
||||
uint32_t last_arm_status_ms;
|
||||
|
||||
// last time we sent a lost transmitter message
|
||||
uint32_t last_lost_tx_ms;
|
||||
|
||||
// transmit functions to manually send a static MAVLink message
|
||||
void send_dynamic_out();
|
||||
void send_static_out();
|
||||
|
|
Loading…
Reference in New Issue