Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

ekf2_main - Add optical flow innovation pre-flight check #13036

Merged
merged 18 commits into from
Oct 22, 2019
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
18 commits
Select commit Hold shift + click to select a range
4f3974a
ekf2: Add FirstOrderLpf and InnovationLpf classes for innovation lowp…
bresch Sep 26, 2019
555bb23
ekf2: use InnovLpf filter class in preflight checks
bresch Sep 26, 2019
33cb18c
ekf2: move selection of yaw test limit for pre-flight check in function
bresch Sep 27, 2019
5fd6349
ekf2: Move pre-flight checks into separate function
bresch Sep 27, 2019
e37ca16
ekf2: use static constexpr insetead of inline for sq (square) function
bresch Sep 27, 2019
3742106
ekf2: Split pre-flight checks in separate functions
bresch Sep 27, 2019
480b990
ekf2: Add optical flow pre-flight check
bresch Sep 27, 2019
5bbaf6b
ekf2: Combine FirstOrderLpf and InnovationLpf in single class
bresch Sep 27, 2019
6f5b75e
ekf2: check vel_pos_innov when ev_pos is active as well
bresch Sep 27, 2019
a0bbc5c
ekf2: transform InnovationLpf into a header only library and pass the
bresch Oct 1, 2019
4bef660
ekf2: Static and const cleanup
bresch Oct 1, 2019
e2c4683
ekf2: use ternary operator in selectHeadingTestLimit instead of if-else
bresch Oct 15, 2019
ebce352
ekf2: store intermediate redults in const bool flags. Those will be u…
bresch Oct 15, 2019
f82d897
ekf2: set variable const whenever possible
bresch Oct 15, 2019
eaef146
ekf2: create PreFlightChecker class that handle all the innovation
bresch Oct 16, 2019
f26ea57
PreFlightChecker: use setter for the innovations to check instead of …
bresch Oct 16, 2019
d303e77
ekf: Use booleans instead of bitmask for ekf preflt checks
bresch Oct 21, 2019
4de3060
Merge branch 'master' into dev-ekf-prearm
bresch Oct 22, 2019
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 4 additions & 2 deletions msg/estimator_status.msg
Original file line number Diff line number Diff line change
Expand Up @@ -106,8 +106,10 @@ uint16 solution_status_flags # Bitmask indicating which filter kinematic state o

float32 time_slip # cumulative amount of time in seconds that the EKF inertial calculation has slipped relative to system time

bool pre_flt_fail # true when estimator has failed pre-flight checks and the vehicle should not be flown regardless of flight mode

bool pre_flt_fail_innov_heading
dagar marked this conversation as resolved.
Show resolved Hide resolved
bool pre_flt_fail_innov_vel_horiz
bool pre_flt_fail_innov_vel_vert
bool pre_flt_fail_innov_height

# legacy local position estimator (LPE) flags
uint8 health_flags # Bitmask to indicate sensor health states (vel, pos, hgt)
Expand Down
18 changes: 16 additions & 2 deletions src/modules/commander/PreflightCheck.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -494,9 +494,23 @@ static bool ekf2Check(orb_advert_t *mavlink_log_pub, vehicle_status_s &vehicle_s
}

// Check if preflight check performed by estimator has failed
if (status.pre_flt_fail) {
if (status.pre_flt_fail_innov_heading ||
status.pre_flt_fail_innov_vel_horiz ||
status.pre_flt_fail_innov_vel_vert ||
status.pre_flt_fail_innov_height) {
if (report_fail) {
mavlink_log_critical(mavlink_log_pub, "Preflight Fail: Position unknown");
if (status.pre_flt_fail_innov_heading) {
mavlink_log_critical(mavlink_log_pub, "Preflight Fail: heading estimate not stable");

} else if (status.pre_flt_fail_innov_vel_horiz) {
mavlink_log_critical(mavlink_log_pub, "Preflight Fail: horizontal velocity estimate not stable");

} else if (status.pre_flt_fail_innov_vel_horiz) {
mavlink_log_critical(mavlink_log_pub, "Preflight Fail: vertical velocity estimate not stable");

} else if (status.pre_flt_fail_innov_height) {
mavlink_log_critical(mavlink_log_pub, "Preflight Fail: height estimate not stable");
}
}

success = false;
Expand Down
4 changes: 4 additions & 0 deletions src/modules/ekf2/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,9 @@
# POSSIBILITY OF SUCH DAMAGE.
#
#############################################################################

add_subdirectory(Utility)

px4_add_module(
MODULE modules__ekf2
MAIN ekf2
Expand All @@ -42,4 +45,5 @@ px4_add_module(
ecl_EKF
ecl_geo
perf
Ekf2Utility
)
45 changes: 45 additions & 0 deletions src/modules/ekf2/Utility/CMakeLists.txt
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)
79 changes: 79 additions & 0 deletions src/modules/ekf2/Utility/InnovationLpf.hpp
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
};
142 changes: 142 additions & 0 deletions src/modules/ekf2/Utility/PreFlightChecker.cpp
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();
}
Loading