PX4 Firmware
PX4 Autopilot Software http://px4.io
PreFlightChecker.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2019 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 /**
35  * @file PreFlightCheckHelper.cpp
36  * Class handling the EKF2 innovation pre flight checks
37  */
38 
39 #include "PreFlightChecker.hpp"
40 
41 void PreFlightChecker::update(const float dt, const ekf2_innovations_s &innov)
42 {
44 
49 }
50 
52 {
53  const float heading_test_limit = selectHeadingTestLimit();
54  const float heading_innov_spike_lim = 2.0f * heading_test_limit;
55 
56  const float heading_innov_lpf = _filter_heading_innov.update(innov.heading_innov, alpha, heading_innov_spike_lim);
57 
58  return checkInnovFailed(innov.heading_innov, heading_innov_lpf, heading_test_limit);
59 }
60 
62 {
63  // Select the max allowed heading innovaton depending on whether we are not aiding navigation using
64  // observations in the NE reference frame and if the vehicle can use GPS course to realign in flight (fixedwing sideslip fusion).
65  const bool is_ne_aiding = _is_using_gps_aiding || _is_using_ev_pos_aiding;
66 
67  return (is_ne_aiding && !_can_observe_heading_in_flight)
68  ? _nav_heading_innov_test_lim // more restrictive test limit
69  : _heading_innov_test_lim; // less restrictive test limit
70 }
71 
73 {
74  bool has_failed = false;
75 
77  const Vector2f vel_ne_innov = Vector2f(innov.vel_pos_innov);
78  Vector2f vel_ne_innov_lpf;
79  vel_ne_innov_lpf(0) = _filter_vel_n_innov.update(vel_ne_innov(0), alpha, _vel_innov_spike_lim);
80  vel_ne_innov_lpf(1) = _filter_vel_n_innov.update(vel_ne_innov(1), alpha, _vel_innov_spike_lim);
81  has_failed |= checkInnov2DFailed(vel_ne_innov, vel_ne_innov_lpf, _vel_innov_test_lim);
82  }
83 
85  const Vector2f flow_innov = Vector2f(innov.flow_innov);
86  Vector2f flow_innov_lpf;
87  flow_innov_lpf(0) = _filter_flow_x_innov.update(flow_innov(0), alpha, _flow_innov_spike_lim);
88  flow_innov_lpf(1) = _filter_flow_x_innov.update(flow_innov(1), alpha, _flow_innov_spike_lim);
89  has_failed |= checkInnov2DFailed(flow_innov, flow_innov_lpf, _flow_innov_test_lim);
90  }
91 
92  return has_failed;
93 }
94 
96 {
97  const float vel_d_innov = innov.vel_pos_innov[2];
98  const float vel_d_innov_lpf = _filter_vel_d_innov.update(vel_d_innov, alpha, _vel_innov_spike_lim);
99  return checkInnovFailed(vel_d_innov, vel_d_innov_lpf, _vel_innov_test_lim);
100 }
101 
103 {
104  const float hgt_innov = innov.vel_pos_innov[5];
105  const float hgt_innov_lpf = _filter_hgt_innov.update(hgt_innov, alpha, _hgt_innov_spike_lim);
106  return checkInnovFailed(hgt_innov, hgt_innov_lpf, _hgt_innov_test_lim);
107 }
108 
109 bool PreFlightChecker::checkInnovFailed(const float innov, const float innov_lpf, const float test_limit)
110 {
111  return fabsf(innov_lpf) > test_limit || fabsf(innov) > 2.0f * test_limit;
112 }
113 
114 bool PreFlightChecker::checkInnov2DFailed(const Vector2f &innov, const Vector2f &innov_lpf, const float test_limit)
115 {
116  return innov_lpf.norm_squared() > sq(test_limit)
117  || innov.norm_squared() > sq(2.0f * test_limit);
118 }
119 
121 {
122  _is_using_gps_aiding = false;
123  _is_using_flow_aiding = false;
124  _is_using_ev_pos_aiding = false;
125  _has_heading_failed = false;
126  _has_horiz_vel_failed = false;
127  _has_vert_vel_failed = false;
128  _has_height_failed = false;
136 }
void reset(float val=0.f)
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)
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)
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)
Vector< float, 6 > f(float t, const Matrix< float, 6, 1 > &, const Matrix< float, 3, 1 > &)
Definition: integration.cpp:8
Vector2< float > Vector2f
Definition: Vector2.hpp:69
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
float dt
Definition: px4io.c:73
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