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  UASSERT(leftImage.type() == CV_8UC1);
83  UASSERT(rightImage.type() == CV_8UC1);
84  std::vector<cv::Point2f> rightCorners;
85  UDEBUG("util2d::calcStereoCorrespondences() begin");
86  rightCorners = util2d::calcStereoCorrespondences(
87  leftImage,
88  rightImage,
89  leftCorners,
90  status,
91  cv::Size(winWidth_, winHeight_),
92  maxLevel_,
96  winSSD_);
97  UDEBUG("util2d::calcStereoCorrespondences() end");
98  return rightCorners;
99 }
100 
101 #ifdef HAVE_OPENCV_CUDEV
102 std::vector<cv::Point2f> Stereo::computeCorrespondences(
103  const cv::cuda::GpuMat & leftImage,
104  const cv::cuda::GpuMat & rightImage,
105  const std::vector<cv::Point2f> & leftCorners,
106  std::vector<unsigned char> & status) const
107 {
108  UERROR("GPU support for this approach is not implemented!");
109  return std::vector<cv::Point2f>();
110 }
111 #endif
112 
114  Stereo(parameters),
115  epsilon_(Parameters::defaultStereoEps()),
116  gpu_(Parameters::defaultStereoGpu())
117 {
118  this->parseParameters(parameters);
119 }
120 
122 {
123  Stereo::parseParameters(parameters);
124  Parameters::parse(parameters, Parameters::kStereoEps(), epsilon_);
125  Parameters::parse(parameters, Parameters::kStereoGpu(), gpu_);
126 #ifndef HAVE_OPENCV_CUDAOPTFLOW
127  if(gpu_)
128  {
129  UERROR("%s is enabled but RTAB-Map is not built with OpenCV CUDA, disabling it.", Parameters::kStereoGpu().c_str());
130  gpu_ = false;
131  }
132 #endif
133 }
134 
136 {
137 #ifdef HAVE_OPENCV_CUDAOPTFLOW
138  return gpu_;
139 #else
140  return false;
141 #endif
142 }
143 
145  const cv::Mat & leftImage,
146  const cv::Mat & rightImage,
147  const std::vector<cv::Point2f> & leftCorners,
148  std::vector<unsigned char> & status) const
149 {
150  UASSERT(leftImage.type() == CV_8UC1);
151  UASSERT(rightImage.type() == CV_8UC1);
152  std::vector<cv::Point2f> rightCorners;
153  std::vector<float> err;
154 #ifdef HAVE_OPENCV_CUDAOPTFLOW
155  if(gpu_)
156  {
157  cv::cuda::GpuMat d_leftImage(leftImage);
158  cv::cuda::GpuMat d_rightImage(rightImage);
159  return computeCorrespondences(d_leftImage, d_rightImage, leftCorners, status);
160  }
161  else
162 #endif
163  {
164  UDEBUG("util2d::calcOpticalFlowPyrLKStereo() begin");
166  leftImage,
167  rightImage,
168  leftCorners,
169  rightCorners,
170  status,
171  err,
172  this->winSize(),
173  this->maxLevel(),
174  cv::TermCriteria(cv::TermCriteria::COUNT+cv::TermCriteria::EPS, this->iterations(), epsilon_),
175  cv::OPTFLOW_LK_GET_MIN_EIGENVALS, 1e-4);
176  UDEBUG("util2d::calcOpticalFlowPyrLKStereo() end");
177  }
178  updateStatus(leftCorners, rightCorners, status);
179  return rightCorners;
180 }
181 
182 #ifdef HAVE_OPENCV_CUDEV
183 std::vector<cv::Point2f> StereoOpticalFlow::computeCorrespondences(
184  const cv::cuda::GpuMat & leftImage,
185  const cv::cuda::GpuMat & rightImage,
186  const std::vector<cv::Point2f> & leftCorners,
187  std::vector<unsigned char> & status) const
188 {
189  std::vector<cv::Point2f> rightCorners;
190 #ifdef HAVE_OPENCV_CUDAOPTFLOW
191  UASSERT(leftImage.type() == CV_8UC1);
192  UASSERT(rightImage.type() == CV_8UC1);
193  UDEBUG("cv::cuda::SparsePyrLKOpticalFlow transfer host to device begin");
194  cv::cuda::GpuMat d_leftImage(leftImage);
195  cv::cuda::GpuMat d_rightImage(rightImage);
196  cv::cuda::GpuMat d_leftCorners(leftCorners);
197  cv::cuda::GpuMat d_rightCorners;
198  UDEBUG("cv::cuda::SparsePyrLKOpticalFlow transfer host to device end");
199  cv::cuda::GpuMat d_status;
200  cv::Ptr<cv::cuda::SparsePyrLKOpticalFlow> d_pyrLK_sparse = cv::cuda::SparsePyrLKOpticalFlow::create(
201  this->winSize(), this->maxLevel(), this->iterations());
202 
203  UDEBUG("cv::cuda::SparsePyrLKOpticalFlow calc begin");
204  d_pyrLK_sparse->calc(d_leftImage, d_rightImage, d_leftCorners, d_rightCorners, d_status);
205  UDEBUG("cv::cuda::SparsePyrLKOpticalFlow calc end");
206 
207  UDEBUG("cv::cuda::SparsePyrLKOpticalFlow transfer device to host begin");
208  // Transfer back data to CPU
209  rightCorners = std::vector<cv::Point2f>(d_rightCorners.cols);
210  cv::Mat matRightCorners(1, d_rightCorners.cols, CV_32FC2, (void*)&rightCorners[0]);
211  d_rightCorners.download(matRightCorners);
212 
213  status = std::vector<unsigned char>(d_status.cols);
214  cv::Mat matStatus(1, d_status.cols, CV_8UC1, (void*)&status[0]);
215  d_status.download(matStatus);
216  UDEBUG("cv::cuda::SparsePyrLKOpticalFlow transfer device to host end");
217 
218  updateStatus(leftCorners, rightCorners, status);
219 
220 #else
221  UERROR("GPU support for this approach is not implemented!");
222 #endif
223  return rightCorners;
224 }
225 #endif
226 
228  const std::vector<cv::Point2f> & leftCorners,
229  const std::vector<cv::Point2f> & rightCorners,
230  std::vector<unsigned char> & status) const
231 {
232  UASSERT(leftCorners.size() == rightCorners.size() && status.size() == leftCorners.size());
233  int countFlowRejected = 0;
234  int countDisparityRejected = 0;
235  for(unsigned int i=0; i<status.size(); ++i)
236  {
237  if(status[i]!=0)
238  {
239  float disparity = leftCorners[i].x - rightCorners[i].x;
240  if(disparity <= this->minDisparity() || disparity > this->maxDisparity())
241  {
242  status[i] = 0;
243  ++countDisparityRejected;
244  }
245  }
246  else
247  {
248  ++countFlowRejected;
249  }
250  }
251  UDEBUG("total=%d countFlowRejected=%d countDisparityRejected=%d", (int)status.size(), countFlowRejected, countDisparityRejected);
252 }
253 
254 } /* 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:135
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:506
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:113
rtabmap::StereoOpticalFlow::parseParameters
virtual void parseParameters(const ParametersMap &parameters)
Definition: Stereo.cpp:121
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:227
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:144
UERROR
#define UERROR(...)
rtabmap::Stereo::minDisparity
float minDisparity() const
Definition: Stereo.h:63
i
int i


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:46:05