54 const float heading_innov_spike_lim = 2.0f * heading_test_limit;
74 bool has_failed =
false;
111 return fabsf(innov_lpf) > test_limit || fabsf(innov) > 2.0f * test_limit;
116 return innov_lpf.norm_squared() >
sq(test_limit)
117 || innov.norm_squared() >
sq(2.0
f * test_limit);
bool _has_vert_vel_failed
void reset(float val=0.f)
bool _is_using_ev_pos_aiding
static constexpr float _innov_lpf_tau_inv
static bool checkInnovFailed(float innov, float innov_lpf, float test_limit)
InnovationLpf _filter_heading_innov
Preflight low pass filter heading innovation magntitude (rad)
InnovationLpf _filter_vel_d_innov
Preflight low pass filter D axis velocity innovations (m/sec)
bool _is_using_flow_aiding
float update(float val, float alpha, float spike_limit)
Update the filter with a new value and returns the filtered state The new value is constained by the ...
float selectHeadingTestLimit()
InnovationLpf _filter_flow_x_innov
Preflight low pass filter optical flow innovation (rad)
bool _can_observe_heading_in_flight
void update(float dt, const ekf2_innovations_s &innov)
static float computeAlphaFromDtAndTauInv(float dt, float tau_inv)
Helper function to compute alpha from dt and the inverse of tau.
InnovationLpf _filter_flow_y_innov
Preflight low pass filter optical flow innovation (rad)
static constexpr float _flow_innov_spike_lim
static constexpr float _hgt_innov_test_lim
bool preFlightCheckHorizVelFailed(const ekf2_innovations_s &innov, float alpha)
bool _has_horiz_vel_failed
Vector< float, 6 > f(float t, const Matrix< float, 6, 1 > &, const Matrix< float, 3, 1 > &)
Vector2< float > Vector2f
static constexpr float sq(float var)
bool preFlightCheckVertVelFailed(const ekf2_innovations_s &innov, float alpha)
InnovationLpf _filter_hgt_innov
Preflight low pass filter height innovation (m)
bool preFlightCheckHeightFailed(const ekf2_innovations_s &innov, float alpha)
static constexpr float _vel_innov_test_lim
static constexpr float _heading_innov_test_lim
static constexpr float _vel_innov_spike_lim
static constexpr float _flow_innov_test_lim
Class handling the EKF2 innovation pre flight checks.
static bool checkInnov2DFailed(const Vector2f &innov, const Vector2f &innov_lpf, float test_limit)
InnovationLpf _filter_vel_e_innov
Preflight low pass filter E axis velocity innovations (m/sec)
static constexpr float _hgt_innov_spike_lim
bool preFlightCheckHeadingFailed(const ekf2_innovations_s &innov, float alpha)
InnovationLpf _filter_vel_n_innov
Preflight low pass filter N axis velocity innovations (m/sec)
static constexpr float _nav_heading_innov_test_lim
bool _is_using_gps_aiding