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