test_cv_camera_no_yaml.cpp
Go to the documentation of this file.
00001 // Copyright [2015] Takashi Ogura<t.ogura@gmail.com>
00002 
00003 #include <ros/ros.h>
00004 #include <sensor_msgs/CameraInfo.h>
00005 #include <sensor_msgs/Image.h>
00006 #include <gtest/gtest.h>
00007 
00008 sensor_msgs::Image g_image;
00009 sensor_msgs::CameraInfo g_camera_info;
00010 
00011 void ImageCallback(const sensor_msgs::Image::ConstPtr &image)
00012 {
00013   g_image = *image;
00014 }
00015 
00016 void InfoCallback(const sensor_msgs::CameraInfo::ConstPtr &info)
00017 {
00018   g_camera_info = *info;
00019 }
00020 
00021 TEST(CvCameraNode, getImage)
00022 {
00023   ros::NodeHandle node;
00024   ros::Subscriber sub = node.subscribe("/cv_camera_no_yaml/image_raw",
00025                                        1,
00026                                        &ImageCallback);
00027   ros::Rate r(10.0);
00028   while (sub.getNumPublishers() == 0)
00029   {
00030     r.sleep();
00031   }
00032   while (g_image.header.frame_id == "")
00033   {
00034     ros::spinOnce();
00035     r.sleep();
00036   }
00037   EXPECT_EQ("camera2", g_image.header.frame_id);
00038   EXPECT_EQ(480, g_image.height);
00039   EXPECT_EQ(640, g_image.width);
00040   EXPECT_EQ("bgr8", g_image.encoding);
00041 }
00042 
00043 TEST(CvCameraNode, getCameraInfo)
00044 {
00045   ros::NodeHandle node;
00046   ros::Subscriber sub = node.subscribe("/cv_camera_no_yaml/camera_info",
00047                                        1,
00048                                        &InfoCallback);
00049   ros::Rate r(10.0);
00050   while (sub.getNumPublishers() == 0)
00051   {
00052     r.sleep();
00053   }
00054   while (g_camera_info.header.frame_id == "")
00055   {
00056     ros::spinOnce();
00057     r.sleep();
00058   }
00059   EXPECT_EQ("camera2", g_camera_info.header.frame_id);
00060   // K
00061   EXPECT_EQ(9, g_camera_info.K.size());
00062   EXPECT_NEAR(0.0, g_camera_info.K.at(0), 0.001);
00063   EXPECT_NEAR(0.0, g_camera_info.K.at(1), 0.001);
00064   EXPECT_NEAR(0.0, g_camera_info.K.at(2), 0.001);
00065   // D
00066   EXPECT_EQ(0, g_camera_info.D.size());
00067 
00068   EXPECT_EQ("", g_camera_info.distortion_model);
00069 
00070   // width
00071   EXPECT_EQ(640, g_camera_info.width);
00072   EXPECT_EQ(480, g_camera_info.height);
00073 }
00074 
00075 int main(int argc, char **argv)
00076 {
00077   ros::init(argc, argv, "test_cv_camera_no_yaml");
00078   testing::InitGoogleTest(&argc, argv);
00079   return RUN_ALL_TESTS();
00080 }


cv_camera
Author(s): Takashi Ogura
autogenerated on Thu May 9 2019 02:53:02