Stereo.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #include <rtabmap/core/Stereo.h>
29 #include <rtabmap/core/util2d.h>
31 #include <opencv2/video/tracking.hpp>
32 
33 #ifdef HAVE_OPENCV_CUDAOPTFLOW
34 #include <opencv2/cudaoptflow.hpp>
35 #endif
36 
37 namespace rtabmap {
38 
39 Stereo * Stereo::create(const ParametersMap & parameters)
40 {
41  bool opticalFlow = Parameters::defaultStereoOpticalFlow();
42  Parameters::parse(parameters, Parameters::kStereoOpticalFlow(), opticalFlow);
43  if(opticalFlow)
44  {
45  return new StereoOpticalFlow(parameters);
46  }
47  else
48  {
49  return new Stereo(parameters);
50  }
51 }
52 
53 Stereo::Stereo(const ParametersMap & parameters) :
54  winWidth_(Parameters::defaultStereoWinWidth()),
55  winHeight_(Parameters::defaultStereoWinHeight()),
56  iterations_(Parameters::defaultStereoIterations()),
57  maxLevel_(Parameters::defaultStereoMaxLevel()),
58  minDisparity_(Parameters::defaultStereoMinDisparity()),
59  maxDisparity_(Parameters::defaultStereoMaxDisparity()),
60  winSSD_(Parameters::defaultStereoSSD())
61 {
62  this->parseParameters(parameters);
63 }
64 
65 void Stereo::parseParameters(const ParametersMap & parameters)
66 {
67  Parameters::parse(parameters, Parameters::kStereoWinWidth(), winWidth_);
68  Parameters::parse(parameters, Parameters::kStereoWinHeight(), winHeight_);
69  Parameters::parse(parameters, Parameters::kStereoIterations(), iterations_);
70  Parameters::parse(parameters, Parameters::kStereoMaxLevel(), maxLevel_);
71  Parameters::parse(parameters, Parameters::kStereoMinDisparity(), minDisparity_);
72  Parameters::parse(parameters, Parameters::kStereoMaxDisparity(), maxDisparity_);
73  Parameters::parse(parameters, Parameters::kStereoSSD(), winSSD_);
74 }
75 
76 std::vector<cv::Point2f> Stereo::computeCorrespondences(
77  const cv::Mat & leftImage,
78  const cv::Mat & rightImage,
79  const std::vector<cv::Point2f> & leftCorners,
80  std::vector<unsigned char> & status) const
81 {
82  std::vector<cv::Point2f> rightCorners;
83  UDEBUG("util2d::calcStereoCorrespondences() begin");
84  rightCorners = util2d::calcStereoCorrespondences(
85  leftImage,
86  rightImage,
87  leftCorners,
88  status,
89  cv::Size(winWidth_, winHeight_),
90  maxLevel_,
94  winSSD_);
95  UDEBUG("util2d::calcStereoCorrespondences() end");
96  return rightCorners;
97 }
98 
99 #ifdef HAVE_OPENCV_CUDEV
100 std::vector<cv::Point2f> Stereo::computeCorrespondences(
101  const cv::cuda::GpuMat & leftImage,
102  const cv::cuda::GpuMat & rightImage,
103  const std::vector<cv::Point2f> & leftCorners,
104  std::vector<unsigned char> & status) const
105 {
106  UERROR("GPU support for this approach is not implemented!");
107  return std::vector<cv::Point2f>();
108 }
109 #endif
110 
112  Stereo(parameters),
113  epsilon_(Parameters::defaultStereoEps()),
114  gpu_(Parameters::defaultStereoGpu())
115 {
116  this->parseParameters(parameters);
117 }
118 
120 {
121  Stereo::parseParameters(parameters);
122  Parameters::parse(parameters, Parameters::kStereoEps(), epsilon_);
123  Parameters::parse(parameters, Parameters::kStereoGpu(), gpu_);
124 #ifndef HAVE_OPENCV_CUDAOPTFLOW
125  if(gpu_)
126  {
127  UERROR("%s is enabled but RTAB-Map is not built with OpenCV CUDA, disabling it.", Parameters::kStereoGpu().c_str());
128  gpu_ = false;
129  }
130 #endif
131 }
132 
134 {
135 #ifdef HAVE_OPENCV_CUDAOPTFLOW
136  return gpu_;
137 #else
138  return false;
139 #endif
140 }
141 
143  const cv::Mat & leftImage,
144  const cv::Mat & rightImage,
145  const std::vector<cv::Point2f> & leftCorners,
146  std::vector<unsigned char> & status) const
147 {
148  std::vector<cv::Point2f> rightCorners;
149  std::vector<float> err;
150 #ifdef HAVE_OPENCV_CUDAOPTFLOW
151  if(gpu_)
152  {
153  cv::cuda::GpuMat d_leftImage(leftImage);
154  cv::cuda::GpuMat d_rightImage(rightImage);
155  return computeCorrespondences(d_leftImage, d_rightImage, leftCorners, status);
156  }
157  else
158 #endif
159  {
160  UDEBUG("util2d::calcOpticalFlowPyrLKStereo() begin");
162  leftImage,
163  rightImage,
164  leftCorners,
165  rightCorners,
166  status,
167  err,
168  this->winSize(),
169  this->maxLevel(),
170  cv::TermCriteria(cv::TermCriteria::COUNT+cv::TermCriteria::EPS, this->iterations(), epsilon_),
171  cv::OPTFLOW_LK_GET_MIN_EIGENVALS, 1e-4);
172  UDEBUG("util2d::calcOpticalFlowPyrLKStereo() end");
173  }
174  updateStatus(leftCorners, rightCorners, status);
175  return rightCorners;
176 }
177 
178 #ifdef HAVE_OPENCV_CUDEV
179 std::vector<cv::Point2f> StereoOpticalFlow::computeCorrespondences(
180  const cv::cuda::GpuMat & leftImage,
181  const cv::cuda::GpuMat & rightImage,
182  const std::vector<cv::Point2f> & leftCorners,
183  std::vector<unsigned char> & status) const
184 {
185  std::vector<cv::Point2f> rightCorners;
186 #ifdef HAVE_OPENCV_CUDAOPTFLOW
187  UDEBUG("cv::cuda::SparsePyrLKOpticalFlow transfer host to device begin");
188  cv::cuda::GpuMat d_leftImage(leftImage);
189  cv::cuda::GpuMat d_rightImage(rightImage);
190  cv::cuda::GpuMat d_leftCorners(leftCorners);
191  cv::cuda::GpuMat d_rightCorners;
192  UDEBUG("cv::cuda::SparsePyrLKOpticalFlow transfer host to device end");
193  cv::cuda::GpuMat d_status;
194  cv::Ptr<cv::cuda::SparsePyrLKOpticalFlow> d_pyrLK_sparse = cv::cuda::SparsePyrLKOpticalFlow::create(
195  this->winSize(), this->maxLevel(), this->iterations());
196 
197  UDEBUG("cv::cuda::SparsePyrLKOpticalFlow calc begin");
198  d_pyrLK_sparse->calc(d_leftImage, d_rightImage, d_leftCorners, d_rightCorners, d_status);
199  UDEBUG("cv::cuda::SparsePyrLKOpticalFlow calc end");
200 
201  UDEBUG("cv::cuda::SparsePyrLKOpticalFlow transfer device to host begin");
202  // Transfer back data to CPU
203  rightCorners = std::vector<cv::Point2f>(d_rightCorners.cols);
204  cv::Mat matRightCorners(1, d_rightCorners.cols, CV_32FC2, (void*)&rightCorners[0]);
205  d_rightCorners.download(matRightCorners);
206 
207  status = std::vector<unsigned char>(d_status.cols);
208  cv::Mat matStatus(1, d_status.cols, CV_8UC1, (void*)&status[0]);
209  d_status.download(matStatus);
210  UDEBUG("cv::cuda::SparsePyrLKOpticalFlow transfer device to host end");
211 
212  updateStatus(leftCorners, rightCorners, status);
213 
214 #else
215  UERROR("GPU support for this approach is not implemented!");
216 #endif
217  return rightCorners;
218 }
219 #endif
220 
222  const std::vector<cv::Point2f> & leftCorners,
223  const std::vector<cv::Point2f> & rightCorners,
224  std::vector<unsigned char> & status) const
225 {
226  UASSERT(leftCorners.size() == rightCorners.size() && status.size() == leftCorners.size());
227  int countFlowRejected = 0;
228  int countDisparityRejected = 0;
229  for(unsigned int i=0; i<status.size(); ++i)
230  {
231  if(status[i]!=0)
232  {
233  float disparity = leftCorners[i].x - rightCorners[i].x;
234  if(disparity <= this->minDisparity() || disparity > this->maxDisparity())
235  {
236  status[i] = 0;
237  ++countDisparityRejected;
238  }
239  }
240  else
241  {
242  ++countFlowRejected;
243  }
244  }
245  UDEBUG("total=%d countFlowRejected=%d countDisparityRejected=%d", (int)status.size(), countFlowRejected, countDisparityRejected);
246 }
247 
248 } /* namespace rtabmap */
rtabmap::Stereo::Stereo
Stereo(const ParametersMap &parameters=ParametersMap())
Definition: Stereo.cpp:53
rtabmap::Stereo::minDisparity_
float minDisparity_
Definition: Stereo.h:73
rtabmap::StereoOpticalFlow::isGpuEnabled
virtual bool isGpuEnabled() const
Definition: Stereo.cpp:133
rtabmap::Stereo
Definition: Stereo.h:38
rtabmap::Stereo::maxLevel
int maxLevel() const
Definition: Stereo.h:62
rtabmap::Stereo::maxDisparity_
float maxDisparity_
Definition: Stereo.h:74
rtabmap::ParametersMap
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:43
rtabmap::Parameters::parse
static bool parse(const ParametersMap &parameters, const std::string &key, bool &value)
Definition: Parameters.cpp:503
rtabmap::Stereo::winHeight_
int winHeight_
Definition: Stereo.h:70
rtabmap::Stereo::parseParameters
virtual void parseParameters(const ParametersMap &parameters)
Definition: Stereo.cpp:65
rtabmap::Stereo::winSize
cv::Size winSize() const
Definition: Stereo.h:60
rtabmap::Stereo::maxLevel_
int maxLevel_
Definition: Stereo.h:72
rtabmap::StereoOpticalFlow::StereoOpticalFlow
StereoOpticalFlow(const ParametersMap &parameters=ParametersMap())
Definition: Stereo.cpp:111
rtabmap::StereoOpticalFlow::parseParameters
virtual void parseParameters(const ParametersMap &parameters)
Definition: Stereo.cpp:119
rtabmap::util2d::calcStereoCorrespondences
std::vector< cv::Point2f > RTABMAP_CORE_EXPORT calcStereoCorrespondences(const cv::Mat &leftImage, const cv::Mat &rightImage, const std::vector< cv::Point2f > &leftCorners, std::vector< unsigned char > &status, cv::Size winSize=cv::Size(6, 3), int maxLevel=3, int iterations=5, float minDisparity=0.0f, float maxDisparity=64.0f, bool ssdApproach=true)
Definition: util2d.cpp:122
rtabmap::StereoOpticalFlow::epsilon_
float epsilon_
Definition: Stereo.h:108
UASSERT
#define UASSERT(condition)
Stereo.h
rtabmap::Parameters
Definition: Parameters.h:170
rtabmap::StereoOpticalFlow
Definition: Stereo.h:78
rtabmap::StereoOpticalFlow::updateStatus
void updateStatus(const std::vector< cv::Point2f > &leftCorners, const std::vector< cv::Point2f > &rightCorners, std::vector< unsigned char > &status) const
Definition: Stereo.cpp:221
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
ULogger.h
ULogger class and convenient macros.
util2d.h
rtabmap::util2d::calcOpticalFlowPyrLKStereo
void RTABMAP_CORE_EXPORT calcOpticalFlowPyrLKStereo(cv::InputArray _prevImg, cv::InputArray _nextImg, cv::InputArray _prevPts, cv::InputOutputArray _nextPts, cv::OutputArray _status, cv::OutputArray _err, cv::Size winSize=cv::Size(15, 3), int maxLevel=3, cv::TermCriteria criteria=cv::TermCriteria(cv::TermCriteria::COUNT+cv::TermCriteria::EPS, 30, 0.01), int flags=0, double minEigThreshold=1e-4)
Definition: util2d.cpp:371
rtabmap::Stereo::winWidth_
int winWidth_
Definition: Stereo.h:69
rtabmap::Stereo::winSSD_
bool winSSD_
Definition: Stereo.h:75
rtabmap::Stereo::iterations_
int iterations_
Definition: Stereo.h:71
c_str
const char * c_str(Args &&...args)
UDEBUG
#define UDEBUG(...)
rtabmap::Stereo::create
static Stereo * create(const ParametersMap &parameters=ParametersMap())
Definition: Stereo.cpp:39
rtabmap::Stereo::maxDisparity
float maxDisparity() const
Definition: Stereo.h:64
rtabmap::StereoOpticalFlow::gpu_
bool gpu_
Definition: Stereo.h:109
rtabmap
Definition: CameraARCore.cpp:35
rtabmap::Stereo::iterations
int iterations() const
Definition: Stereo.h:61
rtabmap::Stereo::computeCorrespondences
virtual std::vector< cv::Point2f > computeCorrespondences(const cv::Mat &leftImage, const cv::Mat &rightImage, const std::vector< cv::Point2f > &leftCorners, std::vector< unsigned char > &status) const
Definition: Stereo.cpp:76
rtabmap::StereoOpticalFlow::computeCorrespondences
virtual std::vector< cv::Point2f > computeCorrespondences(const cv::Mat &leftImage, const cv::Mat &rightImage, const std::vector< cv::Point2f > &leftCorners, std::vector< unsigned char > &status) const
Definition: Stereo.cpp:142
UERROR
#define UERROR(...)
rtabmap::Stereo::minDisparity
float minDisparity() const
Definition: Stereo.h:63
i
int i


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sun Dec 1 2024 03:42:58