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 <stdexcept>
00040 #include <string>
00041 
00042 namespace sensor_msgs
00043 {
00044   namespace image_encodings
00045   {
00046     const std::string RGB8 = "rgb8";
00047     const std::string RGBA8 = "rgba8";
00048     const std::string RGB16 = "rgb16";
00049     const std::string RGBA16 = "rgba16";
00050     const std::string BGR8 = "bgr8";
00051     const std::string BGRA8 = "bgra8";
00052     const std::string BGR16 = "bgr16";
00053     const std::string BGRA16 = "bgra16";
00054     const std::string MONO8="mono8";
00055     const std::string MONO16="mono16";
00056 
00057     // OpenCV CvMat types
00058     const std::string TYPE_8UC1="8UC1";
00059     const std::string TYPE_8UC2="8UC2";
00060     const std::string TYPE_8UC3="8UC3";
00061     const std::string TYPE_8UC4="8UC4";
00062     const std::string TYPE_8SC1="8SC1";
00063     const std::string TYPE_8SC2="8SC2";
00064     const std::string TYPE_8SC3="8SC3";
00065     const std::string TYPE_8SC4="8SC4";
00066     const std::string TYPE_16UC1="16UC1";
00067     const std::string TYPE_16UC2="16UC2";
00068     const std::string TYPE_16UC3="16UC3";
00069     const std::string TYPE_16UC4="16UC4";
00070     const std::string TYPE_16SC1="16SC1";
00071     const std::string TYPE_16SC2="16SC2";
00072     const std::string TYPE_16SC3="16SC3";
00073     const std::string TYPE_16SC4="16SC4";
00074     const std::string TYPE_32SC1="32SC1";
00075     const std::string TYPE_32SC2="32SC2";
00076     const std::string TYPE_32SC3="32SC3";
00077     const std::string TYPE_32SC4="32SC4";
00078     const std::string TYPE_32FC1="32FC1";
00079     const std::string TYPE_32FC2="32FC2";
00080     const std::string TYPE_32FC3="32FC3";
00081     const std::string TYPE_32FC4="32FC4";
00082     const std::string TYPE_64FC1="64FC1";
00083     const std::string TYPE_64FC2="64FC2";
00084     const std::string TYPE_64FC3="64FC3";
00085     const std::string TYPE_64FC4="64FC4";
00086 
00087     // Bayer encodings
00088     const std::string BAYER_RGGB8="bayer_rggb8";
00089     const std::string BAYER_BGGR8="bayer_bggr8";
00090     const std::string BAYER_GBRG8="bayer_gbrg8";
00091     const std::string BAYER_GRBG8="bayer_grbg8";
00092     const std::string BAYER_RGGB16="bayer_rggb16";
00093     const std::string BAYER_BGGR16="bayer_bggr16";
00094     const std::string BAYER_GBRG16="bayer_gbrg16";
00095     const std::string BAYER_GRBG16="bayer_grbg16";
00096 
00097     // Miscellaneous
00098     // This is the UYVY version of YUV422 codec http://www.fourcc.org/yuv.php#UYVY
00099     // with an 8-bit depth
00100     const std::string YUV422="yuv422";
00101 
00102     // Utility functions for inspecting an encoding string
00103     static inline bool isColor(const std::string& encoding)
00104     {
00105       return encoding == RGB8  || encoding == BGR8 ||
00106              encoding == RGBA8 || encoding == BGRA8 ||
00107              encoding == RGB16 || encoding == BGR16 ||
00108              encoding == RGBA16 || encoding == BGRA16;
00109     }
00110 
00111     static inline bool isMono(const std::string& encoding)
00112     {
00113       return encoding == MONO8 || encoding == MONO16;
00114     }
00115 
00116     static inline bool isBayer(const std::string& encoding)
00117     {
00118       return encoding == BAYER_RGGB8 || encoding == BAYER_BGGR8 ||
00119              encoding == BAYER_GBRG8 || encoding == BAYER_GRBG8 ||
00120              encoding == BAYER_RGGB16 || encoding == BAYER_BGGR16 ||
00121              encoding == BAYER_GBRG16 || encoding == BAYER_GRBG16;
00122     }
00123 
00124     static inline bool hasAlpha(const std::string& encoding)
00125     {
00126       return encoding == RGBA8 || encoding == BGRA8 ||
00127              encoding == RGBA16 || encoding == BGRA16;
00128     }
00129 
00130     static inline int numChannels(const std::string& encoding)
00131     {
00132       // First do the common-case encodings
00133       if (encoding == MONO8 ||
00134           encoding == MONO16)
00135         return 1;
00136       if (encoding == BGR8 ||
00137           encoding == RGB8 ||
00138           encoding == BGR16 ||
00139           encoding == RGB16)
00140         return 3;
00141       if (encoding == BGRA8 ||
00142           encoding == RGBA8 ||
00143           encoding == BGRA16 ||
00144           encoding == RGBA16)
00145         return 4;
00146       if (encoding == BAYER_RGGB8 ||
00147           encoding == BAYER_BGGR8 ||
00148           encoding == BAYER_GBRG8 ||
00149           encoding == BAYER_GRBG8 ||
00150           encoding == BAYER_RGGB16 ||
00151           encoding == BAYER_BGGR16 ||
00152           encoding == BAYER_GBRG16 ||
00153           encoding == BAYER_GRBG16)
00154         return 1;
00155 
00156       // Now all the generic content encodings
00157 #define CHECK_CHANNELS(N)                       \
00158       if (encoding == TYPE_8UC##N  ||           \
00159           encoding == TYPE_8SC##N  ||           \
00160           encoding == TYPE_16UC##N ||           \
00161           encoding == TYPE_16SC##N ||           \
00162           encoding == TYPE_32SC##N ||           \
00163           encoding == TYPE_32FC##N ||           \
00164           encoding == TYPE_64FC##N)             \
00165         return N;                               \
00166       /***/
00167       
00168       CHECK_CHANNELS(1);
00169       CHECK_CHANNELS(2);
00170       CHECK_CHANNELS(3);
00171       CHECK_CHANNELS(4);
00172 
00173 #undef CHECK_CHANNELS
00174 
00175       if (encoding == YUV422)
00176         return 2;
00177 
00178       throw std::runtime_error("Unknown encoding " + encoding);
00179       return -1;
00180     }
00181 
00182     static inline int bitDepth(const std::string& encoding)
00183     {
00184       if (encoding == MONO16)
00185         return 16;
00186       if (encoding == MONO8       ||
00187           encoding == BGR8        ||
00188           encoding == RGB8        ||
00189           encoding == BGRA8       ||
00190           encoding == RGBA8       ||
00191           encoding == BAYER_RGGB8 ||
00192           encoding == BAYER_BGGR8 ||
00193           encoding == BAYER_GBRG8 ||
00194           encoding == BAYER_GRBG8)
00195         return 8;
00196 
00197       if (encoding == MONO16       ||
00198           encoding == BGR16        ||
00199           encoding == RGB16        ||
00200           encoding == BGRA16       ||
00201           encoding == RGBA16       ||
00202           encoding == BAYER_RGGB16 ||
00203           encoding == BAYER_BGGR16 ||
00204           encoding == BAYER_GBRG16 ||
00205           encoding == BAYER_GRBG16)
00206         return 16;
00207 
00208       // B = bits (8, 16, ...), T = type (U, S, F)
00209 #define CHECK_BIT_DEPTH(B, T)                   \
00210       if (encoding == TYPE_##B##T##C1 ||        \
00211           encoding == TYPE_##B##T##C2 ||        \
00212           encoding == TYPE_##B##T##C3 ||        \
00213           encoding == TYPE_##B##T##C4)          \
00214         return B;                               \
00215       /***/
00216 
00217       CHECK_BIT_DEPTH(8, U);
00218       CHECK_BIT_DEPTH(8, S);
00219       CHECK_BIT_DEPTH(16, U);
00220       CHECK_BIT_DEPTH(16, S);
00221       CHECK_BIT_DEPTH(32, S);
00222       CHECK_BIT_DEPTH(32, F);
00223       CHECK_BIT_DEPTH(64, F);
00224 
00225 #undef CHECK_BIT_DEPTH
00226 
00227       if (encoding == YUV422)
00228         return 8;
00229 
00230       throw std::runtime_error("Unknown encoding " + encoding);
00231       return -1;
00232     }
00233   }
00234 }
00235 
00236 #endif


sensor_msgs
Author(s):
autogenerated on Sun Oct 5 2014 23:11:21