00001 #include <ros/ros.h>
00002 #include <nodelet/nodelet.h>
00003 #include <image_transport/image_transport.h>
00004 #include <sensor_msgs/image_encodings.h>
00005 #include <dynamic_reconfigure/server.h>
00006 #include <image_proc/DebayerConfig.h>
00007
00008 #include <opencv2/imgproc/imgproc.hpp>
00009
00010 #include "edge_aware.h"
00011 #include "yuv422.h"
00012
00013 #include <boost/make_shared.hpp>
00014
00015 namespace image_proc {
00016
00017 namespace enc = sensor_msgs::image_encodings;
00018
00019 class DebayerNodelet : public nodelet::Nodelet
00020 {
00021
00022 boost::shared_ptr<image_transport::ImageTransport> it_;
00023 image_transport::Subscriber sub_raw_;
00024
00025 boost::mutex connect_mutex_;
00026 image_transport::Publisher pub_mono_;
00027 image_transport::Publisher pub_color_;
00028
00029
00030 boost::recursive_mutex config_mutex_;
00031 typedef image_proc::DebayerConfig Config;
00032 typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00033 boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00034 Config config_;
00035
00036 virtual void onInit();
00037
00038 void connectCb();
00039
00040 void imageCb(const sensor_msgs::ImageConstPtr& raw_msg);
00041
00042 void configCb(Config &config, uint32_t level);
00043 };
00044
00045 void DebayerNodelet::onInit()
00046 {
00047 ros::NodeHandle &nh = getNodeHandle();
00048 ros::NodeHandle &private_nh = getPrivateNodeHandle();
00049 it_.reset(new image_transport::ImageTransport(nh));
00050
00051
00052 reconfigure_server_.reset(new ReconfigureServer(config_mutex_, private_nh));
00053 ReconfigureServer::CallbackType f = boost::bind(&DebayerNodelet::configCb, this, _1, _2);
00054 reconfigure_server_->setCallback(f);
00055
00056
00057 typedef image_transport::SubscriberStatusCallback ConnectCB;
00058 ConnectCB connect_cb = boost::bind(&DebayerNodelet::connectCb, this);
00059
00060 boost::lock_guard<boost::mutex> lock(connect_mutex_);
00061 pub_mono_ = it_->advertise("image_mono", 1, connect_cb, connect_cb);
00062 pub_color_ = it_->advertise("image_color", 1, connect_cb, connect_cb);
00063 }
00064
00065
00066 void DebayerNodelet::connectCb()
00067 {
00068 boost::lock_guard<boost::mutex> lock(connect_mutex_);
00069 if (pub_mono_.getNumSubscribers() == 0 && pub_color_.getNumSubscribers() == 0)
00070 sub_raw_.shutdown();
00071 else if (!sub_raw_)
00072 sub_raw_ = it_->subscribe("image_raw", 1, &DebayerNodelet::imageCb, this);
00073 }
00074
00075 void DebayerNodelet::imageCb(const sensor_msgs::ImageConstPtr& raw_msg)
00076 {
00079
00080 if (enc::isMono(raw_msg->encoding))
00081 {
00082
00083 pub_mono_.publish(raw_msg);
00084 pub_color_.publish(raw_msg);
00085
00086
00087 if (pub_color_.getNumSubscribers() > 0)
00088 {
00089 NODELET_WARN_THROTTLE(30,
00090 "Color topic '%s' requested, but raw image data from topic '%s' is grayscale",
00091 pub_color_.getTopic().c_str(), sub_raw_.getTopic().c_str());
00092 }
00093 }
00094 else if (enc::isColor(raw_msg->encoding))
00095 {
00096 pub_color_.publish(raw_msg);
00097
00098
00099 if (pub_mono_.getNumSubscribers() > 0)
00100 {
00101 int bit_depth = enc::bitDepth(raw_msg->encoding);
00102 int num_channels = enc::numChannels(raw_msg->encoding);
00103 int code = -1;
00104 if (raw_msg->encoding == enc::BGR8 ||
00105 raw_msg->encoding == enc::BGR16)
00106 code = CV_BGR2GRAY;
00107 else if (raw_msg->encoding == enc::RGB8 ||
00108 raw_msg->encoding == enc::RGB16)
00109 code = CV_RGB2GRAY;
00110 else if (raw_msg->encoding == enc::BGRA8 ||
00111 raw_msg->encoding == enc::BGRA16)
00112 code = CV_BGRA2GRAY;
00113 else if (raw_msg->encoding == enc::RGBA8 ||
00114 raw_msg->encoding == enc::RGBA16)
00115 code = CV_RGBA2GRAY;
00116
00117 sensor_msgs::ImagePtr gray_msg = boost::make_shared<sensor_msgs::Image>();
00118 gray_msg->header = raw_msg->header;
00119 gray_msg->height = raw_msg->height;
00120 gray_msg->width = raw_msg->width;
00121 gray_msg->encoding = bit_depth == 8 ? enc::MONO8 : enc::MONO16;
00122 gray_msg->step = gray_msg->width * (bit_depth / 8);
00123 gray_msg->data.resize(gray_msg->height * gray_msg->step);
00124
00125 int type = bit_depth == 8 ? CV_8U : CV_16U;
00126 const cv::Mat color(raw_msg->height, raw_msg->width, CV_MAKETYPE(type, num_channels),
00127 const_cast<uint8_t*>(&raw_msg->data[0]), raw_msg->step);
00128 cv::Mat gray(gray_msg->height, gray_msg->width, CV_MAKETYPE(type, 1),
00129 &gray_msg->data[0], gray_msg->step);
00130 cv::cvtColor(color, gray, code);
00131
00132 pub_mono_.publish(gray_msg);
00133 }
00134 }
00135 else if (enc::isBayer(raw_msg->encoding)) {
00136 int bit_depth = enc::bitDepth(raw_msg->encoding);
00137 int type = bit_depth == 8 ? CV_8U : CV_16U;
00138 const cv::Mat bayer(raw_msg->height, raw_msg->width, CV_MAKETYPE(type, 1),
00139 const_cast<uint8_t*>(&raw_msg->data[0]), raw_msg->step);
00140
00141 if (pub_mono_.getNumSubscribers() > 0)
00142 {
00143 int code = -1;
00144 if (raw_msg->encoding == enc::BAYER_RGGB8 ||
00145 raw_msg->encoding == enc::BAYER_RGGB16)
00146 code = CV_BayerBG2GRAY;
00147 else if (raw_msg->encoding == enc::BAYER_BGGR8 ||
00148 raw_msg->encoding == enc::BAYER_BGGR16)
00149 code = CV_BayerRG2GRAY;
00150 else if (raw_msg->encoding == enc::BAYER_GBRG8 ||
00151 raw_msg->encoding == enc::BAYER_GBRG16)
00152 code = CV_BayerGR2GRAY;
00153 else if (raw_msg->encoding == enc::BAYER_GRBG8 ||
00154 raw_msg->encoding == enc::BAYER_GRBG16)
00155 code = CV_BayerGB2GRAY;
00156
00157 sensor_msgs::ImagePtr gray_msg = boost::make_shared<sensor_msgs::Image>();
00158 gray_msg->header = raw_msg->header;
00159 gray_msg->height = raw_msg->height;
00160 gray_msg->width = raw_msg->width;
00161 gray_msg->encoding = bit_depth == 8 ? enc::MONO8 : enc::MONO16;
00162 gray_msg->step = gray_msg->width * (bit_depth / 8);
00163 gray_msg->data.resize(gray_msg->height * gray_msg->step);
00164
00165 cv::Mat gray(gray_msg->height, gray_msg->width, CV_MAKETYPE(type, 1),
00166 &gray_msg->data[0], gray_msg->step);
00167 cv::cvtColor(bayer, gray, code);
00168
00169 pub_mono_.publish(gray_msg);
00170 }
00171
00172 if (pub_color_.getNumSubscribers() > 0)
00173 {
00174 sensor_msgs::ImagePtr color_msg = boost::make_shared<sensor_msgs::Image>();
00175 color_msg->header = raw_msg->header;
00176 color_msg->height = raw_msg->height;
00177 color_msg->width = raw_msg->width;
00178 color_msg->encoding = bit_depth == 8? enc::BGR8 : enc::BGR16;
00179 color_msg->step = color_msg->width * 3 * (bit_depth / 8);
00180 color_msg->data.resize(color_msg->height * color_msg->step);
00181
00182 cv::Mat color(color_msg->height, color_msg->width, CV_MAKETYPE(type, 3),
00183 &color_msg->data[0], color_msg->step);
00184
00185 int algorithm;
00186 {
00187 boost::lock_guard<boost::recursive_mutex> lock(config_mutex_);
00188 algorithm = config_.debayer;
00189 }
00190
00191 if (algorithm == Debayer_EdgeAware ||
00192 algorithm == Debayer_EdgeAwareWeighted)
00193 {
00194
00195 if (raw_msg->encoding != enc::BAYER_GRBG8)
00196 {
00197 NODELET_WARN_THROTTLE(30, "Edge aware algorithms currently only support GRBG8 Bayer. "
00198 "Falling back to bilinear interpolation.");
00199 algorithm = Debayer_Bilinear;
00200 }
00201 else
00202 {
00203 if (algorithm == Debayer_EdgeAware)
00204 debayerEdgeAware(bayer, color);
00205 else
00206 debayerEdgeAwareWeighted(bayer, color);
00207 }
00208 }
00209 if (algorithm == Debayer_Bilinear ||
00210 algorithm == Debayer_VNG)
00211 {
00212 int code = -1;
00213 if (raw_msg->encoding == enc::BAYER_RGGB8 ||
00214 raw_msg->encoding == enc::BAYER_RGGB16)
00215 code = CV_BayerBG2BGR;
00216 else if (raw_msg->encoding == enc::BAYER_BGGR8 ||
00217 raw_msg->encoding == enc::BAYER_BGGR16)
00218 code = CV_BayerRG2BGR;
00219 else if (raw_msg->encoding == enc::BAYER_GBRG8 ||
00220 raw_msg->encoding == enc::BAYER_GBRG16)
00221 code = CV_BayerGR2BGR;
00222 else if (raw_msg->encoding == enc::BAYER_GRBG8 ||
00223 raw_msg->encoding == enc::BAYER_GRBG16)
00224 code = CV_BayerGB2BGR;
00225
00226 if (algorithm == Debayer_VNG)
00227 code += CV_BayerBG2BGR_VNG - CV_BayerBG2BGR;
00228
00229 cv::cvtColor(bayer, color, code);
00230 }
00231
00232 pub_color_.publish(color_msg);
00233 }
00234 }
00235 else if (raw_msg->encoding == enc::YUV422)
00236 {
00237 const cv::Mat yuv(raw_msg->height, raw_msg->width, CV_8UC2,
00238 const_cast<uint8_t*>(&raw_msg->data[0]), raw_msg->step);
00239
00240 if (pub_mono_.getNumSubscribers() > 0)
00241 {
00242 sensor_msgs::ImagePtr gray_msg = boost::make_shared<sensor_msgs::Image>();
00243 gray_msg->header = raw_msg->header;
00244 gray_msg->height = raw_msg->height;
00245 gray_msg->width = raw_msg->width;
00246 gray_msg->encoding = enc::MONO8;
00247 gray_msg->step = gray_msg->width;
00248 gray_msg->data.resize(gray_msg->height * gray_msg->step);
00249
00250 cv::Mat gray(gray_msg->height, gray_msg->width, CV_8UC1,
00251 &gray_msg->data[0], gray_msg->step);
00252 yuv422ToGray(yuv, gray);
00253
00254 pub_mono_.publish(gray_msg);
00255 }
00256
00257 if (pub_color_.getNumSubscribers() > 0)
00258 {
00259 sensor_msgs::ImagePtr color_msg = boost::make_shared<sensor_msgs::Image>();
00260 color_msg->header = raw_msg->header;
00261 color_msg->height = raw_msg->height;
00262 color_msg->width = raw_msg->width;
00263 color_msg->encoding = enc::BGR8;
00264 color_msg->step = color_msg->width * 3;
00265 color_msg->data.resize(color_msg->height * color_msg->step);
00266
00267 cv::Mat color(color_msg->height, color_msg->width, CV_8UC3,
00268 &color_msg->data[0], color_msg->step);
00269 yuv422ToColor(yuv, color);
00270
00271 pub_color_.publish(color_msg);
00272 }
00273 }
00274 else if (raw_msg->encoding == enc::TYPE_8UC3)
00275 {
00276
00277 NODELET_ERROR_THROTTLE(10,
00278 "Raw image topic '%s' has ambiguous encoding '8UC3'. The "
00279 "source should set the encoding to 'bgr8' or 'rgb8'.",
00280 sub_raw_.getTopic().c_str());
00281 }
00282 else
00283 {
00284 NODELET_ERROR_THROTTLE(10, "Raw image topic '%s' has unsupported encoding '%s'",
00285 sub_raw_.getTopic().c_str(), raw_msg->encoding.c_str());
00286 }
00287 }
00288
00289 void DebayerNodelet::configCb(Config &config, uint32_t level)
00290 {
00291 config_ = config;
00292 }
00293
00294 }
00295
00296
00297 #include <pluginlib/class_list_macros.h>
00298 PLUGINLIB_DECLARE_CLASS(image_proc, debayer, image_proc::DebayerNodelet, nodelet::Nodelet)