GCS_MAVLink: correct mavlink result when airspeed not available

only in progress if we have started a task running
This commit is contained in:
Peter Barker 2023-11-01 10:23:07 +11:00 committed by Peter Barker
parent 4ec80076a1
commit 9d9b95af15
1 changed files with 2 additions and 1 deletions

View File

@ -4352,10 +4352,11 @@ MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration_baro(const mavlink
return MAV_RESULT_TEMPORARILY_REJECTED;
}
airspeed->calibrate(false);
return MAV_RESULT_IN_PROGRESS;
}
#endif
return MAV_RESULT_IN_PROGRESS;
return MAV_RESULT_ACCEPTED;
}
MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg)