34 #include <boost/version.hpp> 35 #if ((BOOST_VERSION / 100) % 1000) >= 53 36 #include <boost/thread/lock_guard.hpp> 43 #include <dynamic_reconfigure/server.h> 45 #include <image_proc/CropDecimateConfig.h> 46 #include <opencv2/imgproc/imgproc.hpp> 65 typedef image_proc::CropDecimateConfig
Config;
70 virtual void onInit();
74 void imageCb(
const sensor_msgs::ImageConstPtr& image_msg,
75 const sensor_msgs::CameraInfoConstPtr& info_msg);
77 void configCb(Config &config, uint32_t level);
90 private_nh.
param(
"queue_size", queue_size_, 5);
91 private_nh.
param(
"target_frame_id", target_frame_id_, std::string());
96 reconfigure_server_->setCallback(f);
102 boost::lock_guard<boost::mutex> lock(connect_mutex_);
103 pub_ = it_out_->advertiseCamera(
"image_raw", 1, connect_cb, connect_cb, connect_cb_info, connect_cb_info);
109 boost::lock_guard<boost::mutex> lock(connect_mutex_);
110 if (pub_.getNumSubscribers() == 0)
119 template <
typename T>
122 typedef cv::Vec<T, 3> DstPixel;
123 dst.create(src.rows / 2, src.cols / 2, cv::DataType<DstPixel>::type);
125 int src_row_step = src.step1();
126 int dst_row_step = dst.step1();
127 const T* src_row = src.ptr<T>();
128 T* dst_row = dst.ptr<T>();
131 for (
int y = 0; y < dst.rows; ++y)
133 for (
int x = 0; x < dst.cols; ++x)
135 dst_row[x*3 + 0] = src_row[x*2 + B];
136 dst_row[x*3 + 1] = (src_row[x*2 + G1] + src_row[x*2 + G2]) / 2;
137 dst_row[x*3 + 2] = src_row[x*2 + R];
139 src_row += src_row_step * 2;
140 dst_row += dst_row_step;
146 void decimate(
const cv::Mat& src, cv::Mat& dst,
int decimation_x,
int decimation_y)
148 dst.create(src.rows / decimation_y, src.cols / decimation_x, src.type());
150 int src_row_step = src.step[0] * decimation_y;
151 int src_pixel_step = N * decimation_x;
152 int dst_row_step = dst.step[0];
154 const uint8_t* src_row = src.ptr();
155 uint8_t* dst_row = dst.ptr();
157 for (
int y = 0; y < dst.rows; ++y)
159 const uint8_t* src_pixel = src_row;
160 uint8_t* dst_pixel = dst_row;
161 for (
int x = 0; x < dst.cols; ++x)
163 memcpy(dst_pixel, src_pixel, N);
164 src_pixel += src_pixel_step;
167 src_row += src_row_step;
168 dst_row += dst_row_step;
173 const sensor_msgs::CameraInfoConstPtr& info_msg)
180 boost::lock_guard<boost::recursive_mutex> lock(config_mutex_);
183 int decimation_x = config.decimation_x;
184 int decimation_y = config.decimation_y;
192 config.x_offset &= ~0x1;
193 config.y_offset &= ~0x1;
194 config.width &= ~0x1;
195 config.height &= ~0x1;
198 int max_width = image_msg->width - config.x_offset;
199 int max_height = image_msg->height - config.y_offset;
200 int width = config.width;
201 int height = config.height;
202 if (width == 0 || width > max_width)
204 if (height == 0 || height > max_height)
208 if (decimation_x == 1 &&
210 config.x_offset == 0 &&
211 config.y_offset == 0 &&
212 width == (
int)image_msg->width &&
213 height == (
int)image_msg->height)
215 pub_.publish(image_msg, info_msg);
223 CvImage output(source->header, source->encoding);
225 output.
image = source->image(cv::Rect(config.x_offset, config.y_offset, width, height));
228 if (is_bayer && (decimation_x > 1 || decimation_y > 1))
230 if (decimation_x % 2 != 0 || decimation_y % 2 != 0)
237 int step = output.
image.step1();
239 debayer2x2toBGR<uint8_t>(output.
image, bgr, 0, 1, step, step + 1);
241 debayer2x2toBGR<uint8_t>(output.
image, bgr, step + 1, 1, step, 0);
243 debayer2x2toBGR<uint8_t>(output.
image, bgr, step, 0, step + 1, 1);
245 debayer2x2toBGR<uint8_t>(output.
image, bgr, 1, 0, step + 1, step);
247 debayer2x2toBGR<uint16_t>(output.
image, bgr, 0, 1, step, step + 1);
249 debayer2x2toBGR<uint16_t>(output.
image, bgr, step + 1, 1, step, 0);
251 debayer2x2toBGR<uint16_t>(output.
image, bgr, step, 0, step + 1, 1);
253 debayer2x2toBGR<uint16_t>(output.
image, bgr, 1, 0, step + 1, step);
268 if (decimation_x > 1 || decimation_y > 1)
272 if (config.interpolation == image_proc::CropDecimate_NN)
275 int pixel_size = output.
image.elemSize();
280 decimate<1>(output.
image, decimated, decimation_x, decimation_y);
283 decimate<2>(output.
image, decimated, decimation_x, decimation_y);
286 decimate<3>(output.
image, decimated, decimation_x, decimation_y);
289 decimate<4>(output.
image, decimated, decimation_x, decimation_y);
292 decimate<6>(output.
image, decimated, decimation_x, decimation_y);
295 decimate<8>(output.
image, decimated, decimation_x, decimation_y);
298 decimate<12>(output.
image, decimated, decimation_x, decimation_y);
301 decimate<16>(output.
image, decimated, decimation_x, decimation_y);
311 cv::Size size(output.
image.cols / decimation_x, output.
image.rows / decimation_y);
312 cv::resize(output.
image, decimated, size, 0.0, 0.0, config.interpolation);
315 output.
image = decimated;
320 sensor_msgs::ImagePtr out_image = output.
toImageMsg();
323 sensor_msgs::CameraInfoPtr out_info = boost::make_shared<sensor_msgs::CameraInfo>(*info_msg);
324 int binning_x = std::max((
int)info_msg->binning_x, 1);
325 int binning_y = std::max((
int)info_msg->binning_y, 1);
326 out_info->binning_x = binning_x * config.decimation_x;
327 out_info->binning_y = binning_y * config.decimation_y;
328 out_info->roi.x_offset += config.x_offset * binning_x;
329 out_info->roi.y_offset += config.y_offset * binning_y;
330 out_info->roi.height = height * binning_y;
331 out_info->roi.width = width * binning_x;
333 if (width != (
int)image_msg->width || height != (
int)image_msg->height)
334 out_info->roi.do_rectify =
true;
336 if (!target_frame_id_.empty()) {
337 out_image->header.frame_id = target_frame_id_;
338 out_info->header.frame_id = target_frame_id_;
341 pub_.publish(out_image, out_info);
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
const std::string BAYER_GRBG8
const std::string BAYER_GRBG16
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
const std::string BAYER_RGGB16
static bool isBayer(const std::string &encoding)
#define NODELET_ERROR_THROTTLE(rate,...)
void debayer2x2toBGR(const cv::Mat &src, cv::Mat &dst, int R, int G1, int G2, int B)
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
void decimate(const cv::Mat &src, cv::Mat &dst, int decimation_x, int decimation_y)
void configCb(Config &config, uint32_t level)
std::string target_frame_id_
const std::string BAYER_GBRG8
const std::string BAYER_GBRG16
boost::shared_ptr< image_transport::ImageTransport > it_out_
const std::string BAYER_BGGR16
PLUGINLIB_EXPORT_CLASS(image_proc::CropNonZeroNodelet, nodelet::Nodelet)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
image_proc::CropDecimateConfig Config
boost::recursive_mutex config_mutex_
image_transport::CameraSubscriber sub_
dynamic_reconfigure::Server< Config > ReconfigureServer
const std::string BAYER_BGGR8
boost::shared_ptr< ReconfigureServer > reconfigure_server_
void imageCb(const sensor_msgs::ImageConstPtr &image_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
const std::string BAYER_RGGB8
image_transport::CameraPublisher pub_
boost::mutex connect_mutex_
sensor_msgs::ImagePtr toImageMsg() const