You can not select more than 25 topics Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.

191 lines
7.3 KiB

/****************************************************************************
*
* Copyright (c) 2019-2020 ECL 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.
*
****************************************************************************/
#include <gtest/gtest.h>
#include <math.h>
#include <memory>
#include "EKF/ekf.h"
#include "sensor_simulator/sensor_simulator.h"
#include "sensor_simulator/ekf_wrapper.h"
class EkfBasicsTest : public ::testing::Test {
public:
EkfBasicsTest(): ::testing::Test(),
_ekf{std::make_shared<Ekf>()},
_sensor_simulator(_ekf),
_ekf_wrapper(_ekf) {};
std::shared_ptr<Ekf> _ekf;
SensorSimulator _sensor_simulator;
EkfWrapper _ekf_wrapper;
5 years ago
// Duration of initalization with only providing baro,mag and IMU
const uint32_t _init_duration_s{3};
// Setup the Ekf with synthetic measurements
void SetUp() override
{
5 years ago
_ekf->init(0);
_sensor_simulator.runSeconds(_init_duration_s);
}
// Use this method to clean up any memory, network etc. after each test
void TearDown() override
{
}
};
TEST_F(EkfBasicsTest, tiltAlign)
{
// GIVEN: reasonable static sensor data for some duration
// THEN: EKF should tilt align
EXPECT_TRUE(_ekf->attitude_valid());
}
TEST_F(EkfBasicsTest, initialControlMode)
{
// GIVEN: reasonable static sensor data for some duration
// THEN: EKF control status should be reasonable
filter_control_status_u control_status;
5 years ago
_ekf->get_control_mode(&control_status.value);
EXPECT_EQ(1, (int) control_status.flags.tilt_align);
EXPECT_EQ(1, (int) control_status.flags.yaw_align);
EXPECT_EQ(0, (int) control_status.flags.gps);
EXPECT_EQ(0, (int) control_status.flags.opt_flow);
EXPECT_EQ(1, (int) control_status.flags.mag_hdg);
EXPECT_EQ(0, (int) control_status.flags.mag_3D);
EXPECT_EQ(0, (int) control_status.flags.mag_dec);
EXPECT_EQ(0, (int) control_status.flags.in_air);
EXPECT_EQ(0, (int) control_status.flags.wind);
EXPECT_EQ(1, (int) control_status.flags.baro_hgt);
EXPECT_EQ(0, (int) control_status.flags.rng_hgt);
EXPECT_EQ(0, (int) control_status.flags.gps_hgt);
EXPECT_EQ(0, (int) control_status.flags.ev_pos);
EXPECT_EQ(0, (int) control_status.flags.ev_yaw);
EXPECT_EQ(0, (int) control_status.flags.ev_hgt);
EXPECT_EQ(0, (int) control_status.flags.fuse_beta);
[ekf] controlMagFusion refactor and mag field strength check (#662) * ekf_control: Inhibit mag fusion when field magnitude is large Move mag inhibition check in separate function * ekf_control: pull out of functionalities out of controlMagFusion - yaw abd mag bias observability checks - mag 3D conditions - load mag covariances - set and clear mag control modes * ekf_control: refactor mag heading/3D start/stop. Move mag declination, mag 3d and mag heading fusion out of the main function * ekf_control: extract mag yaw reset and mag declination fusion requirements * ekf_control: use WMM in isStronMagneticField for mag fusion inhibition - Correct units of WMM strength table * ekf_control: extract mag_state_only functionality of AUTOFW (VTOL custom) Also split inAirYawReset from onGroundYawReset * ekf_control: extract mag automatic selection - transform if-else into switch-case for parameter fusion type selection * ekf_control: extract run3DMagAndDeclFusion, reorganize functions, fix flag naming in Test script * ekf_control: do not run mag fusion if tilt is not aligned. Reset some variables on ground even if mag fusion is not running yet. It could be that it runs later so we need to make sure that those variables are properly set. * ekf_control: move controlMagFusion and related functions to mag_control.cpp * ekf control: check for validity of mag strength from WMM and falls back to average earth mag field with larger gate if not valid * ekf control: remove evyaw check for mag inhibition * ekf control: change nested ternary operator into if-else if * Ekf: create AlphaFilter template class for simple low-pass filtering 0.1/0.9 type low-pass filters are commonly used to smooth data, this class is meant to abstract the computation of this filter * ekf control: reset heading using mag_lpf data to avoid resetting on an outlier fixes ecl issue #525 * ekf control: replace mag_states_only flag with mag_field_disturbed and add parameter to enable or disable mag field strength check * ekf control: remove AUTOFW mag fusion type as not needed This was implemented for VTOL but did not solve the problem and should not be used anymore * ekf control: use start/stop mag functions everywhere instead of setting the flag * ekf control: Run mag fusion depending on yaw_align instead of tilt_align as there is no reason to fuse mag when the ekf isn't aligned * AlphaFilter: add test for float and Vector3f
5 years ago
EXPECT_EQ(0, (int) control_status.flags.mag_field_disturbed);
EXPECT_EQ(0, (int) control_status.flags.fixed_wing);
EXPECT_EQ(0, (int) control_status.flags.mag_fault);
EXPECT_EQ(0, (int) control_status.flags.gnd_effect);
EXPECT_EQ(0, (int) control_status.flags.rng_stuck);
EXPECT_EQ(0, (int) control_status.flags.gps_yaw);
[ekf] controlMagFusion refactor and mag field strength check (#662) * ekf_control: Inhibit mag fusion when field magnitude is large Move mag inhibition check in separate function * ekf_control: pull out of functionalities out of controlMagFusion - yaw abd mag bias observability checks - mag 3D conditions - load mag covariances - set and clear mag control modes * ekf_control: refactor mag heading/3D start/stop. Move mag declination, mag 3d and mag heading fusion out of the main function * ekf_control: extract mag yaw reset and mag declination fusion requirements * ekf_control: use WMM in isStronMagneticField for mag fusion inhibition - Correct units of WMM strength table * ekf_control: extract mag_state_only functionality of AUTOFW (VTOL custom) Also split inAirYawReset from onGroundYawReset * ekf_control: extract mag automatic selection - transform if-else into switch-case for parameter fusion type selection * ekf_control: extract run3DMagAndDeclFusion, reorganize functions, fix flag naming in Test script * ekf_control: do not run mag fusion if tilt is not aligned. Reset some variables on ground even if mag fusion is not running yet. It could be that it runs later so we need to make sure that those variables are properly set. * ekf_control: move controlMagFusion and related functions to mag_control.cpp * ekf control: check for validity of mag strength from WMM and falls back to average earth mag field with larger gate if not valid * ekf control: remove evyaw check for mag inhibition * ekf control: change nested ternary operator into if-else if * Ekf: create AlphaFilter template class for simple low-pass filtering 0.1/0.9 type low-pass filters are commonly used to smooth data, this class is meant to abstract the computation of this filter * ekf control: reset heading using mag_lpf data to avoid resetting on an outlier fixes ecl issue #525 * ekf control: replace mag_states_only flag with mag_field_disturbed and add parameter to enable or disable mag field strength check * ekf control: remove AUTOFW mag fusion type as not needed This was implemented for VTOL but did not solve the problem and should not be used anymore * ekf control: use start/stop mag functions everywhere instead of setting the flag * ekf control: Run mag fusion depending on yaw_align instead of tilt_align as there is no reason to fuse mag when the ekf isn't aligned * AlphaFilter: add test for float and Vector3f
5 years ago
EXPECT_EQ(0, (int) control_status.flags.mag_aligned_in_flight);
EXPECT_EQ(0, (int) control_status.flags.ev_vel);
EXPECT_EQ(0, (int) control_status.flags.synthetic_mag_z);
}
TEST_F(EkfBasicsTest, convergesToZero)
{
5 years ago
// GIVEN: initialized EKF with default IMU, baro and mag input
_sensor_simulator.runSeconds(4);
const Vector3f pos = _ekf->getPosition();
const Vector3f vel = _ekf->getVelocity();
const Vector3f accel_bias = _ekf->getAccelBias();
const Vector3f gyro_bias = _ekf->getGyroBias();
const Vector3f ref{0.0f, 0.0f, 0.0f};
// THEN: EKF should stay or converge to zero
EXPECT_TRUE(matrix::isEqual(pos, ref, 0.001f));
EXPECT_TRUE(matrix::isEqual(vel, ref, 0.001f));
EXPECT_TRUE(matrix::isEqual(accel_bias, ref, 0.001f));
EXPECT_TRUE(matrix::isEqual(gyro_bias, ref, 0.001f));
}
TEST_F(EkfBasicsTest, gpsFusion)
{
5 years ago
// GIVEN: initialized EKF with default IMU, baro and mag input for
// WHEN: setting GPS measurements for 11s, minimum GPS health time is set to 10 sec
_sensor_simulator.startGps();
_sensor_simulator.runSeconds(11);
// THEN: EKF should fuse GPS, but no other position sensor
filter_control_status_u control_status;
5 years ago
_ekf->get_control_mode(&control_status.value);
EXPECT_EQ(1, (int) control_status.flags.tilt_align);
EXPECT_EQ(1, (int) control_status.flags.yaw_align);
EXPECT_EQ(1, (int) control_status.flags.gps);
EXPECT_EQ(0, (int) control_status.flags.opt_flow);
EXPECT_EQ(1, (int) control_status.flags.mag_hdg);
EXPECT_EQ(0, (int) control_status.flags.mag_3D);
EXPECT_EQ(0, (int) control_status.flags.mag_dec);
EXPECT_EQ(0, (int) control_status.flags.in_air);
EXPECT_EQ(0, (int) control_status.flags.wind);
EXPECT_EQ(1, (int) control_status.flags.baro_hgt);
EXPECT_EQ(0, (int) control_status.flags.rng_hgt);
EXPECT_EQ(0, (int) control_status.flags.gps_hgt);
EXPECT_EQ(0, (int) control_status.flags.ev_pos);
EXPECT_EQ(0, (int) control_status.flags.ev_yaw);
EXPECT_EQ(0, (int) control_status.flags.ev_hgt);
EXPECT_EQ(0, (int) control_status.flags.fuse_beta);
[ekf] controlMagFusion refactor and mag field strength check (#662) * ekf_control: Inhibit mag fusion when field magnitude is large Move mag inhibition check in separate function * ekf_control: pull out of functionalities out of controlMagFusion - yaw abd mag bias observability checks - mag 3D conditions - load mag covariances - set and clear mag control modes * ekf_control: refactor mag heading/3D start/stop. Move mag declination, mag 3d and mag heading fusion out of the main function * ekf_control: extract mag yaw reset and mag declination fusion requirements * ekf_control: use WMM in isStronMagneticField for mag fusion inhibition - Correct units of WMM strength table * ekf_control: extract mag_state_only functionality of AUTOFW (VTOL custom) Also split inAirYawReset from onGroundYawReset * ekf_control: extract mag automatic selection - transform if-else into switch-case for parameter fusion type selection * ekf_control: extract run3DMagAndDeclFusion, reorganize functions, fix flag naming in Test script * ekf_control: do not run mag fusion if tilt is not aligned. Reset some variables on ground even if mag fusion is not running yet. It could be that it runs later so we need to make sure that those variables are properly set. * ekf_control: move controlMagFusion and related functions to mag_control.cpp * ekf control: check for validity of mag strength from WMM and falls back to average earth mag field with larger gate if not valid * ekf control: remove evyaw check for mag inhibition * ekf control: change nested ternary operator into if-else if * Ekf: create AlphaFilter template class for simple low-pass filtering 0.1/0.9 type low-pass filters are commonly used to smooth data, this class is meant to abstract the computation of this filter * ekf control: reset heading using mag_lpf data to avoid resetting on an outlier fixes ecl issue #525 * ekf control: replace mag_states_only flag with mag_field_disturbed and add parameter to enable or disable mag field strength check * ekf control: remove AUTOFW mag fusion type as not needed This was implemented for VTOL but did not solve the problem and should not be used anymore * ekf control: use start/stop mag functions everywhere instead of setting the flag * ekf control: Run mag fusion depending on yaw_align instead of tilt_align as there is no reason to fuse mag when the ekf isn't aligned * AlphaFilter: add test for float and Vector3f
5 years ago
EXPECT_EQ(0, (int) control_status.flags.mag_field_disturbed);
EXPECT_EQ(0, (int) control_status.flags.fixed_wing);
EXPECT_EQ(0, (int) control_status.flags.mag_fault);
EXPECT_EQ(0, (int) control_status.flags.gnd_effect);
EXPECT_EQ(0, (int) control_status.flags.rng_stuck);
EXPECT_EQ(0, (int) control_status.flags.gps_yaw);
[ekf] controlMagFusion refactor and mag field strength check (#662) * ekf_control: Inhibit mag fusion when field magnitude is large Move mag inhibition check in separate function * ekf_control: pull out of functionalities out of controlMagFusion - yaw abd mag bias observability checks - mag 3D conditions - load mag covariances - set and clear mag control modes * ekf_control: refactor mag heading/3D start/stop. Move mag declination, mag 3d and mag heading fusion out of the main function * ekf_control: extract mag yaw reset and mag declination fusion requirements * ekf_control: use WMM in isStronMagneticField for mag fusion inhibition - Correct units of WMM strength table * ekf_control: extract mag_state_only functionality of AUTOFW (VTOL custom) Also split inAirYawReset from onGroundYawReset * ekf_control: extract mag automatic selection - transform if-else into switch-case for parameter fusion type selection * ekf_control: extract run3DMagAndDeclFusion, reorganize functions, fix flag naming in Test script * ekf_control: do not run mag fusion if tilt is not aligned. Reset some variables on ground even if mag fusion is not running yet. It could be that it runs later so we need to make sure that those variables are properly set. * ekf_control: move controlMagFusion and related functions to mag_control.cpp * ekf control: check for validity of mag strength from WMM and falls back to average earth mag field with larger gate if not valid * ekf control: remove evyaw check for mag inhibition * ekf control: change nested ternary operator into if-else if * Ekf: create AlphaFilter template class for simple low-pass filtering 0.1/0.9 type low-pass filters are commonly used to smooth data, this class is meant to abstract the computation of this filter * ekf control: reset heading using mag_lpf data to avoid resetting on an outlier fixes ecl issue #525 * ekf control: replace mag_states_only flag with mag_field_disturbed and add parameter to enable or disable mag field strength check * ekf control: remove AUTOFW mag fusion type as not needed This was implemented for VTOL but did not solve the problem and should not be used anymore * ekf control: use start/stop mag functions everywhere instead of setting the flag * ekf control: Run mag fusion depending on yaw_align instead of tilt_align as there is no reason to fuse mag when the ekf isn't aligned * AlphaFilter: add test for float and Vector3f
5 years ago
EXPECT_EQ(0, (int) control_status.flags.mag_aligned_in_flight);
EXPECT_EQ(0, (int) control_status.flags.ev_vel);
EXPECT_EQ(0, (int) control_status.flags.synthetic_mag_z);
}
TEST_F(EkfBasicsTest, accleBiasEstimation)
{
// GIVEN: initialized EKF with default IMU, baro and mag input for 3s
// WHEN: Added more sensor measurements with accel bias and gps measurements
const Vector3f accel_bias_sim = {0.0f,0.0f,0.1f};
_sensor_simulator.startGps();
_sensor_simulator.setImuBias(accel_bias_sim, Vector3f{0.0f,0.0f,0.0f});
_sensor_simulator.runSeconds(10);
const Vector3f pos = _ekf->getPosition();
const Vector3f vel = _ekf->getVelocity();
const Vector3f accel_bias = _ekf->getAccelBias();
const Vector3f gyro_bias = _ekf->getGyroBias();
const Vector3f zero{0.0f, 0.0f, 0.0f};
// THEN: EKF should stay or converge to zero
EXPECT_TRUE(matrix::isEqual(pos, zero, 0.01f));
EXPECT_TRUE(matrix::isEqual(vel, zero, 0.005f));
EXPECT_TRUE(matrix::isEqual(accel_bias, accel_bias_sim, 0.001f));
EXPECT_TRUE(matrix::isEqual(gyro_bias, zero, 0.001f));
}
// TODO: Add sampling tests