From ab05e8ed4af44139a2962d15af859591b1352d6b Mon Sep 17 00:00:00 2001 From: Paul Riseborough Date: Sun, 22 Nov 2020 10:48:37 +1100 Subject: [PATCH] AP_NavEKF3: Update param descriptions --- libraries/AP_NavEKF3/AP_NavEKF3.cpp | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/libraries/AP_NavEKF3/AP_NavEKF3.cpp b/libraries/AP_NavEKF3/AP_NavEKF3.cpp index 60f59fa4c8..0e366d6b1f 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3.cpp @@ -193,17 +193,14 @@ const AP_Param::GroupInfo NavEKF3::var_info[] = { // @Param: BCOEF_X // @DisplayName: Ballistic coefficient measured in X direction // @Description: Ratio of mass to drag coefficient measured along the X body axis. This parameter enables estimation of wind drift for vehicles with bluff bodies and without propulsion forces in the X and Y direction (eg multicopters). The drag produced by this effect scales with speed squared. Set to a postive value > 1.0 to enable. A starting value is the mass in Kg divided by the frontal area. The predicted drag from the rotors is specified separately by the EK3_MCOEF parameter. - // @Range: 0.0 100.0 - // @Increment: 1.0 + // @Range: 0.0 1000.0 // @User: Advanced // @Param: BCOEF_Y // @DisplayName: Ballistic coefficient measured in Y direction // @Description: Ratio of mass to drag coefficient measured along the Y body axis. This parameter enables estimation of wind drift for vehicles with bluff bodies and without propulsion forces in the X and Y direction (eg multicopters). The drag produced by this effect scales with speed squared. Set to a postive value > 1.0 to enable. A starting value is the mass in Kg divided by the side area. The predicted drag from the rotors is specified separately by the EK3_MCOEF parameter. // @Range: 50.0 1000.0 - // @Increment: 10.0 // @User: Advanced - // @Param: BCOEF_Y // @Param: BCOEF_Z // @DisplayName: unused