Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
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
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
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
00099
00100
00101 const std::string YUV422="yuv422";
00102
00103
00104 const std::string ABSTRACT_ENCODING_PREFIXES[] = {
00105 "8UC", "8SC", "16UC", "16SC", "32SC", "32FC", "64FC"};
00106
00107
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
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
00162
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;
00170 int n_channel = atoi(encoding.substr(prefix.size(),
00171 encoding.size() - prefix.size()).c_str());
00172 if (n_channel != 0)
00173 return n_channel;
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
00210
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());
00218 int n_channel = atoi(encoding.substr(prefix.size(),
00219 encoding.size() - prefix.size()).c_str());
00220 if (n_channel != 0)
00221 return atoi(prefix.c_str());
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