diff --git a/gazebo_plugins/CMakeLists.txt b/gazebo_plugins/CMakeLists.txt index d4331fbc9..c62db94d7 100644 --- a/gazebo_plugins/CMakeLists.txt +++ b/gazebo_plugins/CMakeLists.txt @@ -337,24 +337,25 @@ install(DIRECTORY test ) # Tests +# These need to be run with -j1 flag because gazebo can't be run +# in parallel. if (CATKIN_ENABLE_TESTING) find_package(rostest REQUIRED) - # add_rostest_gtest(set_model_state-test - # test/set_model_state_test/set_model_state_test.test - # test/set_model_state_test/set_model_state_test.cpp) - # target_link_libraries(set_model_state-test ${catkin_LIBRARIES}) + add_rostest_gtest(set_model_state-test + test/set_model_state_test/set_model_state_test.test + test/set_model_state_test/set_model_state_test.cpp) + 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) target_link_libraries(depth_camera-test ${catkin_LIBRARIES}) - # add_rostest_gtest(multicamera-test - # test/camera/multicamera.test - # test/camera/multicamera.cpp) - # target_link_libraries(multicamera-test ${catkin_LIBRARIES}) - # add_rostest_gtest(camera-test - # test/camera/camera.test - # test/camera/camera.cpp) - # target_link_libraries(camera-test ${catkin_LIBRARIES}) + add_rostest_gtest(multicamera-test + test/camera/multicamera.test + test/camera/multicamera.cpp) + target_link_libraries(multicamera-test ${catkin_LIBRARIES}) + add_rostest_gtest(camera-test + test/camera/camera.test + test/camera/camera.cpp) + target_link_libraries(camera-test ${catkin_LIBRARIES}) endif() diff --git a/gazebo_plugins/test/camera/camera.cpp b/gazebo_plugins/test/camera/camera.cpp index 25a2932d3..b7805bbae 100644 --- a/gazebo_plugins/test/camera/camera.cpp +++ b/gazebo_plugins/test/camera/camera.cpp @@ -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(); } diff --git a/gazebo_plugins/test/camera/depth_camera.cpp b/gazebo_plugins/test/camera/depth_camera.cpp index b6809e87c..596e6d50f 100644 --- a/gazebo_plugins/test/camera/depth_camera.cpp +++ b/gazebo_plugins/test/camera/depth_camera.cpp @@ -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(); diff --git a/gazebo_plugins/test/camera/multicamera.cpp b/gazebo_plugins/test/camera/multicamera.cpp index cd66a0778..0823c53da 100644 --- a/gazebo_plugins/test/camera/multicamera.cpp +++ b/gazebo_plugins/test/camera/multicamera.cpp @@ -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(); }