util3d_motion_estimation.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 
29 
30 #include "rtabmap/utilite/UStl.h"
31 #include "rtabmap/utilite/UMath.h"
36 #include "rtabmap/core/util3d.h"
37 
38 #include <pcl/common/common.h>
39 
40 #include "opencv/solvepnp.h"
41 
42 namespace rtabmap
43 {
44 
45 namespace util3d
46 {
47 
49  const std::map<int, cv::Point3f> & words3A,
50  const std::map<int, cv::KeyPoint> & words2B,
51  const CameraModel & cameraModel,
52  int minInliers,
53  int iterations,
54  double reprojError,
55  int flagsPnP,
56  int refineIterations,
57  const Transform & guess,
58  const std::map<int, cv::Point3f> & words3B,
59  cv::Mat * covariance,
60  std::vector<int> * matchesOut,
61  std::vector<int> * inliersOut)
62 {
63  UASSERT(cameraModel.isValidForProjection());
64  UASSERT(!guess.isNull());
65  Transform transform;
66  std::vector<int> matches, inliers;
67 
68  if(covariance)
69  {
70  *covariance = cv::Mat::eye(6,6,CV_64FC1);
71  }
72 
73  // find correspondences
74  std::vector<int> ids = uKeys(words2B);
75  std::vector<cv::Point3f> objectPoints(ids.size());
76  std::vector<cv::Point2f> imagePoints(ids.size());
77  int oi=0;
78  matches.resize(ids.size());
79  for(unsigned int i=0; i<ids.size(); ++i)
80  {
81  std::map<int, cv::Point3f>::const_iterator iter=words3A.find(ids[i]);
82  if(iter != words3A.end() && util3d::isFinite(iter->second))
83  {
84  const cv::Point3f & pt = iter->second;
85  objectPoints[oi].x = pt.x;
86  objectPoints[oi].y = pt.y;
87  objectPoints[oi].z = pt.z;
88  imagePoints[oi] = words2B.find(ids[i])->second.pt;
89  matches[oi++] = ids[i];
90  }
91  }
92 
93  objectPoints.resize(oi);
94  imagePoints.resize(oi);
95  matches.resize(oi);
96 
97  UDEBUG("words3A=%d words2B=%d matches=%d words3B=%d guess=%s reprojError=%f iterations=%d",
98  (int)words3A.size(), (int)words2B.size(), (int)matches.size(), (int)words3B.size(),
99  guess.prettyPrint().c_str(), reprojError, iterations);
100 
101  if((int)matches.size() >= minInliers)
102  {
103  //PnPRansac
104  cv::Mat K = cameraModel.K();
105  cv::Mat D = cameraModel.D();
106  Transform guessCameraFrame = (guess * cameraModel.localTransform()).inverse();
107  cv::Mat R = (cv::Mat_<double>(3,3) <<
108  (double)guessCameraFrame.r11(), (double)guessCameraFrame.r12(), (double)guessCameraFrame.r13(),
109  (double)guessCameraFrame.r21(), (double)guessCameraFrame.r22(), (double)guessCameraFrame.r23(),
110  (double)guessCameraFrame.r31(), (double)guessCameraFrame.r32(), (double)guessCameraFrame.r33());
111 
112  cv::Mat rvec(1,3, CV_64FC1);
113  cv::Rodrigues(R, rvec);
114  cv::Mat tvec = (cv::Mat_<double>(1,3) <<
115  (double)guessCameraFrame.x(), (double)guessCameraFrame.y(), (double)guessCameraFrame.z());
116 
118  objectPoints,
119  imagePoints,
120  K,
121  D,
122  rvec,
123  tvec,
124  true,
125  iterations,
126  reprojError,
127  minInliers, // min inliers
128  inliers,
129  flagsPnP,
130  refineIterations);
131 
132  if((int)inliers.size() >= minInliers)
133  {
134  cv::Rodrigues(rvec, R);
135  Transform pnp(R.at<double>(0,0), R.at<double>(0,1), R.at<double>(0,2), tvec.at<double>(0),
136  R.at<double>(1,0), R.at<double>(1,1), R.at<double>(1,2), tvec.at<double>(1),
137  R.at<double>(2,0), R.at<double>(2,1), R.at<double>(2,2), tvec.at<double>(2));
138 
139  transform = (cameraModel.localTransform() * pnp).inverse();
140 
141  // compute variance (like in PCL computeVariance() method of sac_model.h)
142  if(covariance && words3B.size())
143  {
144  std::vector<float> errorSqrdDists(inliers.size());
145  std::vector<float> errorSqrdAngles(inliers.size());
146  oi = 0;
147  for(unsigned int i=0; i<inliers.size(); ++i)
148  {
149  std::map<int, cv::Point3f>::const_iterator iter = words3B.find(matches[inliers[i]]);
150  if(iter != words3B.end() && util3d::isFinite(iter->second))
151  {
152  const cv::Point3f & objPt = objectPoints[inliers[i]];
153  cv::Point3f newPt = util3d::transformPoint(iter->second, transform);
154  errorSqrdDists[oi] = uNormSquared(objPt.x-newPt.x, objPt.y-newPt.y, objPt.z-newPt.z);
155 
156  Eigen::Vector4f v1(objPt.x - transform.x(), objPt.y - transform.y(), objPt.z - transform.z(), 0);
157  Eigen::Vector4f v2(newPt.x - transform.x(), newPt.y - transform.y(), newPt.z - transform.z(), 0);
158  errorSqrdAngles[oi++] = pcl::getAngle3D(v1, v2);
159  }
160  }
161 
162  errorSqrdDists.resize(oi);
163  errorSqrdAngles.resize(oi);
164  if(errorSqrdDists.size())
165  {
166  std::sort(errorSqrdDists.begin(), errorSqrdDists.end());
167  //divide by 4 instead of 2 to ignore very very far features (stereo)
168  double median_error_sqr = 2.1981 * (double)errorSqrdDists[errorSqrdDists.size () >> 2];
169  UASSERT(uIsFinite(median_error_sqr));
170  (*covariance)(cv::Range(0,3), cv::Range(0,3)) *= median_error_sqr;
171  std::sort(errorSqrdAngles.begin(), errorSqrdAngles.end());
172  median_error_sqr = 2.1981 * (double)errorSqrdAngles[errorSqrdAngles.size () >> 2];
173  UASSERT(uIsFinite(median_error_sqr));
174  (*covariance)(cv::Range(3,6), cv::Range(3,6)) *= median_error_sqr;
175  }
176  else
177  {
178  UWARN("Not enough close points to compute covariance!");
179  }
180 
181  if(float(oi) / float(inliers.size()) < 0.2f)
182  {
183  UWARN("A very low number of inliers have valid depth (%d/%d), the transform returned may be wrong!", oi, (int)inliers.size());
184  }
185  }
186  else if(covariance)
187  {
188  // compute variance, which is the rms of reprojection errors
189  std::vector<cv::Point2f> imagePointsReproj;
190  cv::projectPoints(objectPoints, rvec, tvec, K, cv::Mat(), imagePointsReproj);
191  float err = 0.0f;
192  for(unsigned int i=0; i<inliers.size(); ++i)
193  {
194  err += uNormSquared(imagePoints.at(inliers[i]).x - imagePointsReproj.at(inliers[i]).x, imagePoints.at(inliers[i]).y - imagePointsReproj.at(inliers[i]).y);
195  }
196  UASSERT(uIsFinite(err));
197  *covariance *= std::sqrt(err/float(inliers.size()));
198  }
199  }
200  }
201 
202  if(matchesOut)
203  {
204  *matchesOut = matches;
205  }
206  if(inliersOut)
207  {
208  inliersOut->resize(inliers.size());
209  for(unsigned int i=0; i<inliers.size(); ++i)
210  {
211  inliersOut->at(i) = matches[inliers[i]];
212  }
213  }
214 
215  return transform;
216 }
217 
219  const std::map<int, cv::Point3f> & words3A,
220  const std::map<int, cv::Point3f> & words3B,
221  int minInliers,
222  double inliersDistance,
223  int iterations,
224  int refineIterations,
225  cv::Mat * covariance,
226  std::vector<int> * matchesOut,
227  std::vector<int> * inliersOut)
228 {
229  Transform transform;
230  std::vector<cv::Point3f> inliers1; // previous
231  std::vector<cv::Point3f> inliers2; // new
232 
233  std::vector<int> matches;
235  words3A,
236  words3B,
237  inliers1,
238  inliers2,
239  0,
240  &matches);
241  UASSERT(inliers1.size() == inliers2.size());
242  UDEBUG("Unique correspondences = %d", (int)inliers1.size());
243 
244  if(covariance)
245  {
246  *covariance = cv::Mat::eye(6,6,CV_64FC1);
247  }
248 
249  std::vector<int> inliers;
250  if((int)inliers1.size() >= minInliers)
251  {
252  pcl::PointCloud<pcl::PointXYZ>::Ptr inliers1cloud(new pcl::PointCloud<pcl::PointXYZ>);
253  pcl::PointCloud<pcl::PointXYZ>::Ptr inliers2cloud(new pcl::PointCloud<pcl::PointXYZ>);
254  inliers1cloud->resize(inliers1.size());
255  inliers2cloud->resize(inliers1.size());
256  for(unsigned int i=0; i<inliers1.size(); ++i)
257  {
258  (*inliers1cloud)[i].x = inliers1[i].x;
259  (*inliers1cloud)[i].y = inliers1[i].y;
260  (*inliers1cloud)[i].z = inliers1[i].z;
261  (*inliers2cloud)[i].x = inliers2[i].x;
262  (*inliers2cloud)[i].y = inliers2[i].y;
263  (*inliers2cloud)[i].z = inliers2[i].z;
264  }
266  inliers2cloud,
267  inliers1cloud,
268  inliersDistance,
269  iterations,
270  refineIterations,
271  3.0,
272  &inliers,
273  covariance);
274 
275  if(!t.isNull() && (int)inliers.size() >= minInliers)
276  {
277  transform = t;
278  }
279  }
280 
281  if(matchesOut)
282  {
283  *matchesOut = matches;
284  }
285  if(inliersOut)
286  {
287  inliersOut->resize(inliers.size());
288  for(unsigned int i=0; i<inliers.size(); ++i)
289  {
290  inliersOut->at(i) = matches[inliers[i]];
291  }
292  }
293 
294  return transform;
295 }
296 
297 
298 std::vector<float> computeReprojErrors(
299  std::vector<cv::Point3f> opoints,
300  std::vector<cv::Point2f> ipoints,
301  const cv::Mat & cameraMatrix,
302  const cv::Mat & distCoeffs,
303  const cv::Mat & rvec,
304  const cv::Mat & tvec,
305  float reprojErrorThreshold,
306  std::vector<int> & inliers)
307 {
308  UASSERT(opoints.size() == ipoints.size());
309  int count = (int)opoints.size();
310 
311  std::vector<cv::Point2f> projpoints;
312  projectPoints(opoints, rvec, tvec, cameraMatrix, distCoeffs, projpoints);
313 
314  inliers.resize(count,0);
315  std::vector<float> err(count);
316  int oi=0;
317  for (int i = 0; i < count; ++i)
318  {
319  float e = (float)cv::norm( ipoints[i] - projpoints[i]);
320  if(e <= reprojErrorThreshold)
321  {
322  inliers[oi] = i;
323  err[oi++] = e;
324  }
325  }
326  inliers.resize(oi);
327  err.resize(oi);
328  return err;
329 }
330 
332  const std::vector<cv::Point3f> & objectPoints,
333  const std::vector<cv::Point2f> & imagePoints,
334  const cv::Mat & cameraMatrix,
335  const cv::Mat & distCoeffs,
336  cv::Mat & rvec,
337  cv::Mat & tvec,
338  bool useExtrinsicGuess,
339  int iterationsCount,
340  float reprojectionError,
341  int minInliersCount,
342  std::vector<int> & inliers,
343  int flags,
344  int refineIterations,
345  float refineSigma)
346 {
347  if(minInliersCount < 4)
348  {
349  minInliersCount = 4;
350  }
351 
352  // Use OpenCV3 version of solvePnPRansac in OpenCV2.
353  // FIXME: we should use this version of solvePnPRansac in newer 3.3.1 too, which seems a lot less stable!?!? Why!?
355  objectPoints,
356  imagePoints,
357  cameraMatrix,
358  distCoeffs,
359  rvec,
360  tvec,
361  useExtrinsicGuess,
362  iterationsCount,
363  reprojectionError,
364  0.99, // confidence
365  inliers,
366  flags);
367 
368  float inlierThreshold = reprojectionError;
369  if((int)inliers.size() >= minInliersCount && refineIterations>0)
370  {
371  float error_threshold = inlierThreshold;
372  int refine_iterations = 0;
373  bool inlier_changed = false, oscillating = false;
374  std::vector<int> new_inliers, prev_inliers = inliers;
375  std::vector<size_t> inliers_sizes;
376  //Eigen::VectorXf new_model_coefficients = model_coefficients;
377  cv::Mat new_model_rvec = rvec;
378  cv::Mat new_model_tvec = tvec;
379 
380  do
381  {
382  // Get inliers from the current model
383  std::vector<cv::Point3f> opoints_inliers(prev_inliers.size());
384  std::vector<cv::Point2f> ipoints_inliers(prev_inliers.size());
385  for(unsigned int i=0; i<prev_inliers.size(); ++i)
386  {
387  opoints_inliers[i] = objectPoints[prev_inliers[i]];
388  ipoints_inliers[i] = imagePoints[prev_inliers[i]];
389  }
390 
391  UDEBUG("inliers=%d refine_iterations=%d, rvec=%f,%f,%f tvec=%f,%f,%f", (int)prev_inliers.size(), refine_iterations,
392  *new_model_rvec.ptr<double>(0), *new_model_rvec.ptr<double>(1), *new_model_rvec.ptr<double>(2),
393  *new_model_tvec.ptr<double>(0), *new_model_tvec.ptr<double>(1), *new_model_tvec.ptr<double>(2));
394 
395  // Optimize the model coefficients
396  cv::solvePnP(opoints_inliers, ipoints_inliers, cameraMatrix, distCoeffs, new_model_rvec, new_model_tvec, true, flags);
397  inliers_sizes.push_back(prev_inliers.size());
398 
399  UDEBUG("rvec=%f,%f,%f tvec=%f,%f,%f",
400  *new_model_rvec.ptr<double>(0), *new_model_rvec.ptr<double>(1), *new_model_rvec.ptr<double>(2),
401  *new_model_tvec.ptr<double>(0), *new_model_tvec.ptr<double>(1), *new_model_tvec.ptr<double>(2));
402 
403  // Select the new inliers based on the optimized coefficients and new threshold
404  std::vector<float> err = computeReprojErrors(objectPoints, imagePoints, cameraMatrix, distCoeffs, new_model_rvec, new_model_tvec, error_threshold, new_inliers);
405  UDEBUG("RANSAC refineModel: Number of inliers found (before/after): %d/%d, with an error threshold of %f.",
406  (int)prev_inliers.size (), (int)new_inliers.size (), error_threshold);
407 
408  if ((int)new_inliers.size() < minInliersCount)
409  {
410  ++refine_iterations;
411  if (refine_iterations >= refineIterations)
412  {
413  break;
414  }
415  continue;
416  }
417 
418  // Estimate the variance and the new threshold
419  float m = uMean(err.data(), err.size());
420  float variance = uVariance(err.data(), err.size());
421  error_threshold = std::min(inlierThreshold, refineSigma * float(sqrt(variance)));
422 
423  UDEBUG ("RANSAC refineModel: New estimated error threshold: %f (variance=%f mean=%f) on iteration %d out of %d.",
424  error_threshold, variance, m, refine_iterations, refineIterations);
425  inlier_changed = false;
426  std::swap (prev_inliers, new_inliers);
427 
428  // If the number of inliers changed, then we are still optimizing
429  if (new_inliers.size () != prev_inliers.size ())
430  {
431  // Check if the number of inliers is oscillating in between two values
432  if ((int)inliers_sizes.size () >= minInliersCount)
433  {
434  if (inliers_sizes[inliers_sizes.size () - 1] == inliers_sizes[inliers_sizes.size () - 3] &&
435  inliers_sizes[inliers_sizes.size () - 2] == inliers_sizes[inliers_sizes.size () - 4])
436  {
437  oscillating = true;
438  break;
439  }
440  }
441  inlier_changed = true;
442  continue;
443  }
444 
445  // Check the values of the inlier set
446  for (size_t i = 0; i < prev_inliers.size (); ++i)
447  {
448  // If the value of the inliers changed, then we are still optimizing
449  if (prev_inliers[i] != new_inliers[i])
450  {
451  inlier_changed = true;
452  break;
453  }
454  }
455  }
456  while (inlier_changed && ++refine_iterations < refineIterations);
457 
458  // If the new set of inliers is empty, we didn't do a good job refining
459  if ((int)prev_inliers.size() < minInliersCount)
460  {
461  UWARN ("RANSAC refineModel: Refinement failed: got very low inliers (%d)!", (int)prev_inliers.size());
462  }
463 
464  if (oscillating)
465  {
466  UDEBUG("RANSAC refineModel: Detected oscillations in the model refinement.");
467  }
468 
469  std::swap (inliers, new_inliers);
470  rvec = new_model_rvec;
471  tvec = new_model_tvec;
472  }
473 
474 }
475 
476 }
477 
478 }
T uVariance(const T *v, unsigned int size, T meanV)
Definition: UMath.h:491
bool RTABMAP_EXP isFinite(const cv::Point3f &pt)
Definition: util3d.cpp:3108
Transform RTABMAP_EXP estimateMotion3DTo2D(const std::map< int, cv::Point3f > &words3A, const std::map< int, cv::KeyPoint > &words2B, const CameraModel &cameraModel, int minInliers=10, int iterations=100, double reprojError=5., int flagsPnP=0, int pnpRefineIterations=1, const Transform &guess=Transform::getIdentity(), const std::map< int, cv::Point3f > &words3B=std::map< int, cv::Point3f >(), cv::Mat *covariance=0, std::vector< int > *matchesOut=0, std::vector< int > *inliersOut=0)
float r13() const
Definition: Transform.h:64
float r23() const
Definition: Transform.h:67
T uMean(const T *v, unsigned int size)
Definition: UMath.h:401
std::string prettyPrint() const
Definition: Transform.cpp:295
GLM_FUNC_DECL genType min(genType const &x, genType const &y)
cv::Point3f RTABMAP_EXP transformPoint(const cv::Point3f &pt, const Transform &transform)
std::vector< K > uKeys(const std::multimap< K, V > &mm)
Definition: UStl.h:67
f
GLM_FUNC_DECL vecType< T, P > sqrt(vecType< T, P > const &x)
GLM_FUNC_DECL genType e()
Basic mathematics functions.
Transform RTABMAP_EXP transformFromXYZCorrespondences(const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloud1, const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloud2, double inlierThreshold=0.02, int iterations=100, int refineModelIterations=10, double refineModelSigma=3.0, std::vector< int > *inliers=0, cv::Mat *variance=0)
cv::Mat D() const
Definition: CameraModel.h:111
bool solvePnPRansac(InputArray _opoints, InputArray _ipoints, InputArray _cameraMatrix, InputArray _distCoeffs, OutputArray _rvec, OutputArray _tvec, bool useExtrinsicGuess, int iterationsCount, float reprojectionError, double confidence, OutputArray _inliers, int flags)
Definition: solvepnp.cpp:112
bool uIsFinite(const T &value)
Definition: UMath.h:55
#define UASSERT(condition)
Wrappers of STL for convenient functions.
bool isNull() const
Definition: Transform.cpp:107
float r12() const
Definition: Transform.h:63
float r31() const
Definition: Transform.h:68
Transform RTABMAP_EXP estimateMotion3DTo3D(const std::map< int, cv::Point3f > &words3A, const std::map< int, cv::Point3f > &words3B, int minInliers=10, double inliersDistance=0.1, int iterations=100, int refineIterations=5, cv::Mat *covariance=0, std::vector< int > *matchesOut=0, std::vector< int > *inliersOut=0)
float r21() const
Definition: Transform.h:65
void RTABMAP_EXP solvePnPRansac(const std::vector< cv::Point3f > &objectPoints, const std::vector< cv::Point2f > &imagePoints, const cv::Mat &cameraMatrix, const cv::Mat &distCoeffs, cv::Mat &rvec, cv::Mat &tvec, bool useExtrinsicGuess, int iterationsCount, float reprojectionError, int minInliersCount, std::vector< int > &inliers, int flags, int refineIterations=1, float refineSigma=3.0f)
bool isValidForProjection() const
Definition: CameraModel.h:87
float r33() const
Definition: Transform.h:70
#define UDEBUG(...)
T uNormSquared(const std::vector< T > &v)
Definition: UMath.h:560
std::vector< float > computeReprojErrors(std::vector< cv::Point3f > opoints, std::vector< cv::Point2f > ipoints, const cv::Mat &cameraMatrix, const cv::Mat &distCoeffs, const cv::Mat &rvec, const cv::Mat &tvec, float reprojErrorThreshold, std::vector< int > &inliers)
float r22() const
Definition: Transform.h:66
ULogger class and convenient macros.
#define UWARN(...)
cv::Mat K() const
Definition: CameraModel.h:110
float r11() const
Definition: Transform.h:62
void RTABMAP_EXP findCorrespondences(const std::multimap< int, cv::KeyPoint > &wordsA, const std::multimap< int, cv::KeyPoint > &wordsB, std::list< std::pair< cv::Point2f, cv::Point2f > > &pairs)
float r32() const
Definition: Transform.h:69
const Transform & localTransform() const
Definition: CameraModel.h:116
GLM_FUNC_DECL matType< T, P > inverse(matType< T, P > const &m)


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:37:06