Skip to content

Commit

Permalink
ros-simulation#408 Increasing max time because some systems are takin…
Browse files Browse the repository at this point in the history
…g 0.6 seconds to receive the messages (still well less than 2.0 seconds). Also all the tests can be run with run_tests_gazebo_plugins_rostest but only with the -j1 flag ros-simulation#409
  • Loading branch information
lucasw authored and j-rivero committed Feb 13, 2017
1 parent fdf41ea commit 335e7d8
Show file tree
Hide file tree
Showing 4 changed files with 13 additions and 11 deletions.
1 change: 0 additions & 1 deletion gazebo_plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -371,7 +371,6 @@ if (CATKIN_ENABLE_TESTING)
add_rostest(test/range/range_plugin.test)
target_link_libraries(set_model_state-test ${catkin_LIBRARIES})

# Can't run these and the above test together
add_rostest_gtest(depth_camera-test
test/camera/depth_camera.test
test/camera/depth_camera.cpp)
Expand Down
2 changes: 1 addition & 1 deletion gazebo_plugins/test/camera/camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ TEST_F(CameraTest, cameraSubscribeTest)
// this likely isn't that robust - what if the testing system is really slow?
double time_diff = (ros::Time::now() - image_stamp_).toSec();
ROS_INFO_STREAM(time_diff);
EXPECT_LT(time_diff, 0.5);
EXPECT_LT(time_diff, 1.0);
cam_sub_.shutdown();
}

Expand Down
19 changes: 11 additions & 8 deletions gazebo_plugins/test/camera/depth_camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,22 +80,25 @@ TEST_F(DepthCameraTest, cameraSubscribeTest)

EXPECT_EQ(depth_stamp_.toSec(), image_stamp_.toSec());
EXPECT_EQ(depth_stamp_.toSec(), points_stamp_.toSec());
// This check depends on the update period being much longer
// than the expected difference between now and the received image time
// This check depends on the update period (currently 1.0/update_rate = 2.0 seconds)
// being much longer than the expected difference between now and the
// received image time.
const double max_time = 1.0;
const ros::Time current_time = ros::Time::now();
// TODO(lucasw)
// this likely isn't that robust - what if the testing system is really slow?
double time_diff;
time_diff = (ros::Time::now() - image_stamp_).toSec();
time_diff = (current_time - image_stamp_).toSec();
ROS_INFO_STREAM(time_diff);
EXPECT_LT(time_diff, 0.5);
EXPECT_LT(time_diff, max_time);

time_diff = (ros::Time::now() - depth_stamp_).toSec();
time_diff = (current_time - depth_stamp_).toSec();
ROS_INFO_STREAM(time_diff);
EXPECT_LT(time_diff, 0.5);
EXPECT_LT(time_diff, max_time);

time_diff = (ros::Time::now() - points_stamp_).toSec();
time_diff = (current_time - points_stamp_).toSec();
ROS_INFO_STREAM(time_diff);
EXPECT_LT(time_diff, 0.5);
EXPECT_LT(time_diff, max_time);

cam_sub_.shutdown();
depth_sub_.shutdown();
Expand Down
2 changes: 1 addition & 1 deletion gazebo_plugins/test/camera/multicamera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,7 @@ TEST_F(MultiCameraTest, cameraSubscribeTest)
// this likely isn't that robust - what if the testing system is really slow?
double time_diff = (ros::Time::now() - image_left_stamp_).toSec();
ROS_INFO_STREAM(time_diff);
EXPECT_LT(time_diff, 0.5);
EXPECT_LT(time_diff, 1.0);
// cam_sub_.shutdown();
}

Expand Down

0 comments on commit 335e7d8

Please sign in to comment.