mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: Change to leave the lower 16 bits.
This commit is contained in:
parent
c591e45e59
commit
6304ade668
|
@ -1062,7 +1062,7 @@ void GCS_MAVLINK::update_send()
|
|||
#endif
|
||||
|
||||
const uint32_t start = AP_HAL::millis();
|
||||
const uint16_t start16 = AP_HAL::millis16();
|
||||
const uint16_t start16 = start & 0xFFFF;
|
||||
while (AP_HAL::millis() - start < 5) { // spend a max of 5ms sending messages. This should never trigger - out_of_time() should become true
|
||||
if (gcs().out_of_time()) {
|
||||
#if GCS_DEBUG_SEND_MESSAGE_TIMINGS
|
||||
|
|
Loading…
Reference in New Issue