test_cv_camera.cpp
Go to the documentation of this file.
1 // Copyright [2015] Takashi Ogura<t.ogura@gmail.com>
2 
3 #include <ros/ros.h>
4 #include <sensor_msgs/CameraInfo.h>
5 #include <sensor_msgs/Image.h>
6 #include <gtest/gtest.h>
7 
8 sensor_msgs::Image g_image;
9 sensor_msgs::CameraInfo g_camera_info;
10 
11 void ImageCallback(const sensor_msgs::Image::ConstPtr &image)
12 {
13  g_image = *image;
14 }
15 
16 void InfoCallback(const sensor_msgs::CameraInfo::ConstPtr &info)
17 {
18  g_camera_info = *info;
19 }
20 
21 TEST(CvCameraNode, getImage)
22 {
23  ros::NodeHandle node;
24  ros::Subscriber sub = node.subscribe("/cv_camera_node/image_raw",
25  1,
26  &ImageCallback);
27  ros::Rate r(10.0);
28  while (sub.getNumPublishers() == 0)
29  {
30  r.sleep();
31  }
32  while (g_image.header.frame_id == "")
33  {
34  ros::spinOnce();
35  r.sleep();
36  }
37  EXPECT_EQ("camera1", g_image.header.frame_id);
38  EXPECT_EQ(480, g_image.height);
39  EXPECT_EQ(640, g_image.width);
40  EXPECT_EQ("bgr8", g_image.encoding);
41 }
42 
43 TEST(CvCameraNode, getCameraInfo)
44 {
45  ros::NodeHandle node;
46  ros::Subscriber sub = node.subscribe("/cv_camera_node/camera_info",
47  1,
48  &InfoCallback);
49  ros::Rate r(10.0);
50  while (sub.getNumPublishers() == 0)
51  {
52  r.sleep();
53  }
54  while (g_camera_info.header.frame_id == "")
55  {
56  ros::spinOnce();
57  r.sleep();
58  }
59  EXPECT_EQ("camera1", g_camera_info.header.frame_id);
60  // K
61  EXPECT_EQ(9, g_camera_info.K.size());
62  EXPECT_NEAR(4827.94, g_camera_info.K.at(0), 0.001);
63  EXPECT_NEAR(0.0, g_camera_info.K.at(1), 0.001);
64  EXPECT_NEAR(1223.5, g_camera_info.K.at(2), 0.001);
65  // D
66  EXPECT_EQ(5, g_camera_info.D.size());
67  EXPECT_NEAR(-0.41527, g_camera_info.D.at(0), 0.001);
68  EXPECT_NEAR(0.31874, g_camera_info.D.at(1), 0.001);
69  EXPECT_NEAR(-0.00197, g_camera_info.D.at(2), 0.001);
70  EXPECT_NEAR(0.00071, g_camera_info.D.at(3), 0.001);
71  EXPECT_NEAR(0.0, g_camera_info.D.at(4), 0.001);
72 
73  EXPECT_EQ("plumb_bob", g_camera_info.distortion_model);
74 
75  // width
76  EXPECT_EQ(2448, g_camera_info.width);
77  EXPECT_EQ(2050, g_camera_info.height);
78 }
79 
80 int main(int argc, char **argv)
81 {
82  ros::init(argc, argv, "test_cv_camera");
83  testing::InitGoogleTest(&argc, argv);
84  return RUN_ALL_TESTS();
85 }
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
sensor_msgs::Image g_image
void InfoCallback(const sensor_msgs::CameraInfo::ConstPtr &info)
uint32_t getNumPublishers() const
bool sleep()
TEST(CvCameraNode, getImage)
sensor_msgs::CameraInfo g_camera_info
void ImageCallback(const sensor_msgs::Image::ConstPtr &image)
ROSCPP_DECL void spinOnce()


cv_camera
Author(s): Takashi Ogura
autogenerated on Fri May 10 2019 02:14:17