From 216d5a5103cf3925b00dd009ffbf757a7f460fe8 Mon Sep 17 00:00:00 2001 From: Arjo Chakravarty Date: Wed, 9 Nov 2022 21:11:58 +0800 Subject: [PATCH] Addresses flakiness in `Hydrodynamics.VelocityTestInOil`. (#1787) This PR adjusts the hydrodynamics tests so they are abit less flaky. Currently, it seems like the test checks if one item falls faster than another. However due to the inherent parrallelism, it seems like on different computers the balls start falling at different times. This means the 4 time steps we wait for may not be enough for a difference in velocity to appear. I suspect we no longer need to disable this test on windows. Signed-off-by: Arjo Chakravarty --- test/integration/hydrodynamics.cc | 26 ++++++++++++++++---------- test/worlds/hydrodynamics.sdf | 8 -------- 2 files changed, 16 insertions(+), 18 deletions(-) diff --git a/test/integration/hydrodynamics.cc b/test/integration/hydrodynamics.cc index cfcab01f93..aeb29dc2da 100644 --- a/test/integration/hydrodynamics.cc +++ b/test/integration/hydrodynamics.cc @@ -120,6 +120,8 @@ TEST_F(HydrodynamicsTest, VelocityTestinOil) auto sphere1Vels = this->TestWorld(world, "sphere1"); auto sphere2Vels = this->TestWorld(world, "sphere2"); + auto whenSphere1ExceedsSphere2Vel = 2000; + for (unsigned int i = 0; i < 1000; ++i) { // Sanity check @@ -128,19 +130,23 @@ TEST_F(HydrodynamicsTest, VelocityTestinOil) EXPECT_FLOAT_EQ(0.0, sphere2Vels[i].X()); EXPECT_FLOAT_EQ(0.0, sphere2Vels[i].Y()); - // Wait a couple of iterations for the body to move - if(i > 4) + // Expect sphere1 to fall faster than sphere 2 as no hydro + // drag is applied to it. + EXPECT_LE(sphere1Vels[i].Z(), sphere2Vels[i].Z()); + if(sphere1Vels[i].Z() < sphere2Vels[i].Z() + && whenSphere1ExceedsSphere2Vel > 1000) + { + // Mark this as the time when velocity of sphere1 exceeds sphere 2 + whenSphere1ExceedsSphere2Vel = i; + } + if (i > 900) { - EXPECT_LT(sphere1Vels[i].Z(), sphere2Vels[i].Z()); - - if (i > 900) - { - // Expect for the velocity to stabilize - EXPECT_NEAR(sphere1Vels[i-1].Z(), sphere1Vels[i].Z(), 1e-6); - EXPECT_NEAR(sphere2Vels[i-1].Z(), sphere2Vels[i].Z(), 1e-6); - } + // Expect for the velocity to stabilize + EXPECT_NEAR(sphere1Vels[i-1].Z(), sphere1Vels[i].Z(), 1e-6); + EXPECT_NEAR(sphere2Vels[i-1].Z(), sphere2Vels[i].Z(), 1e-6); } } + EXPECT_LT(whenSphere1ExceedsSphere2Vel, 500); } ///////////////////////////////////////////////// diff --git a/test/worlds/hydrodynamics.sdf b/test/worlds/hydrodynamics.sdf index 234d6314ea..7fc4790c84 100644 --- a/test/worlds/hydrodynamics.sdf +++ b/test/worlds/hydrodynamics.sdf @@ -15,14 +15,6 @@ filename="ignition-gazebo-physics-system" name="ignition::gazebo::systems::Physics"> - - - - true