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> 85 typedef stereo_image_proc::DisparityConfig
Config;
93 virtual void onInit();
97 void imageCb(
const ImageConstPtr& l_image_msg,
const CameraInfoConstPtr& l_info_msg,
98 const ImageConstPtr& r_image_msg,
const CameraInfoConstPtr& r_info_msg);
100 void configCb(Config &config, uint32_t level);
113 private_nh.
param(
"queue_size", queue_size, 5);
115 private_nh.
param(
"approximate_sync", approx,
false);
119 sub_l_image_, sub_l_info_,
120 sub_r_image_, sub_r_info_) );
122 this, _1, _2, _3, _4));
127 sub_l_image_, sub_l_info_,
128 sub_r_image_, sub_r_info_) );
130 this, _1, _2, _3, _4));
137 reconfigure_server_->setCallback(f);
142 boost::lock_guard<boost::mutex> lock(connect_mutex_);
143 pub_disparity_ = nh.
advertise<DisparityImage>(
"disparity", 1, connect_cb, connect_cb);
149 boost::lock_guard<boost::mutex> lock(connect_mutex_);
150 if (pub_disparity_.getNumSubscribers() == 0)
152 sub_l_image_.unsubscribe();
153 sub_l_info_ .unsubscribe();
154 sub_r_image_.unsubscribe();
155 sub_r_info_ .unsubscribe();
157 else if (!sub_l_image_.getSubscriber())
163 sub_l_image_.subscribe(*it_,
"left/image_rect", 1, hints);
164 sub_l_info_ .subscribe(nh,
"left/camera_info", 1);
165 sub_r_image_.subscribe(*it_,
"right/image_rect", 1, hints);
166 sub_r_info_ .subscribe(nh,
"right/camera_info", 1);
171 const CameraInfoConstPtr& l_info_msg,
172 const ImageConstPtr& r_image_msg,
173 const CameraInfoConstPtr& r_info_msg)
176 model_.fromCameraInfo(l_info_msg, r_info_msg);
179 DisparityImagePtr disp_msg = boost::make_shared<DisparityImage>();
180 disp_msg->header = l_info_msg->header;
181 disp_msg->image.header = l_info_msg->header;
184 int border = block_matcher_.getCorrelationWindowSize() / 2;
185 int left = block_matcher_.getDisparityRange() + block_matcher_.getMinDisparity() + border - 1;
186 int wtf = (block_matcher_.getMinDisparity() >= 0) ? border + block_matcher_.getMinDisparity() : std::max(border, -block_matcher_.getMinDisparity());
187 int right = disp_msg->image.width - 1 - wtf;
189 int bottom = disp_msg->image.height - 1 - border;
190 disp_msg->valid_window.x_offset = left;
191 disp_msg->valid_window.y_offset = top;
192 disp_msg->valid_window.width = right - left;
193 disp_msg->valid_window.height = bottom - top;
200 block_matcher_.processDisparity(l_image, r_image, model_, *disp_msg);
203 double cx_l = model_.left().cx();
204 double cx_r = model_.right().cx();
206 cv::Mat_<float> disp_image(disp_msg->image.height, disp_msg->image.width,
207 reinterpret_cast<float*>(&disp_msg->image.data[0]),
208 disp_msg->image.step);
209 cv::subtract(disp_image, cv::Scalar(cx_l - cx_r), disp_image);
212 pub_disparity_.publish(disp_msg);
218 config.prefilter_size |= 0x1;
219 config.correlation_window_size |= 0x1;
220 config.disparity_range = (config.disparity_range / 16) * 16;
225 block_matcher_.setPreFilterCap(config.prefilter_cap);
226 block_matcher_.setCorrelationWindowSize(config.correlation_window_size);
227 block_matcher_.setMinDisparity(config.min_disparity);
228 block_matcher_.setDisparityRange(config.disparity_range);
229 block_matcher_.setUniquenessRatio(config.uniqueness_ratio);
230 block_matcher_.setSpeckleSize(config.speckle_size);
231 block_matcher_.setSpeckleRange(config.speckle_range);
232 if (config.stereo_algorithm == stereo_image_proc::Disparity_StereoBM) {
234 block_matcher_.setPreFilterSize(config.prefilter_size);
235 block_matcher_.setTextureThreshold(config.texture_threshold);
237 else if (config.stereo_algorithm == stereo_image_proc::Disparity_StereoSGBM) {
239 block_matcher_.setSgbmMode(config.fullDP);
240 block_matcher_.setP1(config.P1);
241 block_matcher_.setP2(config.P2);
242 block_matcher_.setDisp12MaxDiff(config.disp12MaxDiff);
boost::mutex connect_mutex_
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
ExactTime< Image, CameraInfo, Image, CameraInfo > ExactPolicy
boost::shared_ptr< ReconfigureServer > reconfigure_server_
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
ros::Publisher pub_disparity_
ApproximateTime< Image, CameraInfo, Image, CameraInfo > ApproximatePolicy
void imageCb(const ImageConstPtr &l_image_msg, const CameraInfoConstPtr &l_info_msg, const ImageConstPtr &r_image_msg, const CameraInfoConstPtr &r_info_msg)
boost::shared_ptr< ExactSync > exact_sync_
boost::shared_ptr< image_transport::ImageTransport > it_
image_geometry::StereoCameraModel model_
dynamic_reconfigure::Server< Config > ReconfigureServer
message_filters::Synchronizer< ExactPolicy > ExactSync
boost::recursive_mutex config_mutex_
message_filters::Synchronizer< ApproximatePolicy > ApproximateSync
PLUGINLIB_EXPORT_CLASS(image_proc::CropNonZeroNodelet, nodelet::Nodelet)
message_filters::Subscriber< CameraInfo > sub_r_info_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
stereo_image_proc::StereoProcessor block_matcher_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
stereo_image_proc::DisparityConfig Config
image_transport::SubscriberFilter sub_r_image_
boost::shared_ptr< ApproximateSync > approximate_sync_
void configCb(Config &config, uint32_t level)