AP_Airspeed: fixed autotest for copter param parse

This command was failing:

  Tools/autotest/param_metadata/param_parse.py --vehicle Copter

I don't understand why it starts to fail now, but this is the fix
This commit is contained in:
Andrew Tridgell 2022-06-07 17:04:28 +10:00 committed by Peter Barker
parent 02e23302be
commit eed14b3688

View File

@ -138,8 +138,8 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = {
#if AP_AIRSPEED_AUTOCAL_ENABLE
// @Param: _AUTOCAL
// @DisplayName{Plane}: Automatic airspeed ratio calibration
// @Description{Copter, Blimp, Rover, Sub}: This parameter and function is not used by this vehicle. Always set to 0.
// @DisplayName: Automatic airspeed ratio calibration
// @DisplayName{Copter, Blimp, Rover, Sub}: This parameter and function is not used by this vehicle. Always set to 0.
// @Description: Enables automatic adjustment of ARSPD_RATIO during a calibration flight based on estimation of ground speed and true airspeed. New ratio saved every 2 minutes if change is > 5%. Should not be left enabled.
// @User: Advanced
AP_GROUPINFO("_AUTOCAL", 5, AP_Airspeed, param[0].autocal, 0),