diff --git a/gazebo_plugins/CMakeLists.txt b/gazebo_plugins/CMakeLists.txt index 3b3f31fc6..9ee4c40a3 100644 --- a/gazebo_plugins/CMakeLists.txt +++ b/gazebo_plugins/CMakeLists.txt @@ -361,6 +361,8 @@ 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 @@ -370,12 +372,16 @@ if (CATKIN_ENABLE_TESTING) target_link_libraries(set_model_state-test ${catkin_LIBRARIES}) # Can't run these and the above test together - # 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(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}) endif() diff --git a/gazebo_plugins/src/gazebo_ros_multicamera.cpp b/gazebo_plugins/src/gazebo_ros_multicamera.cpp index 1017b2e2d..a53f4988c 100644 --- a/gazebo_plugins/src/gazebo_ros_multicamera.cpp +++ b/gazebo_plugins/src/gazebo_ros_multicamera.cpp @@ -98,7 +98,6 @@ void GazeboRosMultiCamera::Load(sensors::SensorPtr _parent, void GazeboRosMultiCamera::OnNewFrame(const unsigned char *_image, GazeboRosCameraUtils* util) { - GazeboRosCameraUtils* util = this->utils[0]; # if GAZEBO_MAJOR_VERSION >= 7 common::Time sensor_update_time = util->parentSensor_->LastMeasurementTime(); # else diff --git a/gazebo_plugins/test/camera/camera.test b/gazebo_plugins/test/camera/camera.test index 06f58a4e6..3a91b824b 100644 --- a/gazebo_plugins/test/camera/camera.test +++ b/gazebo_plugins/test/camera/camera.test @@ -1,11 +1,17 @@ + + + + + + diff --git a/gazebo_plugins/test/camera/camera.world b/gazebo_plugins/test/camera/camera.world index f48a94c00..3154be354 100644 --- a/gazebo_plugins/test/camera/camera.world +++ b/gazebo_plugins/test/camera/camera.world @@ -21,7 +21,7 @@ false - 0.0 2.0 2.0 0.0 0.0 0.0 + 2.0 0.0 4.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 @@ -85,7 +85,14 @@ 100.0 + + + + true + 0.0 0.0 0.5 0.0 0.0 0.0 + + 0.0 0.0 0.0 0.0 0.0 0.0 0.5 diff --git a/gazebo_plugins/test/camera/depth_camera.cpp b/gazebo_plugins/test/camera/depth_camera.cpp new file mode 100644 index 000000000..b7d4eae76 --- /dev/null +++ b/gazebo_plugins/test/camera/depth_camera.cpp @@ -0,0 +1,92 @@ +#include +#include +#include + +class DepthCameraTest : public testing::Test +{ +protected: + virtual void SetUp() + { + has_new_image_ = false; + has_new_depth_ = false; + } + + ros::NodeHandle nh_; + image_transport::Subscriber cam_sub_; + image_transport::Subscriber depth_sub_; + bool has_new_image_; + ros::Time image_stamp_; + bool has_new_depth_; + ros::Time depth_stamp_; +public: + void imageCallback(const sensor_msgs::ImageConstPtr& msg) + { + image_stamp_ = msg->header.stamp; + has_new_image_ = true; + } + void depthCallback(const sensor_msgs::ImageConstPtr& msg) + { + depth_stamp_ = msg->header.stamp; + has_new_depth_ = true; + } +}; + +// Test if the camera image is published at all, and that the timestamp +// is not too long in the past. +TEST_F(DepthCameraTest, cameraSubscribeTest) +{ + image_transport::ImageTransport it(nh_); + cam_sub_ = it.subscribe("camera1/image_raw", 1, + &DepthCameraTest::imageCallback, + dynamic_cast(this)); + depth_sub_ = it.subscribe("camera1/depth/image_raw", 1, + &DepthCameraTest::depthCallback, + dynamic_cast(this)); + +#if 0 + // wait for gazebo to start publishing + // TODO(lucasw) this isn't really necessary since this test + // is purely passive + bool wait_for_topic = true; + while (wait_for_topic) + { + // @todo this fails without the additional 0.5 second sleep after the + // publisher comes online, which means on a slower or more heavily + // loaded system it may take longer than 0.5 seconds, and the test + // would hang until the timeout is reached and fail. + if (cam_sub_.getNumPublishers() > 0) + wait_for_topic = false; + ros::Duration(0.5).sleep(); + } +#endif + + while (!has_new_image_ || !has_new_depth_) + { + ros::spinOnce(); + ros::Duration(0.1).sleep(); + } + + EXPECT_EQ(depth_stamp_.toSec(), image_stamp_.toSec()); + // This check depends on the update period being much longer + // than the expected difference between now and the received image time + // 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(); + ROS_INFO_STREAM(time_diff); + EXPECT_LT(time_diff, 0.5); + + time_diff = (ros::Time::now() - depth_stamp_).toSec(); + ROS_INFO_STREAM(time_diff); + EXPECT_LT(time_diff, 0.5); + + cam_sub_.shutdown(); + depth_sub_.shutdown(); +} + +int main(int argc, char** argv) +{ + ros::init(argc, argv, "gazebo_depth_camera_test"); + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/gazebo_plugins/test/camera/depth_camera.test b/gazebo_plugins/test/camera/depth_camera.test new file mode 100644 index 000000000..3f4dd72bc --- /dev/null +++ b/gazebo_plugins/test/camera/depth_camera.test @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + diff --git a/gazebo_plugins/test/camera/depth_camera.world b/gazebo_plugins/test/camera/depth_camera.world index 25ade9c52..978a0a4b2 100644 --- a/gazebo_plugins/test/camera/depth_camera.world +++ b/gazebo_plugins/test/camera/depth_camera.world @@ -21,7 +21,7 @@ false - 0.0 2.0 2.0 0.0 0.0 0.0 + 2.0 0.0 4.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 @@ -85,8 +85,15 @@ 100.0 + + - + + true + 0.0 0.0 0.5 0.0 0.0 0.0 + + 0.0 0.0 0.0 0.0 0.0 0.0 + 0.5 0.0 + camera1 image_raw + camera_info depth/image_raw + depth/camera_info points - camera_info - depth_cam camera_link 0.07 @@ -127,7 +136,6 @@ 0.0 0.0 - true