mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF2: reduce EK2_HRT_FILT max to 30
This commit is contained in:
parent
c26c6fd078
commit
e2d3afaaa7
|
@ -577,7 +577,7 @@ const AP_Param::GroupInfo NavEKF2::var_info[] = {
|
|||
// @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
|
||||
// @Range: 0.1 30.0
|
||||
// @Units: Hz
|
||||
// @RebootRequired: False
|
||||
AP_GROUPINFO("HRT_FILT", 53, NavEKF2, _hrt_filt_freq, 2.0f),
|
||||
|
|
|
@ -758,7 +758,7 @@ void NavEKF2_core::calcOutputStates()
|
|||
|
||||
// Perform filter calculation using backwards Euler integration
|
||||
// Coefficients selected to place all three filter poles at omega
|
||||
const float CompFiltOmega = M_2PI * constrain_float(frontend->_hrt_filt_freq, 0.1f, 100.0f);
|
||||
const float CompFiltOmega = M_2PI * constrain_float(frontend->_hrt_filt_freq, 0.1f, 30.0f);
|
||||
float omega2 = CompFiltOmega * CompFiltOmega;
|
||||
float pos_err = outputDataNew.position.z - vertCompFiltState.pos;
|
||||
float integ1_input = pos_err * omega2 * CompFiltOmega * imuDataNew.delVelDT;
|
||||
|
|
Loading…
Reference in New Issue