4 #include <sensor_msgs/CameraInfo.h> 5 #include <sensor_msgs/Image.h> 6 #include <gtest/gtest.h> 21 TEST(CvCameraNode, getImage)
32 while (
g_image.header.frame_id ==
"")
37 EXPECT_EQ(
"camera2",
g_image.header.frame_id);
40 EXPECT_EQ(
"bgr8",
g_image.encoding);
43 TEST(CvCameraNode, getCameraInfo)
75 int main(
int argc,
char **argv)
77 ros::init(argc, argv,
"test_cv_camera_no_yaml");
78 testing::InitGoogleTest(&argc, argv);
79 return RUN_ALL_TESTS();
int main(int argc, char **argv)
sensor_msgs::CameraInfo g_camera_info
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
TEST(CvCameraNode, getImage)
void ImageCallback(const sensor_msgs::Image::ConstPtr &image)
uint32_t getNumPublishers() const
sensor_msgs::Image g_image
void InfoCallback(const sensor_msgs::CameraInfo::ConstPtr &info)
ROSCPP_DECL void spinOnce()