Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #include <rtabmap/core/StereoDense.h>
00029 #include <rtabmap/utilite/ULogger.h>
00030 #include <opencv2/calib3d/calib3d.hpp>
00031 #include <opencv2/imgproc/imgproc.hpp>
00032
00033 namespace rtabmap {
00034
00035 StereoBM::StereoBM(int blockSize, int numDisparities) :
00036 blockSize_(blockSize),
00037 minDisparity_(Parameters::defaultStereoBMMinDisparity()),
00038 numDisparities_(numDisparities),
00039 preFilterSize_(Parameters::defaultStereoBMPreFilterSize()),
00040 preFilterCap_(Parameters::defaultStereoBMPreFilterCap()),
00041 uniquenessRatio_(Parameters::defaultStereoBMUniquenessRatio()),
00042 textureThreshold_(Parameters::defaultStereoBMTextureThreshold()),
00043 speckleWindowSize_(Parameters::defaultStereoBMSpeckleWindowSize()),
00044 speckleRange_(Parameters::defaultStereoBMSpeckleRange())
00045 {
00046 }
00047 StereoBM::StereoBM(const ParametersMap & parameters) :
00048 StereoDense(parameters),
00049 blockSize_(Parameters::defaultStereoBMBlockSize()),
00050 minDisparity_(Parameters::defaultStereoBMMinDisparity()),
00051 numDisparities_(Parameters::defaultStereoBMNumDisparities()),
00052 preFilterSize_(Parameters::defaultStereoBMPreFilterSize()),
00053 preFilterCap_(Parameters::defaultStereoBMPreFilterCap()),
00054 uniquenessRatio_(Parameters::defaultStereoBMUniquenessRatio()),
00055 textureThreshold_(Parameters::defaultStereoBMTextureThreshold()),
00056 speckleWindowSize_(Parameters::defaultStereoBMSpeckleWindowSize()),
00057 speckleRange_(Parameters::defaultStereoBMSpeckleRange())
00058 {
00059 this->parseParameters(parameters);
00060 }
00061
00062 void StereoBM::parseParameters(const ParametersMap & parameters)
00063 {
00064 Parameters::parse(parameters, Parameters::kStereoBMBlockSize(), blockSize_);
00065 Parameters::parse(parameters, Parameters::kStereoBMMinDisparity(), minDisparity_);
00066 Parameters::parse(parameters, Parameters::kStereoBMNumDisparities(), numDisparities_);
00067 Parameters::parse(parameters, Parameters::kStereoBMPreFilterSize(), preFilterSize_);
00068 Parameters::parse(parameters, Parameters::kStereoBMPreFilterCap(), preFilterCap_);
00069 Parameters::parse(parameters, Parameters::kStereoBMUniquenessRatio(), uniquenessRatio_);
00070 Parameters::parse(parameters, Parameters::kStereoBMTextureThreshold(), textureThreshold_);
00071 Parameters::parse(parameters, Parameters::kStereoBMPreFilterSize(), speckleWindowSize_);
00072 Parameters::parse(parameters, Parameters::kStereoBMSpeckleRange(), speckleRange_);
00073 }
00074
00075 cv::Mat StereoBM::computeDisparity(
00076 const cv::Mat & leftImage,
00077 const cv::Mat & rightImage) const
00078 {
00079 UASSERT(!leftImage.empty() && !rightImage.empty());
00080 UASSERT(leftImage.cols == rightImage.cols && leftImage.rows == rightImage.rows);
00081 UASSERT((leftImage.type() == CV_8UC1 || leftImage.type() == CV_8UC3) && rightImage.type() == CV_8UC1);
00082
00083 cv::Mat leftMono;
00084 if(leftImage.channels() == 3)
00085 {
00086 cv::cvtColor(leftImage, leftMono, CV_BGR2GRAY);
00087 }
00088 else
00089 {
00090 leftMono = leftImage;
00091 }
00092
00093 cv::Mat disparity;
00094 #if CV_MAJOR_VERSION < 3
00095 cv::StereoBM stereo(cv::StereoBM::BASIC_PRESET);
00096 stereo.state->SADWindowSize = blockSize_;
00097 stereo.state->minDisparity = minDisparity_;
00098 stereo.state->numberOfDisparities = numDisparities_;
00099 stereo.state->preFilterSize = preFilterSize_;
00100 stereo.state->preFilterCap = preFilterCap_;
00101 stereo.state->uniquenessRatio = uniquenessRatio_;
00102 stereo.state->textureThreshold = textureThreshold_;
00103 stereo.state->speckleWindowSize = speckleWindowSize_;
00104 stereo.state->speckleRange = speckleRange_;
00105 stereo(leftMono, rightImage, disparity, CV_16SC1);
00106 #else
00107 cv::Ptr<cv::StereoBM> stereo = cv::StereoBM::create();
00108 stereo->setBlockSize(blockSize_);
00109 stereo->setMinDisparity(minDisparity_);
00110 stereo->setNumDisparities(numDisparities_);
00111 stereo->setPreFilterSize(preFilterSize_);
00112 stereo->setPreFilterCap(preFilterCap_);
00113 stereo->setUniquenessRatio(uniquenessRatio_);
00114 stereo->setTextureThreshold(textureThreshold_);
00115 stereo->setSpeckleWindowSize(speckleWindowSize_);
00116 stereo->setSpeckleRange(speckleRange_);
00117 stereo->compute(leftMono, rightImage, disparity);
00118 #endif
00119 return disparity;
00120 }
00121
00122 }