Browse Source

test recording of velocity reset

master
Kamil Ritz 5 years ago committed by Mathieu Bresciani
parent
commit
adacca099d
  1. 3
      test/CMakeLists.txt
  2. 18
      test/test_EKF_externalVision.cpp
  3. 21
      test/test_EKF_flow.cpp
  4. 11
      test/test_EKF_gps.cpp
  5. 40
      test/test_helper/CMakeLists.txt
  6. 81
      test/test_helper/reset_logging_checker.cpp
  7. 86
      test/test_helper/reset_logging_checker.h

3
test/CMakeLists.txt

@ -34,6 +34,7 @@ @@ -34,6 +34,7 @@
include(gtest.cmake)
add_subdirectory(sensor_simulator)
add_subdirectory(test_helper)
set(SRCS
main.cpp
@ -54,6 +55,6 @@ set(SRCS @@ -54,6 +55,6 @@ set(SRCS
)
add_executable(ECL_GTESTS ${SRCS})
target_link_libraries(ECL_GTESTS gtest_main ecl_EKF ecl_sensor_sim)
target_link_libraries(ECL_GTESTS gtest_main ecl_EKF ecl_sensor_sim ecl_test_helper)
add_test(NAME ECL_GTESTS COMMAND ECL_GTESTS)

18
test/test_EKF_externalVision.cpp

@ -40,6 +40,7 @@ @@ -40,6 +40,7 @@
#include "EKF/ekf.h"
#include "sensor_simulator/sensor_simulator.h"
#include "sensor_simulator/ekf_wrapper.h"
#include "test_helper/reset_logging_checker.h"
class EkfExternalVisionTest : public ::testing::Test {
@ -103,6 +104,9 @@ TEST_F(EkfExternalVisionTest, checkVisionFusionLogic) @@ -103,6 +104,9 @@ TEST_F(EkfExternalVisionTest, checkVisionFusionLogic)
TEST_F(EkfExternalVisionTest, visionVelocityReset)
{
ResetLoggingChecker reset_logging_checker(_ekf);
reset_logging_checker.capturePreResetState();
const Vector3f simulated_velocity(0.3f, -1.0f, 0.4f);
_sensor_simulator._vio.setVelocity(simulated_velocity);
@ -113,10 +117,18 @@ TEST_F(EkfExternalVisionTest, visionVelocityReset) @@ -113,10 +117,18 @@ TEST_F(EkfExternalVisionTest, visionVelocityReset)
// THEN: a reset to Vision velocity should be done
const Vector3f estimated_velocity = _ekf->getVelocity();
EXPECT_TRUE(isEqual(estimated_velocity, simulated_velocity, 1e-5f));
// AND: the reset in velocity should be saved correctly
reset_logging_checker.capturePostResetState();
EXPECT_TRUE(reset_logging_checker.isHorizontalVelocityResetCounterIncreasedBy(1));
EXPECT_TRUE(reset_logging_checker.isVerticalVelocityResetCounterIncreasedBy(1));
EXPECT_TRUE(reset_logging_checker.isVelocityDeltaLoggedCorrectly(1e-5f));
}
TEST_F(EkfExternalVisionTest, visionVelocityResetWithAlignment)
{
ResetLoggingChecker reset_logging_checker(_ekf);
reset_logging_checker.capturePreResetState();
// GIVEN: Drone is pointing north, and we use mag (ROTATE_EV)
// Heading of drone in EKF frame is 0°
@ -140,6 +152,12 @@ TEST_F(EkfExternalVisionTest, visionVelocityResetWithAlignment) @@ -140,6 +152,12 @@ TEST_F(EkfExternalVisionTest, visionVelocityResetWithAlignment)
Quatf estimatedExternalVisionFrameOffset = _ekf->getVisionAlignmentQuaternion();
EXPECT_TRUE(matrix::isEqual(vision_to_ekf.canonical(),
estimatedExternalVisionFrameOffset.canonical()));
// AND: the reset in velocity should be saved correctly
reset_logging_checker.capturePostResetState();
EXPECT_TRUE(reset_logging_checker.isHorizontalVelocityResetCounterIncreasedBy(1));
EXPECT_TRUE(reset_logging_checker.isVerticalVelocityResetCounterIncreasedBy(1));
EXPECT_TRUE(reset_logging_checker.isVelocityDeltaLoggedCorrectly(1e-5f));
}
TEST_F(EkfExternalVisionTest, visionVarianceCheck)

21
test/test_EKF_flow.cpp

@ -40,6 +40,7 @@ @@ -40,6 +40,7 @@
#include "EKF/ekf.h"
#include "sensor_simulator/sensor_simulator.h"
#include "sensor_simulator/ekf_wrapper.h"
#include "test_helper/reset_logging_checker.h"
class EkfFlowTest : public ::testing::Test {
@ -69,6 +70,8 @@ class EkfFlowTest : public ::testing::Test { @@ -69,6 +70,8 @@ class EkfFlowTest : public ::testing::Test {
TEST_F(EkfFlowTest, resetToFlowVelocityInAir)
{
ResetLoggingChecker reset_logging_checker(_ekf);
// WHEN: simulate being 5m above ground
const float simulated_distance_to_ground = 5.f;
_sensor_simulator._rng.setData(simulated_distance_to_ground, 100);
@ -80,6 +83,8 @@ TEST_F(EkfFlowTest, resetToFlowVelocityInAir) @@ -80,6 +83,8 @@ TEST_F(EkfFlowTest, resetToFlowVelocityInAir)
const float estimated_distance_to_ground = _ekf->getTerrainVertPos();
EXPECT_FLOAT_EQ(estimated_distance_to_ground, simulated_distance_to_ground);
reset_logging_checker.capturePreResetState();
// WHEN: start fusing flow data
const Vector2f simulated_horz_velocity(0.5f, -0.2f);
flowSample flow_sample = _sensor_simulator._flow.dataAtRest();
@ -94,14 +99,24 @@ TEST_F(EkfFlowTest, resetToFlowVelocityInAir) @@ -94,14 +99,24 @@ TEST_F(EkfFlowTest, resetToFlowVelocityInAir)
// THEN: estimated velocity should match simulated velocity
const Vector2f estimated_horz_velocity = Vector2f(_ekf->getVelocity());
EXPECT_FALSE(isEqual(estimated_horz_velocity, simulated_horz_velocity)); // TODO: This needs to change
// AND: the reset in velocity should be saved correctly
reset_logging_checker.capturePostResetState();
EXPECT_TRUE(reset_logging_checker.isHorizontalVelocityResetCounterIncreasedBy(1));
EXPECT_TRUE(reset_logging_checker.isVerticalVelocityResetCounterIncreasedBy(0));
EXPECT_TRUE(reset_logging_checker.isVelocityDeltaLoggedCorrectly(1e-9f));
}
TEST_F(EkfFlowTest, resetToFlowVelocityOnGround)
{
ResetLoggingChecker reset_logging_checker(_ekf);
// WHEN: being on ground
const float estimated_distance_to_ground = _ekf->getTerrainVertPos();
EXPECT_LT(estimated_distance_to_ground, 0.3f);
reset_logging_checker.capturePreResetState();
// WHEN: start fusing flow data
_ekf_wrapper.enableFlowFusion();
_sensor_simulator.startFlow();
@ -110,4 +125,10 @@ TEST_F(EkfFlowTest, resetToFlowVelocityOnGround) @@ -110,4 +125,10 @@ TEST_F(EkfFlowTest, resetToFlowVelocityOnGround)
// THEN: estimated velocity should match simulated velocity
const Vector2f estimated_horz_velocity = Vector2f(_ekf->getVelocity());
EXPECT_TRUE(isEqual(estimated_horz_velocity, Vector2f(0.f, 0.f)));
// AND: the reset in velocity should be saved correctly
reset_logging_checker.capturePostResetState();
EXPECT_TRUE(reset_logging_checker.isHorizontalVelocityResetCounterIncreasedBy(1));
EXPECT_TRUE(reset_logging_checker.isVerticalVelocityResetCounterIncreasedBy(0));
EXPECT_TRUE(reset_logging_checker.isVelocityDeltaLoggedCorrectly(1e-9f));
}

11
test/test_EKF_gps.cpp

@ -40,7 +40,7 @@ @@ -40,7 +40,7 @@
#include "EKF/ekf.h"
#include "sensor_simulator/sensor_simulator.h"
#include "sensor_simulator/ekf_wrapper.h"
#include "test_helper/reset_logging_checker.h"
class EkfGpsTest : public ::testing::Test {
public:
@ -86,6 +86,7 @@ TEST_F(EkfGpsTest, gpsTimeout) @@ -86,6 +86,7 @@ TEST_F(EkfGpsTest, gpsTimeout)
TEST_F(EkfGpsTest, resetToGpsVelocity)
{
ResetLoggingChecker reset_logging_checker(_ekf);
// GIVEN:EKF that fuses GPS
// and has gps checks already passed
@ -93,6 +94,8 @@ TEST_F(EkfGpsTest, resetToGpsVelocity) @@ -93,6 +94,8 @@ TEST_F(EkfGpsTest, resetToGpsVelocity)
_sensor_simulator.stopGps();
_sensor_simulator.runSeconds(11);
reset_logging_checker.capturePreResetState();
// AND: simulate constant velocity gps samples for short time
_sensor_simulator.startGps();
const Vector3f simulated_velocity(0.5f, 1.0f, -0.3f);
@ -107,4 +110,10 @@ TEST_F(EkfGpsTest, resetToGpsVelocity) @@ -107,4 +110,10 @@ TEST_F(EkfGpsTest, resetToGpsVelocity)
// THEN: a reset to GPS velocity should be done
const Vector3f estimated_velocity = _ekf->getVelocity();
EXPECT_TRUE(isEqual(estimated_velocity, simulated_velocity, 1e-2f));
// AND: the reset in velocity should be saved correctly
reset_logging_checker.capturePostResetState();
EXPECT_TRUE(reset_logging_checker.isHorizontalVelocityResetCounterIncreasedBy(1));
EXPECT_TRUE(reset_logging_checker.isVerticalVelocityResetCounterIncreasedBy(1));
EXPECT_TRUE(reset_logging_checker.isVelocityDeltaLoggedCorrectly(1e-2f));
}

40
test/test_helper/CMakeLists.txt

@ -0,0 +1,40 @@ @@ -0,0 +1,40 @@
############################################################################
#
# 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 ECL 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.
#
############################################################################
set(SRCS
reset_logging_checker.cpp
)
add_library(ecl_test_helper ${SRCS})
target_link_libraries(ecl_test_helper ecl_EKF)

81
test/test_helper/reset_logging_checker.cpp

@ -0,0 +1,81 @@ @@ -0,0 +1,81 @@
#include "reset_logging_checker.h"
// call immediately after state reset
void ResetLoggingChecker::capturePreResetState() {
float a[2];
float b;
uint8_t c;
_ekf->get_velNE_reset(a, &c);
horz_vel_reset_counter_before_reset = c;
_ekf->get_velD_reset(&b, &c);
vert_vel_reset_counter_before_reset = c;
_ekf->get_posNE_reset(a, &c);
horz_pos_reset_counter_before_reset = c;
_ekf->get_posD_reset(&b, &c);
vert_pos_reset_counter_before_reset = c;
velocity_before_reset = _ekf->getVelocity();
position_before_reset = _ekf->getPosition();
}
// call immediately after state reset
void ResetLoggingChecker::capturePostResetState() {
float a[2];
float b;
uint8_t c;
_ekf->get_velNE_reset(a, &c);
logged_delta_velocity(0) = a[0];
logged_delta_velocity(1) = a[1];
horz_vel_reset_counter_after_reset = c;
_ekf->get_velD_reset(&b, &c);
logged_delta_velocity(2) = b;
vert_vel_reset_counter_after_reset = c;
_ekf->get_posNE_reset(a, &c);
logged_delta_position(0) = a[0];
logged_delta_position(1) = a[1];
horz_pos_reset_counter_after_reset = c;
_ekf->get_posD_reset(&b, &c);
logged_delta_position(2) = b;
vert_pos_reset_counter_after_reset = c;
velocity_after_reset = _ekf->getVelocity();
position_after_reset = _ekf->getPosition();
}
bool ResetLoggingChecker::isVelocityDeltaLoggedCorrectly(float accuracy) {
const Vector3f measured_delta_velocity = velocity_after_reset -
velocity_before_reset;
return matrix::isEqual(logged_delta_velocity,
measured_delta_velocity,
accuracy);
}
bool ResetLoggingChecker::isHorizontalVelocityResetCounterIncreasedBy(int offset) {
return horz_vel_reset_counter_after_reset ==
horz_vel_reset_counter_before_reset + offset;
}
bool ResetLoggingChecker::isVerticalVelocityResetCounterIncreasedBy(int offset) {
return vert_vel_reset_counter_after_reset ==
vert_vel_reset_counter_before_reset + offset;
}
bool ResetLoggingChecker::isPositionDeltaLoggedCorrectly(float accuracy) {
const Vector3f measured_delta_position = position_after_reset -
position_before_reset;
return matrix::isEqual(logged_delta_position,
measured_delta_position,
accuracy);
}
bool ResetLoggingChecker::isHorizontalPositionResetCounterIncreasedBy(int offset) {
return horz_pos_reset_counter_after_reset ==
horz_pos_reset_counter_before_reset + offset;
}
bool ResetLoggingChecker::isVerticalPositionResetCounterIncreasedBy(int offset) {
return vert_pos_reset_counter_after_reset ==
vert_pos_reset_counter_before_reset + offset;
}

86
test/test_helper/reset_logging_checker.h

@ -0,0 +1,86 @@ @@ -0,0 +1,86 @@
/****************************************************************************
*
* Copyright (c) 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.
*
****************************************************************************/
/**
* Helper class to check the state_reset_status member of the ekf object.
* Used for checking if state resets are logged correctly.
* @author Kamil Ritz <ka.ritz@hotmail.com>
*/
#pragma once
#include <memory>
#include "EKF/ekf.h"
class ResetLoggingChecker {
public:
ResetLoggingChecker(std::shared_ptr<Ekf> ekf) : _ekf(ekf) {}
// call immediately before state reset
void capturePreResetState();
// call immediately after state reset
void capturePostResetState();
bool isVelocityDeltaLoggedCorrectly(float accuracy);
bool isHorizontalVelocityResetCounterIncreasedBy(int offset);
bool isVerticalVelocityResetCounterIncreasedBy(int offset);
bool isPositionDeltaLoggedCorrectly(float accuracy);
bool isHorizontalPositionResetCounterIncreasedBy(int offset);
bool isVerticalPositionResetCounterIncreasedBy(int offset);
private:
std::shared_ptr<Ekf> _ekf;
Vector3f velocity_before_reset;
Vector3f position_before_reset;
int horz_vel_reset_counter_before_reset;
int vert_vel_reset_counter_before_reset;
int horz_pos_reset_counter_before_reset;
int vert_pos_reset_counter_before_reset;
Vector3f velocity_after_reset;
Vector3f position_after_reset;
int horz_vel_reset_counter_after_reset;
int vert_vel_reset_counter_after_reset;
int horz_pos_reset_counter_after_reset;
int vert_pos_reset_counter_after_reset;
Vector3f logged_delta_velocity;
Vector3f logged_delta_position;
};
Loading…
Cancel
Save