From 3e2ff717503ec63b8aeb9ca355f6a30af77ef518 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 7 Dec 2020 07:37:08 +1100 Subject: [PATCH] AP_Baro: rename params to suit new BARO param naming --- libraries/AP_Baro/AP_Baro.cpp | 12 ++++++------ libraries/AP_Baro/AP_Baro_Wind.cpp | 4 ++-- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/libraries/AP_Baro/AP_Baro.cpp b/libraries/AP_Baro/AP_Baro.cpp index c9569b7727..11027c43d7 100644 --- a/libraries/AP_Baro/AP_Baro.cpp +++ b/libraries/AP_Baro/AP_Baro.cpp @@ -199,20 +199,20 @@ const AP_Param::GroupInfo AP_Baro::var_info[] = { #endif #if HAL_BARO_WIND_COMP_ENABLED - // @Group: WCF1_ + // @Group: 1_WCF_ // @Path: AP_Baro_Wind.cpp - AP_SUBGROUPINFO(sensors[0].wind_coeff, "WCF1_", 18, AP_Baro, WindCoeff), + AP_SUBGROUPINFO(sensors[0].wind_coeff, "1_WCF_", 18, AP_Baro, WindCoeff), #if BARO_MAX_INSTANCES > 1 - // @Group: WCF2_ + // @Group: 2_WCF_ // @Path: AP_Baro_Wind.cpp - AP_SUBGROUPINFO(sensors[1].wind_coeff, "WCF2_", 19, AP_Baro, WindCoeff), + AP_SUBGROUPINFO(sensors[1].wind_coeff, "2_WCF_", 19, AP_Baro, WindCoeff), #endif #if BARO_MAX_INSTANCES > 2 - // @Group: WCF3_ + // @Group: 3_WCF_ // @Path: AP_Baro_Wind.cpp - AP_SUBGROUPINFO(sensors[2].wind_coeff, "WCF3_", 20, AP_Baro, WindCoeff), + AP_SUBGROUPINFO(sensors[2].wind_coeff, "3_WCF_", 20, AP_Baro, WindCoeff), #endif #endif diff --git a/libraries/AP_Baro/AP_Baro_Wind.cpp b/libraries/AP_Baro/AP_Baro_Wind.cpp index 75d29c9531..f8694c7050 100644 --- a/libraries/AP_Baro/AP_Baro_Wind.cpp +++ b/libraries/AP_Baro/AP_Baro_Wind.cpp @@ -21,13 +21,13 @@ const AP_Param::GroupInfo AP_Baro::WindCoeff::var_info[] = { // @User: Advanced AP_GROUPINFO("FWD", 2, WindCoeff, xp, 0.0), - // @Param: BAK + // @Param: BCK // @DisplayName: Pressure error coefficient in negative X direction (backwards) // @Description: This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the X body axis. If the baro height estimate rises during backwards flight, then this will be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_BCOEF_X and EK3_BCOEF_Y parameters have been tuned. // @Range: -1.0 1.0 // @Increment: 0.05 // @User: Advanced - AP_GROUPINFO("BAK", 3, WindCoeff, xn, 0.0), + AP_GROUPINFO("BCK", 3, WindCoeff, xn, 0.0), // @Param: RGT // @DisplayName: Pressure error coefficient in positive Y direction (right)