From 79ab474c51c0930a6fe1d8cc84148730a599998e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 18 Jan 2024 16:32:46 +1100 Subject: [PATCH] AP_Soaring: convert remaining uses of TRIM_ARSPD_CM to AIRSPEED_CRUISE --- libraries/AP_Soaring/AP_Soaring.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Soaring/AP_Soaring.cpp b/libraries/AP_Soaring/AP_Soaring.cpp index 56fb621b19..bb51cd3948 100644 --- a/libraries/AP_Soaring/AP_Soaring.cpp +++ b/libraries/AP_Soaring/AP_Soaring.cpp @@ -144,14 +144,14 @@ const AP_Param::GroupInfo SoaringController::var_info[] = { // @Param: THML_ARSPD // @DisplayName: Specific setting for airspeed when soaring in THERMAL mode. - // @Description: If non-zero this airspeed will be used when thermalling. A value of 0 will use TRIM_ARSPD_CM. + // @Description: If non-zero this airspeed will be used when thermalling. A value of 0 will use AIRSPEED_CRUISE. // @Range: 0 50 // @User: Advanced AP_GROUPINFO("THML_ARSPD", 20, SoaringController, soar_thermal_airspeed, 0), // @Param: CRSE_ARSPD // @DisplayName: Specific setting for airspeed when soaring in AUTO mode. - // @Description: If non-zero this airspeed will be used when cruising between thermals in AUTO. If set to -1, airspeed will be selected based on speed-to-fly theory. If set to 0, then TRIM_ARSPD_CM will be used while cruising between thermals. + // @Description: If non-zero this airspeed will be used when cruising between thermals in AUTO. If set to -1, airspeed will be selected based on speed-to-fly theory. If set to 0, then AIRSPEED_CRUISE will be used while cruising between thermals. // @Range: -1 50 // @User: Advanced AP_GROUPINFO("CRSE_ARSPD", 21, SoaringController, soar_cruise_airspeed, 0),