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