utest.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2009, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 #include <gtest/gtest.h>
00036 
00037 #include "opencv/cxcore.h"  
00038 #include "opencv/cvwimage.h"
00039 #include "opencv/cv.h"
00040 #include "opencv/highgui.h"
00041 
00042 #include "cv_bridge/CvBridge.h"
00043 #include "sensor_msgs/Image.h"
00044 
00045 TEST(OpencvTests, testCase_encode_decode)
00046 {
00047   int fmts[] = { IPL_DEPTH_8U, -1, IPL_DEPTH_8S, IPL_DEPTH_16U, IPL_DEPTH_16S, IPL_DEPTH_32S, IPL_DEPTH_32F, IPL_DEPTH_64F, -1 };
00048 
00049   for (int w = 100; w < 800; w += 100) {
00050     for (int h = 100; h < 800; h += 100) {
00051       for (int fi = 0; fmts[fi] != -1; fi++) {
00052         for (int channels = 1; channels <= 4; channels++) {
00053           IplImage *original = cvCreateImage(cvSize(w, h), fmts[fi], channels);
00054           CvRNG r = cvRNG(77);
00055           cvRandArr(&r, original, CV_RAND_UNI, cvScalar(0,0,0,0), cvScalar(255,255,255,255));
00056 
00057           sensor_msgs::Image image_message;
00058           sensor_msgs::CvBridge img_bridge_;
00059 
00060           int success;
00061           success = img_bridge_.fromIpltoRosImage(original, image_message);
00062           EXPECT_TRUE(success);
00063           success = img_bridge_.fromImage(image_message);
00064           EXPECT_TRUE(success);
00065           IplImage *final = img_bridge_.toIpl();
00066 
00067           // cvSaveImage("final.png", final);
00068           IplImage *diff = cvCloneImage(original);
00069           cvAbsDiff(original, final, diff);
00070           CvScalar sum = cvSum(diff);
00071           for (int c = 0; c < channels; c++) {
00072             EXPECT_TRUE(sum.val[c] == 0);
00073           }
00074         }
00075       }
00076     }
00077   }
00078 }
00079 
00080 
00081 TEST(OpencvTests, testCase_decode_8u)
00082 {
00083   IplImage *original = cvCreateImage(cvSize(640, 480), IPL_DEPTH_8U, 1);
00084   CvRNG r = cvRNG(77);
00085   cvRandArr(&r, original, CV_RAND_UNI, cvScalar(0,0,0,0), cvScalar(255,255,255,255));
00086 
00087   sensor_msgs::Image image_message;
00088   sensor_msgs::CvBridge img_bridge_;
00089 
00090   int success;
00091   success = img_bridge_.fromIpltoRosImage(original, image_message);
00092   EXPECT_TRUE(success);
00093 
00094   success = img_bridge_.fromImage(image_message, "passthrough");
00095   EXPECT_TRUE(success);
00096   EXPECT_TRUE(CV_MAT_CN(cvGetElemType(img_bridge_.toIpl())) == 1);
00097 
00098   success = img_bridge_.fromImage(image_message, "mono8");
00099   EXPECT_TRUE(success);
00100   EXPECT_TRUE(CV_MAT_CN(cvGetElemType(img_bridge_.toIpl())) == 1);
00101 
00102   success = img_bridge_.fromImage(image_message, "rgb8");
00103   EXPECT_TRUE(success);
00104   EXPECT_TRUE(CV_MAT_CN(cvGetElemType(img_bridge_.toIpl())) == 3);
00105 
00106   success = img_bridge_.fromImage(image_message, "bgr8");
00107   EXPECT_TRUE(success);
00108   EXPECT_TRUE(CV_MAT_CN(cvGetElemType(img_bridge_.toIpl())) == 3);
00109 }
00110 
00111 TEST(OpencvTests, testCase_decode_16u)
00112 {
00113   IplImage *original = cvCreateImage(cvSize(640, 480), IPL_DEPTH_16U, 1);
00114   CvRNG r = cvRNG(77);
00115   cvRandArr(&r, original, CV_RAND_UNI, cvScalar(0,0,0,0), cvScalar(255,255,255,255));
00116 
00117   sensor_msgs::Image image_message;
00118   sensor_msgs::CvBridge img_bridge_;
00119 
00120   int success;
00121   success = img_bridge_.fromIpltoRosImage(original, image_message);
00122   EXPECT_TRUE(success);
00123 
00124   success = img_bridge_.fromImage(image_message, "mono16");
00125   EXPECT_TRUE(success);
00126   printf("%d\n", cvGetElemType(img_bridge_.toIpl()));
00127   EXPECT_TRUE(cvGetElemType(img_bridge_.toIpl()) == CV_16UC1);
00128 }
00129 
00130 TEST(OpencvTests, testCase_decode_8uc3)
00131 {
00132   IplImage *original = cvCreateImage(cvSize(640, 480), IPL_DEPTH_8U, 3);
00133   CvRNG r = cvRNG(77);
00134   cvRandArr(&r, original, CV_RAND_UNI, cvScalar(0,0,0,0), cvScalar(255,255,255,255));
00135 
00136   sensor_msgs::Image image_message;
00137   sensor_msgs::CvBridge img_bridge_;
00138 
00139   int success;
00140   success = img_bridge_.fromIpltoRosImage(original, image_message);
00141   EXPECT_TRUE(success);
00142 
00143   success = img_bridge_.fromImage(image_message, "passthrough");
00144   EXPECT_TRUE(success);
00145   EXPECT_TRUE(CV_MAT_CN(cvGetElemType(img_bridge_.toIpl())) == 3);
00146 
00147   success = img_bridge_.fromImage(image_message, "mono8");
00148   EXPECT_TRUE(success);
00149   EXPECT_TRUE(CV_MAT_CN(cvGetElemType(img_bridge_.toIpl())) == 1);
00150 
00151   success = img_bridge_.fromImage(image_message, "rgb8");
00152   EXPECT_TRUE(success);
00153   EXPECT_TRUE(CV_MAT_CN(cvGetElemType(img_bridge_.toIpl())) == 3);
00154 
00155   success = img_bridge_.fromImage(image_message, "bgr8");
00156   EXPECT_TRUE(success);
00157   EXPECT_TRUE(CV_MAT_CN(cvGetElemType(img_bridge_.toIpl())) == 3);
00158 }
00159 
00160 TEST(OpencvTests, testCase_new_methods)
00161 {
00162   int channels = 3;
00163   IplImage *original = cvCreateImage(cvSize(640, 480), IPL_DEPTH_8U, channels);
00164   CvRNG r = cvRNG(77);
00165   cvRandArr(&r, original, CV_RAND_UNI, cvScalar(0,0,0,0), cvScalar(255,255,255,255));
00166 
00167   sensor_msgs::CvBridge img_bridge_;
00168   sensor_msgs::Image::Ptr rosimg = img_bridge_.cvToImgMsg(original);
00169 
00170   IplImage *final = img_bridge_.imgMsgToCv(rosimg);
00171 
00172   IplImage *diff = cvCloneImage(original);
00173   cvAbsDiff(original, final, diff);
00174   CvScalar sum = cvSum(diff);
00175   for (int c = 0; c < channels; c++) {
00176     EXPECT_TRUE(sum.val[c] == 0);
00177   }
00178 }
00179 
00180 TEST(OpencvTests, testCase_16u_bgr)
00181 {
00182   int channels = 1;
00183   IplImage *original = cvCreateImage(cvSize(640, 480), IPL_DEPTH_16U, channels);
00184   CvRNG r = cvRNG(77);
00185   cvRandArr(&r, original, CV_RAND_UNI, cvScalar(0,0,0,0), cvScalar(255,255,255,255));
00186 
00187   sensor_msgs::CvBridge img_bridge_;
00188   sensor_msgs::Image::Ptr image_message = img_bridge_.cvToImgMsg(original, "mono16");
00189 
00190   int success;
00191   success = img_bridge_.fromImage(*image_message, "mono16");
00192   EXPECT_TRUE(success);
00193   EXPECT_TRUE(cvGetElemType(img_bridge_.toIpl()) == CV_16UC1);
00194 
00195   //why would this work? its mono16 -> bgr8...
00196   success = img_bridge_.fromImage(*image_message, "bgr8");
00197   EXPECT_TRUE(success);
00198   EXPECT_TRUE(cvGetElemType(img_bridge_.toIpl()) == CV_8UC3);
00199 }
00200 
00201 int main(int argc, char **argv)
00202 {
00203   testing::InitGoogleTest(&argc, argv);
00204   return RUN_ALL_TESTS();
00205 }


opencv_tests
Author(s): James Bowman
autogenerated on Sat Dec 28 2013 17:53:20