-
Notifications
You must be signed in to change notification settings - Fork 13.7k
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
ekf2_main - Add optical flow innovation pre-flight check (#13036)
* ekf2: Add FirstOrderLpf and InnovationLpf classes for innovation lowpass filtering * ekf2: use InnovLpf filter class in preflight checks * ekf2: move selection of yaw test limit for pre-flight check in function * ekf2: Move pre-flight checks into separate function * ekf2: use static constexpr insetead of inline for sq (square) function * ekf2: Split pre-flight checks in separate functions Also use the same check for all the innovations: innov_lpf < test and innov < 2xtest * ekf2: Add optical flow pre-flight check * ekf2: Combine FirstOrderLpf and InnovationLpf in single class * ekf2: check vel_pos_innov when ev_pos is active as well * ekf2: transform InnovationLpf into a header only library and pass the spike limit during the update call to avoid storing it here * ekf2: Static and const cleanup - set spike_lim constants as static constexpr, set innovation - set checker helper functions as static - rename the mix of heading and yaw as heading to avoid confusion * ekf2: use ternary operator in selectHeadingTestLimit instead of if-else * ekf2: store intermediate redults in const bool flags. Those will be used for logging * ekf2: set variable const whenever possible * ekf2: create PreFlightChecker class that handle all the innovation pre-flight checks. Add simple unit testing Use bitmask instead of general flag to have more granularity * PreFlightChecker: use setter for the innovations to check instead of sending booleans in the update function This makes it more scalable as more checks will be added * ekf: Use booleans instead of bitmask for ekf preflt checks Rename "down" to "vert"
- Loading branch information
Showing
9 changed files
with
620 additions
and
87 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,45 @@ | ||
############################################################################ | ||
# | ||
# Copyright (c) 2019 PX4 Development Team. All rights reserved. | ||
# | ||
# Redistribution and use in source and binary forms, with or without | ||
# modification, are permitted provided that the following conditions | ||
# are met: | ||
# | ||
# 1. Redistributions of source code must retain the above copyright | ||
# notice, this list of conditions and the following disclaimer. | ||
# 2. Redistributions in binary form must reproduce the above copyright | ||
# notice, this list of conditions and the following disclaimer in | ||
# the documentation and/or other materials provided with the | ||
# distribution. | ||
# 3. Neither the name PX4 nor the names of its contributors may be | ||
# used to endorse or promote products derived from this software | ||
# without specific prior written permission. | ||
# | ||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS | ||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT | ||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS | ||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE | ||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, | ||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, | ||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS | ||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED | ||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT | ||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN | ||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE | ||
# POSSIBILITY OF SUCH DAMAGE. | ||
# | ||
############################################################################# | ||
|
||
px4_add_library(Ekf2Utility | ||
PreFlightChecker.cpp | ||
) | ||
|
||
target_include_directories(Ekf2Utility | ||
PUBLIC | ||
${CMAKE_CURRENT_SOURCE_DIR} | ||
) | ||
|
||
target_link_libraries(Ekf2Utility PRIVATE mathlib) | ||
|
||
px4_add_unit_gtest(SRC PreFlightCheckerTest.cpp LINKLIBS Ekf2Utility) |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,79 @@ | ||
/**************************************************************************** | ||
* | ||
* Copyright (c) 2019 PX4 Development Team. All rights reserved. | ||
* | ||
* Redistribution and use in source and binary forms, with or without | ||
* modification, are permitted provided that the following conditions | ||
* are met: | ||
* | ||
* 1. Redistributions of source code must retain the above copyright | ||
* notice, this list of conditions and the following disclaimer. | ||
* 2. Redistributions in binary form must reproduce the above copyright | ||
* notice, this list of conditions and the following disclaimer in | ||
* the documentation and/or other materials provided with the | ||
* distribution. | ||
* 3. Neither the name PX4 nor the names of its contributors may be | ||
* used to endorse or promote products derived from this software | ||
* without specific prior written permission. | ||
* | ||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS | ||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT | ||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS | ||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE | ||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, | ||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, | ||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS | ||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED | ||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT | ||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN | ||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE | ||
* POSSIBILITY OF SUCH DAMAGE. | ||
* | ||
****************************************************************************/ | ||
|
||
/** | ||
* First order "alpha" IIR digital filter with input saturation | ||
*/ | ||
|
||
#include <mathlib/mathlib.h> | ||
|
||
class InnovationLpf final | ||
{ | ||
public: | ||
InnovationLpf() = default; | ||
~InnovationLpf() = default; | ||
|
||
void reset(float val = 0.f) { _x = val; } | ||
|
||
/** | ||
* Update the filter with a new value and returns the filtered state | ||
* The new value is constained by the limit set in setSpikeLimit | ||
* @param val new input | ||
* @param alpha normalized weight of the new input | ||
* @param spike_limit the amplitude of the saturation at the input of the filter | ||
* @return filtered output | ||
*/ | ||
float update(float val, float alpha, float spike_limit) | ||
{ | ||
float val_constrained = math::constrain(val, -spike_limit, spike_limit); | ||
float beta = 1.f - alpha; | ||
|
||
_x = beta * _x + alpha * val_constrained; | ||
|
||
return _x; | ||
} | ||
|
||
/** | ||
* Helper function to compute alpha from dt and the inverse of tau | ||
* @param dt sampling time in seconds | ||
* @param tau_inv inverse of the time constant of the filter | ||
* @return alpha, the normalized weight of a new measurement | ||
*/ | ||
static float computeAlphaFromDtAndTauInv(float dt, float tau_inv) | ||
{ | ||
return dt * tau_inv; | ||
} | ||
|
||
private: | ||
float _x; ///< current state of the filter | ||
}; |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,142 @@ | ||
/**************************************************************************** | ||
* | ||
* Copyright (c) 2019 PX4 Development Team. All rights reserved. | ||
* | ||
* Redistribution and use in source and binary forms, with or without | ||
* modification, are permitted provided that the following conditions | ||
* are met: | ||
* | ||
* 1. Redistributions of source code must retain the above copyright | ||
* notice, this list of conditions and the following disclaimer. | ||
* 2. Redistributions in binary form must reproduce the above copyright | ||
* notice, this list of conditions and the following disclaimer in | ||
* the documentation and/or other materials provided with the | ||
* distribution. | ||
* 3. Neither the name PX4 nor the names of its contributors may be | ||
* used to endorse or promote products derived from this software | ||
* without specific prior written permission. | ||
* | ||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS | ||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT | ||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS | ||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE | ||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, | ||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, | ||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS | ||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED | ||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT | ||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN | ||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE | ||
* POSSIBILITY OF SUCH DAMAGE. | ||
* | ||
****************************************************************************/ | ||
|
||
/** | ||
* @file PreFlightCheckHelper.cpp | ||
* Class handling the EKF2 innovation pre flight checks | ||
*/ | ||
|
||
#include "PreFlightChecker.hpp" | ||
|
||
void PreFlightChecker::update(const float dt, const ekf2_innovations_s &innov) | ||
{ | ||
const float alpha = InnovationLpf::computeAlphaFromDtAndTauInv(dt, _innov_lpf_tau_inv); | ||
|
||
_has_heading_failed = preFlightCheckHeadingFailed(innov, alpha); | ||
_has_horiz_vel_failed = preFlightCheckHorizVelFailed(innov, alpha); | ||
_has_vert_vel_failed = preFlightCheckVertVelFailed(innov, alpha); | ||
_has_height_failed = preFlightCheckHeightFailed(innov, alpha); | ||
} | ||
|
||
bool PreFlightChecker::preFlightCheckHeadingFailed(const ekf2_innovations_s &innov, const float alpha) | ||
{ | ||
const float heading_test_limit = selectHeadingTestLimit(); | ||
const float heading_innov_spike_lim = 2.0f * heading_test_limit; | ||
|
||
const float heading_innov_lpf = _filter_heading_innov.update(innov.heading_innov, alpha, heading_innov_spike_lim); | ||
|
||
return checkInnovFailed(innov.heading_innov, heading_innov_lpf, heading_test_limit); | ||
} | ||
|
||
float PreFlightChecker::selectHeadingTestLimit() | ||
{ | ||
// Select the max allowed heading innovaton depending on whether we are not aiding navigation using | ||
// observations in the NE reference frame and if the vehicle can use GPS course to realign in flight (fixedwing sideslip fusion). | ||
const bool is_ne_aiding = _is_using_gps_aiding || _is_using_ev_pos_aiding; | ||
|
||
return (is_ne_aiding && !_can_observe_heading_in_flight) | ||
? _nav_heading_innov_test_lim // more restrictive test limit | ||
: _heading_innov_test_lim; // less restrictive test limit | ||
} | ||
|
||
bool PreFlightChecker::preFlightCheckHorizVelFailed(const ekf2_innovations_s &innov, const float alpha) | ||
{ | ||
bool has_failed = false; | ||
|
||
if (_is_using_gps_aiding || _is_using_ev_pos_aiding) { | ||
const Vector2f vel_ne_innov = Vector2f(innov.vel_pos_innov); | ||
Vector2f vel_ne_innov_lpf; | ||
vel_ne_innov_lpf(0) = _filter_vel_n_innov.update(vel_ne_innov(0), alpha, _vel_innov_spike_lim); | ||
vel_ne_innov_lpf(1) = _filter_vel_n_innov.update(vel_ne_innov(1), alpha, _vel_innov_spike_lim); | ||
has_failed |= checkInnov2DFailed(vel_ne_innov, vel_ne_innov_lpf, _vel_innov_test_lim); | ||
} | ||
|
||
if (_is_using_flow_aiding) { | ||
const Vector2f flow_innov = Vector2f(innov.flow_innov); | ||
Vector2f flow_innov_lpf; | ||
flow_innov_lpf(0) = _filter_flow_x_innov.update(flow_innov(0), alpha, _flow_innov_spike_lim); | ||
flow_innov_lpf(1) = _filter_flow_x_innov.update(flow_innov(1), alpha, _flow_innov_spike_lim); | ||
has_failed |= checkInnov2DFailed(flow_innov, flow_innov_lpf, _flow_innov_test_lim); | ||
} | ||
|
||
return has_failed; | ||
} | ||
|
||
bool PreFlightChecker::preFlightCheckVertVelFailed(const ekf2_innovations_s &innov, const float alpha) | ||
{ | ||
const float vel_d_innov = innov.vel_pos_innov[2]; | ||
const float vel_d_innov_lpf = _filter_vel_d_innov.update(vel_d_innov, alpha, _vel_innov_spike_lim); | ||
return checkInnovFailed(vel_d_innov, vel_d_innov_lpf, _vel_innov_test_lim); | ||
} | ||
|
||
bool PreFlightChecker::preFlightCheckHeightFailed(const ekf2_innovations_s &innov, const float alpha) | ||
{ | ||
const float hgt_innov = innov.vel_pos_innov[5]; | ||
const float hgt_innov_lpf = _filter_hgt_innov.update(hgt_innov, alpha, _hgt_innov_spike_lim); | ||
return checkInnovFailed(hgt_innov, hgt_innov_lpf, _hgt_innov_test_lim); | ||
} | ||
|
||
bool PreFlightChecker::checkInnovFailed(const float innov, const float innov_lpf, const float test_limit) | ||
{ | ||
return fabsf(innov_lpf) > test_limit || fabsf(innov) > 2.0f * test_limit; | ||
} | ||
|
||
bool PreFlightChecker::checkInnov2DFailed(const Vector2f &innov, const Vector2f &innov_lpf, const float test_limit) | ||
{ | ||
return innov_lpf.norm_squared() > sq(test_limit) | ||
|| innov.norm_squared() > sq(2.0f * test_limit); | ||
} | ||
|
||
uint8_t PreFlightChecker::prefltFailBoolToBitMask(const bool heading_failed, const bool horiz_vel_failed, | ||
const bool vert_vel_failed, const bool height_failed) | ||
{ | ||
return heading_failed | (horiz_vel_failed << 1) | (vert_vel_failed << 2) | (height_failed << 3); | ||
} | ||
|
||
void PreFlightChecker::reset() | ||
{ | ||
_is_using_gps_aiding = false; | ||
_is_using_flow_aiding = false; | ||
_is_using_ev_pos_aiding = false; | ||
_has_heading_failed = false; | ||
_has_horiz_vel_failed = false; | ||
_has_vert_vel_failed = false; | ||
_has_height_failed = false; | ||
_filter_vel_n_innov.reset(); | ||
_filter_vel_e_innov.reset(); | ||
_filter_vel_d_innov.reset(); | ||
_filter_hgt_innov.reset(); | ||
_filter_heading_innov.reset(); | ||
_filter_flow_x_innov.reset(); | ||
_filter_flow_y_innov.reset(); | ||
} |
Oops, something went wrong.