00001 #include <ros/ros.h>
00002 #include <nodelet/nodelet.h>
00003 #include <image_transport/image_transport.h>
00004 #include <image_transport/subscriber_filter.h>
00005 #include <message_filters/subscriber.h>
00006 #include <message_filters/synchronizer.h>
00007 #include <message_filters/sync_policies/exact_time.h>
00008 #include <message_filters/sync_policies/approximate_time.h>
00009 #include <image_proc/advertisement_checker.h>
00010
00011 #include <image_geometry/stereo_camera_model.h>
00012 #include <opencv2/calib3d/calib3d.hpp>
00013
00014 #include <sensor_msgs/image_encodings.h>
00015 #include <stereo_msgs/DisparityImage.h>
00016
00017 #include <stereo_image_proc/DisparityConfig.h>
00018 #include <dynamic_reconfigure/server.h>
00019
00020 namespace stereo_image_proc {
00021
00022 using namespace sensor_msgs;
00023 using namespace stereo_msgs;
00024 using namespace message_filters::sync_policies;
00025
00026 class DisparityNodelet : public nodelet::Nodelet
00027 {
00028 boost::shared_ptr<image_transport::ImageTransport> it_;
00029
00030
00031 image_transport::SubscriberFilter sub_l_image_, sub_r_image_;
00032 message_filters::Subscriber<CameraInfo> sub_l_info_, sub_r_info_;
00033 typedef ExactTime<Image, CameraInfo, Image, CameraInfo> ExactPolicy;
00034 typedef ApproximateTime<Image, CameraInfo, Image, CameraInfo> ApproximatePolicy;
00035 typedef message_filters::Synchronizer<ExactPolicy> ExactSync;
00036 typedef message_filters::Synchronizer<ApproximatePolicy> ApproximateSync;
00037 boost::shared_ptr<ExactSync> exact_sync_;
00038 boost::shared_ptr<ApproximateSync> approximate_sync_;
00039 bool subscribed_;
00040
00041
00042 ros::Publisher pub_disparity_;
00043
00044
00045 typedef stereo_image_proc::DisparityConfig Config;
00046 typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00047 boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00048
00049
00050 image_geometry::StereoCameraModel model_;
00051 cv::StereoBM block_matcher_;
00052
00053
00054 boost::shared_ptr<image_proc::AdvertisementChecker> check_inputs_;
00055
00056 virtual void onInit();
00057
00058 void connectCb();
00059
00060 void imageCb(const ImageConstPtr& l_image_msg, const CameraInfoConstPtr& l_info_msg,
00061 const ImageConstPtr& r_image_msg, const CameraInfoConstPtr& r_info_msg);
00062
00063 void configCallback(Config &config, uint32_t level);
00064 };
00065
00066 void DisparityNodelet::onInit()
00067 {
00068 ros::NodeHandle &nh = getNodeHandle();
00069 ros::NodeHandle &private_nh = getPrivateNodeHandle();
00070
00071 it_.reset(new image_transport::ImageTransport(nh));
00072
00073
00074 subscribed_ = false;
00075 ros::SubscriberStatusCallback connect_cb = boost::bind(&DisparityNodelet::connectCb, this);
00076 pub_disparity_ = nh.advertise<DisparityImage>("disparity", 1,
00077 connect_cb, connect_cb);
00078
00079
00080
00081 int queue_size;
00082 private_nh.param("queue_size", queue_size, 5);
00083 bool approx;
00084 private_nh.param("approximate_sync", approx, false);
00085 if (approx)
00086 {
00087 approximate_sync_.reset( new ApproximateSync(ApproximatePolicy(queue_size),
00088 sub_l_image_, sub_l_info_,
00089 sub_r_image_, sub_r_info_) );
00090 approximate_sync_->registerCallback(boost::bind(&DisparityNodelet::imageCb,
00091 this, _1, _2, _3, _4));
00092 }
00093 else
00094 {
00095 exact_sync_.reset( new ExactSync(ExactPolicy(queue_size),
00096 sub_l_image_, sub_l_info_,
00097 sub_r_image_, sub_r_info_) );
00098 exact_sync_->registerCallback(boost::bind(&DisparityNodelet::imageCb,
00099 this, _1, _2, _3, _4));
00100 }
00101
00102
00103 ReconfigureServer::CallbackType f = boost::bind(&DisparityNodelet::configCallback,
00104 this, _1, _2);
00105 reconfigure_server_.reset(new ReconfigureServer(private_nh));
00106 reconfigure_server_->setCallback(f);
00107
00108
00109 const std::vector<std::string>& argv = getMyArgv();
00110 bool do_input_checks = std::find(argv.begin(), argv.end(),
00111 "--no-input-checks") == argv.end();
00112
00113
00114 if (do_input_checks)
00115 {
00116 ros::V_string topics;
00117 topics.push_back("left/image_rect");
00118 topics.push_back("left/camera_info");
00119 topics.push_back("right/image_rect");
00120 topics.push_back("right/camera_info");
00121 check_inputs_.reset( new image_proc::AdvertisementChecker(nh, getName()) );
00122 check_inputs_->start(topics, 60.0);
00123 }
00124 }
00125
00126
00127 void DisparityNodelet::connectCb()
00128 {
00129 if (pub_disparity_.getNumSubscribers() == 0)
00130 {
00131 sub_l_image_.unsubscribe();
00132 sub_l_info_ .unsubscribe();
00133 sub_r_image_.unsubscribe();
00134 sub_r_info_ .unsubscribe();
00135 subscribed_ = false;
00136 }
00137 else if (!subscribed_)
00138 {
00139 ros::NodeHandle &nh = getNodeHandle();
00140
00141 sub_l_image_.subscribe(*it_, "left/image_rect", 1);
00142 sub_l_info_ .subscribe(nh, "left/camera_info", 1);
00143 sub_r_image_.subscribe(*it_, "right/image_rect", 1);
00144 sub_r_info_ .subscribe(nh, "right/camera_info", 1);
00145 subscribed_ = true;
00146 }
00147 }
00148
00149 void DisparityNodelet::imageCb(const ImageConstPtr& l_image_msg,
00150 const CameraInfoConstPtr& l_info_msg,
00151 const ImageConstPtr& r_image_msg,
00152 const CameraInfoConstPtr& r_info_msg)
00153 {
00155 assert(l_image_msg->encoding == sensor_msgs::image_encodings::MONO8);
00156 assert(r_image_msg->encoding == sensor_msgs::image_encodings::MONO8);
00157
00158
00159 model_.fromCameraInfo(l_info_msg, r_info_msg);
00160
00161
00162 DisparityImagePtr disp_msg = boost::make_shared<DisparityImage>();
00163 disp_msg->header = l_info_msg->header;
00164 disp_msg->image.header = l_info_msg->header;
00165 disp_msg->image.height = l_image_msg->height;
00166 disp_msg->image.width = l_image_msg->width;
00167 disp_msg->image.encoding = sensor_msgs::image_encodings::TYPE_32FC1;
00168 disp_msg->image.step = disp_msg->image.width * sizeof(float);
00169 disp_msg->image.data.resize(disp_msg->image.height * disp_msg->image.step);
00170
00171
00172 disp_msg->f = model_.right().fx();
00173 disp_msg->T = model_.baseline();
00174
00175
00176 cv::Ptr<CvStereoBMState> params = block_matcher_.state;
00177 int border = params->SADWindowSize / 2;
00178 int left = params->numberOfDisparities + params->minDisparity + border - 1;
00179 int wtf = (params->minDisparity >= 0) ? border + params->minDisparity : std::max(border, -params->minDisparity);
00180 int right = disp_msg->image.width - 1 - wtf;
00181 int top = border;
00182 int bottom = disp_msg->image.height - 1 - border;
00183 disp_msg->valid_window.x_offset = left;
00184 disp_msg->valid_window.y_offset = top;
00185 disp_msg->valid_window.width = right - left;
00186 disp_msg->valid_window.height = bottom - top;
00187
00188
00189 disp_msg->min_disparity = params->minDisparity;
00190 disp_msg->max_disparity = params->minDisparity + params->numberOfDisparities - 1;
00191 disp_msg->delta_d = 1.0 / 16;
00192
00193
00194 const cv::Mat_<uint8_t> l_image(l_image_msg->height, l_image_msg->width,
00195 const_cast<uint8_t*>(&l_image_msg->data[0]),
00196 l_image_msg->step);
00197 const cv::Mat_<uint8_t> r_image(r_image_msg->height, r_image_msg->width,
00198 const_cast<uint8_t*>(&r_image_msg->data[0]),
00199 r_image_msg->step);
00200 cv::Mat_<float> disp_image(disp_msg->image.height, disp_msg->image.width,
00201 reinterpret_cast<float*>(&disp_msg->image.data[0]),
00202 disp_msg->image.step);
00203
00204
00205 block_matcher_(l_image, r_image, disp_image, CV_32F);
00206
00207
00208 double cx_l = model_.left().cx();
00209 double cx_r = model_.right().cx();
00210 if (cx_l != cx_r)
00211 cv::subtract(disp_image, cv::Scalar(cx_l - cx_r), disp_image);
00212
00213 pub_disparity_.publish(disp_msg);
00214 }
00215
00216 void DisparityNodelet::configCallback(Config &config, uint32_t level)
00217 {
00218
00219 config.prefilter_size |= 0x1;
00220 config.correlation_window_size |= 0x1;
00221 config.disparity_range = (config.disparity_range / 16) * 16;
00222
00223 block_matcher_.state->preFilterSize = config.prefilter_size;
00224 block_matcher_.state->preFilterCap = config.prefilter_cap;
00225 block_matcher_.state->SADWindowSize = config.correlation_window_size;
00226 block_matcher_.state->minDisparity = config.min_disparity;
00227 block_matcher_.state->numberOfDisparities = config.disparity_range;
00228 block_matcher_.state->uniquenessRatio = config.uniqueness_ratio;
00229 block_matcher_.state->textureThreshold = config.texture_threshold;
00230 block_matcher_.state->speckleWindowSize = config.speckle_size;
00231 block_matcher_.state->speckleRange = config.speckle_range;
00232 }
00233
00234 }
00235
00236
00237 #include <pluginlib/class_list_macros.h>
00238 PLUGINLIB_DECLARE_CLASS(stereo_image_proc, disparity,
00239 stereo_image_proc::DisparityNodelet, nodelet::Nodelet)