utest2.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 <string>
00036 #include <vector>
00037 #include <gtest/gtest.h>
00038 
00039 #include "opencv2/core/core.hpp"  
00040 
00041 #include "cv_bridge/cv_bridge.h"
00042 #include <sensor_msgs/Image.h>
00043 #include <sensor_msgs/image_encodings.h>
00044 
00045 using namespace sensor_msgs::image_encodings;
00046 
00047 bool isUnsigned(const std::string & encoding) {
00048   return encoding == RGB8 || encoding == RGBA8 || encoding == RGB16 || encoding == RGBA16 || encoding == BGR8 || encoding == BGRA8 || encoding == BGR16 || encoding == BGRA16 || encoding == MONO8 || encoding == MONO16 ||
00049                            encoding == MONO8 || encoding == MONO16 || encoding == TYPE_8UC1 || encoding == TYPE_8UC2 || encoding == TYPE_8UC3 || encoding == TYPE_8UC4 ||
00050                            encoding == TYPE_16UC1 || encoding == TYPE_16UC2 || encoding == TYPE_16UC3 || encoding == TYPE_16UC4;
00051                            //BAYER_RGGB8, BAYER_BGGR8, BAYER_GBRG8, BAYER_GRBG8, BAYER_RGGB16, BAYER_BGGR16, BAYER_GBRG16, BAYER_GRBG16,
00052                            //YUV422
00053 }
00054 std::vector<std::string>
00055 getEncodings() {
00056 // TODO for Groovy, the following types should be uncommented
00057 std::string encodings[] = { RGB8, RGBA8, RGB16, RGBA16, BGR8, BGRA8, BGR16, BGRA16, MONO8, MONO16,
00058                            TYPE_8UC1, /*TYPE_8UC2,*/ TYPE_8UC3, TYPE_8UC4,
00059                            TYPE_8SC1, /*TYPE_8SC2,*/ TYPE_8SC3, TYPE_8SC4,
00060                            TYPE_16UC1, /*TYPE_16UC2,*/ TYPE_16UC3, TYPE_16UC4,
00061                            TYPE_16SC1, /*TYPE_16SC2,*/ TYPE_16SC3, TYPE_16SC4,
00062                            TYPE_32SC1, /*TYPE_32SC2,*/ TYPE_32SC3, TYPE_32SC4,
00063                            TYPE_32FC1, /*TYPE_32FC2,*/ TYPE_32FC3, TYPE_32FC4,
00064                            TYPE_64FC1, /*TYPE_64FC2,*/ TYPE_64FC3, TYPE_64FC4,
00065                            //BAYER_RGGB8, BAYER_BGGR8, BAYER_GBRG8, BAYER_GRBG8, BAYER_RGGB16, BAYER_BGGR16, BAYER_GBRG16, BAYER_GRBG16,
00066                            YUV422
00067                          };
00068 return std::vector<std::string>(encodings, encodings+47-8-7);
00069 }
00070 
00071 TEST(OpencvTests, testCase_encode_decode)
00072 {
00073   std::vector<std::string> encodings = getEncodings();
00074   for(size_t i=0; i<encodings.size(); ++i) {
00075     std::string src_encoding = encodings[i];
00076     bool is_src_color_format = isColor(src_encoding) || isMono(src_encoding) || (src_encoding == sensor_msgs::image_encodings::YUV422);
00077     cv::Mat image_original(cv::Size(400, 400), cv_bridge::getCvType(src_encoding));
00078     cv::RNG r(77);
00079     r.fill(image_original, cv::RNG::UNIFORM, 0, 127);
00080 
00081     sensor_msgs::Image image_message;
00082     cv_bridge::CvImage image_bridge(std_msgs::Header(), src_encoding, image_original);
00083 
00084     // Convert to a sensor_msgs::Image
00085     sensor_msgs::ImagePtr image_msg = image_bridge.toImageMsg();
00086 
00087     for(size_t j=0; j<encodings.size(); ++j) {
00088       std::string dst_encoding = encodings[j];
00089       bool is_dst_color_format = isColor(dst_encoding) || isMono(dst_encoding) || (dst_encoding == sensor_msgs::image_encodings::YUV422);
00090       bool is_num_channels_the_same = (numChannels(src_encoding) == numChannels(dst_encoding));
00091 
00092       cv_bridge::CvImageConstPtr cv_image;
00093       cv::Mat image_back;
00094       // If the first type does not contain any color information
00095       if (!is_src_color_format) {
00096         // Converting from a non color type to a color type does no make sense
00097         if (is_dst_color_format) {
00098           EXPECT_THROW(cv_bridge::toCvShare(image_msg, dst_encoding), cv_bridge::Exception);
00099           continue;
00100         }
00101         // We can only convert non-color types with the same number of channels
00102         if (!is_num_channels_the_same) {
00103           EXPECT_THROW(cv_bridge::toCvShare(image_msg, dst_encoding), cv_bridge::Exception);
00104           continue;
00105         }
00106         cv_image = cv_bridge::toCvShare(image_msg, dst_encoding);
00107       } else {
00108         // If we are converting to a non-color, you cannot convert to a different number of channels
00109         if (!is_dst_color_format) {
00110           if (!is_num_channels_the_same) {
00111             EXPECT_THROW(cv_bridge::toCvShare(image_msg, dst_encoding), cv_bridge::Exception);
00112             continue;
00113           }
00114           cv_image = cv_bridge::toCvShare(image_msg, dst_encoding);
00115           // We cannot convert from non-color to color
00116           EXPECT_THROW(cvtColor(cv_image, src_encoding)->image, cv_bridge::Exception);
00117           continue;
00118         }
00119         // We do not support conversion to YUV422 for now, except from YUV422
00120         if ((dst_encoding == YUV422) && (src_encoding != YUV422)) {
00121           EXPECT_THROW(cv_bridge::toCvShare(image_msg, dst_encoding), cv_bridge::Exception);
00122           continue;
00123         }
00124 
00125         cv_image = cv_bridge::toCvShare(image_msg, dst_encoding);
00126 
00127         // We do not support conversion to YUV422 for now, except from YUV422
00128         if ((src_encoding == YUV422) && (dst_encoding != YUV422)) {
00129           EXPECT_THROW(cvtColor(cv_image, src_encoding)->image, cv_bridge::Exception);
00130           continue;
00131         }
00132       }
00133       // And convert back to a cv::Mat
00134       image_back = cvtColor(cv_image, src_encoding)->image;
00135 
00136       // If the number of channels,s different some information got lost at some point, so no possible test
00137       if (!is_num_channels_the_same)
00138         continue;
00139       if (bitDepth(src_encoding) >= 32) {
00140         // In the case where the input has floats, we will lose precision but no more than 1
00141         EXPECT_LT(cv::norm(image_original, image_back, cv::NORM_INF), 1) << "problem converting from " << src_encoding << " to " << dst_encoding << " and back.";
00142       } else if ((bitDepth(src_encoding) == 16) && (bitDepth(dst_encoding) == 8)) {
00143         // In the case where the input has floats, we will lose precision but no more than 1 * max(127)
00144         EXPECT_LT(cv::norm(image_original, image_back, cv::NORM_INF), 128) << "problem converting from " << src_encoding << " to " << dst_encoding << " and back.";
00145       } else {
00146         EXPECT_EQ(cv::norm(image_original, image_back, cv::NORM_INF), 0) << "problem converting from " << src_encoding << " to " << dst_encoding << " and back.";
00147       }
00148     }
00149   }
00150 }


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