diff --git a/libraries/AP_NavEKF3/AP_NavEKF3.cpp b/libraries/AP_NavEKF3/AP_NavEKF3.cpp index 303751734c..9c7c281ed0 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3.cpp @@ -588,6 +588,14 @@ const AP_Param::GroupInfo NavEKF3::var_info[] = { // @RebootRequired: True AP_GROUPINFO("FLOW_USE", 54, NavEKF3, _flowUse, FLOW_USE_DEFAULT), + // @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", 55, NavEKF3, _hrt_filt_freq, 2.0f), + AP_GROUPEND }; diff --git a/libraries/AP_NavEKF3/AP_NavEKF3.h b/libraries/AP_NavEKF3/AP_NavEKF3.h index 53ec71a16a..7be4bc8ccd 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3.h +++ b/libraries/AP_NavEKF3/AP_NavEKF3.h @@ -447,6 +447,7 @@ private: AP_Float _visOdmVelErrMin; // Observation 1-STD velocity error assumed for visual odometry sensor at highest reported quality (m/s) AP_Float _wencOdmVelErr; // Observation 1-STD velocity error assumed for wheel odometry sensor (m/s) AP_Int8 _flowUse; // Controls if the optical flow data is fused into the main navigation estimator and/or the terrain estimator. + 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_NavEKF3/AP_NavEKF3_Outputs.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp index 5197db7044..ed18c8bba4 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp @@ -224,7 +224,7 @@ float NavEKF3_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_NavEKF3/AP_NavEKF3_PosVelFusion.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp index de4306cfa7..e80ebe2cdf 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp @@ -157,6 +157,7 @@ void NavEKF3_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); @@ -1409,8 +1426,8 @@ void NavEKF3_core::StoreOutputReset() } outputDataDelayed = outputDataNew; // reset the states for the complementary filter used to provide a vertical position derivative 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_NavEKF3/AP_NavEKF3_core.h b/libraries/AP_NavEKF3/AP_NavEKF3_core.h index db670d8fa7..783110841f 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_core.h +++ b/libraries/AP_NavEKF3/AP_NavEKF3_core.h @@ -1022,8 +1022,11 @@ private: resetDataSource velResetSource; // preferred source of data for a velocity reset // variables used to calculate a vertical velocity that is kinematically consistent with the vertical position - float posDownDerivative; // Rate of change 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