void StereoProcessor::processDisparity(const cv::Mat& left_rect, const cv::Mat& right_rect, const image_geometry::StereoCameraModel& model, stereo_msgs::DisparityImage& disparity) const { // Fixed-point disparity is 16 times the true value: d = d_fp / 16.0 = x_l - x_r. static const int DPP = 16; // disparities per pixel static const double inv_dpp = 1.0 / DPP; // Block matcher produces 16-bit signed (fixed point) disparity image block_matcher_(left_rect, right_rect, disparity16_); // Fill in DisparityImage image data, converting to 32-bit float sensor_msgs::Image& dimage = disparity.image; dimage.height = disparity16_.rows; dimage.width = disparity16_.cols; dimage.encoding = sensor_msgs::image_encodings::TYPE_32FC1; dimage.step = dimage.width * sizeof(float); dimage.data.resize(dimage.step * dimage.height); cv::Mat_<float> dmat(dimage.height, dimage.width, (float*)&dimage.data[0], dimage.step); // We convert from fixed-point to float disparity and also adjust for any x-offset between // the principal points: d = d_fp*inv_dpp - (cx_l - cx_r) disparity16_.convertTo(dmat, dmat.type(), inv_dpp, -(model.left().cx() - model.right().cx())); ROS_ASSERT(dmat.data == &dimage.data[0]); /// @todo is_bigendian? :) // Stereo parameters disparity.f = model.right().fx(); disparity.T = model.baseline(); /// @todo Window of (potentially) valid disparities // Disparity search range disparity.min_disparity = getMinDisparity(); disparity.max_disparity = getMinDisparity() + getDisparityRange() - 1; disparity.delta_d = inv_dpp; }
void DisparityWideNodelet::imageCb(const ImageConstPtr& l_image_msg, const CameraInfoConstPtr& l_info_msg, const ImageConstPtr& r_image_msg, const CameraInfoConstPtr& r_info_msg) { /// @todo Convert (share) with new cv_bridge assert(l_image_msg->encoding == sensor_msgs::image_encodings::MONO8); assert(r_image_msg->encoding == sensor_msgs::image_encodings::MONO8); // Update the camera model model_.fromCameraInfo(l_info_msg, r_info_msg); // Allocate new disparity image message DisparityImagePtr disp_msg = boost::make_shared<DisparityImage>(); disp_msg->header = l_info_msg->header; disp_msg->image.header = l_info_msg->header; disp_msg->image.height = l_image_msg->height; disp_msg->image.width = l_image_msg->width; disp_msg->image.encoding = sensor_msgs::image_encodings::TYPE_32FC1; disp_msg->image.step = disp_msg->image.width * sizeof(float); disp_msg->image.data.resize(disp_msg->image.height * disp_msg->image.step); // Stereo parameters disp_msg->f = model_.right().fx(); disp_msg->T = model_.baseline(); // Compute window of (potentially) valid disparities cv::Ptr<CvStereoBMState> params = block_matcher_.state; int border = params->SADWindowSize / 2; int left = params->numberOfDisparities + params->minDisparity + border - 1; int wtf = (params->minDisparity >= 0) ? border + params->minDisparity : std::max(border, -params->minDisparity); int right = disp_msg->image.width - 1 - wtf; int top = border; int bottom = disp_msg->image.height - 1 - border; disp_msg->valid_window.x_offset = left; disp_msg->valid_window.y_offset = top; disp_msg->valid_window.width = right - left; disp_msg->valid_window.height = bottom - top; // Disparity search range disp_msg->min_disparity = params->minDisparity; disp_msg->max_disparity = params->minDisparity + params->numberOfDisparities - 1; disp_msg->delta_d = 1.0 / 16; // OpenCV uses 16 disparities per pixel // Create cv::Mat views onto all buffers const cv::Mat_<uint8_t> l_image(l_image_msg->height, l_image_msg->width, const_cast<uint8_t*>(&l_image_msg->data[0]), l_image_msg->step); const cv::Mat_<uint8_t> r_image(r_image_msg->height, r_image_msg->width, const_cast<uint8_t*>(&r_image_msg->data[0]), r_image_msg->step); cv::Mat_<float> disp_image(disp_msg->image.height, disp_msg->image.width, reinterpret_cast<float*>(&disp_msg->image.data[0]), disp_msg->image.step); // Perform block matching to find the disparities block_matcher_(l_image, r_image, disp_image, CV_32F); // Adjust for any x-offset between the principal points: d' = d - (cx_l - cx_r) double cx_l = model_.left().cx(); double cx_r = model_.right().cx(); if (cx_l != cx_r) cv::subtract(disp_image, cv::Scalar(cx_l - cx_r), disp_image); pub_disparity_.publish(disp_msg); }