mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
AP_Baro: rename wind coefficient params to be clearer
This commit is contained in:
parent
4884476c09
commit
9563c1ed33
@ -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
|
||||
|
||||
|
@ -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
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user