-
Notifications
You must be signed in to change notification settings - Fork 13.6k
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
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
- Loading branch information
Showing
8 changed files
with
489 additions
and
158 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
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -45,4 +45,5 @@ px4_add_module( | |
ecl_EKF | ||
ecl_geo | ||
perf | ||
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
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,150 @@ | ||
/**************************************************************************** | ||
* | ||
* 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 bool is_ne_aiding, | ||
const bool is_flow_aiding, | ||
const vehicle_status_s &vehicle_status, | ||
const ekf2_innovations_s &innov) | ||
{ | ||
const float alpha = InnovationLpf::computeAlphaFromDtAndTauInv(dt, _innov_lpf_tau_inv); | ||
|
||
_has_heading_failed = preFlightCheckHeadingFailed(is_ne_aiding, vehicle_status, innov, alpha); | ||
_has_horiz_vel_failed = preFlightCheckHorizVelFailed(is_ne_aiding, is_flow_aiding, innov, alpha); | ||
_has_down_vel_failed = preFlightCheckDownVelFailed(innov, alpha); | ||
_has_height_failed = preFlightCheckHeightFailed(innov, alpha); | ||
} | ||
|
||
bool PreFlightChecker::preFlightCheckHeadingFailed(const bool is_ne_aiding, | ||
const vehicle_status_s &vehicle_status, | ||
const ekf2_innovations_s &innov, | ||
const float alpha) | ||
{ | ||
const float heading_test_limit = selectHeadingTestLimit(is_ne_aiding, vehicle_status); | ||
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(const bool is_ne_aiding, | ||
const vehicle_status_s &vehicle_status) | ||
{ | ||
// 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 cannot_realign_in_flight = (vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING); | ||
|
||
return (is_ne_aiding && cannot_realign_in_flight) | ||
? _nav_heading_innov_test_lim | ||
: _heading_innov_test_lim; | ||
} | ||
|
||
bool PreFlightChecker::preFlightCheckHorizVelFailed(const bool is_ne_aiding, | ||
const bool is_flow_aiding, | ||
const ekf2_innovations_s &innov, | ||
const float alpha) | ||
{ | ||
bool has_failed = false; | ||
|
||
if (is_ne_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_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::preFlightCheckDownVelFailed(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 down_vel_failed, const bool height_failed) | ||
{ | ||
return heading_failed | (horiz_vel_failed << 1) | (down_vel_failed << 2) | (height_failed << 3); | ||
} | ||
|
||
void PreFlightChecker::reset() | ||
{ | ||
_has_heading_failed = false; | ||
_has_horiz_vel_failed = false; | ||
_has_down_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(); | ||
} |
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,198 @@ | ||
/**************************************************************************** | ||
* | ||
* 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 PreFlightChecker.hpp | ||
* Class handling the EKF2 innovation pre flight checks | ||
* | ||
* First call the update(...) function and then get the results | ||
* using the hasXxxFailed() getters | ||
*/ | ||
|
||
#pragma once | ||
|
||
#include <uORB/topics/vehicle_status.h> | ||
#include <uORB/topics/ekf2_innovations.h> | ||
|
||
#include <matrix/matrix/math.hpp> | ||
|
||
#include "InnovationLpf.hpp" | ||
|
||
using matrix::Vector2f; | ||
|
||
class PreFlightChecker | ||
{ | ||
public: | ||
PreFlightChecker() = default; | ||
~PreFlightChecker() = default; | ||
|
||
/* | ||
* Reset all the internal states of the class to their default value | ||
*/ | ||
void reset(); | ||
|
||
/* | ||
* Update the internal states | ||
* @param dt the sampling time | ||
* @param is_ne_aiding true if the EKF is currently fusing NE vel and pos | ||
* @param is_flow_aiding true if the EKF is currently fusing optical flow | ||
* @param vehicle_status the vehicle_status_s struct containing the status flags | ||
* @param innov the ekf2_innovation_s struct containing the current innovations | ||
*/ | ||
void update(float dt, bool is_ne_aiding, bool is_flow_aiding, const vehicle_status_s &vehicle_status, | ||
const ekf2_innovations_s &innov); | ||
|
||
bool hasHeadingFailed() const { return _has_heading_failed; } | ||
bool hasHorizVelFailed() const { return _has_horiz_vel_failed; } | ||
bool hasDownVelFailed() const { return _has_down_vel_failed; } | ||
bool hasHeightFailed() const { return _has_height_failed; } | ||
|
||
/* | ||
* Overall state of the pre fligh checks | ||
* @return true if any of the check failed | ||
*/ | ||
bool hasFailed() const { return hasHorizFailed() || hasVertFailed(); } | ||
|
||
/* | ||
* Horizontal checks overall result | ||
* @return true if one of the horizontal checks failed | ||
*/ | ||
bool hasHorizFailed() const { return _has_heading_failed || _has_horiz_vel_failed; } | ||
|
||
/* | ||
* Vertical checks overall result | ||
* @return true if one of the vertical checks failed | ||
*/ | ||
bool hasVertFailed() const { return _has_down_vel_failed || _has_height_failed; } | ||
|
||
/* | ||
* Bitfield representation of the failures | ||
* @return a bitfield where the bits represent | ||
* #0 _has_heading_failed | ||
* #1 _has_horiz_vel_failed | ||
* #2 _has_down_vel_failed | ||
* #3 _has_height_failed | ||
*/ | ||
uint8_t getBitmask() const | ||
{ | ||
return prefltFailBoolToBitMask(_has_heading_failed, | ||
_has_horiz_vel_failed, | ||
_has_down_vel_failed, | ||
_has_height_failed); | ||
} | ||
|
||
/* | ||
* Check if the innovation fails the test | ||
* To pass the test, the following conditions should be true: | ||
* innov <= test_limit | ||
* innov_lpf <= 2 * test_limit | ||
* @param innov the current unfiltered innovation | ||
* @param innov_lpf the low-pass filtered innovation | ||
* @param test_limit the magnitude test limit | ||
* @return true if the check failed the test, false otherwise | ||
*/ | ||
static bool checkInnovFailed(float innov, float innov_lpf, float test_limit); | ||
|
||
/* | ||
* Check if the a innovation of a 2D vector fails the test | ||
* To pass the test, the following conditions should be true: | ||
* innov <= test_limit | ||
* innov_lpf <= 2 * test_limit | ||
* @param innov the current unfiltered innovation | ||
* @param innov_lpf the low-pass filtered innovation | ||
* @param test_limit the magnitude test limit | ||
* @return true if the check failed the test, false otherwise | ||
*/ | ||
static bool checkInnov2DFailed(const Vector2f &innov, const Vector2f &innov_lpf, float test_limit); | ||
|
||
/* | ||
* Packs the boolean flags into a bit field | ||
*/ | ||
static uint8_t prefltFailBoolToBitMask(bool heading_failed, bool horiz_vel_failed, bool down_vel_failed, | ||
bool height_failed); | ||
|
||
/* | ||
* Select the appropriate heading test limit depending on the type of aiding and | ||
* the ability of the vehicle to observe heading in flight | ||
* @param is_ne_aiding true if the vehicle is relying on heading for vel/pos fusion | ||
* @param vehicle_status the vehicle_status_s containing the status flags | ||
* @return the appropriate heading test limit | ||
*/ | ||
static float selectHeadingTestLimit(bool is_ne_aiding, const vehicle_status_s &vehicle_status); | ||
static constexpr float sq(float var) { return var * var; } | ||
|
||
private: | ||
bool preFlightCheckHeadingFailed(bool is_ne_aiding, | ||
const vehicle_status_s &vehicle_status, | ||
const ekf2_innovations_s &innov, | ||
float alpha); | ||
bool preFlightCheckHorizVelFailed(bool is_ne_aiding, bool is_flow_aiding, const ekf2_innovations_s &innov, | ||
float alpha); | ||
bool preFlightCheckDownVelFailed(const ekf2_innovations_s &innov, float alpha); | ||
bool preFlightCheckHeightFailed(const ekf2_innovations_s &innov, float alpha); | ||
|
||
void resetPreFlightChecks(); | ||
|
||
bool _has_heading_failed{}; | ||
bool _has_horiz_vel_failed{}; | ||
bool _has_down_vel_failed{}; | ||
bool _has_height_failed{}; | ||
|
||
// Low-pass filters for innovation pre-flight checks | ||
InnovationLpf _filter_vel_n_innov; ///< Preflight low pass filter N axis velocity innovations (m/sec) | ||
InnovationLpf _filter_vel_e_innov; ///< Preflight low pass filter E axis velocity innovations (m/sec) | ||
InnovationLpf _filter_vel_d_innov; ///< Preflight low pass filter D axis velocity innovations (m/sec) | ||
InnovationLpf _filter_hgt_innov; ///< Preflight low pass filter height innovation (m) | ||
InnovationLpf _filter_heading_innov; ///< Preflight low pass filter heading innovation magntitude (rad) | ||
InnovationLpf _filter_flow_x_innov; ///< Preflight low pass filter optical flow innovation (rad) | ||
InnovationLpf _filter_flow_y_innov; ///< Preflight low pass filter optical flow innovation (rad) | ||
|
||
// Preflight low pass filter time constant inverse (1/sec) | ||
static constexpr float _innov_lpf_tau_inv = 0.2f; | ||
// Maximum permissible velocity innovation to pass pre-flight checks (m/sec) | ||
static constexpr float _vel_innov_test_lim = 0.5f; | ||
// Maximum permissible height innovation to pass pre-flight checks (m) | ||
static constexpr float _hgt_innov_test_lim = 1.5f; | ||
// Maximum permissible yaw innovation to pass pre-flight checks when aiding inertial nav using NE frame observations (rad) | ||
static constexpr float _nav_heading_innov_test_lim = 0.25f; | ||
// Maximum permissible yaw innovation to pass pre-flight checks when not aiding inertial nav using NE frame observations (rad) | ||
static constexpr float _heading_innov_test_lim = 0.52f; | ||
// Maximum permissible flow innovation to pass pre-flight checks | ||
static constexpr float _flow_innov_test_lim = 0.1f; | ||
// Preflight velocity innovation spike limit (m/sec) | ||
static constexpr float _vel_innov_spike_lim = 2.0f * _vel_innov_test_lim; | ||
// Preflight position innovation spike limit (m) | ||
static constexpr float _hgt_innov_spike_lim = 2.0f * _hgt_innov_test_lim; | ||
// Preflight flow innovation spike limit (rad) | ||
static constexpr float _flow_innov_spike_lim = 2.0f * _flow_innov_test_lim; | ||
}; |
Oops, something went wrong.