From 9563c1ed334a9cbb57c9d4efb5f9603c94569884 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell <andrew@tridgell.net> Date: Wed, 25 Nov 2020 11:59:44 +1100 Subject: [PATCH] AP_Baro: rename wind coefficient params to be clearer --- libraries/AP_Baro/AP_Baro.cpp | 12 ++++++------ libraries/AP_Baro/AP_Baro_Wind.cpp | 24 ++++++++++++------------ 2 files changed, 18 insertions(+), 18 deletions(-) diff --git a/libraries/AP_Baro/AP_Baro.cpp b/libraries/AP_Baro/AP_Baro.cpp index e28752cf65..c9569b7727 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: WCOF1_ + // @Group: WCF1_ // @Path: AP_Baro_Wind.cpp - AP_SUBGROUPINFO(sensors[0].wind_coeff, "WCOF1_", 18, AP_Baro, WindCoeff), + AP_SUBGROUPINFO(sensors[0].wind_coeff, "WCF1_", 18, AP_Baro, WindCoeff), #if BARO_MAX_INSTANCES > 1 - // @Group: WCOF2_ + // @Group: WCF2_ // @Path: AP_Baro_Wind.cpp - AP_SUBGROUPINFO(sensors[1].wind_coeff, "WCOF2_", 19, AP_Baro, WindCoeff), + AP_SUBGROUPINFO(sensors[1].wind_coeff, "WCF2_", 19, AP_Baro, WindCoeff), #endif #if BARO_MAX_INSTANCES > 2 - // @Group: WCOF3_ + // @Group: WCF3_ // @Path: AP_Baro_Wind.cpp - AP_SUBGROUPINFO(sensors[2].wind_coeff, "WCOF3_", 20, AP_Baro, WindCoeff), + AP_SUBGROUPINFO(sensors[2].wind_coeff, "WCF3_", 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 4476732af9..75d29c9531 100644 --- a/libraries/AP_Baro/AP_Baro_Wind.cpp +++ b/libraries/AP_Baro/AP_Baro_Wind.cpp @@ -13,37 +13,37 @@ const AP_Param::GroupInfo AP_Baro::WindCoeff::var_info[] = { // @User: Advanced AP_GROUPINFO_FLAGS("ENABLE", 1, WindCoeff, enable, 0, AP_PARAM_FLAG_ENABLE), - // @Param: XP - // @DisplayName: Pressure error coefficient in positive X direction + // @Param: FWD + // @DisplayName: Pressure error coefficient in positive X direction (forward) // @Description: This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the X body axis. If the baro height estimate rises during forwards 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("XP", 2, WindCoeff, xp, 0.0), + AP_GROUPINFO("FWD", 2, WindCoeff, xp, 0.0), - // @Param: XN - // @DisplayName: Pressure error coefficient in negative X direction + // @Param: BAK + // @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("XN", 3, WindCoeff, xn, 0.0), + AP_GROUPINFO("BAK", 3, WindCoeff, xn, 0.0), - // @Param: YP - // @DisplayName: Pressure error coefficient in positive Y direction + // @Param: RGT + // @DisplayName: Pressure error coefficient in positive Y direction (right) // @Description: This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the Y body axis. If the baro height estimate rises during sideways flight to the right, then this should 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("YP", 4, WindCoeff, yp, 0.0), + AP_GROUPINFO("RGT", 4, WindCoeff, yp, 0.0), - // @Param: YN - // @DisplayName: Pressure error coefficient in negative Y direction + // @Param: LFT + // @DisplayName: Pressure error coefficient in negative Y direction (left) // @Description: This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the Y body axis. If the baro height estimate rises during sideways flight to the left, then this should 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("YN", 5, WindCoeff, yn, 0.0), + AP_GROUPINFO("LFT", 5, WindCoeff, yn, 0.0), AP_GROUPEND };