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, initialization)
00024 {
00025   sensor_msgs::Image image;
00026   cv_bridge::CvImagePtr cv_ptr;
00027 
00028   image.encoding = "bgr8";
00029   image.height = 200;
00030   image.width = 200;
00031 
00032   try {
00033     cv_ptr = cv_bridge::toCvCopy(image, "mono8");
00034     // Before the fix, it would never get here, as it would segfault
00035     EXPECT_EQ(1, 0);
00036   } catch (cv_bridge::Exception& e) {
00037     EXPECT_EQ(1, 1);
00038   }
00039 
00040   // Check some normal images with different ratios
00041   for(int height = 100; height <= 300; ++height) {
00042     image.encoding = sensor_msgs::image_encodings::RGB8;
00043     image.step = image.width*3;
00044     image.data.resize(image.height*image.step);
00045     cv_ptr = cv_bridge::toCvCopy(image, "mono8");
00046   }
00047 }
00048 
00049 TEST(CvBridgeTest, imageMessageStep)
00050 {
00051   // Test 1: image step is padded
00052   sensor_msgs::Image image;
00053   cv_bridge::CvImagePtr cv_ptr;
00054 
00055   image.encoding = "mono8";
00056   image.height = 220;
00057   image.width = 200;
00058   image.is_bigendian = false;
00059   image.step = 208;
00060 
00061   image.data.resize(image.height*image.step);
00062 
00063   ASSERT_NO_THROW(cv_ptr = cv_bridge::toCvCopy(image, "mono8"));
00064   ASSERT_EQ(220, cv_ptr->image.rows);
00065   ASSERT_EQ(200, cv_ptr->image.cols);
00066   //OpenCV copyTo argument removes the stride
00067   ASSERT_EQ(200, cv_ptr->image.step[0]);
00068 
00069   //Test 2: image step is invalid
00070   image.step = 199;
00071 
00072   ASSERT_THROW(cv_ptr = cv_bridge::toCvCopy(image, "mono8"), cv_bridge::Exception);
00073 
00074   //Test 3: image step == image.width * element size * number of channels
00075   image.step = 200;
00076   image.data.resize(image.height*image.step);
00077 
00078   ASSERT_NO_THROW(cv_ptr = cv_bridge::toCvCopy(image, "mono8"));
00079   ASSERT_EQ(220, cv_ptr->image.rows);
00080   ASSERT_EQ(200, cv_ptr->image.cols);
00081   ASSERT_EQ(200, cv_ptr->image.step[0]);
00082 }
00083 
00084 int main(int argc, char** argv)
00085 {
00086   testing::InitGoogleTest(&argc, argv);
00087   return RUN_ALL_TESTS();
00088 }


cv_bridge
Author(s): Patrick Mihelich, James Bowman
autogenerated on Wed Sep 2 2015 12:05:06