mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: correct wind estimate param descriptions
EK3_MCOEF becomes EK3_DRAG_MCOEF EK3_BCOEF_X/Y becomes EK3_DRAG_BCOEF_X/Y
This commit is contained in:
parent
56513a0761
commit
37e9ce3fb7
|
@ -664,7 +664,7 @@ const AP_Param::GroupInfo NavEKF3::var_info2[] = {
|
|||
|
||||
// @Param: DRAG_BCOEF_X
|
||||
// @DisplayName: Ballistic coefficient for X axis drag
|
||||
// @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.
|
||||
// @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_DRAG_MCOEF parameter.
|
||||
// @Range: 0.0 1000.0
|
||||
// @Units: kg/m/m
|
||||
// @User: Advanced
|
||||
|
@ -672,7 +672,7 @@ const AP_Param::GroupInfo NavEKF3::var_info2[] = {
|
|||
|
||||
// @Param: DRAG_BCOEF_Y
|
||||
// @DisplayName: Ballistic coefficient for Y axis drag
|
||||
// @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.
|
||||
// @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_DRAG_MCOEF parameter.
|
||||
// @Range: 50.0 1000.0
|
||||
// @Units: kg/m/m
|
||||
// @User: Advanced
|
||||
|
@ -680,7 +680,7 @@ const AP_Param::GroupInfo NavEKF3::var_info2[] = {
|
|||
|
||||
// @Param: DRAG_M_NSE
|
||||
// @DisplayName: Observation noise for drag acceleration
|
||||
// @Description: This sets the amount of noise used when fusing X and Y acceleration as an observation that enables esitmation of wind velocity for multi-rotor vehicles. This feature is enabled by the EK3_BCOEF_X and EK3_BCOEF_Y parameters
|
||||
// @Description: This sets the amount of noise used when fusing X and Y acceleration as an observation that enables esitmation of wind velocity for multi-rotor vehicles. This feature is enabled by the EK3_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters
|
||||
// @Range: 0.1 2.0
|
||||
// @Increment: 0.1
|
||||
// @User: Advanced
|
||||
|
@ -689,7 +689,7 @@ const AP_Param::GroupInfo NavEKF3::var_info2[] = {
|
|||
|
||||
// @Param: DRAG_MCOEF
|
||||
// @DisplayName: Momentum coefficient for propeller drag
|
||||
// @Description: This parameter is used to predict the drag produced by the rotors when flying a multi-copter, enabling estimation of wind drift. The drag produced by this effect scales with speed not speed squared and is produced because some of the air velocity normal to the rotors axis of rotation is lost when passing through the rotor disc which changes the momentum of the airflow causing drag. For unducted rotors the effect is roughly proportional to the area of the propeller blades when viewed side on and changes with different propellers. It is higher for ducted rotors. For example if flying at 15 m/s at sea level conditions produces a rotor induced drag acceleration of 1.5 m/s/s, then EK3_MCOEF would be set to 0.1 = (1.5/15.0). Set EK3_MCOEF to a postive value to enable wind estimation using this drag effect. To account for the drag produced by the body which scales with speed squared, see documentation for the EK3_BCOEF_X and EK3_BCOEF_Y parameters.
|
||||
// @Description: This parameter is used to predict the drag produced by the rotors when flying a multi-copter, enabling estimation of wind drift. The drag produced by this effect scales with speed not speed squared and is produced because some of the air velocity normal to the rotors axis of rotation is lost when passing through the rotor disc which changes the momentum of the airflow causing drag. For unducted rotors the effect is roughly proportional to the area of the propeller blades when viewed side on and changes with different propellers. It is higher for ducted rotors. For example if flying at 15 m/s at sea level conditions produces a rotor induced drag acceleration of 1.5 m/s/s, then EK3_DRAG_MCOEF would be set to 0.1 = (1.5/15.0). Set EK3_MCOEF to a postive value to enable wind estimation using this drag effect. To account for the drag produced by the body which scales with speed squared, see documentation for the EK3_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters.
|
||||
// @Range: 0.0 1.0
|
||||
// @Increment: 0.01
|
||||
// @Units: 1/s
|
||||
|
|
Loading…
Reference in New Issue