From d20e46567e3cee788e209f7f071f9fecb5628d69 Mon Sep 17 00:00:00 2001 From: bresch Date: Mon, 24 Jan 2022 11:33:31 +0100 Subject: [PATCH] ekf2: improve flow for terrain unit test --- src/modules/ekf2/test/test_EKF_terrain_estimator.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/modules/ekf2/test/test_EKF_terrain_estimator.cpp b/src/modules/ekf2/test/test_EKF_terrain_estimator.cpp index 1fd6ae336e..4fa4d99355 100644 --- a/src/modules/ekf2/test/test_EKF_terrain_estimator.cpp +++ b/src/modules/ekf2/test/test_EKF_terrain_estimator.cpp @@ -73,6 +73,8 @@ public: _ekf_wrapper.enableGpsFusion(); _ekf_wrapper.setBaroHeight(); _sensor_simulator.runSeconds(2); // Run to pass the GPS checks + _sensor_simulator.runSeconds(3.2); // And a bit more to start the GPS fusion TODO: this shouldn't be necessary + EXPECT_TRUE(_ekf_wrapper.isIntendingGpsFusion()); const Vector3f simulated_velocity(0.5f, -1.0f, 0.f); @@ -98,7 +100,7 @@ public: _sensor_simulator.startFlow(); _ekf->set_in_air_status(true); - _sensor_simulator.runSeconds(8); + _sensor_simulator.runSeconds(7); } };