test_cv_camera.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_node/image_raw",
00025                                        1,
00026                                        &ImageCallback);
00027   ros::Rate r(10.0);
00028   while (sub.getNumPublishers() == 0) {
00029     r.sleep();
00030   }
00031   while (g_image.header.frame_id == "") {
00032     ros::spinOnce();
00033     r.sleep();
00034   }
00035   EXPECT_EQ("camera1", g_image.header.frame_id);
00036   EXPECT_EQ(480, g_image.height);
00037   EXPECT_EQ(640, g_image.width);
00038   EXPECT_EQ("bgr8", g_image.encoding);
00039 }
00040 
00041 TEST(CvCameraNode, getCameraInfo)
00042 {
00043   ros::NodeHandle node;
00044   ros::Subscriber sub = node.subscribe("/cv_camera_node/camera_info",
00045                                        1,
00046                                        &InfoCallback);
00047   ros::Rate r(10.0);
00048   while (sub.getNumPublishers() == 0) {
00049     r.sleep();
00050   }
00051   while (g_camera_info.header.frame_id == "") {
00052     ros::spinOnce();
00053     r.sleep();
00054   }
00055   EXPECT_EQ("camera1", g_camera_info.header.frame_id);
00056   // K
00057   EXPECT_EQ(9, g_camera_info.K.size());
00058   EXPECT_NEAR(4827.94, g_camera_info.K.at(0), 0.001);
00059   EXPECT_NEAR(0.0, g_camera_info.K.at(1), 0.001);
00060   EXPECT_NEAR(1223.5, g_camera_info.K.at(2), 0.001);
00061   // D
00062   EXPECT_EQ(5, g_camera_info.D.size());
00063   EXPECT_NEAR(-0.41527, g_camera_info.D.at(0), 0.001);
00064   EXPECT_NEAR(0.31874, g_camera_info.D.at(1), 0.001);
00065   EXPECT_NEAR(-0.00197, g_camera_info.D.at(2), 0.001);
00066   EXPECT_NEAR(0.00071, g_camera_info.D.at(3), 0.001);
00067   EXPECT_NEAR(0.0, g_camera_info.D.at(4), 0.001);
00068 
00069   EXPECT_EQ("plumb_bob", g_camera_info.distortion_model);
00070 
00071   // width
00072   EXPECT_EQ(2448, g_camera_info.width);
00073   EXPECT_EQ(2050, g_camera_info.height);
00074 }
00075 
00076 int main(int argc, char **argv)
00077 {
00078   ros::init(argc, argv, "test_cv_camera");
00079   testing::InitGoogleTest(&argc, argv);
00080   return RUN_ALL_TESTS();
00081 }


cv_camera
Author(s): Takashi Ogura
autogenerated on Thu Oct 5 2017 02:35:21