mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
AP_Baro: correct param description refering to EK3 wind est params
AP_NavEKF3: correct wind estimate param descriptions mention of EK3_BCOEF_X/Y becomes EK3_DRAG_BCOEF_X/Y
This commit is contained in:
parent
37e9ce3fb7
commit
002bcca7f9
@ -15,7 +15,7 @@ const AP_Param::GroupInfo AP_Baro::WindCoeff::var_info[] = {
|
||||
|
||||
// @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.
|
||||
// @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_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.
|
||||
// @Range: -1.0 1.0
|
||||
// @Increment: 0.05
|
||||
// @User: Advanced
|
||||
@ -23,7 +23,7 @@ const AP_Param::GroupInfo AP_Baro::WindCoeff::var_info[] = {
|
||||
|
||||
// @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.
|
||||
// @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_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.
|
||||
// @Range: -1.0 1.0
|
||||
// @Increment: 0.05
|
||||
// @User: Advanced
|
||||
@ -31,7 +31,7 @@ const AP_Param::GroupInfo AP_Baro::WindCoeff::var_info[] = {
|
||||
|
||||
// @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.
|
||||
// @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_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.
|
||||
// @Range: -1.0 1.0
|
||||
// @Increment: 0.05
|
||||
// @User: Advanced
|
||||
@ -39,7 +39,7 @@ const AP_Param::GroupInfo AP_Baro::WindCoeff::var_info[] = {
|
||||
|
||||
// @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.
|
||||
// @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_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.
|
||||
// @Range: -1.0 1.0
|
||||
// @Increment: 0.05
|
||||
// @User: Advanced
|
||||
|
Loading…
Reference in New Issue
Block a user