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