utest.cpp
Go to the documentation of this file.
00001 #include "cv_bridge/cv_bridge.h"
00002 #include <sensor_msgs/image_encodings.h>
00003 #include <gtest/gtest.h>
00004 
00005 
00006 // Tests conversion of non-continuous cv::Mat. #5206
00007 TEST(CvBridgeTest, NonContinuous)
00008 {
00009   cv::Mat full = cv::Mat::eye(8, 8, CV_16U);
00010   cv::Mat partial = full.colRange(2, 5);
00011   
00012   cv_bridge::CvImage cvi;
00013   cvi.encoding = sensor_msgs::image_encodings::MONO16;
00014   cvi.image = partial;
00015 
00016   sensor_msgs::ImagePtr msg = cvi.toImageMsg();
00017   EXPECT_EQ(msg->height, 8);
00018   EXPECT_EQ(msg->width, 3);
00019   EXPECT_EQ(msg->encoding, cvi.encoding);
00020   EXPECT_EQ(msg->step, 6);
00021 }
00022 
00023 TEST(CvBridgeTest, ChannelOrder)
00024 {
00025   cv::Mat_<uint16_t> mat(200, 200);
00026   mat.setTo(cv::Scalar(1000,0,0,0));
00027   sensor_msgs::ImagePtr image(new sensor_msgs::Image());
00028 
00029   image = cv_bridge::CvImage(image->header, sensor_msgs::image_encodings::MONO16, mat).toImageMsg();
00030 
00031   cv_bridge::CvImageConstPtr cv_ptr = cv_bridge::toCvShare(image);
00032 
00033   cv_bridge::CvImagePtr res = cv_bridge::cvtColor(cv_ptr, sensor_msgs::image_encodings::BGR8);
00034   EXPECT_EQ(res->encoding, sensor_msgs::image_encodings::BGR8);
00035   EXPECT_EQ(res->image.type(), cv_bridge::getCvType(res->encoding));
00036   EXPECT_EQ(res->image.channels(), sensor_msgs::image_encodings::numChannels(res->encoding));
00037   EXPECT_EQ(res->image.depth(), CV_8U);
00038 
00039   // The matrix should be the following
00040   cv::Mat_<cv::Vec3b> gt(200, 200);
00041   gt.setTo(cv::Scalar(1, 1, 1)*1000.*255./65535.);
00042 
00043   ASSERT_EQ(res->image.type(), gt.type());
00044   EXPECT_EQ(cv::norm(res->image, gt, cv::NORM_INF), 0);
00045 }
00046 
00047 TEST(CvBridgeTest, initialization)
00048 {
00049   sensor_msgs::Image image;
00050   cv_bridge::CvImagePtr cv_ptr;
00051 
00052   image.encoding = "bgr8";
00053   image.height = 200;
00054   image.width = 200;
00055 
00056   try {
00057     cv_ptr = cv_bridge::toCvCopy(image, "mono8");
00058     // Before the fix, it would never get here, as it would segfault
00059     EXPECT_EQ(1, 0);
00060   } catch (cv_bridge::Exception& e) {
00061     EXPECT_EQ(1, 1);
00062   }
00063 
00064   // Check some normal images with different ratios
00065   for(int height = 100; height <= 300; ++height) {
00066     image.encoding = sensor_msgs::image_encodings::RGB8;
00067     image.step = image.width*3;
00068     image.data.resize(image.height*image.step);
00069     cv_ptr = cv_bridge::toCvCopy(image, "mono8");
00070   }
00071 }
00072 
00073 TEST(CvBridgeTest, imageMessageStep)
00074 {
00075   // Test 1: image step is padded
00076   sensor_msgs::Image image;
00077   cv_bridge::CvImagePtr cv_ptr;
00078 
00079   image.encoding = "mono8";
00080   image.height = 220;
00081   image.width = 200;
00082   image.is_bigendian = false;
00083   image.step = 208;
00084 
00085   image.data.resize(image.height*image.step);
00086 
00087   ASSERT_NO_THROW(cv_ptr = cv_bridge::toCvCopy(image, "mono8"));
00088   ASSERT_EQ(220, cv_ptr->image.rows);
00089   ASSERT_EQ(200, cv_ptr->image.cols);
00090   //OpenCV copyTo argument removes the stride
00091   ASSERT_EQ(200, cv_ptr->image.step[0]);
00092 
00093   //Test 2: image step is invalid
00094   image.step = 199;
00095 
00096   ASSERT_THROW(cv_ptr = cv_bridge::toCvCopy(image, "mono8"), cv_bridge::Exception);
00097 
00098   //Test 3: image step == image.width * element size * number of channels
00099   image.step = 200;
00100   image.data.resize(image.height*image.step);
00101 
00102   ASSERT_NO_THROW(cv_ptr = cv_bridge::toCvCopy(image, "mono8"));
00103   ASSERT_EQ(220, cv_ptr->image.rows);
00104   ASSERT_EQ(200, cv_ptr->image.cols);
00105   ASSERT_EQ(200, cv_ptr->image.step[0]);
00106 }
00107 
00108 int main(int argc, char** argv)
00109 {
00110   testing::InitGoogleTest(&argc, argv);
00111   return RUN_ALL_TESTS();
00112 }


cv_bridge
Author(s): Patrick Mihelich, James Bowman
autogenerated on Wed Aug 9 2017 02:51:41