34 #include <boost/make_shared.hpp>
35 #include <boost/version.hpp>
36 #if ((BOOST_VERSION / 100) % 1000) >= 53
37 #include <boost/thread/lock_guard.hpp>
44 #include <dynamic_reconfigure/server.h>
45 #include <image_proc/DebayerConfig.h>
47 #include <opencv2/imgproc/imgproc.hpp>
69 typedef image_proc::DebayerConfig
Config;
78 void imageCb(
const sensor_msgs::ImageConstPtr& raw_msg);
91 ReconfigureServer::CallbackType
f = boost::bind(&
DebayerNodelet::configCb,
this, boost::placeholders::_1, boost::placeholders::_2);
99 pub_mono_ =
it_->advertise(
"image_mono", 1, connect_cb, connect_cb);
100 pub_color_ =
it_->advertise(
"image_color", 1, connect_cb, connect_cb);
118 int bit_depth = enc::bitDepth(raw_msg->encoding);
120 if (raw_msg->encoding == enc::YUV422)
126 if (enc::isMono(raw_msg->encoding))
130 if ((bit_depth != 8) && (bit_depth != 16))
133 "Raw image data from topic '%s' has unsupported depth: %d",
138 sensor_msgs::ImagePtr gray_msg;
159 if (enc::isMono(raw_msg->encoding))
166 "Color topic '%s' requested, but raw image data from topic '%s' is grayscale",
169 else if (enc::isColor(raw_msg->encoding))
173 else if (enc::isBayer(raw_msg->encoding)) {
174 int type = bit_depth == 8 ? CV_8U : CV_16U;
175 const cv::Mat bayer(raw_msg->height, raw_msg->width, CV_MAKETYPE(type, 1),
176 const_cast<uint8_t*
>(&raw_msg->data[0]), raw_msg->step);
178 sensor_msgs::ImagePtr color_msg = boost::make_shared<sensor_msgs::Image>();
179 color_msg->header = raw_msg->header;
180 color_msg->height = raw_msg->height;
181 color_msg->width = raw_msg->width;
183 color_msg->step = color_msg->width * 3 * (bit_depth / 8);
184 color_msg->data.resize(color_msg->height * color_msg->step);
186 cv::Mat color(color_msg->height, color_msg->width, CV_MAKETYPE(type, 3),
187 &color_msg->data[0], color_msg->step);
191 boost::lock_guard<boost::recursive_mutex> lock(
config_mutex_);
195 if (algorithm == Debayer_EdgeAware ||
196 algorithm == Debayer_EdgeAwareWeighted)
199 if (raw_msg->encoding != enc::BAYER_GRBG8)
202 "Falling back to bilinear interpolation.");
203 algorithm = Debayer_Bilinear;
207 if (algorithm == Debayer_EdgeAware)
213 if (algorithm == Debayer_Bilinear ||
214 algorithm == Debayer_VNG)
217 if (raw_msg->encoding == enc::BAYER_RGGB8 ||
218 raw_msg->encoding == enc::BAYER_RGGB16)
219 code = cv::COLOR_BayerBG2BGR;
220 else if (raw_msg->encoding == enc::BAYER_BGGR8 ||
221 raw_msg->encoding == enc::BAYER_BGGR16)
222 code = cv::COLOR_BayerRG2BGR;
223 else if (raw_msg->encoding == enc::BAYER_GBRG8 ||
224 raw_msg->encoding == enc::BAYER_GBRG16)
225 code = cv::COLOR_BayerGR2BGR;
226 else if (raw_msg->encoding == enc::BAYER_GRBG8 ||
227 raw_msg->encoding == enc::BAYER_GRBG16)
228 code = cv::COLOR_BayerGB2BGR;
230 if (algorithm == Debayer_VNG)
231 code += cv::COLOR_BayerBG2BGR_VNG - cv::COLOR_BayerBG2BGR;
235 cv::cvtColor(bayer, color, code);
237 catch (cv::Exception &e)
240 e.what(), code, bayer.cols, bayer.rows);
247 else if (raw_msg->encoding == enc::YUV422)
250 sensor_msgs::ImagePtr color_msg;
261 else if (raw_msg->encoding == enc::TYPE_8UC3)
265 "Raw image topic '%s' has ambiguous encoding '8UC3'. The "
266 "source should set the encoding to 'bgr8' or 'rgb8'.",