diff --git a/gazebo_plugins/src/gazebo_ros_triggered_camera.cpp b/gazebo_plugins/src/gazebo_ros_triggered_camera.cpp index f8030d059..045d8a5fa 100644 --- a/gazebo_plugins/src/gazebo_ros_triggered_camera.cpp +++ b/gazebo_plugins/src/gazebo_ros_triggered_camera.cpp @@ -64,6 +64,7 @@ void GazeboRosTriggeredCamera::Load(sensors::SensorPtr _parent, sdf::ElementPtr GazeboRosCameraUtils::Load(_parent, _sdf); + this->SetCameraEnabled(false); this->preRenderConnection_ = event::Events::ConnectPreRender( std::bind(&GazeboRosTriggeredCamera::PreRender, this)); @@ -76,6 +77,7 @@ void GazeboRosTriggeredCamera::Load(sensors::SensorPtr _parent, { GazeboRosCameraUtils::Load(_parent, _sdf, _camera_name_suffix, _hack_baseline); + this->SetCameraEnabled(false); this->preRenderConnection_ = event::Events::ConnectPreRender( std::bind(&GazeboRosTriggeredCamera::PreRender, this)); diff --git a/gazebo_plugins/test/camera/triggered_camera.cpp b/gazebo_plugins/test/camera/triggered_camera.cpp index 1bce41fd4..4ce6f628a 100644 --- a/gazebo_plugins/test/camera/triggered_camera.cpp +++ b/gazebo_plugins/test/camera/triggered_camera.cpp @@ -32,22 +32,13 @@ TEST_F(CameraTest, cameraSubscribeTest) &CameraTest::imageCallback, dynamic_cast(this)); - // check for first image - while (!images_received_) - { - ros::spinOnce(); - ros::Duration(0.1).sleep(); - } - - // then wait for 3 seconds to confirm that we don't receive any more images - images_received_ = 0; + // wait for 3 seconds to confirm that we don't receive any images for (unsigned int i = 0; i < 30; ++i) { ros::spinOnce(); ros::Duration(0.1).sleep(); } EXPECT_EQ(images_received_, 0); - images_received_ = 0; // make sure something is subscribing to image_trigger topic // there is no easy API, so call getSystemState