1 #include <gtest/gtest.h>
8 #include <sensor_msgs/Image.h>
36 const sensor_msgs::ImageConstPtr& left_msg,
37 const sensor_msgs::ImageConstPtr& right_msg)
54 cam_left_sub_.subscribe(nh_,
"stereo/camera/left/image_raw", 1);
55 cam_right_sub_.subscribe(nh_,
"stereo/camera/right/image_raw", 1);
57 cam_left_sub_, cam_right_sub_, 4);
59 dynamic_cast<MultiCameraTest*
>(
this), boost::placeholders::_1, boost::placeholders::_2));
64 bool wait_for_topic =
true;
65 while (wait_for_topic)
71 if (cam_sub_.getNumPublishers() > 0)
72 wait_for_topic =
false;
77 while (!has_new_image_)
83 double sync_diff = (image_left_stamp_ - image_right_stamp_).toSec();
84 EXPECT_EQ(sync_diff, 0.0);
92 EXPECT_LT(time_diff, 1.0);
102 for (
int i = 0; i < payload[1].
size(); ++i)
106 std::string topic = payload[1][i][0];
107 EXPECT_EQ(topic.find(
"image_trigger"), std::string::npos);
111 int main(
int argc,
char** argv)
113 ros::init(argc, argv,
"gazebo_multicamera_test");
114 testing::InitGoogleTest(&argc, argv);
115 return RUN_ALL_TESTS();