diff --git a/libraries/AP_NavEKF2/AP_NavEKF2.cpp b/libraries/AP_NavEKF2/AP_NavEKF2.cpp index 259926899e..3dc7526e7f 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2.cpp @@ -574,6 +574,14 @@ const AP_Param::GroupInfo NavEKF2::var_info[] = { // @Units: mGauss AP_GROUPINFO("MAG_EF_LIM", 52, NavEKF2, _mag_ef_limit, 50), + // @Param: HRT_FILT + // @DisplayName: Height rate filter crossover frequency + // @Description: Specifies the crossover frequency of the complementary filter used to calculate the output predictor height rate derivative. + // @Range: 0.1 100.0 + // @Units: Hz + // @RebootRequired: False + AP_GROUPINFO("HRT_FILT", 53, NavEKF2, _hrt_filt_freq, 2.0f), + AP_GROUPEND }; diff --git a/libraries/AP_NavEKF2/AP_NavEKF2.h b/libraries/AP_NavEKF2/AP_NavEKF2.h index e5b4dee6ca..b0d4bc39ef 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2.h +++ b/libraries/AP_NavEKF2/AP_NavEKF2.h @@ -417,6 +417,7 @@ private: AP_Int8 _extnavDelay_ms; // effective average delay of external nav system measurements relative to inertial measurements (msec) AP_Int8 _flowUse; // Controls if the optical flow data is fused into the main navigation estimator and/or the terrain estimator. AP_Int16 _mag_ef_limit; // limit on difference between WMM tables and learned earth field. + AP_Float _hrt_filt_freq; // frequency of output observer height rate complementary filter in Hz // Possible values for _flowUse #define FLOW_USE_NONE 0 diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp index 054915ee93..ccb958b05b 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp @@ -217,7 +217,7 @@ float NavEKF2_core::getPosDownDerivative(void) const { // return the value calculated from a complementary filter applied to the EKF height and vertical acceleration // correct for the IMU offset (EKF calculations are at the IMU) - return posDownDerivative + velOffsetNED.z; + return vertCompFiltState.vel + velOffsetNED.z; } // This returns the specific forces in the NED frame diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_PosVelFusion.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_PosVelFusion.cpp index 4cf7ddf07e..61d947f4f2 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_PosVelFusion.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_PosVelFusion.cpp @@ -159,6 +159,7 @@ void NavEKF2_core::ResetHeight(void) for (uint8_t i=0; i_hrt_filt_freq, 0.1f, 100.0f); + float omega2 = CompFiltOmega * CompFiltOmega; + float pos_err = outputDataNew.position.z - vertCompFiltState.pos; + float integ1_input = pos_err * omega2 * CompFiltOmega * imuDataNew.delVelDT; + vertCompFiltState.acc += integ1_input; + float integ2_input = delVelNav.z + (vertCompFiltState.acc + pos_err * omega2 * 3.0f) * imuDataNew.delVelDT; + vertCompFiltState.vel += integ2_input; + float integ3_input = (vertCompFiltState.vel + pos_err * CompFiltOmega * 3.0f) * imuDataNew.delVelDT; + vertCompFiltState.pos += integ3_input; + // apply a trapezoidal integration to velocities to calculate position outputDataNew.position += (outputDataNew.velocity + lastVelocity) * (imuDataNew.delVelDT*0.5f); @@ -1406,8 +1423,8 @@ void NavEKF2_core::StoreOutputReset() } outputDataDelayed = outputDataNew; // reset the states for the complementary filter used to provide a vertical position dervative output - posDown = stateStruct.position.z; - posDownDerivative = stateStruct.velocity.z; + vertCompFiltState.pos = stateStruct.position.z; + vertCompFiltState.vel = stateStruct.velocity.z; } // Reset the stored output quaternion history to current EKF state diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_core.h b/libraries/AP_NavEKF2/AP_NavEKF2_core.h index 4a14e52f7e..1ce57d38dc 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_core.h +++ b/libraries/AP_NavEKF2/AP_NavEKF2_core.h @@ -951,8 +951,11 @@ private: Vector3f posOffsetNED; // This adds to the earth frame position estimate at the IMU to give the position at the body origin (m) // variables used to calculate a vertical velocity that is kinematically consistent with the verical position - float posDownDerivative; // Rate of chage of vertical position (dPosD/dt) in m/s. This is the first time derivative of PosD. - float posDown; // Down position state used in calculation of posDownRate + struct { + float pos; + float vel; + float acc; + } vertCompFiltState; // variables used by the pre-initialisation GPS checks struct Location gpsloc_prev; // LLH location of previous GPS measurement