1 #include <gtest/gtest.h>
4 #include <sensor_msgs/PointCloud2.h>
49 cam_sub_ = it.
subscribe(
"camera1/image_raw", 1,
52 depth_sub_ = it.
subscribe(
"camera1/depth/image_raw", 1,
55 points_sub_ = nh_.subscribe(
"camera1/points", 1,
62 bool wait_for_topic =
true;
63 while (wait_for_topic)
69 if (cam_sub_.getNumPublishers() > 0)
70 wait_for_topic =
false;
75 while (!has_new_image_ || !has_new_depth_ || !has_new_points_)
81 EXPECT_EQ(depth_stamp_.toSec(), image_stamp_.toSec());
82 EXPECT_EQ(depth_stamp_.toSec(), points_stamp_.toSec());
86 const double max_time = 1.0;
91 time_diff = (current_time - image_stamp_).toSec();
93 EXPECT_LT(time_diff, max_time);
95 time_diff = (current_time - depth_stamp_).toSec();
97 EXPECT_LT(time_diff, max_time);
99 time_diff = (current_time - points_stamp_).toSec();
101 EXPECT_LT(time_diff, max_time);
104 depth_sub_.shutdown();
105 points_sub_.shutdown();
114 for (
int i = 0; i < payload[1].
size(); ++i)
118 std::string topic = payload[1][i][0];
119 EXPECT_EQ(topic.find(
"image_trigger"), std::string::npos);
123 int main(
int argc,
char** argv)
125 ros::init(argc, argv,
"gazebo_depth_camera_test");
126 testing::InitGoogleTest(&argc, argv);
127 return RUN_ALL_TESTS();