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
parent 4002c2a0af
commit 4145acb6b1
1 changed files with 2 additions and 1 deletions

View File

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