Skip to content

Commit

Permalink
👩‍🌾 Make depth camera tests more robust (#897)
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <louise@openrobotics.org>
  • Loading branch information
chapulina authored Jul 1, 2021
1 parent 276ec0f commit 7cf129e
Show file tree
Hide file tree
Showing 5 changed files with 25 additions and 23 deletions.
15 changes: 8 additions & 7 deletions test/integration/depth_camera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@

using namespace ignition;
using namespace gazebo;
using namespace std::chrono_literals;

/// \brief Test DepthCameraTest system
class DepthCameraTest : public ::testing::Test
Expand Down Expand Up @@ -87,15 +88,15 @@ TEST_F(DepthCameraTest, IGN_UTILS_TEST_DISABLED_ON_MAC(DepthCameraBox))
size_t iters100 = 100u;
server.Run(true, iters100, false);

auto waitTime = std::chrono::duration_cast< std::chrono::milliseconds>(
std::chrono::duration<double>(0.001));
int i = 0;
while (i < 300)
int sleep{0};
int maxSleep{30};
while (depthBuffer == nullptr && sleep < maxSleep)
{
std::this_thread::sleep_for(waitTime);
i++;
std::this_thread::sleep_for(100ms);
sleep++;
}
EXPECT_NE(depthBuffer, nullptr);
EXPECT_LT(sleep, maxSleep);
ASSERT_NE(depthBuffer, nullptr);

// Take into account box of 1 m on each side and 0.05 cm sensor offset
double expectedRangeAtMidPointBox1 = 2.45;
Expand Down
12 changes: 6 additions & 6 deletions test/integration/pose_publisher_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -356,9 +356,9 @@ TEST_F(PosePublisherTest, UpdateFrequency)
std::size_t nExpMessages = 100;
// Wait for 100 messages to be received
bool received = false;
for (int sleep = 0; sleep < 300; ++sleep)
for (int sleep = 0; sleep < 30; ++sleep)
{
std::this_thread::sleep_for(std::chrono::milliseconds(10));
std::this_thread::sleep_for(std::chrono::milliseconds(100));

{
std::lock_guard<std::mutex> lock(mutex);
Expand Down Expand Up @@ -678,9 +678,9 @@ TEST_F(PosePublisherTest, StaticPoseUpdateFrequency)
std::size_t nExpMessages = 100;
// Wait for 100 messages to be received
bool received = false;
for (int sleep = 0; sleep < 300; ++sleep)
for (int sleep = 0; sleep < 30; ++sleep)
{
std::this_thread::sleep_for(std::chrono::milliseconds(10));
std::this_thread::sleep_for(std::chrono::milliseconds(100));

{
std::lock_guard<std::mutex> lock(mutex);
Expand Down Expand Up @@ -738,9 +738,9 @@ TEST_F(PosePublisherTest, NestedModelLoadPlugin)

// Wait for messages to be received
int sleep = 0;
while (poseMsgs.empty() && sleep++ < 300)
while (poseMsgs.empty() && sleep++ < 30)
{
std::this_thread::sleep_for(std::chrono::milliseconds(10));
std::this_thread::sleep_for(std::chrono::milliseconds(100));
}

EXPECT_TRUE(!poseMsgs.empty());
Expand Down
13 changes: 7 additions & 6 deletions test/integration/rgbd_camera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@

using namespace ignition;
using namespace gazebo;
using namespace std::chrono_literals;

/// \brief Test RgbdCameraTest system
class RgbdCameraTest : public ::testing::Test
Expand Down Expand Up @@ -87,14 +88,14 @@ TEST_F(RgbdCameraTest, IGN_UTILS_TEST_DISABLED_ON_MAC(RgbdCameraBox))
size_t iters100 = 100u;
server.Run(true, iters100, false);

auto waitTime = std::chrono::duration_cast< std::chrono::milliseconds>(
std::chrono::duration<double>(0.001));
int i = 0;
while (nullptr == depthBuffer && i < 500)
int sleep{0};
int maxSleep{30};
while (depthBuffer == nullptr && sleep < maxSleep)
{
std::this_thread::sleep_for(waitTime);
i++;
std::this_thread::sleep_for(100ms);
sleep++;
}
EXPECT_LT(sleep, maxSleep);
ASSERT_NE(depthBuffer, nullptr);

// Take into account box of 1 m on each side and 0.05 cm sensor offset
Expand Down
6 changes: 3 additions & 3 deletions test/integration/scene_broadcaster_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,7 @@ TEST_P(SceneBroadcasterTest, PoseInfo)
server.Run(true, 1, false);

unsigned int sleep{0u};
unsigned int maxSleep{10u};
unsigned int maxSleep{30u};
// cppcheck-suppress unmatchedSuppression
// cppcheck-suppress knownConditionTrueFalse
while (!received && sleep++ < maxSleep)
Expand Down Expand Up @@ -468,7 +468,7 @@ TEST_P(SceneBroadcasterTest, State)

// Run server
unsigned int sleep{0u};
unsigned int maxSleep{10u};
unsigned int maxSleep{30u};
while (!received && sleep++ < maxSleep)
{
IGN_SLEEP_MS(100);
Expand Down Expand Up @@ -592,7 +592,7 @@ TEST_P(SceneBroadcasterTest, StateStatic)

// Run server
unsigned int sleep{0u};
unsigned int maxSleep{10u};
unsigned int maxSleep{30u};
while (!received && sleep++ < maxSleep)
{
IGN_SLEEP_MS(100);
Expand Down
2 changes: 1 addition & 1 deletion test/integration/thermal_sensor_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -190,7 +190,7 @@ TEST_F(ThermalSensorTest,

// wait for image
bool received = false;
for (unsigned int i = 0; i < 20; ++i)
for (unsigned int i = 0; i < 30; ++i)
{
{
std::lock_guard<std::mutex> lock(g_mutex);
Expand Down

0 comments on commit 7cf129e

Please sign in to comment.