Skip to content

Commit 5b985f6

Browse files
borongyuanmatlabbe
andauthored
Add params to filter out poor stereo flow matches (#1667)
* Add params to filter out poor stereo flow matches * Added parameters: Vis/CorFlowUseMinEigenVals, Vis/CorFlowMinEigThreshold, Vis/CorFlowErrorThreshold. Renamed Stereo/GetMinEigenVals to Stereo/UseMinEigenVals * Setting suggested default value of 20 for Vis/CorFlowErrorThreshold --------- Co-authored-by: matlabbe <matlabbe@gmail.com>
1 parent 0151f8c commit 5b985f6

File tree

7 files changed

+304
-75
lines changed

7 files changed

+304
-75
lines changed

corelib/include/rtabmap/core/Parameters.h

Lines changed: 9 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -740,8 +740,11 @@ class RTABMAP_CORE_EXPORT Parameters
740740
RTABMAP_PARAM(Vis, CorFlowIterations, int, 30, uFormat("[%s=1] See cv::calcOpticalFlowPyrLK(). Used for optical flow approach.", kVisCorType().c_str()));
741741
RTABMAP_PARAM(Vis, CorFlowEps, float, 0.01, uFormat("[%s=1] See cv::calcOpticalFlowPyrLK(). Used for optical flow approach.", kVisCorType().c_str()));
742742
RTABMAP_PARAM(Vis, CorFlowMaxLevel, int, 3, uFormat("[%s=1] See cv::calcOpticalFlowPyrLK(). Used for optical flow approach.", kVisCorType().c_str()));
743-
RTABMAP_PARAM(Vis, CorFlowGpu, bool, false, uFormat("[%s=1] Enable GPU version of the optical flow approach (only available if OpenCV is built with CUDA).", kVisCorType().c_str()));
744-
#if defined(RTABMAP_G2O) || defined(RTABMAP_ORB_SLAM)
743+
RTABMAP_PARAM(Vis, CorFlowUseMinEigenVals, bool, true, uFormat("[%s=1] See cv::calcOpticalFlowPyrLK(). Used for optical flow approach. Use minimum eigen values as an error measure, otherwise L1 distance between patches is used as an error measure.", kVisCorType().c_str()));
744+
RTABMAP_PARAM(Vis, CorFlowMinEigThreshold, float, 1e-4, uFormat("[%s=true] If the minimum eigenvalue of a feature's spatial gradient matrix is less than this threshold, then the feature is filtered out.", kVisCorFlowUseMinEigenVals().c_str()));
745+
RTABMAP_PARAM(Vis, CorFlowErrorThreshold, float, 20, uFormat("[%s=false] Filter out features with error greater than this threshold.", kVisCorFlowUseMinEigenVals().c_str()));
746+
RTABMAP_PARAM(Vis, CorFlowGpu, bool, false, uFormat("[%s=1] Enable GPU version of the optical flow approach (only available if OpenCV is built with CUDA). Note that %s is not used in the GPU implementation.", kVisCorType().c_str(), kVisCorFlowUseMinEigenVals().c_str()));
747+
#if defined(RTABMAP_G2O) || defined(RTABMAP_ORB_SLAM)
745748
RTABMAP_PARAM(Vis, BundleAdjustment, int, 1, "Optimization with bundle adjustment: 0=disabled, 1=g2o, 2=cvsba, 3=Ceres.");
746749
#else
747750
RTABMAP_PARAM(Vis, BundleAdjustment, int, 0, "Optimization with bundle adjustment: 0=disabled, 1=g2o, 2=cvsba, 3=Ceres.");
@@ -818,7 +821,10 @@ class RTABMAP_CORE_EXPORT Parameters
818821
RTABMAP_PARAM(Stereo, OpticalFlow, bool, true, "Use optical flow to find stereo correspondences, otherwise a simple block matching approach is used.");
819822
RTABMAP_PARAM(Stereo, SSD, bool, true, uFormat("[%s=false] Use Sum of Squared Differences (SSD) window, otherwise Sum of Absolute Differences (SAD) window is used.", kStereoOpticalFlow().c_str()));
820823
RTABMAP_PARAM(Stereo, Eps, double, 0.01, uFormat("[%s=true] Epsilon stop criterion.", kStereoOpticalFlow().c_str()));
821-
RTABMAP_PARAM(Stereo, Gpu, bool, false, uFormat("[%s=true] Enable GPU version of the optical flow approach (only available if OpenCV is built with CUDA).", kStereoOpticalFlow().c_str()));
824+
RTABMAP_PARAM(Stereo, UseMinEigenVals, bool, true, uFormat("[%s=true] Use minimum eigen values as an error measure, otherwise L1 distance between patches is used as an error measure.", kStereoOpticalFlow().c_str()));
825+
RTABMAP_PARAM(Stereo, MinEigThreshold, double, 1e-4, uFormat("[%s=true] If the minimum eigenvalue of a feature's spatial gradient matrix is less than this threshold, then the feature is filtered out.", kStereoUseMinEigenVals().c_str()));
826+
RTABMAP_PARAM(Stereo, ErrorThreshold, double, 50, uFormat("[%s=false] Filter out features with error greater than this threshold.", kStereoUseMinEigenVals().c_str()));
827+
RTABMAP_PARAM(Stereo, Gpu, bool, false, uFormat("[%s=true] Enable GPU version of the optical flow approach (only available if OpenCV is built with CUDA). Note that %s is not used in the GPU implementation.", kStereoOpticalFlow().c_str(), kStereoUseMinEigenVals().c_str()));
822828

823829
RTABMAP_PARAM(Stereo, DenseStrategy, int, 0, "0=cv::StereoBM, 1=cv::StereoSGBM");
824830

corelib/include/rtabmap/core/RegistrationVis.h

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -91,6 +91,9 @@ class RTABMAP_CORE_EXPORT RegistrationVis : public Registration
9191
float _flowEps;
9292
int _flowMaxLevel;
9393
bool _flowGpu;
94+
bool _flowUseMinEigenVals;
95+
float _flowMinEigThreshold;
96+
float _flowErrorThreshold;
9497
float _nndr;
9598
int _nnType;
9699
bool _gmsWithRotation;

corelib/include/rtabmap/core/Stereo.h

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -96,16 +96,23 @@ class RTABMAP_CORE_EXPORT StereoOpticalFlow : public Stereo {
9696
#endif
9797

9898
float epsilon() const {return epsilon_;}
99+
bool usingMinEigenVals() const {return useMinEigenVals_;}
100+
float minEigThreshold() const {return minEigThreshold_;}
101+
float errorThreshold() const {return errorThreshold_;}
99102
virtual bool isGpuEnabled() const;
100103

101104
private:
102105
void updateStatus(
103106
const std::vector<cv::Point2f> & leftCorners,
104107
const std::vector<cv::Point2f> & rightCorners,
105-
std::vector<unsigned char> & status) const;
108+
std::vector<unsigned char> & status,
109+
std::vector<float> err = {}) const;
106110

107111
private:
108112
float epsilon_;
113+
bool useMinEigenVals_;
114+
float minEigThreshold_;
115+
float errorThreshold_;
109116
bool gpu_;
110117
};
111118

