mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Tracker: update time last heartbeat packet sent
This is required to support dataflash messages
This commit is contained in:
parent
6a5c5969fa
commit
8aa286eaaa
@ -178,6 +178,7 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id)
|
||||
switch (id) {
|
||||
case MSG_HEARTBEAT:
|
||||
CHECK_PAYLOAD_SIZE(HEARTBEAT);
|
||||
tracker.gcs[chan-MAVLINK_COMM_0].last_heartbeat_time = AP_HAL::millis();
|
||||
tracker.send_heartbeat(chan);
|
||||
return true;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user