util3d_motion_estimation.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #include "rtabmap/core/util3d_motion_estimation.h"
00029 
00030 #include "rtabmap/utilite/UStl.h"
00031 #include "rtabmap/utilite/UMath.h"
00032 #include "rtabmap/utilite/ULogger.h"
00033 #include "rtabmap/core/util3d_transforms.h"
00034 #include "rtabmap/core/util3d_registration.h"
00035 #include "rtabmap/core/util3d_correspondences.h"
00036 #include "rtabmap/core/util3d.h"
00037 
00038 #include "rtabmap/core/OptimizerG2O.h"
00039 
00040 #if CV_MAJOR_VERSION < 3
00041 #include "opencv/solvepnp.h"
00042 #endif
00043 
00044 namespace rtabmap
00045 {
00046 
00047 namespace util3d
00048 {
00049 
00050 Transform estimateMotion3DTo2D(
00051                         const std::map<int, cv::Point3f> & words3A,
00052                         const std::map<int, cv::KeyPoint> & words2B,
00053                         const CameraModel & cameraModel,
00054                         int minInliers,
00055                         int iterations,
00056                         double reprojError,
00057                         int flagsPnP,
00058                         int refineIterations,
00059                         const Transform & guess,
00060                         const std::map<int, cv::Point3f> & words3B,
00061                         double * varianceOut,
00062                         std::vector<int> * matchesOut,
00063                         std::vector<int> * inliersOut)
00064 {
00065         UASSERT(cameraModel.isValidForProjection());
00066         UASSERT(!guess.isNull());
00067         Transform transform;
00068         std::vector<int> matches, inliers;
00069 
00070         if(varianceOut)
00071         {
00072                 *varianceOut = 1.0;
00073         }
00074 
00075         // find correspondences
00076         std::vector<int> ids = uKeys(words2B);
00077         std::vector<cv::Point3f> objectPoints(ids.size());
00078         std::vector<cv::Point2f> imagePoints(ids.size());
00079         int oi=0;
00080         matches.resize(ids.size());
00081         for(unsigned int i=0; i<ids.size(); ++i)
00082         {
00083                 std::map<int, cv::Point3f>::const_iterator iter=words3A.find(ids[i]);
00084                 if(iter != words3A.end() && util3d::isFinite(iter->second))
00085                 {
00086                         const cv::Point3f & pt = iter->second;
00087                         objectPoints[oi].x = pt.x;
00088                         objectPoints[oi].y = pt.y;
00089                         objectPoints[oi].z = pt.z;
00090                         imagePoints[oi] = words2B.find(ids[i])->second.pt;
00091                         matches[oi++] = ids[i];
00092                 }
00093         }
00094 
00095         objectPoints.resize(oi);
00096         imagePoints.resize(oi);
00097         matches.resize(oi);
00098 
00099         UDEBUG("words3A=%d words2B=%d matches=%d words3B=%d",
00100                         (int)words3A.size(), (int)words2B.size(), (int)matches.size(), (int)words3B.size());
00101 
00102         if((int)matches.size() >= minInliers)
00103         {
00104                 //PnPRansac
00105                 cv::Mat K = cameraModel.K();
00106                 cv::Mat D = cameraModel.D();
00107                 Transform guessCameraFrame = (guess * cameraModel.localTransform()).inverse();
00108                 cv::Mat R = (cv::Mat_<double>(3,3) <<
00109                                 (double)guessCameraFrame.r11(), (double)guessCameraFrame.r12(), (double)guessCameraFrame.r13(),
00110                                 (double)guessCameraFrame.r21(), (double)guessCameraFrame.r22(), (double)guessCameraFrame.r23(),
00111                                 (double)guessCameraFrame.r31(), (double)guessCameraFrame.r32(), (double)guessCameraFrame.r33());
00112 
00113                 cv::Mat rvec(1,3, CV_64FC1);
00114                 cv::Rodrigues(R, rvec);
00115                 cv::Mat tvec = (cv::Mat_<double>(1,3) <<
00116                                 (double)guessCameraFrame.x(), (double)guessCameraFrame.y(), (double)guessCameraFrame.z());
00117 
00118                 util3d::solvePnPRansac(
00119                                 objectPoints,
00120                                 imagePoints,
00121                                 K,
00122                                 D,
00123                                 rvec,
00124                                 tvec,
00125                                 true,
00126                                 iterations,
00127                                 reprojError,
00128                                 minInliers, // min inliers
00129                                 inliers,
00130                                 flagsPnP,
00131                                 refineIterations);
00132 
00133                 if((int)inliers.size() >= minInliers)
00134                 {
00135                         cv::Rodrigues(rvec, R);
00136                         Transform pnp(R.at<double>(0,0), R.at<double>(0,1), R.at<double>(0,2), tvec.at<double>(0),
00137                                                    R.at<double>(1,0), R.at<double>(1,1), R.at<double>(1,2), tvec.at<double>(1),
00138                                                    R.at<double>(2,0), R.at<double>(2,1), R.at<double>(2,2), tvec.at<double>(2));
00139 
00140                         transform = (cameraModel.localTransform() * pnp).inverse();
00141 
00142                         // compute variance (like in PCL computeVariance() method of sac_model.h)
00143                         if(varianceOut && words3B.size())
00144                         {
00145                                 std::vector<float> errorSqrdDists(inliers.size());
00146                                 oi = 0;
00147                                 for(unsigned int i=0; i<inliers.size(); ++i)
00148                                 {
00149                                         std::map<int, cv::Point3f>::const_iterator iter = words3B.find(matches[inliers[i]]);
00150                                         if(iter != words3B.end() && util3d::isFinite(iter->second))
00151                                         {
00152                                                 const cv::Point3f & objPt = objectPoints[inliers[i]];
00153                                                 cv::Point3f newPt = util3d::transformPoint(iter->second, transform);
00154                                                 errorSqrdDists[oi] = uNormSquared(objPt.x-newPt.x, objPt.y-newPt.y, objPt.z-newPt.z);
00155                                                 //ignore very very far features (stereo)
00156                                                 if(errorSqrdDists[oi] < 100.0f)
00157                                                 {
00158                                                         ++oi;
00159                                                 }
00160                                         }
00161                                 }
00162                                 errorSqrdDists.resize(oi);
00163                                 if(errorSqrdDists.size())
00164                                 {
00165                                         std::sort(errorSqrdDists.begin(), errorSqrdDists.end());
00166                                         double median_error_sqr = (double)errorSqrdDists[errorSqrdDists.size () >> 1];
00167                                         *varianceOut = 2.1981 * median_error_sqr;
00168                                 }
00169                         }
00170                         else if(varianceOut)
00171                         {
00172                                 // compute variance, which is the rms of reprojection errors
00173                                 std::vector<cv::Point2f> imagePointsReproj;
00174                                 cv::projectPoints(objectPoints, rvec, tvec, K, cv::Mat(), imagePointsReproj);
00175                                 float err = 0.0f;
00176                                 for(unsigned int i=0; i<inliers.size(); ++i)
00177                                 {
00178                                         err += uNormSquared(imagePoints.at(inliers[i]).x - imagePointsReproj.at(inliers[i]).x, imagePoints.at(inliers[i]).y - imagePointsReproj.at(inliers[i]).y);
00179                                 }
00180                                 *varianceOut = std::sqrt(err/float(inliers.size()));
00181                         }
00182                 }
00183         }
00184 
00185         if(matchesOut)
00186         {
00187                 *matchesOut = matches;
00188         }
00189         if(inliersOut)
00190         {
00191                 inliersOut->resize(inliers.size());
00192                 for(unsigned int i=0; i<inliers.size(); ++i)
00193                 {
00194                         inliersOut->at(i) = matches[inliers[i]];
00195                 }
00196         }
00197 
00198         return transform;
00199 }
00200 
00201 Transform estimateMotion3DTo3D(
00202                         const std::map<int, cv::Point3f> & words3A,
00203                         const std::map<int, cv::Point3f> & words3B,
00204                         int minInliers,
00205                         double inliersDistance,
00206                         int iterations,
00207                         int refineIterations,
00208                         double * varianceOut,
00209                         std::vector<int> * matchesOut,
00210                         std::vector<int> * inliersOut)
00211 {
00212         Transform transform;
00213         std::vector<cv::Point3f> inliers1; // previous
00214         std::vector<cv::Point3f> inliers2; // new
00215 
00216         std::vector<int> matches;
00217         util3d::findCorrespondences(
00218                         words3A,
00219                         words3B,
00220                         inliers1,
00221                         inliers2,
00222                         0,
00223                         &matches);
00224         UASSERT(inliers1.size() == inliers2.size());
00225         UDEBUG("Unique correspondences = %d", (int)inliers1.size());
00226 
00227         if(varianceOut)
00228         {
00229                 *varianceOut = 1.0;
00230         }
00231 
00232         if((int)inliers1.size() >= minInliers)
00233         {
00234                 std::vector<int> inliers;
00235                 pcl::PointCloud<pcl::PointXYZ>::Ptr inliers1cloud(new pcl::PointCloud<pcl::PointXYZ>);
00236                 pcl::PointCloud<pcl::PointXYZ>::Ptr inliers2cloud(new pcl::PointCloud<pcl::PointXYZ>);
00237                 inliers1cloud->resize(inliers1.size());
00238                 inliers2cloud->resize(inliers1.size());
00239                 for(unsigned int i=0; i<inliers1.size(); ++i)
00240                 {
00241                         (*inliers1cloud)[i].x = inliers1[i].x;
00242                         (*inliers1cloud)[i].y = inliers1[i].y;
00243                         (*inliers1cloud)[i].z = inliers1[i].z;
00244                         (*inliers2cloud)[i].x = inliers2[i].x;
00245                         (*inliers2cloud)[i].y = inliers2[i].y;
00246                         (*inliers2cloud)[i].z = inliers2[i].z;
00247                 }
00248                 Transform t = util3d::transformFromXYZCorrespondences(
00249                                 inliers2cloud,
00250                                 inliers1cloud,
00251                                 inliersDistance,
00252                                 iterations,
00253                                 refineIterations,
00254                                 3.0,
00255                                 &inliers,
00256                                 varianceOut);
00257 
00258                 if(!t.isNull() && (int)inliers.size() >= minInliers)
00259                 {
00260                         transform = t;
00261                 }
00262 
00263                 if(matchesOut)
00264                 {
00265                         *matchesOut = matches;
00266                 }
00267 
00268                 if(inliersOut)
00269                 {
00270                         inliersOut->resize(inliers.size());
00271                         for(unsigned int i=0; i<inliers.size(); ++i)
00272                         {
00273                                 inliersOut->at(i) = matches[inliers[i]];
00274                         }
00275                 }
00276         }
00277         return transform;
00278 }
00279 
00280 
00281 std::vector<float> computeReprojErrors(
00282                 std::vector<cv::Point3f> opoints,
00283                 std::vector<cv::Point2f> ipoints,
00284                 const cv::Mat & cameraMatrix,
00285                 const cv::Mat & distCoeffs,
00286                 const cv::Mat & rvec,
00287                 const cv::Mat & tvec,
00288                 float reprojErrorThreshold,
00289                 std::vector<int> & inliers)
00290 {
00291         UASSERT(opoints.size() == ipoints.size());
00292         int count = (int)opoints.size();
00293 
00294         std::vector<cv::Point2f> projpoints;
00295         projectPoints(opoints, rvec, tvec, cameraMatrix, distCoeffs, projpoints);
00296 
00297         inliers.resize(count,0);
00298         std::vector<float> err(count);
00299         int oi=0;
00300         for (int i = 0; i < count; ++i)
00301         {
00302                 float e = (float)cv::norm( ipoints[i] - projpoints[i]);
00303                 if(e <= reprojErrorThreshold)
00304                 {
00305                         inliers[oi] = i;
00306                         err[oi++] = e;
00307                 }
00308         }
00309         inliers.resize(oi);
00310         err.resize(oi);
00311         return err;
00312 }
00313 
00314 void solvePnPRansac(
00315                 const std::vector<cv::Point3f> & objectPoints,
00316                 const std::vector<cv::Point2f> & imagePoints,
00317                 const cv::Mat & cameraMatrix,
00318                 const cv::Mat & distCoeffs,
00319                 cv::Mat & rvec,
00320                 cv::Mat & tvec,
00321                 bool useExtrinsicGuess,
00322         int iterationsCount,
00323         float reprojectionError,
00324         int minInliersCount,
00325         std::vector<int> & inliers,
00326         int flags,
00327         int refineIterations,
00328         float refineSigma)
00329 {
00330         if(minInliersCount < 4)
00331         {
00332                 minInliersCount = 4;
00333         }
00334 #if CV_MAJOR_VERSION < 3
00335         cv3::solvePnPRansac( //use OpenCV3 version of solvePnPRansac in OpenCV2
00336 #else
00337         cv::solvePnPRansac( // use directly version from OpenCV 3
00338 #endif
00339                         objectPoints,
00340                         imagePoints,
00341                         cameraMatrix,
00342                         distCoeffs,
00343                         rvec,
00344                         tvec,
00345                         useExtrinsicGuess,
00346                         iterationsCount,
00347                         reprojectionError,
00348                         0.99, // confidence
00349                         inliers,
00350                         flags);
00351 
00352         float inlierThreshold = reprojectionError;
00353         if((int)inliers.size() >= minInliersCount && refineIterations>0)
00354         {
00355                 float error_threshold = inlierThreshold;
00356                 int refine_iterations = 0;
00357                 bool inlier_changed = false, oscillating = false;
00358                 std::vector<int> new_inliers, prev_inliers = inliers;
00359                 std::vector<size_t> inliers_sizes;
00360                 //Eigen::VectorXf new_model_coefficients = model_coefficients;
00361                 cv::Mat new_model_rvec = rvec;
00362                 cv::Mat new_model_tvec = tvec;
00363 
00364                 do
00365                 {
00366                         // Get inliers from the current model
00367                         std::vector<cv::Point3f> opoints_inliers(prev_inliers.size());
00368                         std::vector<cv::Point2f> ipoints_inliers(prev_inliers.size());
00369                         for(unsigned int i=0; i<prev_inliers.size(); ++i)
00370                         {
00371                                 opoints_inliers[i] = objectPoints[prev_inliers[i]];
00372                                 ipoints_inliers[i] = imagePoints[prev_inliers[i]];
00373                         }
00374 
00375                         UDEBUG("inliers=%d refine_iterations=%d, rvec=%f,%f,%f tvec=%f,%f,%f", (int)prev_inliers.size(), refine_iterations,
00376                                         *new_model_rvec.ptr<double>(0), *new_model_rvec.ptr<double>(1), *new_model_rvec.ptr<double>(2),
00377                                         *new_model_tvec.ptr<double>(0), *new_model_tvec.ptr<double>(1), *new_model_tvec.ptr<double>(2));
00378 
00379                         // Optimize the model coefficients
00380                         cv::solvePnP(opoints_inliers, ipoints_inliers, cameraMatrix, distCoeffs, new_model_rvec, new_model_tvec, true, flags);
00381                         inliers_sizes.push_back(prev_inliers.size());
00382 
00383                         UDEBUG("rvec=%f,%f,%f tvec=%f,%f,%f",
00384                                         *new_model_rvec.ptr<double>(0), *new_model_rvec.ptr<double>(1), *new_model_rvec.ptr<double>(2),
00385                                         *new_model_tvec.ptr<double>(0), *new_model_tvec.ptr<double>(1), *new_model_tvec.ptr<double>(2));
00386 
00387                         // Select the new inliers based on the optimized coefficients and new threshold
00388                         std::vector<float> err = computeReprojErrors(objectPoints, imagePoints, cameraMatrix, distCoeffs, new_model_rvec, new_model_tvec, error_threshold, new_inliers);
00389                         UDEBUG("RANSAC refineModel: Number of inliers found (before/after): %d/%d, with an error threshold of %f.",
00390                                         (int)prev_inliers.size (), (int)new_inliers.size (), error_threshold);
00391 
00392                         if ((int)new_inliers.size() < minInliersCount)
00393                         {
00394                                 ++refine_iterations;
00395                                 if (refine_iterations >= refineIterations)
00396                                 {
00397                                         break;
00398                                 }
00399                                 continue;
00400                         }
00401 
00402                         // Estimate the variance and the new threshold
00403                         float m = uMean(err.data(), err.size());
00404                         float variance = uVariance(err.data(), err.size());
00405                         error_threshold = std::min(inlierThreshold, refineSigma * float(sqrt(variance)));
00406 
00407                         UDEBUG ("RANSAC refineModel: New estimated error threshold: %f (variance=%f mean=%f) on iteration %d out of %d.",
00408                                   error_threshold, variance, m, refine_iterations, refineIterations);
00409                         inlier_changed = false;
00410                         std::swap (prev_inliers, new_inliers);
00411 
00412                         // If the number of inliers changed, then we are still optimizing
00413                         if (new_inliers.size () != prev_inliers.size ())
00414                         {
00415                                 // Check if the number of inliers is oscillating in between two values
00416                                 if ((int)inliers_sizes.size () >= minInliersCount)
00417                                 {
00418                                         if (inliers_sizes[inliers_sizes.size () - 1] == inliers_sizes[inliers_sizes.size () - 3] &&
00419                                         inliers_sizes[inliers_sizes.size () - 2] == inliers_sizes[inliers_sizes.size () - 4])
00420                                         {
00421                                                 oscillating = true;
00422                                                 break;
00423                                         }
00424                                 }
00425                                 inlier_changed = true;
00426                                 continue;
00427                         }
00428 
00429                         // Check the values of the inlier set
00430                         for (size_t i = 0; i < prev_inliers.size (); ++i)
00431                         {
00432                                 // If the value of the inliers changed, then we are still optimizing
00433                                 if (prev_inliers[i] != new_inliers[i])
00434                                 {
00435                                         inlier_changed = true;
00436                                         break;
00437                                 }
00438                         }
00439                 }
00440                 while (inlier_changed && ++refine_iterations < refineIterations);
00441 
00442                 // If the new set of inliers is empty, we didn't do a good job refining
00443                 if ((int)prev_inliers.size() < minInliersCount)
00444                 {
00445                         UWARN ("RANSAC refineModel: Refinement failed: got very low inliers (%d)!", (int)prev_inliers.size());
00446                 }
00447 
00448                 if (oscillating)
00449                 {
00450                         UDEBUG("RANSAC refineModel: Detected oscillations in the model refinement.");
00451                 }
00452 
00453                 std::swap (inliers, new_inliers);
00454                 rvec = new_model_rvec;
00455                 tvec = new_model_tvec;
00456         }
00457 
00458 }
00459 
00460 }
00461 
00462 }


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sat Jul 23 2016 11:44:28