mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-02 00:24:08 +08:00
GTest and Coverage cleanup and Basic EKF GTest
This commit is contained in:
parent
fcea13eef8
commit
cac5f3fd6d
@ -36,8 +36,8 @@ cmake_minimum_required(VERSION 3.0)
|
||||
project(ECL CXX)
|
||||
|
||||
if (NOT CMAKE_BUILD_TYPE)
|
||||
set(CMAKE_BUILD_TYPE "RelWithDebInfo" CACHE STRING "Build type" FORCE)
|
||||
message(STATUS "set build type to ${CMAKE_BUILD_TYPE}")
|
||||
set(CMAKE_BUILD_TYPE "RelWithDebInfo" CACHE STRING "Build type" FORCE)
|
||||
message(STATUS "set build type to ${CMAKE_BUILD_TYPE}")
|
||||
endif()
|
||||
|
||||
set_property(CACHE CMAKE_BUILD_TYPE PROPERTY STRINGS "Debug;Release;RelWithDebInfo;MinSizeRel;Coverage")
|
||||
@ -60,11 +60,11 @@ option(COV_HTML "Display html for coverage" OFF)
|
||||
option(ECL_ASAN "Enable ECL address sanitizer" OFF)
|
||||
|
||||
set(CMAKE_CXX_FLAGS_COVERAGE
|
||||
"--coverage -fprofile-arcs -ftest-coverage -fno-default-inline -fno-inline -fno-inline-small-functions -fno-elide-constructors"
|
||||
CACHE STRING "Flags used by the C++ compiler during coverage builds" FORCE)
|
||||
"--coverage -fprofile-arcs -ftest-coverage -fno-default-inline -fno-inline -fno-inline-small-functions -fno-elide-constructors"
|
||||
CACHE STRING "Flags used by the C++ compiler during coverage builds" FORCE)
|
||||
set(CMAKE_EXE_LINKER_FLAGS_COVERAGE
|
||||
"--coverage -ftest-coverage -lgcov"
|
||||
CACHE STRING "Flags used for linking binaries during coverage builds" FORCE)
|
||||
"--coverage -ftest-coverage -lgcov"
|
||||
CACHE STRING "Flags used for linking binaries during coverage builds" FORCE)
|
||||
mark_as_advanced(CMAKE_CXX_FLAGS_COVERAGE CMAKE_C_FLAGS_COVERAGE CMAKE_EXE_LINKER_FLAGS_COVERAGE)
|
||||
|
||||
|
||||
@ -92,18 +92,17 @@ if(CMAKE_SOURCE_DIR STREQUAL PROJECT_SOURCE_DIR)
|
||||
-pedantic
|
||||
|
||||
-Wall
|
||||
-Wextra
|
||||
#-Wextra # This was causing an issue in the swig stuff
|
||||
-Werror
|
||||
|
||||
-Wno-missing-field-initializers # ignore for GCC 4.8 support
|
||||
)
|
||||
endif()
|
||||
|
||||
# testing
|
||||
include(CTest)
|
||||
enable_testing()
|
||||
|
||||
if(BUILD_TESTING)
|
||||
|
||||
include(CTest)
|
||||
|
||||
option(ECL_TESTS "Build ECL tests" ON)
|
||||
|
||||
add_custom_target(check
|
||||
@ -118,6 +117,8 @@ if(CMAKE_SOURCE_DIR STREQUAL PROJECT_SOURCE_DIR)
|
||||
# swig requires -fPIC
|
||||
set(CMAKE_POSITION_INDEPENDENT_CODE ON)
|
||||
endif()
|
||||
|
||||
|
||||
endif()
|
||||
|
||||
# fetch latest matrix from github
|
||||
@ -164,28 +165,36 @@ add_subdirectory(geo)
|
||||
add_subdirectory(geo_lookup)
|
||||
add_subdirectory(l1)
|
||||
add_subdirectory(tecs)
|
||||
add_subdirectory(validation)
|
||||
if(BUILD_TESTING)
|
||||
add_subdirectory(validation)
|
||||
add_subdirectory(test)
|
||||
endif()
|
||||
|
||||
#=============================================================================
|
||||
# Coverage
|
||||
#
|
||||
if (${CMAKE_BUILD_TYPE} STREQUAL "Coverage")
|
||||
|
||||
add_custom_target(coverage
|
||||
COMMAND ${CMAKE_CTEST_COMMAND}
|
||||
COMMAND lcov --capture --directory . --output-file coverage.info
|
||||
COMMAND lcov --remove coverage.info '/usr/*' --output-file coverage.info # filter out system
|
||||
COMMAND lcov --remove coverage.info 'build/coverage_build/EKF/swig/*' --output-file coverage.info
|
||||
COMMAND lcov --summary coverage.info
|
||||
WORKING_DIRECTORY ${CMAKE_BUILD_DIR}
|
||||
DEPENDS check
|
||||
)
|
||||
add_custom_target(coverage
|
||||
COMMAND ${CMAKE_CTEST_COMMAND}
|
||||
COMMAND lcov --capture --directory . --output-file coverage.info
|
||||
COMMAND lcov --remove coverage.info --output-file coverage.info '/usr/*' '${CMAKE_BINARY_DIR}/*' # filter out system
|
||||
COMMAND lcov --summary coverage.info
|
||||
WORKING_DIRECTORY ${CMAKE_BUILD_DIR}
|
||||
DEPENDS check
|
||||
)
|
||||
|
||||
add_custom_target(coverage_html
|
||||
COMMAND genhtml coverage.info --output-directory out
|
||||
WORKING_DIRECTORY ${CMAKE_BUILD_DIR}
|
||||
DEPENDS coverage
|
||||
)
|
||||
add_custom_target(coverage_html
|
||||
COMMAND genhtml coverage.info --output-directory out
|
||||
WORKING_DIRECTORY ${CMAKE_BUILD_DIR}
|
||||
DEPENDS coverage
|
||||
)
|
||||
|
||||
add_custom_target(coverage_html_view
|
||||
COMMAND x-www-browser out/index.html
|
||||
WORKING_DIRECTORY ${CMAKE_BUILD_DIR}
|
||||
DEPENDS coverage_html
|
||||
)
|
||||
|
||||
endif()
|
||||
|
||||
@ -223,17 +232,3 @@ if(CMAKE_SOURCE_DIR STREQUAL PROJECT_SOURCE_DIR)
|
||||
endif()
|
||||
endif()
|
||||
|
||||
|
||||
enable_testing()
|
||||
include_directories(${GTEST_INCLUDE_DIR})
|
||||
add_subdirectory("/usr/src/gtest" ${CMAKE_BINARY_DIR}/gtest)
|
||||
|
||||
set(SRCS
|
||||
test/main.cpp
|
||||
test/test_example.cpp
|
||||
)
|
||||
add_executable(TestECL ${SRCS})
|
||||
|
||||
target_include_directories(TestECL PRIVATE ${GTEST_INCLUDE_DIRS})
|
||||
target_link_libraries(TestECL gtest gtest_main)
|
||||
add_test(NAME TestECL COMMAND TestECL)
|
||||
|
||||
@ -58,10 +58,10 @@ set_target_properties(ecl_EKF PROPERTIES PUBLIC_HEADER "ekf.h")
|
||||
|
||||
target_compile_options(ecl_EKF PRIVATE -fno-associative-math)
|
||||
|
||||
#if(EKF_PYTHON_TESTS)
|
||||
# add_subdirectory(swig)
|
||||
#endif()
|
||||
if(EKF_PYTHON_TESTS)
|
||||
add_subdirectory(swig)
|
||||
endif()
|
||||
|
||||
#if(BUILD_TESTING)
|
||||
# add_subdirectory(tests)
|
||||
#endif()
|
||||
if(BUILD_TESTING)
|
||||
add_subdirectory(tests)
|
||||
endif()
|
||||
|
||||
19
Makefile
19
Makefile
@ -78,7 +78,7 @@ SRC_DIR := $(shell dirname $(realpath $(lastword $(MAKEFILE_LIST))))
|
||||
define cmake-build
|
||||
+@$(eval BUILD_DIR = $(SRC_DIR)/build/$@$(BUILD_DIR_SUFFIX))
|
||||
+@if [ $(PX4_CMAKE_GENERATOR) = "Ninja" ] && [ -e $(BUILD_DIR)/Makefile ]; then rm -rf $(BUILD_DIR); fi
|
||||
+@if [ ! -e $(BUILD_DIR)/CMakeCache.txt ]; then mkdir -p $(BUILD_DIR) && cd $(BUILD_DIR) && cmake $(2) -G"$(PX4_CMAKE_GENERATOR)" $(CMAKE_ARGS) $(3) $(4) || (rm -rf $(BUILD_DIR)); fi
|
||||
+@if [ ! -e $(BUILD_DIR)/CMakeCache.txt ]; then mkdir -p $(BUILD_DIR) && cd $(BUILD_DIR) && cmake $(2) -G"$(PX4_CMAKE_GENERATOR)" $(CMAKE_ARGS) $(3) $(4) $(5) || (rm -rf $(BUILD_DIR)); fi
|
||||
+@(cd $(BUILD_DIR) && $(PX4_MAKE) $(PX4_MAKE_ARGS) $(ARGS))
|
||||
endef
|
||||
|
||||
@ -98,19 +98,19 @@ doxygen:
|
||||
.PHONY: test_build test test_EKF
|
||||
|
||||
test_build:
|
||||
@$(call cmake-build,$@,$(SRC_DIR), "-DEKF_PYTHON_TESTS=ON")
|
||||
@$(call cmake-build,$@,$(SRC_DIR), "-DEKF_PYTHON_TESTS=ON", "-DBUILD_TESTING=ON")
|
||||
|
||||
test: test_build
|
||||
@cmake --build $(SRC_DIR)/build/test_build --target check
|
||||
|
||||
test_EKF: test_build
|
||||
@cmake --build $(SRC_DIR)/build/test_build --target ecl_EKF_pytest-quick
|
||||
|
||||
|
||||
test_EKF_plots: test_build
|
||||
@cmake --build $(SRC_DIR)/build/test_build --target ecl_EKF_pytest-plots
|
||||
|
||||
test_build_asan:
|
||||
@$(call cmake-build,$@,$(SRC_DIR), "-DECL_ASAN=ON")
|
||||
@$(call cmake-build,$@,$(SRC_DIR), "-DECL_ASAN=ON", "-DBUILD_TESTING=ON")
|
||||
|
||||
test_asan: test_build_asan
|
||||
@cmake --build $(SRC_DIR)/build/test_build_asan --target check
|
||||
@ -119,21 +119,24 @@ test_asan: test_build_asan
|
||||
# --------------------------------------------------------------------
|
||||
|
||||
coverage_build:
|
||||
@$(call cmake-build,$@,$(SRC_DIR), "-DCMAKE_BUILD_TYPE=Coverage", "-DEKF_PYTHON_TESTS=ON")
|
||||
|
||||
@$(call cmake-build,$@,$(SRC_DIR), "-DCMAKE_BUILD_TYPE=Coverage", "-DEKF_PYTHON_TESTS=ON", "-DBUILD_TESTING=ON")
|
||||
|
||||
coverage: coverage_build
|
||||
@cmake --build $(SRC_DIR)/build/coverage_build --target coverage
|
||||
|
||||
coverage_html: coverage
|
||||
coverage_html: coverage_build
|
||||
@cmake --build $(SRC_DIR)/build/coverage_build --target coverage_html
|
||||
|
||||
coverage_html_view: coverage_build
|
||||
@cmake --build $(SRC_DIR)/build/coverage_build --target coverage_html_view
|
||||
|
||||
# Cleanup
|
||||
# --------------------------------------------------------------------
|
||||
.PHONY: clean distclean
|
||||
|
||||
clean:
|
||||
@rm -rf $(SRC_DIR)/build
|
||||
|
||||
|
||||
distclean:
|
||||
@git clean -ff -x -d .
|
||||
|
||||
|
||||
@ -1,6 +1,6 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2015-2018 ECL Development Team. All rights reserved.
|
||||
# Copyright (c) 2019 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
|
||||
@ -31,9 +31,14 @@
|
||||
#
|
||||
############################################################################
|
||||
|
||||
add_executable(ecl_EKF_tests_ringbuffer ringbuffer.cpp)
|
||||
target_link_libraries(ecl_EKF_tests_ringbuffer ecl_EKF)
|
||||
include(gtest.cmake)
|
||||
|
||||
add_test(NAME ecl_EKF_tests_ringbuffer
|
||||
COMMAND ecl_EKF_tests_ringbuffer
|
||||
)
|
||||
set(SRCS
|
||||
main.cpp
|
||||
test_EKF_basics.cpp
|
||||
)
|
||||
add_executable(ECL_GTESTS ${SRCS})
|
||||
|
||||
target_link_libraries(ECL_GTESTS gtest_main ecl_EKF)
|
||||
|
||||
add_test(NAME ECL_GTESTS COMMAND ECL_GTESTS)
|
||||
19
test/CMakeLists.txt.in
Normal file
19
test/CMakeLists.txt.in
Normal file
@ -0,0 +1,19 @@
|
||||
cmake_minimum_required(VERSION 2.8.4)
|
||||
|
||||
project(googletest-download NONE)
|
||||
|
||||
include(ExternalProject)
|
||||
ExternalProject_Add(googletest
|
||||
URL https://github.com/google/googletest/archive/8b6d3f9c4a774bef3081195d422993323b6bb2e0.zip
|
||||
SOURCE_DIR "${CMAKE_CURRENT_BINARY_DIR}/googletest-src"
|
||||
BINARY_DIR "${CMAKE_CURRENT_BINARY_DIR}/googletest-build"
|
||||
CONFIGURE_COMMAND ""
|
||||
BUILD_COMMAND ""
|
||||
INSTALL_COMMAND ""
|
||||
TEST_COMMAND ""
|
||||
# Wrap download, configure and build steps in a script to log output
|
||||
LOG_DOWNLOAD ON
|
||||
LOG_CONFIGURE ON
|
||||
LOG_BUILD ON
|
||||
)
|
||||
|
||||
50
test/gtest.cmake
Normal file
50
test/gtest.cmake
Normal file
@ -0,0 +1,50 @@
|
||||
############################################################################
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
# Download and unpack googletest at configure time
|
||||
configure_file(${CMAKE_CURRENT_LIST_DIR}/CMakeLists.txt.in googletest-download/CMakeLists.txt)
|
||||
execute_process(COMMAND ${CMAKE_COMMAND} -G "${CMAKE_GENERATOR}" . RESULT_VARIABLE result1 WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/googletest-download)
|
||||
execute_process(COMMAND ${CMAKE_COMMAND} --build . RESULT_VARIABLE result2 WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/googletest-download)
|
||||
if(result1 OR result2)
|
||||
message(FATAL_ERROR "Preparing googletest failed: ${result1} ${result2}")
|
||||
endif()
|
||||
|
||||
# Add googletest, defines gtest and gtest_main targets
|
||||
add_subdirectory(${CMAKE_CURRENT_BINARY_DIR}/googletest-src ${CMAKE_CURRENT_BINARY_DIR}/googletest-build EXCLUDE_FROM_ALL)
|
||||
|
||||
# Remove visibility.h from the compile flags for gtest because of poisoned exit()
|
||||
get_target_property(GTEST_COMPILE_FLAGS gtest COMPILE_OPTIONS)
|
||||
list(REMOVE_ITEM GTEST_COMPILE_FLAGS "-include")
|
||||
list(REMOVE_ITEM GTEST_COMPILE_FLAGS "visibility.h")
|
||||
set_target_properties(gtest PROPERTIES COMPILE_OPTIONS "${GTEST_COMPILE_FLAGS}")
|
||||
|
||||
@ -2,6 +2,6 @@
|
||||
|
||||
int main(int argc, char **argv) {
|
||||
testing::InitGoogleTest(&argc, argv);
|
||||
std::cout << "init test \n";
|
||||
std::cout << "Run ECL gtests" << std::endl;
|
||||
return RUN_ALL_TESTS();
|
||||
}
|
||||
|
||||
295
test/test_EKF_basics.cpp
Normal file
295
test/test_EKF_basics.cpp
Normal file
@ -0,0 +1,295 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2019 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 <cmath>
|
||||
#include "EKF/ekf.h"
|
||||
|
||||
class EkfInitializationTest : public ::testing::Test {
|
||||
public:
|
||||
|
||||
Ekf _ekf{};
|
||||
|
||||
// Basics sensors
|
||||
const uint32_t _imu_dt_us{4000}; // 250 Hz Period between IMU updates
|
||||
const uint32_t _baro_dt_us{12500}; // 80 Hz Period between barometer updates
|
||||
const uint32_t _mag_dt_us{12500}; // 80 Hz Period between magnetometer updates
|
||||
const uint32_t _gps_dt_us{200000}; // 5 Hz Period between GPS updates
|
||||
|
||||
// Flags that control if a sensor is fused
|
||||
bool _fuse_imu{true};
|
||||
bool _fuse_baro{true};
|
||||
bool _fuse_mag{true};
|
||||
bool _fuse_gps{false}; // GPS measurements are expected to not come in from beginning
|
||||
|
||||
// GPS message
|
||||
gps_message _gps_message{};
|
||||
|
||||
uint32_t _update_dt_us{}; // greatest common divider of all basic sensor periods
|
||||
const uint32_t _init_duration_us{2000000}; // 2s Duration of
|
||||
|
||||
// counter of how many sensor measurement are put into Ekf
|
||||
uint32_t _counter_imu{0};
|
||||
uint32_t _counter_baro{0};
|
||||
uint32_t _counter_mag{0};
|
||||
|
||||
uint32_t _t_us{0};
|
||||
|
||||
// Setup the Ekf with synthetic measurements
|
||||
void SetUp() override
|
||||
{
|
||||
|
||||
_ekf.init(0);
|
||||
|
||||
// setup gps message to reasonable default values
|
||||
_gps_message.time_usec = 0;
|
||||
_gps_message.lat = 473566094;
|
||||
_gps_message.lon = 85190237;
|
||||
_gps_message.alt = 422056;
|
||||
_gps_message.yaw = 0.0f;
|
||||
_gps_message.yaw_offset = 0.0f;
|
||||
_gps_message.fix_type = 3;
|
||||
_gps_message.eph = 0.5f;
|
||||
_gps_message.epv = 0.8f;
|
||||
_gps_message.sacc = 0.2f;
|
||||
_gps_message.vel_m_s = 0.0;
|
||||
_gps_message.vel_ned[0] = 0.0f;
|
||||
_gps_message.vel_ned[1] = 0.0f;
|
||||
_gps_message.vel_ned[2] = 0.0f;
|
||||
_gps_message.vel_ned_valid = 1;
|
||||
_gps_message.nsats = 16;
|
||||
_gps_message.gdop = 0.0f;
|
||||
|
||||
update_with_const_sensors(_init_duration_us);
|
||||
|
||||
// output how many sensor measurement were put into the EKF
|
||||
// std::cout << "Initialized EKF with:" << std::endl;
|
||||
// std::cout << "update_dt_us: " << _update_dt_us << std::endl;
|
||||
// std::cout << "counter_imu: " << _counter_imu << std::endl
|
||||
// << "counter_baro: " << _counter_baro << std::endl
|
||||
// << "counter_mag: " << _counter_mag << std::endl;
|
||||
}
|
||||
|
||||
void update_with_const_sensors(uint32_t duration_us,
|
||||
Vector3f ang_vel = Vector3f{0.0f,0.0f,0.0f},
|
||||
Vector3f accel = Vector3f{0.0f,0.0f,-CONSTANTS_ONE_G},
|
||||
Vector3f mag_data = Vector3f{0.2f, 0.0f, 0.4f},
|
||||
float baro_data = 122.2f)
|
||||
{
|
||||
// store start time
|
||||
uint32_t start_time_us = _t_us;
|
||||
|
||||
// compute update time step such that we can update the basic sensor at different rates
|
||||
_update_dt_us = std::__gcd(_imu_dt_us,std::__gcd(_mag_dt_us,std::__gcd(_baro_dt_us,_gps_dt_us)));
|
||||
|
||||
// update EKF with synthetic sensor measurements
|
||||
for( ; _t_us < start_time_us+duration_us; _t_us += _update_dt_us)
|
||||
{
|
||||
// Check which sensors update we should do
|
||||
if(_fuse_imu && !(_t_us %_imu_dt_us))
|
||||
{
|
||||
// push imu data into estimator
|
||||
imuSample imu_sample_new;
|
||||
imu_sample_new.time_us = _t_us;
|
||||
imu_sample_new.delta_ang_dt = _imu_dt_us * 1.e-6f;
|
||||
imu_sample_new.delta_ang = ang_vel * imu_sample_new.delta_ang_dt;
|
||||
imu_sample_new.delta_vel_dt = _imu_dt_us * 1.e-6f;
|
||||
imu_sample_new.delta_vel = accel * imu_sample_new.delta_vel_dt;
|
||||
|
||||
_ekf.setIMUData(imu_sample_new);
|
||||
_counter_imu++;
|
||||
}
|
||||
if(_fuse_baro && !(_t_us % _baro_dt_us))
|
||||
{
|
||||
_ekf.setBaroData(_t_us,baro_data);
|
||||
_counter_baro++;
|
||||
}
|
||||
if(_fuse_mag && !(_t_us % _mag_dt_us))
|
||||
{
|
||||
float mag[3];
|
||||
mag_data.copyTo(mag);
|
||||
_ekf.setMagData(_t_us,mag);
|
||||
_counter_mag++;
|
||||
}
|
||||
if(_fuse_gps && !(_t_us % _gps_dt_us))
|
||||
{
|
||||
_gps_message.time_usec = _t_us;
|
||||
_ekf.setGpsData(_t_us,_gps_message);
|
||||
_counter_mag++;
|
||||
}
|
||||
|
||||
_ekf.update();
|
||||
}
|
||||
}
|
||||
|
||||
// Use this method to clean up any memory, network etc. after each test
|
||||
void TearDown() override
|
||||
{
|
||||
|
||||
}
|
||||
};
|
||||
|
||||
|
||||
TEST_F(EkfInitializationTest, tiltAlign)
|
||||
{
|
||||
// GIVEN: reasonable static sensor data for some duration
|
||||
// THEN: EKF should tilt align
|
||||
EXPECT_EQ(true,_ekf.attitude_valid());
|
||||
}
|
||||
|
||||
TEST_F(EkfInitializationTest, initialControlMode)
|
||||
{
|
||||
// GIVEN: reasonable static sensor data for some duration
|
||||
// THEN: EKF control status should be reasonable
|
||||
filter_control_status_u control_status;
|
||||
_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);
|
||||
EXPECT_EQ(0, (int) control_status.flags.update_mag_states_only);
|
||||
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);
|
||||
EXPECT_EQ(0, (int) control_status.flags.mag_align_complete);
|
||||
EXPECT_EQ(0, (int) control_status.flags.ev_vel);
|
||||
EXPECT_EQ(0, (int) control_status.flags.synthetic_mag_z);
|
||||
}
|
||||
|
||||
TEST_F(EkfInitializationTest, convergesToZero)
|
||||
{
|
||||
// GIVEN: initialized EKF with default IMU, baro and mag input for 2s
|
||||
// WHEN: Added more defautl sensor measurements
|
||||
update_with_const_sensors(4000000); // for further 4s
|
||||
|
||||
float converged_pos[3];
|
||||
float converged_vel[3];
|
||||
float converged_accel_bias[3];
|
||||
float converged_gyro_bias[3];
|
||||
_ekf.get_position(converged_pos);
|
||||
_ekf.get_velocity(converged_vel);
|
||||
_ekf.get_accel_bias(converged_accel_bias);
|
||||
_ekf.get_gyro_bias(converged_gyro_bias);
|
||||
|
||||
// THEN: EKF should stay or converge to zero
|
||||
for(int i=0; i<3; ++i)
|
||||
{
|
||||
EXPECT_NEAR(0.0f,converged_pos[i],0.001f);
|
||||
EXPECT_NEAR(0.0f,converged_vel[i],0.001f);
|
||||
EXPECT_NEAR(0.0f,converged_accel_bias[i],0.001f);
|
||||
EXPECT_NEAR(0.0f,converged_gyro_bias[i],0.001f);
|
||||
}
|
||||
}
|
||||
|
||||
TEST_F(EkfInitializationTest, gpsFusion)
|
||||
{
|
||||
// GIVEN: initialized EKF with default IMU, baro and mag input for 2s
|
||||
// WHEN: setting GPS measurements for 11s, minimum GPS health time is set to 10 sec
|
||||
|
||||
_fuse_gps = true;
|
||||
update_with_const_sensors(11000000,Vector3f{0.0f,0.0f,0.0f},Vector3f{0.0f,0.0f,-CONSTANTS_ONE_G}); // for further 3s
|
||||
|
||||
// THEN: EKF should fuse GPS, but no other position sensor
|
||||
filter_control_status_u control_status;
|
||||
_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);
|
||||
EXPECT_EQ(0, (int) control_status.flags.update_mag_states_only);
|
||||
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);
|
||||
EXPECT_EQ(0, (int) control_status.flags.mag_align_complete);
|
||||
EXPECT_EQ(0, (int) control_status.flags.ev_vel);
|
||||
EXPECT_EQ(0, (int) control_status.flags.synthetic_mag_z);
|
||||
}
|
||||
|
||||
TEST_F(EkfInitializationTest, accleBiasEstimation)
|
||||
{
|
||||
// GIVEN: initialized EKF with default IMU, baro and mag input for 2s
|
||||
// WHEN: Added more sensor measurements with accel bias and gps measurements
|
||||
Vector3f accel_bias = {0.0f,0.0f,0.1f};
|
||||
|
||||
_fuse_gps = true;
|
||||
update_with_const_sensors(10000000,Vector3f{0.0f,0.0f,0.0f},Vector3f{0.0f,0.0f,-CONSTANTS_ONE_G}+accel_bias); // for further 10s
|
||||
|
||||
float converged_pos[3];
|
||||
float converged_vel[3];
|
||||
float converged_accel_bias[3];
|
||||
float converged_gyro_bias[3];
|
||||
_ekf.get_position(converged_pos);
|
||||
_ekf.get_velocity(converged_vel);
|
||||
_ekf.get_accel_bias(converged_accel_bias);
|
||||
_ekf.get_gyro_bias(converged_gyro_bias);
|
||||
|
||||
// THEN: EKF should estimate bias correctelly
|
||||
for(int i=0; i<3; ++i)
|
||||
{
|
||||
EXPECT_NEAR(0.0f,converged_pos[i],0.001f) << "i: " << i;
|
||||
EXPECT_NEAR(0.0f,converged_vel[i],0.001f) << "i: " << i;
|
||||
EXPECT_NEAR(accel_bias(i),converged_accel_bias[i],0.001f) << "i: " << i;
|
||||
EXPECT_NEAR(0.0f,converged_gyro_bias[i],0.001f) << "i: " << i;
|
||||
}
|
||||
}
|
||||
|
||||
// TODO: Add sampling tests
|
||||
@ -1,7 +0,0 @@
|
||||
#include "gtest/gtest.h"
|
||||
|
||||
TEST(test_example, sample_test)
|
||||
{
|
||||
printf("blabla \n" );
|
||||
EXPECT_EQ(1, 1);
|
||||
}
|
||||
Loading…
x
Reference in New Issue
Block a user