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     const std::string YUV422="yuv422";
00099 
00100     // Utility functions for inspecting an encoding string
00101     static inline bool isColor(const std::string& encoding)
00102     {
00103       return encoding == RGB8  || encoding == BGR8 ||
00104              encoding == RGBA8 || encoding == BGRA8 ||
00105              encoding == RGB16 || encoding == BGR16 ||
00106              encoding == RGBA16 || encoding == BGRA16;
00107     }
00108 
00109     static inline bool isMono(const std::string& encoding)
00110     {
00111       return encoding == MONO8 || encoding == MONO16;
00112     }
00113 
00114     static inline bool isBayer(const std::string& encoding)
00115     {
00116       return encoding == BAYER_RGGB8 || encoding == BAYER_BGGR8 ||
00117              encoding == BAYER_GBRG8 || encoding == BAYER_GRBG8 ||
00118              encoding == BAYER_RGGB16 || encoding == BAYER_BGGR16 ||
00119              encoding == BAYER_GBRG16 || encoding == BAYER_GRBG16;
00120     }
00121 
00122     static inline bool hasAlpha(const std::string& encoding)
00123     {
00124       return encoding == RGBA8 || encoding == BGRA8 ||
00125              encoding == RGBA16 || encoding == BGRA16;
00126     }
00127 
00128     static inline int numChannels(const std::string& encoding)
00129     {
00130       // First do the common-case encodings
00131       if (encoding == MONO8 ||
00132           encoding == MONO16)
00133         return 1;
00134       if (encoding == BGR8 ||
00135           encoding == RGB8 ||
00136           encoding == BGR16 ||
00137           encoding == RGB16)
00138         return 3;
00139       if (encoding == BGRA8 ||
00140           encoding == RGBA8 ||
00141           encoding == BGRA16 ||
00142           encoding == RGBA16)
00143         return 4;
00144       if (encoding == BAYER_RGGB8 ||
00145           encoding == BAYER_BGGR8 ||
00146           encoding == BAYER_GBRG8 ||
00147           encoding == BAYER_GRBG8 ||
00148           encoding == BAYER_RGGB16 ||
00149           encoding == BAYER_BGGR16 ||
00150           encoding == BAYER_GBRG16 ||
00151           encoding == BAYER_GRBG16)
00152         return 1;
00153 
00154       // Now all the generic content encodings
00155 #define CHECK_CHANNELS(N)                       \
00156       if (encoding == TYPE_8UC##N  ||           \
00157           encoding == TYPE_8SC##N  ||           \
00158           encoding == TYPE_16UC##N ||           \
00159           encoding == TYPE_16SC##N ||           \
00160           encoding == TYPE_32SC##N ||           \
00161           encoding == TYPE_32FC##N ||           \
00162           encoding == TYPE_64FC##N)             \
00163         return N;                               \
00164       /***/
00165       
00166       CHECK_CHANNELS(1);
00167       CHECK_CHANNELS(2);
00168       CHECK_CHANNELS(3);
00169       CHECK_CHANNELS(4);
00170 
00171 #undef CHECK_CHANNELS
00172 
00173       throw std::runtime_error("Unknown encoding " + encoding);
00174       return -1;
00175     }
00176 
00177     static inline int bitDepth(const std::string& encoding)
00178     {
00179       if (encoding == MONO16)
00180         return 16;
00181       if (encoding == MONO8       ||
00182           encoding == BGR8        ||
00183           encoding == RGB8        ||
00184           encoding == BGRA8       ||
00185           encoding == RGBA8       ||
00186           encoding == BAYER_RGGB8 ||
00187           encoding == BAYER_BGGR8 ||
00188           encoding == BAYER_GBRG8 ||
00189           encoding == BAYER_GRBG8)
00190         return 8;
00191 
00192       if (encoding == MONO16       ||
00193           encoding == BGR16        ||
00194           encoding == RGB16        ||
00195           encoding == BGRA16       ||
00196           encoding == RGBA16       ||
00197           encoding == BAYER_RGGB16 ||
00198           encoding == BAYER_BGGR16 ||
00199           encoding == BAYER_GBRG16 ||
00200           encoding == BAYER_GRBG16)
00201         return 16;
00202 
00203       // B = bits (8, 16, ...), T = type (U, S, F)
00204 #define CHECK_BIT_DEPTH(B, T)                   \
00205       if (encoding == TYPE_##B##T##C1 ||        \
00206           encoding == TYPE_##B##T##C2 ||        \
00207           encoding == TYPE_##B##T##C3 ||        \
00208           encoding == TYPE_##B##T##C4)          \
00209         return B;                               \
00210       /***/
00211 
00212       CHECK_BIT_DEPTH(8, U);
00213       CHECK_BIT_DEPTH(8, S);
00214       CHECK_BIT_DEPTH(16, U);
00215       CHECK_BIT_DEPTH(16, S);
00216       CHECK_BIT_DEPTH(32, S);
00217       CHECK_BIT_DEPTH(32, F);
00218       CHECK_BIT_DEPTH(64, F);
00219 
00220 #undef CHECK_BIT_DEPTH
00221 
00222       throw std::runtime_error("Unknown encoding " + encoding);
00223       return -1;
00224     }
00225   }
00226 }
00227 
00228 #endif


sensor_msgs
Author(s): Maintained by Tully Foote/tfoote@willowgarage.com
autogenerated on Sat Dec 28 2013 16:52:51