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 "sensor_msgs/image_encodings.h" 00036 #include <stdexcept> 00037 00038 namespace sensor_msgs 00039 { 00040 namespace image_encodings 00041 { 00042 const std::string RGB8 = "rgb8"; 00043 const std::string RGBA8 = "rgba8"; 00044 const std::string BGR8 = "bgr8"; 00045 const std::string BGRA8 = "bgra8"; 00046 const std::string MONO8="mono8"; 00047 const std::string MONO16="mono16"; 00048 00049 // OpenCV CvMat encodings 00050 const std::string TYPE_8UC1="8UC1"; 00051 const std::string TYPE_8UC2="8UC2"; 00052 const std::string TYPE_8UC3="8UC3"; 00053 const std::string TYPE_8UC4="8UC4"; 00054 const std::string TYPE_8SC1="8SC1"; 00055 const std::string TYPE_8SC2="8SC2"; 00056 const std::string TYPE_8SC3="8SC3"; 00057 const std::string TYPE_8SC4="8SC4"; 00058 const std::string TYPE_16UC1="16UC1"; 00059 const std::string TYPE_16UC2="16UC2"; 00060 const std::string TYPE_16UC3="16UC3"; 00061 const std::string TYPE_16UC4="16UC4"; 00062 const std::string TYPE_16SC1="16SC1"; 00063 const std::string TYPE_16SC2="16SC2"; 00064 const std::string TYPE_16SC3="16SC3"; 00065 const std::string TYPE_16SC4="16SC4"; 00066 const std::string TYPE_32SC1="32SC1"; 00067 const std::string TYPE_32SC2="32SC2"; 00068 const std::string TYPE_32SC3="32SC3"; 00069 const std::string TYPE_32SC4="32SC4"; 00070 const std::string TYPE_32FC1="32FC1"; 00071 const std::string TYPE_32FC2="32FC2"; 00072 const std::string TYPE_32FC3="32FC3"; 00073 const std::string TYPE_32FC4="32FC4"; 00074 const std::string TYPE_64FC1="64FC1"; 00075 const std::string TYPE_64FC2="64FC2"; 00076 const std::string TYPE_64FC3="64FC3"; 00077 const std::string TYPE_64FC4="64FC4"; 00078 00079 // Bayer encodings 00080 const std::string BAYER_RGGB8="bayer_rggb8"; 00081 const std::string BAYER_BGGR8="bayer_bggr8"; 00082 const std::string BAYER_GBRG8="bayer_gbrg8"; 00083 const std::string BAYER_GRBG8="bayer_grbg8"; 00084 00085 bool isColor(const std::string& encoding) 00086 { 00087 return encoding == RGB8 || encoding == BGR8 || 00088 encoding == RGBA8 || encoding == BGRA8; 00089 } 00090 00091 bool isMono(const std::string& encoding) 00092 { 00093 return encoding == MONO8 || encoding == MONO16; 00094 } 00095 00096 bool isBayer(const std::string& encoding) 00097 { 00098 return encoding == BAYER_RGGB8 || encoding == BAYER_BGGR8 || 00099 encoding == BAYER_GBRG8 || encoding == BAYER_GRBG8; 00100 } 00101 00102 bool hasAlpha(const std::string& encoding) 00103 { 00104 return encoding == RGBA8 || encoding == BGRA8; 00105 } 00106 00107 int numChannels(const std::string& encoding) 00108 { 00109 // First do the common-case encodings 00110 if (encoding == MONO8 || 00111 encoding == MONO16) 00112 return 1; 00113 if (encoding == BGR8 || 00114 encoding == RGB8) 00115 return 3; 00116 if (encoding == BGRA8 || 00117 encoding == RGBA8) 00118 return 4; 00119 if (encoding == BAYER_RGGB8 || 00120 encoding == BAYER_BGGR8 || 00121 encoding == BAYER_GBRG8 || 00122 encoding == BAYER_GRBG8) 00123 return 1; 00124 00125 // Now all the generic content encodings 00126 #define CHECK_CHANNELS(N) \ 00127 if (encoding == TYPE_8UC##N || \ 00128 encoding == TYPE_8SC##N || \ 00129 encoding == TYPE_16UC##N || \ 00130 encoding == TYPE_16SC##N || \ 00131 encoding == TYPE_32SC##N || \ 00132 encoding == TYPE_32FC##N || \ 00133 encoding == TYPE_64FC##N) \ 00134 return N; \ 00135 /***/ 00136 00137 CHECK_CHANNELS(1); 00138 CHECK_CHANNELS(2); 00139 CHECK_CHANNELS(3); 00140 CHECK_CHANNELS(4); 00141 00142 #undef CHECK_CHANNELS 00143 00144 throw std::runtime_error("Unknown encoding " + encoding); 00145 return -1; 00146 } 00147 00148 int bitDepth(const std::string& encoding) 00149 { 00150 if (encoding == MONO16) 00151 return 16; 00152 if (encoding == MONO8 || 00153 encoding == BGR8 || 00154 encoding == RGB8 || 00155 encoding == BGRA8 || 00156 encoding == RGBA8 || 00157 encoding == BAYER_RGGB8 || 00158 encoding == BAYER_BGGR8 || 00159 encoding == BAYER_GBRG8 || 00160 encoding == BAYER_GRBG8) 00161 return 8; 00162 00163 // B = bits (8, 16, ...), T = type (U, S, F) 00164 #define CHECK_BIT_DEPTH(B, T) \ 00165 if (encoding == TYPE_##B##T##C1 || \ 00166 encoding == TYPE_##B##T##C2 || \ 00167 encoding == TYPE_##B##T##C3 || \ 00168 encoding == TYPE_##B##T##C4) \ 00169 return B; \ 00170 /***/ 00171 00172 CHECK_BIT_DEPTH(8, U); 00173 CHECK_BIT_DEPTH(8, S); 00174 CHECK_BIT_DEPTH(16, U); 00175 CHECK_BIT_DEPTH(16, S); 00176 CHECK_BIT_DEPTH(32, S); 00177 CHECK_BIT_DEPTH(32, F); 00178 CHECK_BIT_DEPTH(64, F); 00179 00180 #undef CHECK_BIT_DEPTH; 00181 00182 throw std::runtime_error("Unknown encoding " + encoding); 00183 return -1; 00184 } 00185 } 00186 }