mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-20 20:03:54 +08:00
ekf2: Add parameter for propeller momentum drag
This commit is contained in:
committed by
Daniel Agar
parent
909326e9d8
commit
2d6363e0ef
@@ -152,6 +152,7 @@ EKF2::EKF2(bool multi_mode, const px4::wq_config_t &config, bool replay_mode):
|
||||
_param_ekf2_drag_noise(_params->drag_noise),
|
||||
_param_ekf2_bcoef_x(_params->bcoef_x),
|
||||
_param_ekf2_bcoef_y(_params->bcoef_y),
|
||||
_param_ekf2_mcoef(_params->mcoef),
|
||||
_param_ekf2_aspd_max(_params->max_correction_airspeed),
|
||||
_param_ekf2_pcoef_xp(_params->static_pressure_coef_xp),
|
||||
_param_ekf2_pcoef_xn(_params->static_pressure_coef_xn),
|
||||
|
||||
@@ -489,6 +489,7 @@ private:
|
||||
_param_ekf2_drag_noise, ///< observation noise variance for drag specific force measurements (m/sec**2)**2
|
||||
(ParamExtFloat<px4::params::EKF2_BCOEF_X>) _param_ekf2_bcoef_x, ///< ballistic coefficient along the X-axis (kg/m**2)
|
||||
(ParamExtFloat<px4::params::EKF2_BCOEF_Y>) _param_ekf2_bcoef_y, ///< ballistic coefficient along the Y-axis (kg/m**2)
|
||||
(ParamExtFloat<px4::params::EKF2_MCOEF>) _param_ekf2_mcoef, ///< propeller momentum drag coefficient (1/s)
|
||||
|
||||
// Corrections for static pressure position error where Ps_error = Ps_meas - Ps_truth
|
||||
// Coef = Ps_error / Pdynamic, where Pdynamic = 1/2 * density * TAS**2
|
||||
|
||||
@@ -1151,9 +1151,9 @@ PARAM_DEFINE_FLOAT(EKF2_EVP_GATE, 5.0f);
|
||||
PARAM_DEFINE_FLOAT(EKF2_DRAG_NOISE, 2.5f);
|
||||
|
||||
/**
|
||||
* X-axis ballistic coefficient used by the multi-rotor specific drag force model.
|
||||
* X-axis ballistic coefficient used for multi-rotor wind estimation.
|
||||
*
|
||||
* This should be adjusted to minimise variance of the X-axis drag specific force innovation sequence.
|
||||
* This parameter controls the prediction of drag produced by bluff body drag when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_AID_MASK parameter. The EKF2_BCOEF_X paraemter should be set initially to the ratio of mass / x axis projected area and adjusted together with EKF2_MCOEF to minimise variance of the X-axis drag specific force innovation sequence. The drag produced by this effect scales with speed squared. The predicted drag from the rotors is specified separately by the EKF2_MCOEF parameter.
|
||||
*
|
||||
* @group EKF2
|
||||
* @min 1.0
|
||||
@@ -1161,12 +1161,12 @@ PARAM_DEFINE_FLOAT(EKF2_DRAG_NOISE, 2.5f);
|
||||
* @unit kg/m^2
|
||||
* @decimal 1
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(EKF2_BCOEF_X, 25.0f);
|
||||
PARAM_DEFINE_FLOAT(EKF2_BCOEF_X, 100.0f);
|
||||
|
||||
/**
|
||||
* Y-axis ballistic coefficient used by the multi-rotor specific drag force model.
|
||||
* Y-axis ballistic coefficient used for multi-rotor wind estimation.
|
||||
*
|
||||
* This should be adjusted to minimise variance of the Y-axis drag specific force innovation sequence.
|
||||
* This parameter controls the prediction of drag produced by bluff body drag when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_AID_MASK parameter. The EKF2_BCOEF_Y paraemter should be set initially to the ratio of mass / Y axis projected area and adjusted together with EKF2_MCOEF to minimise variance of the Y-axis drag specific force innovation sequence. The drag produced by this effect scales with speed squared. The predicted drag from the rotors is specified separately by the EKF2_MCOEF parameter.
|
||||
*
|
||||
* @group EKF2
|
||||
* @min 1.0
|
||||
@@ -1174,7 +1174,21 @@ PARAM_DEFINE_FLOAT(EKF2_BCOEF_X, 25.0f);
|
||||
* @unit kg/m^2
|
||||
* @decimal 1
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(EKF2_BCOEF_Y, 25.0f);
|
||||
PARAM_DEFINE_FLOAT(EKF2_BCOEF_Y, 100.0f);
|
||||
|
||||
/**
|
||||
* propeller momentum drag coefficient used for multi-rotor wind estimation.
|
||||
*
|
||||
* This parameter controls the prediction of drag produced by the propellers when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_AID_MASK parameter. The drag produced by this effect scales with speed not speed squared and is produced because some of the air velocity normal to the propeller axis of rotation is lost when passing through the rotor disc. This changes the momentum of the flow which creates a drag reaction force. When comparing un-ducted propellers of the same diameter, the effect is roughly proportional to the area of the propeller blades when viewed side on and changes with propeller selection. Momentum drag is significantly higher for ducted rotors. For example, if flying at 10 m/s at sea level conditions produces a rotor induced drag deceleration of 1.0m/s/s when the multi-copter levelled to zero roll/pitch, then EKF2_MCOEF would be set to 0.1 = (1.0/10.0). Set EKF2_MCOEF to a positive 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 EKF2_BCOEF_X and EKF2_BCOEF_Y parameters. The EKF2_MCOEF parameter should be adjusted together with EKF2_BCOEF_X and EKF2_BCOEF_Y to minimise variance of the X and y axis drag specific force innovation sequences.
|
||||
*
|
||||
* @group EKF2
|
||||
* @min 0
|
||||
* @max 1.0
|
||||
* @unit 1/s
|
||||
* @decimal 2
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(EKF2_MCOEF, 0.1f);
|
||||
|
||||
|
||||
/**
|
||||
* Upper limit on airspeed along individual axes used to correct baro for position error effects
|
||||
|
||||
Reference in New Issue
Block a user