3 #include <gtest/gtest.h> 7 TEST(CvBridgeTest, NonContinuous)
9 cv::Mat full = cv::Mat::eye(8, 8, CV_16U);
10 cv::Mat partial = full.colRange(2, 5);
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);
23 TEST(CvBridgeTest, ChannelOrder)
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());
37 EXPECT_EQ(res->image.depth(), CV_8U);
40 cv::Mat_<cv::Vec3b> gt(200, 200);
41 gt.setTo(cv::Scalar(1, 1, 1)*1000.*255./65535.);
43 ASSERT_EQ(res->image.type(), gt.type());
44 EXPECT_EQ(cv::norm(res->image, gt, cv::NORM_INF), 0);
47 TEST(CvBridgeTest, initialization)
49 sensor_msgs::Image image;
52 image.encoding =
"bgr8";
65 for(
int height = 100; height <= 300; ++height) {
67 image.step = image.width*3;
68 image.data.resize(image.height*image.step);
73 TEST(CvBridgeTest, imageMessageStep)
76 sensor_msgs::Image image;
79 image.encoding =
"mono8";
82 image.is_bigendian =
false;
85 image.data.resize(image.height*image.step);
88 ASSERT_EQ(220, cv_ptr->image.rows);
89 ASSERT_EQ(200, cv_ptr->image.cols);
91 ASSERT_EQ(200, cv_ptr->image.step[0]);
100 image.data.resize(image.height*image.step);
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]);
108 TEST(CvBridgeTest, imageMessageConversion)
110 sensor_msgs::Image imgmsg;
114 imgmsg.is_bigendian =
false;
117 imgmsg.encoding =
"32FC1";
118 imgmsg.step = imgmsg.width * 32 / 8 * 1;
119 imgmsg.data.resize(imgmsg.height * imgmsg.step);
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]);
127 imgmsg.encoding =
"32FC10";
128 imgmsg.step = imgmsg.width * 32 / 8 * 10;
129 imgmsg.data.resize(imgmsg.height * imgmsg.step);
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]);
137 int main(
int argc,
char** argv)
139 testing::InitGoogleTest(&argc, argv);
140 return RUN_ALL_TESTS();
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...
std::string encoding
Image encoding ("mono8", "bgr8", etc.)
CvImagePtr cvtColor(const CvImageConstPtr &source, const std::string &encoding)
Convert a CvImage to another encoding using the same rules as toCvCopy.
TEST(CvBridgeTest, NonContinuous)
int main(int argc, char **argv)
Image message class that is interoperable with sensor_msgs/Image but uses a more convenient cv::Mat r...
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...
cv::Mat image
Image data for use with OpenCV.
int getCvType(const std::string &encoding)
Get the OpenCV type enum corresponding to the encoding.
static int numChannels(const std::string &encoding)
sensor_msgs::ImagePtr toImageMsg() const
Convert this message to a ROS sensor_msgs::Image message.