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 #include <cv_bridge/cv_bridge.h>
00036 #include <opencv2/imgproc/imgproc.hpp>
00037 #include <sensor_msgs/image_encodings.h>
00038 #include <boost/make_shared.hpp>
00039
00040 namespace enc = sensor_msgs::image_encodings;
00041
00042 namespace cv_bridge {
00043
00044 int getCvType(const std::string& encoding)
00045 {
00046
00047 if (encoding == enc::BGR8) return CV_8UC3;
00048 if (encoding == enc::MONO8) return CV_8UC1;
00049 if (encoding == enc::RGB8) return CV_8UC3;
00050 if (encoding == enc::MONO16) return CV_16UC1;
00051 if (encoding == enc::BGR16) return CV_16UC3;
00052 if (encoding == enc::RGB16) return CV_16UC3;
00053 if (encoding == enc::BGRA8) return CV_8UC4;
00054 if (encoding == enc::RGBA8) return CV_8UC4;
00055 if (encoding == enc::BGRA16) return CV_16UC4;
00056 if (encoding == enc::RGBA16) return CV_16UC4;
00057
00058
00059 if (encoding == enc::BAYER_RGGB8) return CV_8UC1;
00060 if (encoding == enc::BAYER_BGGR8) return CV_8UC1;
00061 if (encoding == enc::BAYER_GBRG8) return CV_8UC1;
00062 if (encoding == enc::BAYER_GRBG8) return CV_8UC1;
00063 if (encoding == enc::BAYER_RGGB16) return CV_16UC1;
00064 if (encoding == enc::BAYER_BGGR16) return CV_16UC1;
00065 if (encoding == enc::BAYER_GBRG16) return CV_16UC1;
00066 if (encoding == enc::BAYER_GRBG16) return CV_16UC1;
00067
00068
00069 #define CHECK_ENCODING(code) \
00070 if (encoding == enc::TYPE_##code) return CV_##code \
00071
00072 #define CHECK_CHANNEL_TYPE(t) \
00073 CHECK_ENCODING(t##1); \
00074 CHECK_ENCODING(t##2); \
00075 CHECK_ENCODING(t##3); \
00076 CHECK_ENCODING(t##4); \
00077
00078
00079 CHECK_CHANNEL_TYPE(8UC);
00080 CHECK_CHANNEL_TYPE(8SC);
00081 CHECK_CHANNEL_TYPE(16UC);
00082 CHECK_CHANNEL_TYPE(16SC);
00083 CHECK_CHANNEL_TYPE(32SC);
00084 CHECK_CHANNEL_TYPE(32FC);
00085 CHECK_CHANNEL_TYPE(64FC);
00086
00087 #undef CHECK_CHANNEL_TYPE
00088 #undef CHECK_ENCODING
00089
00090 throw Exception("Unrecognized image encoding [" + encoding + "]");
00091 }
00092
00094
00095 enum Format { INVALID = -1, GRAY = 0, RGB, BGR, RGBA, BGRA };
00096
00097 Format getFormat(const std::string& encoding)
00098 {
00099 if (encoding == enc::BGR8) return BGR;
00100 if (encoding == enc::MONO8) return GRAY;
00101 if (encoding == enc::RGB8) return RGB;
00102 if (encoding == enc::MONO16) return GRAY;
00103 if (encoding == enc::BGR16) return BGR;
00104 if (encoding == enc::RGB16) return RGB;
00105 if (encoding == enc::BGRA8) return BGRA;
00106 if (encoding == enc::RGBA8) return RGBA;
00107 if (encoding == enc::BGRA16) return BGRA;
00108 if (encoding == enc::RGBA16) return RGBA;
00109
00110
00111 return INVALID;
00112 }
00113
00114 static const int SAME_FORMAT = -1;
00115
00116 int getConversionCode(Format src_format, Format dst_format)
00117 {
00118 static const int CONVERSION_CODES[] = { SAME_FORMAT,
00119 CV_GRAY2RGB,
00120 CV_GRAY2BGR,
00121 CV_GRAY2RGBA,
00122 CV_GRAY2BGRA,
00123 CV_RGB2GRAY,
00124 SAME_FORMAT,
00125 CV_RGB2BGR,
00126 CV_RGB2RGBA,
00127 CV_RGB2BGRA,
00128 CV_BGR2GRAY,
00129 CV_BGR2RGB,
00130 SAME_FORMAT,
00131 CV_BGR2RGBA,
00132 CV_BGR2BGRA,
00133 CV_RGBA2GRAY,
00134 CV_RGBA2RGB,
00135 CV_RGBA2BGR,
00136 SAME_FORMAT,
00137 CV_RGBA2BGRA,
00138 CV_BGRA2GRAY,
00139 CV_BGRA2RGB,
00140 CV_BGRA2BGR,
00141 CV_BGRA2RGBA,
00142 SAME_FORMAT };
00143 return CONVERSION_CODES[src_format*5 + dst_format];
00144 }
00145
00146
00147 CvImagePtr toCvCopyImpl(const cv::Mat& source,
00148 const std_msgs::Header& src_header,
00149 const std::string& src_encoding,
00150 const std::string& dst_encoding)
00151 {
00153
00154
00155 CvImagePtr ptr = boost::make_shared<CvImage>();
00156 ptr->header = src_header;
00157
00158
00159 if (dst_encoding.empty() || dst_encoding == src_encoding)
00160 {
00161 ptr->encoding = src_encoding;
00162 source.copyTo(ptr->image);
00163 }
00164 else
00165 {
00166
00167 Format src_format = getFormat(src_encoding);
00168 Format dst_format = getFormat(dst_encoding);
00169 if (src_format == INVALID || dst_format == INVALID)
00170 throw Exception("Unsupported conversion from [" + src_encoding +
00171 "] to [" + dst_encoding + "]");
00172
00173 int conversion_code = getConversionCode(src_format, dst_format);
00174 if (conversion_code == SAME_FORMAT)
00175 {
00176
00177 double alpha = 1.0;
00178 int src_depth = enc::bitDepth(src_encoding);
00179 int dst_depth = enc::bitDepth(dst_encoding);
00180
00181 if (src_depth == 8 && dst_depth == 16)
00182 alpha = 65535. / 255.;
00183 else if (src_depth == 16 && dst_depth == 8)
00184 alpha = 255. / 65535.;
00185 source.convertTo(ptr->image, getCvType(dst_encoding), alpha);
00186 }
00187 else
00188 {
00189
00190 cv::cvtColor(source, ptr->image, conversion_code);
00191 }
00192 ptr->encoding = dst_encoding;
00193 }
00194
00195 return ptr;
00196 }
00197
00199
00200 sensor_msgs::ImagePtr CvImage::toImageMsg() const
00201 {
00202 sensor_msgs::ImagePtr ptr = boost::make_shared<sensor_msgs::Image>();
00203 toImageMsg(*ptr);
00204 return ptr;
00205 }
00206
00207 void CvImage::toImageMsg(sensor_msgs::Image& ros_image) const
00208 {
00209 ros_image.header = header;
00210 ros_image.height = image.rows;
00211 ros_image.width = image.cols;
00212 ros_image.encoding = encoding;
00213 ros_image.is_bigendian = false;
00214 ros_image.step = image.cols * image.elemSize();
00215 size_t size = ros_image.step * image.rows;
00216 ros_image.data.resize(size);
00217
00218 if (image.isContinuous())
00219 {
00220 memcpy((char*)(&ros_image.data[0]), image.data, size);
00221 }
00222 else
00223 {
00224
00225 uchar* ros_data_ptr = (uchar*)(&ros_image.data[0]);
00226 uchar* cv_data_ptr = image.data;
00227 for (int i = 0; i < image.rows; ++i)
00228 {
00229 memcpy(ros_data_ptr, cv_data_ptr, ros_image.step);
00230 ros_data_ptr += ros_image.step;
00231 cv_data_ptr += image.step;
00232 }
00233 }
00234 }
00235
00236
00237 CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr& source,
00238 const std::string& encoding)
00239 {
00240 return toCvCopy(*source, encoding);
00241 }
00242
00243 CvImagePtr toCvCopy(const sensor_msgs::Image& source,
00244 const std::string& encoding)
00245 {
00246
00247 int source_type = getCvType(source.encoding);
00248 const cv::Mat tmp((int)source.height, (int)source.width, source_type,
00249 const_cast<uint8_t*>(&source.data[0]), (size_t)source.step);
00250
00251 return toCvCopyImpl(tmp, source.header, source.encoding, encoding);
00252 }
00253
00254
00255 CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr& source,
00256 const std::string& encoding)
00257 {
00258 return toCvShare(*source, source, encoding);
00259 }
00260
00261 CvImageConstPtr toCvShare(const sensor_msgs::Image& source,
00262 const boost::shared_ptr<void const>& tracked_object,
00263 const std::string& encoding)
00264 {
00265 if (!encoding.empty() && source.encoding != encoding)
00266 return toCvCopy(source, encoding);
00267
00268 CvImagePtr ptr = boost::make_shared<CvImage>();
00269 ptr->header = source.header;
00270 ptr->encoding = source.encoding;
00271 ptr->tracked_object_ = tracked_object;
00272 int type = getCvType(source.encoding);
00273 ptr->image = cv::Mat(source.height, source.width, type,
00274 const_cast<uchar*>(&source.data[0]), source.step);
00275 return ptr;
00276 }
00277
00278 CvImagePtr cvtColor(const CvImageConstPtr& source,
00279 const std::string& encoding)
00280 {
00281 return toCvCopyImpl(source->image, source->header, source->encoding, encoding);
00282 }
00283
00284 }