Rover: allow mavlink when in sensor error
This commit is contained in:
parent
97e54f6359
commit
ce9352942f
@ -313,6 +313,7 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id)
|
|||||||
// 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() &&
|
||||||
|
!AP_BoardConfig::in_sensor_config_error() &&
|
||||||
rover.scheduler.time_available_usec() < 200) {
|
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