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 <cv_bridge/cv_bridge.h>
00007 #include <image_proc/CropDecimateConfig.h>
00008 #include <opencv2/imgproc/imgproc.hpp>
00009
00010 namespace image_proc {
00011
00012 using namespace cv_bridge;
00013
00014 class CropDecimateNodelet : public nodelet::Nodelet
00015 {
00016
00017 boost::shared_ptr<image_transport::ImageTransport> it_in_, it_out_;
00018 image_transport::CameraSubscriber sub_;
00019 int queue_size_;
00020
00021 boost::mutex connect_mutex_;
00022 image_transport::CameraPublisher pub_;
00023
00024
00025 boost::recursive_mutex config_mutex_;
00026 typedef image_proc::CropDecimateConfig Config;
00027 typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00028 boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00029 Config config_;
00030
00031 virtual void onInit();
00032
00033 void connectCb();
00034
00035 void imageCb(const sensor_msgs::ImageConstPtr& image_msg,
00036 const sensor_msgs::CameraInfoConstPtr& info_msg);
00037
00038 void configCb(Config &config, uint32_t level);
00039 };
00040
00041 void CropDecimateNodelet::onInit()
00042 {
00043 ros::NodeHandle& nh = getNodeHandle();
00044 ros::NodeHandle& private_nh = getPrivateNodeHandle();
00045 ros::NodeHandle nh_in (nh, "camera");
00046 ros::NodeHandle nh_out(nh, "camera_out");
00047 it_in_ .reset(new image_transport::ImageTransport(nh_in));
00048 it_out_.reset(new image_transport::ImageTransport(nh_out));
00049
00050
00051 private_nh.param("queue_size", queue_size_, 5);
00052
00053
00054 reconfigure_server_.reset(new ReconfigureServer(config_mutex_, private_nh));
00055 ReconfigureServer::CallbackType f = boost::bind(&CropDecimateNodelet::configCb, this, _1, _2);
00056 reconfigure_server_->setCallback(f);
00057
00058
00059 image_transport::SubscriberStatusCallback connect_cb = boost::bind(&CropDecimateNodelet::connectCb, this);
00060 ros::SubscriberStatusCallback connect_cb_info = boost::bind(&CropDecimateNodelet::connectCb, this);
00061
00062 boost::lock_guard<boost::mutex> lock(connect_mutex_);
00063 pub_ = it_out_->advertiseCamera("image_raw", 1, connect_cb, connect_cb, connect_cb_info, connect_cb_info);
00064 }
00065
00066
00067 void CropDecimateNodelet::connectCb()
00068 {
00069 boost::lock_guard<boost::mutex> lock(connect_mutex_);
00070 if (pub_.getNumSubscribers() == 0)
00071 sub_.shutdown();
00072 else if (!sub_)
00073 {
00074 image_transport::TransportHints hints("raw", ros::TransportHints(), getPrivateNodeHandle());
00075 sub_ = it_in_->subscribeCamera("image_raw", queue_size_, &CropDecimateNodelet::imageCb, this, hints);
00076 }
00077 }
00078
00079 template <typename T>
00080 void debayer2x2toBGR(const cv::Mat& src, cv::Mat& dst, int R, int G1, int G2, int B)
00081 {
00082 typedef cv::Vec<T, 3> DstPixel;
00083 dst.create(src.rows / 2, src.cols / 2, cv::DataType<DstPixel>::type);
00084
00085 int src_row_step = src.step1();
00086 int dst_row_step = dst.step1();
00087 const T* src_row = src.ptr<T>();
00088 T* dst_row = dst.ptr<T>();
00089
00090
00091 for (int y = 0; y < dst.rows; ++y)
00092 {
00093 for (int x = 0; x < dst.cols; ++x)
00094 {
00095 dst_row[x*3 + 0] = src_row[x*2 + B];
00096 dst_row[x*3 + 1] = (src_row[x*2 + G1] + src_row[x*2 + G2]) / 2;
00097 dst_row[x*3 + 2] = src_row[x*2 + R];
00098 }
00099 src_row += src_row_step * 2;
00100 dst_row += dst_row_step;
00101 }
00102 }
00103
00104
00105 template <int N>
00106 void decimate(const cv::Mat& src, cv::Mat& dst, int decimation_x, int decimation_y)
00107 {
00108 dst.create(src.rows / decimation_y, src.cols / decimation_x, src.type());
00109
00110 int src_row_step = src.step[0] * decimation_y;
00111 int src_pixel_step = N * decimation_x;
00112 int dst_row_step = dst.step[0];
00113
00114 const uint8_t* src_row = src.ptr();
00115 uint8_t* dst_row = dst.ptr();
00116
00117 for (int y = 0; y < dst.rows; ++y)
00118 {
00119 const uint8_t* src_pixel = src_row;
00120 uint8_t* dst_pixel = dst_row;
00121 for (int x = 0; x < dst.cols; ++x)
00122 {
00123 memcpy(dst_pixel, src_pixel, N);
00124 src_pixel += src_pixel_step;
00125 dst_pixel += N;
00126 }
00127 src_row += src_row_step;
00128 dst_row += dst_row_step;
00129 }
00130 }
00131
00132 void CropDecimateNodelet::imageCb(const sensor_msgs::ImageConstPtr& image_msg,
00133 const sensor_msgs::CameraInfoConstPtr& info_msg)
00134 {
00137
00138 Config config;
00139 {
00140 boost::lock_guard<boost::recursive_mutex> lock(config_mutex_);
00141 config = config_;
00142 }
00143 int decimation_x = config.decimation_x;
00144 int decimation_y = config.decimation_y;
00145
00146
00147 bool is_bayer = sensor_msgs::image_encodings::isBayer(image_msg->encoding);
00148 if (is_bayer)
00149 {
00150
00151
00152 config.x_offset &= ~0x1;
00153 config.y_offset &= ~0x1;
00154 config.width &= ~0x1;
00155 config.height &= ~0x1;
00156 }
00157
00158 int max_width = image_msg->width - config.x_offset;
00159 int max_height = image_msg->height - config.y_offset;
00160 int width = config.width;
00161 int height = config.height;
00162 if (width == 0 || width > max_width)
00163 width = max_width;
00164 if (height == 0 || height > max_height)
00165 height = max_height;
00166
00167
00168 if (decimation_x == 1 &&
00169 decimation_y == 1 &&
00170 config.x_offset == 0 &&
00171 config.y_offset == 0 &&
00172 width == (int)image_msg->width &&
00173 height == (int)image_msg->height)
00174 {
00175 pub_.publish(image_msg, info_msg);
00176 return;
00177 }
00178
00179
00180 CvImageConstPtr source = toCvShare(image_msg);
00181
00182
00183 CvImage output(source->header, source->encoding);
00184
00185 output.image = source->image(cv::Rect(config.x_offset, config.y_offset, width, height));
00186
00187
00188 if (is_bayer && (decimation_x > 1 || decimation_y > 1))
00189 {
00190 if (decimation_x % 2 != 0 || decimation_y % 2 != 0)
00191 {
00192 NODELET_ERROR_THROTTLE(2, "Odd decimation not supported for Bayer images");
00193 return;
00194 }
00195
00196 cv::Mat bgr;
00197 int step = output.image.step1();
00198 if (image_msg->encoding == sensor_msgs::image_encodings::BAYER_RGGB8)
00199 debayer2x2toBGR<uint8_t>(output.image, bgr, 0, 1, step, step + 1);
00200 else if (image_msg->encoding == sensor_msgs::image_encodings::BAYER_BGGR8)
00201 debayer2x2toBGR<uint8_t>(output.image, bgr, step + 1, 1, step, 0);
00202 else if (image_msg->encoding == sensor_msgs::image_encodings::BAYER_GBRG8)
00203 debayer2x2toBGR<uint8_t>(output.image, bgr, step, 0, step + 1, 1);
00204 else if (image_msg->encoding == sensor_msgs::image_encodings::BAYER_GRBG8)
00205 debayer2x2toBGR<uint8_t>(output.image, bgr, 1, 0, step + 1, step);
00206 else if (image_msg->encoding == sensor_msgs::image_encodings::BAYER_RGGB16)
00207 debayer2x2toBGR<uint16_t>(output.image, bgr, 0, 1, step, step + 1);
00208 else if (image_msg->encoding == sensor_msgs::image_encodings::BAYER_BGGR16)
00209 debayer2x2toBGR<uint16_t>(output.image, bgr, step + 1, 1, step, 0);
00210 else if (image_msg->encoding == sensor_msgs::image_encodings::BAYER_GBRG16)
00211 debayer2x2toBGR<uint16_t>(output.image, bgr, step, 0, step + 1, 1);
00212 else if (image_msg->encoding == sensor_msgs::image_encodings::BAYER_GRBG16)
00213 debayer2x2toBGR<uint16_t>(output.image, bgr, 1, 0, step + 1, step);
00214 else
00215 {
00216 NODELET_ERROR_THROTTLE(2, "Unrecognized Bayer encoding '%s'", image_msg->encoding.c_str());
00217 return;
00218 }
00219
00220 output.image = bgr;
00221 output.encoding = (bgr.depth() == CV_8U) ? sensor_msgs::image_encodings::BGR8
00222 : sensor_msgs::image_encodings::BGR16;
00223 decimation_x /= 2;
00224 decimation_y /= 2;
00225 }
00226
00227
00228 if (decimation_x > 1 || decimation_y > 1)
00229 {
00230 cv::Mat decimated;
00231
00232 if (config.interpolation == image_proc::CropDecimate_NN)
00233 {
00234
00235 int pixel_size = output.image.elemSize();
00236 switch (pixel_size)
00237 {
00238
00239 case 1:
00240 decimate<1>(output.image, decimated, decimation_x, decimation_y);
00241 break;
00242 case 2:
00243 decimate<2>(output.image, decimated, decimation_x, decimation_y);
00244 break;
00245 case 3:
00246 decimate<3>(output.image, decimated, decimation_x, decimation_y);
00247 break;
00248 case 4:
00249 decimate<4>(output.image, decimated, decimation_x, decimation_y);
00250 break;
00251 case 6:
00252 decimate<6>(output.image, decimated, decimation_x, decimation_y);
00253 break;
00254 case 8:
00255 decimate<8>(output.image, decimated, decimation_x, decimation_y);
00256 break;
00257 case 12:
00258 decimate<12>(output.image, decimated, decimation_x, decimation_y);
00259 break;
00260 case 16:
00261 decimate<16>(output.image, decimated, decimation_x, decimation_y);
00262 break;
00263 default:
00264 NODELET_ERROR_THROTTLE(2, "Unsupported pixel size, %d bytes", pixel_size);
00265 return;
00266 }
00267 }
00268 else
00269 {
00270
00271 cv::Size size(output.image.cols / decimation_x, output.image.rows / decimation_y);
00272 cv::resize(output.image, decimated, size, 0.0, 0.0, config.interpolation);
00273 }
00274
00275 output.image = decimated;
00276 }
00277
00278
00280 sensor_msgs::ImagePtr out_image = output.toImageMsg();
00281
00282
00283 sensor_msgs::CameraInfoPtr out_info = boost::make_shared<sensor_msgs::CameraInfo>(*info_msg);
00284 int binning_x = std::max((int)info_msg->binning_x, 1);
00285 int binning_y = std::max((int)info_msg->binning_y, 1);
00286 out_info->binning_x = binning_x * config.decimation_x;
00287 out_info->binning_y = binning_y * config.decimation_y;
00288 out_info->roi.x_offset += config.x_offset * binning_x;
00289 out_info->roi.y_offset += config.y_offset * binning_y;
00290 out_info->roi.height = height * binning_y;
00291 out_info->roi.width = width * binning_x;
00292
00293 if (width != (int)image_msg->width || height != (int)image_msg->height)
00294 out_info->roi.do_rectify = true;
00295
00296 pub_.publish(out_image, out_info);
00297 }
00298
00299 void CropDecimateNodelet::configCb(Config &config, uint32_t level)
00300 {
00301 config_ = config;
00302 }
00303
00304 }
00305
00306
00307 #include <pluginlib/class_list_macros.h>
00308 PLUGINLIB_DECLARE_CLASS(image_proc, crop_decimate, image_proc::CropDecimateNodelet, nodelet::Nodelet)