Skip to content

Commit

Permalink
fix untriggered first image
Browse files Browse the repository at this point in the history
  • Loading branch information
scpeters committed Apr 19, 2018
1 parent 23d995b commit e9d72ba
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 10 deletions.
2 changes: 2 additions & 0 deletions gazebo_plugins/src/gazebo_ros_triggered_camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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));
Expand All @@ -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));
Expand Down
11 changes: 1 addition & 10 deletions gazebo_plugins/test/camera/triggered_camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,22 +32,13 @@ TEST_F(CameraTest, cameraSubscribeTest)
&CameraTest::imageCallback,
dynamic_cast<CameraTest*>(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
Expand Down

0 comments on commit e9d72ba

Please sign in to comment.