corelib/src/RegistrationVis.cpp

Lines changed: 13 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -84,6 +84,9 @@ RegistrationVis::RegistrationVis(const ParametersMap & parameters, Registration
8484
_flowEps(Parameters::defaultVisCorFlowEps()),
8585
_flowMaxLevel(Parameters::defaultVisCorFlowMaxLevel()),
8686
_flowGpu(Parameters::defaultVisCorFlowGpu()),
87+
_flowUseMinEigenVals(Parameters::defaultVisCorFlowUseMinEigenVals()),
88+
_flowMinEigThreshold(Parameters::defaultVisCorFlowMinEigThreshold()),
89+
_flowErrorThreshold(Parameters::defaultVisCorFlowErrorThreshold()),
8790
_nndr(Parameters::defaultVisCorNNDR()),
8891
_nnType(Parameters::defaultVisCorNNType()),
8992
_gmsWithRotation(Parameters::defaultGMSWithRotation()),
@@ -145,6 +148,9 @@ void RegistrationVis::parseParameters(const ParametersMap & parameters)
145148
Parameters::parse(parameters, Parameters::kVisCorFlowEps(), _flowEps);
146149
Parameters::parse(parameters, Parameters::kVisCorFlowMaxLevel(), _flowMaxLevel);
147150
Parameters::parse(parameters, Parameters::kVisCorFlowGpu(), _flowGpu);
151+
Parameters::parse(parameters, Parameters::kVisCorFlowUseMinEigenVals(), _flowUseMinEigenVals);
152+
Parameters::parse(parameters, Parameters::kVisCorFlowMinEigThreshold(), _flowMinEigThreshold);
153+
Parameters::parse(parameters, Parameters::kVisCorFlowErrorThreshold(), _flowErrorThreshold);
148154
Parameters::parse(parameters, Parameters::kVisCorNNDR(), _nndr);
149155
Parameters::parse(parameters, Parameters::kVisCorNNType(), _nnType);
150156
Parameters::parse(parameters, Parameters::kGMSWithRotation(), _gmsWithRotation);
@@ -656,6 +662,7 @@ Transform RegistrationVis::computeTransformationImpl(
656662
// Find features in the new left image
657663
UDEBUG("guessSet = %d", guessSet?1:0);
658664
std::vector<unsigned char> status;
665+
std::vector<float> err;
659666
#ifdef HAVE_OPENCV_CUDAOPTFLOW
660667
if (_flowGpu)
661668
{
@@ -685,7 +692,6 @@ Transform RegistrationVis::computeTransformationImpl(
685692
else
686693
#endif
687694
{
688-
std::vector<float> err;
689695
UDEBUG("cv::calcOpticalFlowPyrLK() begin");
690696
cv::calcOpticalFlowPyrLK(
691697
imageFrom,
@@ -697,7 +703,8 @@ Transform RegistrationVis::computeTransformationImpl(
697703
cv::Size(_flowWinSize, _flowWinSize),
698704
guessSet ? 0 : _flowMaxLevel,
699705
cv::TermCriteria(cv::TermCriteria::COUNT + cv::TermCriteria::EPS, _flowIterations, _flowEps),
700-
cv::OPTFLOW_LK_GET_MIN_EIGENVALS | (guessSet ? cv::OPTFLOW_USE_INITIAL_FLOW : 0), 1e-4);
706+
(_flowUseMinEigenVals ? cv::OPTFLOW_LK_GET_MIN_EIGENVALS : 0) | (guessSet ? cv::OPTFLOW_USE_INITIAL_FLOW : 0),
707+
_flowMinEigThreshold);
701708
UDEBUG("cv::calcOpticalFlowPyrLK() end");
702709
}
703710

@@ -706,11 +713,14 @@ Transform RegistrationVis::computeTransformationImpl(
706713
std::vector<cv::Point3f> kptsFrom3DKept(kptsFrom3D.size());
707714
std::vector<int> orignalWordsFromIdsCpy = orignalWordsFromIds;
708715
int ki = 0;
716+
UASSERT((status.empty() || cornersTo.size() == status.size()) &&
717+
(err.empty() || cornersTo.size() == err.size()));
709718
for(unsigned int i=0; i<status.size(); ++i)
710719
{
711720
if(status[i] &&
712721
uIsInBounds(cornersTo[i].x, 0.0f, float(imageTo.cols)) &&
713-
uIsInBounds(cornersTo[i].y, 0.0f, float(imageTo.rows)))
722+
uIsInBounds(cornersTo[i].y, 0.0f, float(imageTo.rows)) &&
723+
(_flowUseMinEigenVals || err.empty() || err[i] < _flowErrorThreshold))
714724
{
715725
if(orignalWordsFromIdsCpy.size())
716726
{

corelib/src/Stereo.cpp

Lines changed: 22 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -113,6 +113,9 @@ std::vector<cv::Point2f> Stereo::computeCorrespondences(
113113
StereoOpticalFlow::StereoOpticalFlow(const ParametersMap & parameters) :
114114
Stereo(parameters),
115115
epsilon_(Parameters::defaultStereoEps()),
116+
useMinEigenVals_(Parameters::defaultStereoUseMinEigenVals()),
117+
minEigThreshold_(Parameters::defaultStereoMinEigThreshold()),
118+
errorThreshold_(Parameters::defaultStereoErrorThreshold()),
116119
gpu_(Parameters::defaultStereoGpu())
117120
{
118121
this->parseParameters(parameters);
@@ -122,6 +125,9 @@ void StereoOpticalFlow::parseParameters(const ParametersMap & parameters)
122125
{
123126
Stereo::parseParameters(parameters);
124127
Parameters::parse(parameters, Parameters::kStereoEps(), epsilon_);
128+
Parameters::parse(parameters, Parameters::kStereoUseMinEigenVals(), useMinEigenVals_);
129+
Parameters::parse(parameters, Parameters::kStereoMinEigThreshold(), minEigThreshold_);
130+
Parameters::parse(parameters, Parameters::kStereoErrorThreshold(), errorThreshold_);
125131
Parameters::parse(parameters, Parameters::kStereoGpu(), gpu_);
126132
#ifndef HAVE_OPENCV_CUDAOPTFLOW
127133
if(gpu_)
@@ -171,11 +177,18 @@ std::vector<cv::Point2f> StereoOpticalFlow::computeCorrespondences(
171177
err,
172178
this->winSize(),
173179
this->maxLevel(),
174-
cv::TermCriteria(cv::TermCriteria::COUNT+cv::TermCriteria::EPS, this->iterations(), epsilon_),
175-
cv::OPTFLOW_LK_GET_MIN_EIGENVALS, 1e-4);
180+
cv::TermCriteria(cv::TermCriteria::COUNT+cv::TermCriteria::EPS, this->iterations(), this->epsilon()),
181+
this->usingMinEigenVals() ? cv::OPTFLOW_LK_GET_MIN_EIGENVALS : 0, this->minEigThreshold());
176182
UDEBUG("util2d::calcOpticalFlowPyrLKStereo() end");
177183
}
178-
updateStatus(leftCorners, rightCorners, status);
184+
if(this->usingMinEigenVals())
185+
{
186+
updateStatus(leftCorners, rightCorners, status);
187+
}
188+
else
189+
{
190+
updateStatus(leftCorners, rightCorners, status, err);
191+
}
179192
return rightCorners;
180193
}
181194

@@ -227,14 +240,17 @@ std::vector<cv::Point2f> StereoOpticalFlow::computeCorrespondences(
227240
void StereoOpticalFlow::updateStatus(
228241
const std::vector<cv::Point2f> & leftCorners,
229242
const std::vector<cv::Point2f> & rightCorners,
230-
std::vector<unsigned char> & status) const
243+
std::vector<unsigned char> & status,
244+
std::vector<float> err) const
231245
{
232-
UASSERT(leftCorners.size() == rightCorners.size() && status.size() == leftCorners.size());
246+
UASSERT(
247+
leftCorners.size() == rightCorners.size() && status.size() == leftCorners.size() &&
248+
(err.empty() || err.size() == leftCorners.size()));
233249
int countFlowRejected = 0;
234250
int countDisparityRejected = 0;
235251
for(unsigned int i=0; i<status.size(); ++i)
236252
{
237-
if(status[i]!=0)
253+
if(status[i]!=0 && (err.empty() || err[i] < this->errorThreshold()))
238254
{
239255
float disparity = leftCorners[i].x - rightCorners[i].x;
240256
if(disparity <= this->minDisparity() || disparity > this->maxDisparity())

guilib/src/PreferencesDialog.cpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1358,6 +1358,9 @@ PreferencesDialog::PreferencesDialog(QWidget * parent) :
13581358
_ui->odom_flow_iterations->setObjectName(Parameters::kVisCorFlowIterations().c_str());
13591359
_ui->odom_flow_eps->setObjectName(Parameters::kVisCorFlowEps().c_str());
13601360
_ui->odom_flow_gpu->setObjectName(Parameters::kVisCorFlowGpu().c_str());
1361+
_ui->odom_flow_useMinEigenVals->setObjectName(Parameters::kVisCorFlowUseMinEigenVals().c_str());
1362+
_ui->odom_flow_minEigThreshold->setObjectName(Parameters::kVisCorFlowMinEigThreshold().c_str());
1363+
_ui->odom_flow_errorThreshold->setObjectName(Parameters::kVisCorFlowErrorThreshold().c_str());
13611364
_ui->loopClosure_bundle->setObjectName(Parameters::kVisBundleAdjustment().c_str());
13621365

13631366
//RegistrationIcp
@@ -1678,6 +1681,9 @@ PreferencesDialog::PreferencesDialog(QWidget * parent) :
16781681
_ui->stereo_maxDisparity->setObjectName(Parameters::kStereoMaxDisparity().c_str());
16791682
_ui->stereo_ssd->setObjectName(Parameters::kStereoSSD().c_str());
16801683
_ui->stereo_flow_eps->setObjectName(Parameters::kStereoEps().c_str());
1684+
_ui->stereo_flow_useMinEigenVals->setObjectName(Parameters::kStereoUseMinEigenVals().c_str());
1685+
_ui->stereo_flow_minEigThreshold->setObjectName(Parameters::kStereoMinEigThreshold().c_str());
1686+
_ui->stereo_flow_errorThreshold->setObjectName(Parameters::kStereoErrorThreshold().c_str());
16811687
_ui->stereo_opticalFlow->setObjectName(Parameters::kStereoOpticalFlow().c_str());
16821688
_ui->stereo_flow_gpu->setObjectName(Parameters::kStereoGpu().c_str());
16831689

0 commit comments

Comments
 (0)