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)
39 image_left_stamp_ = left_msg->header.stamp;
40 image_right_stamp_ = right_msg->header.stamp;
41 has_new_image_ =
true;
59 dynamic_cast<MultiCameraTest*>(
this), _1, _2));
64 bool wait_for_topic =
true;
65 while (wait_for_topic)
71 if (cam_sub_.getNumPublishers() > 0)
72 wait_for_topic =
false;
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();
ros::Time image_right_stamp_
message_filters::Subscriber< sensor_msgs::Image > cam_left_sub_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL const std::string & getName()
Connection registerCallback(C &callback)
ROSCPP_DECL bool execute(const std::string &method, const XmlRpc::XmlRpcValue &request, XmlRpc::XmlRpcValue &response, XmlRpc::XmlRpcValue &payload, bool wait_for_master)
ros::Time image_left_stamp_
TEST_F(MultiCameraTest, cameraSubscribeTest)
int main(int argc, char **argv)
#define ROS_INFO_STREAM(args)
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
void imageCallback(const sensor_msgs::ImageConstPtr &left_msg, const sensor_msgs::ImageConstPtr &right_msg)
ROSCPP_DECL void spinOnce()
message_filters::Subscriber< sensor_msgs::Image > cam_right_sub_