mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
Rover: shorten time remaining in try_send_message
The scheduler table entry for retrying defered messages doesn't allow enough time for try_send_messages to run. This change makes the time-remaining requirement the same as Plane.
This commit is contained in:
parent
95df35f102
commit
90124c20cb
@ -258,11 +258,11 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id)
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
// if we don't have at least 1ms remaining before the main loop
|
// if we don't have at least 0.2ms remaining before the main loop
|
||||||
// wants to fire then don't send a mavlink message. We want to
|
// wants to fire then don't send a mavlink message. We want to
|
||||||
// prioritise the main flight control loop over communications
|
// prioritise the main flight control loop over communications
|
||||||
if (!hal.scheduler->in_delay_callback() &&
|
if (!hal.scheduler->in_delay_callback() &&
|
||||||
rover.scheduler.time_available_usec() < 1200) {
|
rover.scheduler.time_available_usec() < 200) {
|
||||||
gcs().set_out_of_time(true);
|
gcs().set_out_of_time(true);
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user