Rover: allow mavlink when in sensor error

This commit is contained in:
Andrew Tridgell 2019-01-04 17:57:36 +11:00
parent 97e54f6359
commit ce9352942f
1 changed files with 1 additions and 0 deletions

View File

@ -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
// prioritise the main flight control loop over communications
if (!hal.scheduler->in_delay_callback() &&
!AP_BoardConfig::in_sensor_config_error() &&
rover.scheduler.time_available_usec() < 200) {
gcs().set_out_of_time(true);
return false;