From 9d9b95af15faaf0c065f95ef9ee291287e67cb62 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 1 Nov 2023 10:23:07 +1100 Subject: [PATCH] GCS_MAVLink: correct mavlink result when airspeed not available only in progress if we have started a task running --- libraries/GCS_MAVLink/GCS_Common.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index d5c407ed2f..1d383a1003 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -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)