image_encodings.h
Go to the documentation of this file.
00001 
00002 /*********************************************************************
00003 * Software License Agreement (BSD License)
00004 * 
00005 *  Copyright (c) 2009, Willow Garage, Inc.
00006 *  All rights reserved.
00007 * 
00008 *  Redistribution and use in source and binary forms, with or without
00009 *  modification, are permitted provided that the following conditions
00010 *  are met:
00011 * 
00012 *   * Redistributions of source code must retain the above copyright
00013 *     notice, this list of conditions and the following disclaimer.
00014 *   * Redistributions in binary form must reproduce the above
00015 *     copyright notice, this list of conditions and the following
00016 *     disclaimer in the documentation and/or other materials provided
00017 *     with the distribution.
00018 *   * Neither the name of the Willow Garage nor the names of its
00019 *     contributors may be used to endorse or promote products derived
00020 *     from this software without specific prior written permission.
00021 * 
00022 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 *  POSSIBILITY OF SUCH DAMAGE.
00034 *********************************************************************/
00035 
00036 #ifndef SENSOR_MSGS_IMAGE_ENCODINGS_H
00037 #define SENSOR_MSGS_IMAGE_ENCODINGS_H
00038 
00039 #include <cstdlib>
00040 #include <stdexcept>
00041 #include <string>
00042 
00043 namespace sensor_msgs
00044 {
00045   namespace image_encodings
00046   {
00047     const std::string RGB8 = "rgb8";
00048     const std::string RGBA8 = "rgba8";
00049     const std::string RGB16 = "rgb16";
00050     const std::string RGBA16 = "rgba16";
00051     const std::string BGR8 = "bgr8";
00052     const std::string BGRA8 = "bgra8";
00053     const std::string BGR16 = "bgr16";
00054     const std::string BGRA16 = "bgra16";
00055     const std::string MONO8="mono8";
00056     const std::string MONO16="mono16";
00057 
00058     // OpenCV CvMat types
00059     const std::string TYPE_8UC1="8UC1";
00060     const std::string TYPE_8UC2="8UC2";
00061     const std::string TYPE_8UC3="8UC3";
00062     const std::string TYPE_8UC4="8UC4";
00063     const std::string TYPE_8SC1="8SC1";
00064     const std::string TYPE_8SC2="8SC2";
00065     const std::string TYPE_8SC3="8SC3";
00066     const std::string TYPE_8SC4="8SC4";
00067     const std::string TYPE_16UC1="16UC1";
00068     const std::string TYPE_16UC2="16UC2";
00069     const std::string TYPE_16UC3="16UC3";
00070     const std::string TYPE_16UC4="16UC4";
00071     const std::string TYPE_16SC1="16SC1";
00072     const std::string TYPE_16SC2="16SC2";
00073     const std::string TYPE_16SC3="16SC3";
00074     const std::string TYPE_16SC4="16SC4";
00075     const std::string TYPE_32SC1="32SC1";
00076     const std::string TYPE_32SC2="32SC2";
00077     const std::string TYPE_32SC3="32SC3";
00078     const std::string TYPE_32SC4="32SC4";
00079     const std::string TYPE_32FC1="32FC1";
00080     const std::string TYPE_32FC2="32FC2";
00081     const std::string TYPE_32FC3="32FC3";
00082     const std::string TYPE_32FC4="32FC4";
00083     const std::string TYPE_64FC1="64FC1";
00084     const std::string TYPE_64FC2="64FC2";
00085     const std::string TYPE_64FC3="64FC3";
00086     const std::string TYPE_64FC4="64FC4";
00087 
00088     // Bayer encodings
00089     const std::string BAYER_RGGB8="bayer_rggb8";
00090     const std::string BAYER_BGGR8="bayer_bggr8";
00091     const std::string BAYER_GBRG8="bayer_gbrg8";
00092     const std::string BAYER_GRBG8="bayer_grbg8";
00093     const std::string BAYER_RGGB16="bayer_rggb16";
00094     const std::string BAYER_BGGR16="bayer_bggr16";
00095     const std::string BAYER_GBRG16="bayer_gbrg16";
00096     const std::string BAYER_GRBG16="bayer_grbg16";
00097 
00098     // Miscellaneous
00099     // This is the UYVY version of YUV422 codec http://www.fourcc.org/yuv.php#UYVY
00100     // with an 8-bit depth
00101     const std::string YUV422="yuv422";
00102 
00103     // Prefixes for abstract image encodings
00104     const std::string ABSTRACT_ENCODING_PREFIXES[] = {
00105         "8UC", "8SC", "16UC", "16SC", "32SC", "32FC", "64FC"};
00106 
00107     // Utility functions for inspecting an encoding string
00108     static inline bool isColor(const std::string& encoding)
00109     {
00110       return encoding == RGB8  || encoding == BGR8 ||
00111              encoding == RGBA8 || encoding == BGRA8 ||
00112              encoding == RGB16 || encoding == BGR16 ||
00113              encoding == RGBA16 || encoding == BGRA16;
00114     }
00115 
00116     static inline bool isMono(const std::string& encoding)
00117     {
00118       return encoding == MONO8 || encoding == MONO16;
00119     }
00120 
00121     static inline bool isBayer(const std::string& encoding)
00122     {
00123       return encoding == BAYER_RGGB8 || encoding == BAYER_BGGR8 ||
00124              encoding == BAYER_GBRG8 || encoding == BAYER_GRBG8 ||
00125              encoding == BAYER_RGGB16 || encoding == BAYER_BGGR16 ||
00126              encoding == BAYER_GBRG16 || encoding == BAYER_GRBG16;
00127     }
00128 
00129     static inline bool hasAlpha(const std::string& encoding)
00130     {
00131       return encoding == RGBA8 || encoding == BGRA8 ||
00132              encoding == RGBA16 || encoding == BGRA16;
00133     }
00134 
00135     static inline int numChannels(const std::string& encoding)
00136     {
00137       // First do the common-case encodings
00138       if (encoding == MONO8 ||
00139           encoding == MONO16)
00140         return 1;
00141       if (encoding == BGR8 ||
00142           encoding == RGB8 ||
00143           encoding == BGR16 ||
00144           encoding == RGB16)
00145         return 3;
00146       if (encoding == BGRA8 ||
00147           encoding == RGBA8 ||
00148           encoding == BGRA16 ||
00149           encoding == RGBA16)
00150         return 4;
00151       if (encoding == BAYER_RGGB8 ||
00152           encoding == BAYER_BGGR8 ||
00153           encoding == BAYER_GBRG8 ||
00154           encoding == BAYER_GRBG8 ||
00155           encoding == BAYER_RGGB16 ||
00156           encoding == BAYER_BGGR16 ||
00157           encoding == BAYER_GBRG16 ||
00158           encoding == BAYER_GRBG16)
00159         return 1;
00160 
00161       // Now all the generic content encodings
00162       // TODO: Rewrite with regex when ROS supports C++11
00163       for (size_t i=0; i < sizeof(ABSTRACT_ENCODING_PREFIXES) / sizeof(*ABSTRACT_ENCODING_PREFIXES); i++)
00164       {
00165         std::string prefix = ABSTRACT_ENCODING_PREFIXES[i];
00166         if (encoding.substr(0, prefix.size()) != prefix)
00167           continue;
00168         if (encoding.size() == prefix.size())
00169           return 1;  // ex. 8UC -> 1
00170         int n_channel = atoi(encoding.substr(prefix.size(),
00171                                              encoding.size() - prefix.size()).c_str());  // ex. 8UC5 -> 5
00172         if (n_channel != 0)
00173           return n_channel;  // valid encoding string
00174       }
00175 
00176       if (encoding == YUV422)
00177         return 2;
00178 
00179       throw std::runtime_error("Unknown encoding " + encoding);
00180       return -1;
00181     }
00182 
00183     static inline int bitDepth(const std::string& encoding)
00184     {
00185       if (encoding == MONO16)
00186         return 16;
00187       if (encoding == MONO8       ||
00188           encoding == BGR8        ||
00189           encoding == RGB8        ||
00190           encoding == BGRA8       ||
00191           encoding == RGBA8       ||
00192           encoding == BAYER_RGGB8 ||
00193           encoding == BAYER_BGGR8 ||
00194           encoding == BAYER_GBRG8 ||
00195           encoding == BAYER_GRBG8)
00196         return 8;
00197 
00198       if (encoding == MONO16       ||
00199           encoding == BGR16        ||
00200           encoding == RGB16        ||
00201           encoding == BGRA16       ||
00202           encoding == RGBA16       ||
00203           encoding == BAYER_RGGB16 ||
00204           encoding == BAYER_BGGR16 ||
00205           encoding == BAYER_GBRG16 ||
00206           encoding == BAYER_GRBG16)
00207         return 16;
00208 
00209       // Now all the generic content encodings
00210       // TODO: Rewrite with regex when ROS supports C++11
00211       for (size_t i=0; i < sizeof(ABSTRACT_ENCODING_PREFIXES) / sizeof(*ABSTRACT_ENCODING_PREFIXES); i++)
00212       {
00213         std::string prefix = ABSTRACT_ENCODING_PREFIXES[i];
00214         if (encoding.substr(0, prefix.size()) != prefix)
00215           continue;
00216         if (encoding.size() == prefix.size())
00217           return atoi(prefix.c_str());  // ex. 8UC -> 8
00218         int n_channel = atoi(encoding.substr(prefix.size(),
00219                                              encoding.size() - prefix.size()).c_str());  // ex. 8UC10 -> 10
00220         if (n_channel != 0)
00221           return atoi(prefix.c_str());  // valid encoding string
00222       }
00223 
00224       if (encoding == YUV422)
00225         return 8;
00226 
00227       throw std::runtime_error("Unknown encoding " + encoding);
00228       return -1;
00229     }
00230   }
00231 }
00232 
00233 #endif


sensor_msgs
Author(s):
autogenerated on Thu Jun 6 2019 18:15:45