34 #include <boost/version.hpp>
35 #if ((BOOST_VERSION / 100) % 1000) >= 53
36 #include <boost/thread/lock_guard.hpp>
49 #include <opencv2/calib3d/calib3d.hpp>
53 #include <stereo_msgs/DisparityImage.h>
55 #include <stereo_image_proc/DisparityConfig.h>
56 #include <dynamic_reconfigure/server.h>
63 using namespace stereo_msgs;
80 boost::mutex connect_mutex_;
84 boost::recursive_mutex config_mutex_;
85 typedef stereo_image_proc::DisparityConfig Config;
86 typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
88 int downsampling_factor_;
94 virtual void onInit();
98 void imageCb(
const ImageConstPtr& l_image_msg,
const CameraInfoConstPtr& l_info_msg,
99 const ImageConstPtr& r_image_msg,
const CameraInfoConstPtr& r_info_msg);
101 void configCb(
Config &config, uint32_t level);
114 private_nh.
param(
"queue_size", queue_size, 5);
116 private_nh.
param(
"approximate_sync", approx,
false);
117 private_nh.
param(
"downsampling_factor", downsampling_factor_, 1);
121 sub_l_image_, sub_l_info_,
122 sub_r_image_, sub_r_info_) );
124 this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
128 exact_sync_.reset(
new ExactSync(ExactPolicy(queue_size),
129 sub_l_image_, sub_l_info_,
130 sub_r_image_, sub_r_info_) );
132 this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
137 this, boost::placeholders::_1, boost::placeholders::_2);
139 reconfigure_server_->setCallback(f);
144 boost::lock_guard<boost::mutex> lock(connect_mutex_);
145 pub_disparity_ = nh.
advertise<DisparityImage>(
"disparity", 1, connect_cb, connect_cb);
151 boost::lock_guard<boost::mutex> lock(connect_mutex_);
152 if (pub_disparity_.getNumSubscribers() == 0)
154 sub_l_image_.unsubscribe();
155 sub_l_info_ .unsubscribe();
156 sub_r_image_.unsubscribe();
157 sub_r_info_ .unsubscribe();
159 else if (!sub_l_image_.getSubscriber())
165 sub_l_image_.subscribe(*it_,
"left/image_rect", 1, hints);
166 sub_l_info_ .subscribe(nh,
"left/camera_info", 1);
167 sub_r_image_.subscribe(*it_,
"right/image_rect", 1, hints);
168 sub_r_info_ .subscribe(nh,
"right/camera_info", 1);
173 const cv::Mat& input_image,
174 const uint32_t downsample_factor_per_dimension) {
175 cv::Mat blurred_image;
176 const int32_t kernel_size = 2 * downsample_factor_per_dimension + 1;
178 input_image, blurred_image, cv::Size(kernel_size, kernel_size),
179 downsample_factor_per_dimension);
183 uint32_t downsampled_height = std::ceil(
184 input_image.size().height /
185 static_cast<double>(downsample_factor_per_dimension));
186 uint32_t downsampled_width = std::ceil(
187 input_image.size().width /
188 static_cast<double>(downsample_factor_per_dimension));
189 cv::Mat downsampled_image(
190 downsampled_height, downsampled_width, input_image.type());
192 for (uint32_t destination_row = 0u;
193 destination_row < downsampled_image.size().height; destination_row++) {
194 for (uint32_t destination_col = 0u;
195 destination_col < downsampled_image.size().width; destination_col++) {
196 downsampled_image.at<uint8_t>(destination_row, destination_col) =
197 blurred_image.at<uint8_t>(
198 destination_row * downsample_factor_per_dimension,
199 destination_col * downsample_factor_per_dimension);
202 return downsampled_image;
206 const cv::Mat& disparity,
const cv::Size& destination_size,
207 const uint32_t upsample_factor_per_dimension) {
208 cv::Mat upsampled_disparity(destination_size, disparity.type(), -1.);
210 for (uint32_t destination_row = 0u;
211 destination_row < upsampled_disparity.size().height; destination_row++) {
212 for (uint32_t destination_col = 0u;
213 destination_col < upsampled_disparity.size().width;
215 upsampled_disparity.at<
float>(destination_row, destination_col) =
216 upsample_factor_per_dimension *
218 destination_row / upsample_factor_per_dimension,
219 destination_col / upsample_factor_per_dimension);
222 return upsampled_disparity;
226 const CameraInfoConstPtr& l_info_msg,
227 const ImageConstPtr& r_image_msg,
228 const CameraInfoConstPtr& r_info_msg)
231 model_.fromCameraInfo(l_info_msg, r_info_msg);
234 DisparityImagePtr disp_msg = boost::make_shared<DisparityImage>();
235 disp_msg->header = l_info_msg->header;
236 disp_msg->header.frame_id = l_image_msg->header.frame_id;
237 disp_msg->image.header = l_info_msg->header;
238 disp_msg->image.header.frame_id = l_image_msg->header.frame_id;
241 int border = block_matcher_.getCorrelationWindowSize() / 2;
242 int left = block_matcher_.getDisparityRange() + block_matcher_.getMinDisparity() + border - 1;
243 int wtf = (block_matcher_.getMinDisparity() >= 0) ? border + block_matcher_.getMinDisparity() : std::max(border, -block_matcher_.getMinDisparity());
244 int right = disp_msg->image.width - 1 - wtf;
246 int bottom = disp_msg->image.height - 1 - border;
247 disp_msg->valid_window.x_offset = left;
248 disp_msg->valid_window.y_offset = top;
249 disp_msg->valid_window.width = right - left;
250 disp_msg->valid_window.height = bottom - top;
256 cv::Mat_<uint8_t> l_sub_image;
257 cv::Mat_<uint8_t> r_sub_image;
259 if (downsampling_factor_ != 1) {
263 l_sub_image = l_image;
264 r_sub_image = r_image;
268 block_matcher_.processDisparity(l_sub_image, r_sub_image, model_, *disp_msg);
271 if (downsampling_factor_ != 1) {
272 const cv::Mat disp_subsampled_image =
276 const cv::Mat disp_upsampled_image =
278 disp_subsampled_image, l_image.size(), downsampling_factor_);
281 disp_upsampled_image);
282 disp_image_container.
toImageMsg(disp_msg->image);
286 double cx_l = model_.left().cx();
287 double cx_r = model_.right().cx();
289 cv::Mat_<float> disp_image(disp_msg->image.height, disp_msg->image.width,
290 reinterpret_cast<float*
>(&disp_msg->image.data[0]),
291 disp_msg->image.step);
292 cv::subtract(disp_image, cv::Scalar(cx_l - cx_r), disp_image);
295 pub_disparity_.publish(disp_msg);
301 config.prefilter_size |= 0x1;
302 config.correlation_window_size |= 0x1;
303 config.disparity_range = (config.disparity_range / 16) * 16;
308 block_matcher_.setPreFilterCap(config.prefilter_cap);
309 block_matcher_.setCorrelationWindowSize(config.correlation_window_size);
310 block_matcher_.setMinDisparity(config.min_disparity);
311 block_matcher_.setDisparityRange(config.disparity_range);
312 block_matcher_.setUniquenessRatio(config.uniqueness_ratio);
313 block_matcher_.setSpeckleSize(config.speckle_size);
314 block_matcher_.setSpeckleRange(config.speckle_range);
315 if (config.stereo_algorithm == stereo_image_proc::Disparity_StereoBM) {
317 block_matcher_.setPreFilterSize(config.prefilter_size);
318 block_matcher_.setTextureThreshold(config.texture_threshold);
320 else if (config.stereo_algorithm == stereo_image_proc::Disparity_StereoSGBM) {
322 block_matcher_.setSgbmMode(config.fullDP);
323 block_matcher_.setP1(config.P1);
324 block_matcher_.setP2(config.P2);
325 block_matcher_.setDisp12MaxDiff(config.disp12MaxDiff);