1 #include <gtest/gtest.h>
4 #include <std_msgs/Empty.h>
31 cam_sub_ = it.
subscribe(
"camera1/image_raw", 5,
36 for (
unsigned int i = 0; i < 30; ++i)
41 EXPECT_EQ(images_received_, 0);
50 int trigger_listeners = 0;
51 for (
int i = 0; i < payload[1].
size(); ++i)
55 std::string topic = payload[1][i][0];
56 if (topic.find(
"image_trigger") != std::string::npos)
61 EXPECT_EQ(trigger_listeners, 1);
64 ros::Publisher trigger_pub = nh_.advertise<std_msgs::Empty>(
"camera1/image_trigger", 1,
true);
68 for (
unsigned int i = 0; i < 10 && !images_received_; ++i)
73 EXPECT_EQ(images_received_, 1);
76 for (
unsigned int i = 0; i < 30; ++i)
81 EXPECT_EQ(images_received_, 1);
91 for (
unsigned int i = 0; i < 10 && images_received_ < 2; ++i)
96 EXPECT_EQ(images_received_, 3);
99 for (
unsigned int i = 0; i < 30; ++i)
104 EXPECT_EQ(images_received_, 3);
109 int main(
int argc,
char** argv)
111 ros::init(argc, argv,
"gazebo_camera_test");
112 testing::InitGoogleTest(&argc, argv);
113 return RUN_ALL_TESTS();