utest.cpp
Go to the documentation of this file.
1 #include "cv_bridge/cv_bridge.h"
3 #include <gtest/gtest.h>
4 
5 
6 // Tests conversion of non-continuous cv::Mat. #5206
7 TEST(CvBridgeTest, NonContinuous)
8 {
9  cv::Mat full = cv::Mat::eye(8, 8, CV_16U);
10  cv::Mat partial = full.colRange(2, 5);
11 
14  cvi.image = partial;
15 
16  sensor_msgs::ImagePtr msg = cvi.toImageMsg();
17  EXPECT_EQ(msg->height, 8);
18  EXPECT_EQ(msg->width, 3);
19  EXPECT_EQ(msg->encoding, cvi.encoding);
20  EXPECT_EQ(msg->step, 6);
21 }
22 
23 TEST(CvBridgeTest, ChannelOrder)
24 {
25  cv::Mat_<uint16_t> mat(200, 200);
26  mat.setTo(cv::Scalar(1000,0,0,0));
27  sensor_msgs::ImagePtr image(new sensor_msgs::Image());
28 
30 
32 
34  EXPECT_EQ(res->encoding, sensor_msgs::image_encodings::BGR8);
35  EXPECT_EQ(res->image.type(), cv_bridge::getCvType(res->encoding));
36  EXPECT_EQ(res->image.channels(), sensor_msgs::image_encodings::numChannels(res->encoding));
37  EXPECT_EQ(res->image.depth(), CV_8U);
38 
39  // The matrix should be the following
40  cv::Mat_<cv::Vec3b> gt(200, 200);
41  gt.setTo(cv::Scalar(1, 1, 1)*1000.*255./65535.);
42 
43  ASSERT_EQ(res->image.type(), gt.type());
44  EXPECT_EQ(cv::norm(res->image, gt, cv::NORM_INF), 0);
45 }
46 
47 TEST(CvBridgeTest, initialization)
48 {
49  sensor_msgs::Image image;
50  cv_bridge::CvImagePtr cv_ptr;
51 
52  image.encoding = "bgr8";
53  image.height = 200;
54  image.width = 200;
55 
56  try {
57  cv_ptr = cv_bridge::toCvCopy(image, "mono8");
58  // Before the fix, it would never get here, as it would segfault
59  EXPECT_EQ(1, 0);
60  } catch (cv_bridge::Exception& e) {
61  EXPECT_EQ(1, 1);
62  }
63 
64  // Check some normal images with different ratios
65  for(int height = 100; height <= 300; ++height) {
66  image.encoding = sensor_msgs::image_encodings::RGB8;
67  image.step = image.width*3;
68  image.data.resize(image.height*image.step);
69  cv_ptr = cv_bridge::toCvCopy(image, "mono8");
70  }
71 }
72 
73 TEST(CvBridgeTest, imageMessageStep)
74 {
75  // Test 1: image step is padded
76  sensor_msgs::Image image;
77  cv_bridge::CvImagePtr cv_ptr;
78 
79  image.encoding = "mono8";
80  image.height = 220;
81  image.width = 200;
82  image.is_bigendian = false;
83  image.step = 208;
84 
85  image.data.resize(image.height*image.step);
86 
87  ASSERT_NO_THROW(cv_ptr = cv_bridge::toCvCopy(image, "mono8"));
88  ASSERT_EQ(220, cv_ptr->image.rows);
89  ASSERT_EQ(200, cv_ptr->image.cols);
90  //OpenCV copyTo argument removes the stride
91  ASSERT_EQ(200, cv_ptr->image.step[0]);
92 
93  //Test 2: image step is invalid
94  image.step = 199;
95 
96  ASSERT_THROW(cv_ptr = cv_bridge::toCvCopy(image, "mono8"), cv_bridge::Exception);
97 
98  //Test 3: image step == image.width * element size * number of channels
99  image.step = 200;
100  image.data.resize(image.height*image.step);
101 
102  ASSERT_NO_THROW(cv_ptr = cv_bridge::toCvCopy(image, "mono8"));
103  ASSERT_EQ(220, cv_ptr->image.rows);
104  ASSERT_EQ(200, cv_ptr->image.cols);
105  ASSERT_EQ(200, cv_ptr->image.step[0]);
106 }
107 
108 TEST(CvBridgeTest, imageMessageConversion)
109 {
110  sensor_msgs::Image imgmsg;
111  cv_bridge::CvImagePtr cv_ptr;
112  imgmsg.height = 220;
113  imgmsg.width = 200;
114  imgmsg.is_bigendian = false;
115 
116  // image with data type float32 and 1 channels
117  imgmsg.encoding = "32FC1";
118  imgmsg.step = imgmsg.width * 32 / 8 * 1;
119  imgmsg.data.resize(imgmsg.height * imgmsg.step);
120  ASSERT_NO_THROW(cv_ptr = cv_bridge::toCvCopy(imgmsg, imgmsg.encoding));
121  ASSERT_EQ(imgmsg.height, cv_ptr->image.rows);
122  ASSERT_EQ(imgmsg.width, cv_ptr->image.cols);
123  ASSERT_EQ(1, cv_ptr->image.channels());
124  ASSERT_EQ(imgmsg.step, cv_ptr->image.step[0]);
125 
126  // image with data type float32 and 10 channels
127  imgmsg.encoding = "32FC10";
128  imgmsg.step = imgmsg.width * 32 / 8 * 10;
129  imgmsg.data.resize(imgmsg.height * imgmsg.step);
130  ASSERT_NO_THROW(cv_ptr = cv_bridge::toCvCopy(imgmsg, imgmsg.encoding));
131  ASSERT_EQ(imgmsg.height, cv_ptr->image.rows);
132  ASSERT_EQ(imgmsg.width, cv_ptr->image.cols);
133  ASSERT_EQ(10, cv_ptr->image.channels());
134  ASSERT_EQ(imgmsg.step, cv_ptr->image.step[0]);
135 }
136 
137 int main(int argc, char** argv)
138 {
139  testing::InitGoogleTest(&argc, argv);
140  return RUN_ALL_TESTS();
141 }
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
Convert an immutable sensor_msgs::Image message to an OpenCV-compatible CvImage, sharing the image da...
Definition: cv_bridge.cpp:406
std::string encoding
Image encoding ("mono8", "bgr8", etc.)
Definition: cv_bridge.h:80
CvImagePtr cvtColor(const CvImageConstPtr &source, const std::string &encoding)
Convert a CvImage to another encoding using the same rules as toCvCopy.
Definition: cv_bridge.cpp:429
TEST(CvBridgeTest, NonContinuous)
Definition: utest.cpp:7
int main(int argc, char **argv)
Definition: utest.cpp:137
Image message class that is interoperable with sensor_msgs/Image but uses a more convenient cv::Mat r...
Definition: cv_bridge.h:76
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
Convert a sensor_msgs::Image message to an OpenCV-compatible CvImage, copying the image data...
Definition: cv_bridge.cpp:392
const std::string MONO16
cv::Mat image
Image data for use with OpenCV.
Definition: cv_bridge.h:81
int getCvType(const std::string &encoding)
Get the OpenCV type enum corresponding to the encoding.
Definition: cv_bridge.cpp:72
static int numChannels(const std::string &encoding)
sensor_msgs::ImagePtr toImageMsg() const
Convert this message to a ROS sensor_msgs::Image message.
Definition: cv_bridge.cpp:355


cv_bridge
Author(s): Patrick Mihelich, James Bowman
autogenerated on Thu Jun 6 2019 19:57:55