Skip to content

Commit

Permalink
Addresses flakiness in Hydrodynamics.VelocityTestInOil. (#1787)
Browse files Browse the repository at this point in the history
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 <[email protected]>
  • Loading branch information
arjo129 authored Nov 9, 2022
1 parent 25ba1ce commit 216d5a5
Show file tree
Hide file tree
Showing 2 changed files with 16 additions and 18 deletions.
26 changes: 16 additions & 10 deletions test/integration/hydrodynamics.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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);
}

/////////////////////////////////////////////////
Expand Down
8 changes: 0 additions & 8 deletions test/worlds/hydrodynamics.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -15,14 +15,6 @@
filename="ignition-gazebo-physics-system"
name="ignition::gazebo::systems::Physics">
</plugin>
<plugin
filename="ignition-gazebo-user-commands-system"
name="ignition::gazebo::systems::UserCommands">
</plugin>
<plugin
filename="ignition-gazebo-scene-broadcaster-system"
name="ignition::gazebo::systems::SceneBroadcaster">
</plugin>

<light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
Expand Down

0 comments on commit 216d5a5

Please sign in to comment.