motion_estimation.cpp
Go to the documentation of this file.
00001 #include <stdio.h>
00002 #include <stdlib.h>
00003 #include <string.h>
00004 #include <assert.h>
00005 #include <math.h>
00006 
00007 #include <iostream>
00008 #include <iomanip>
00009 
00010 #include "motion_estimation.hpp"
00011 #include "absolute_orientation_horn.hpp"
00012 #include "depth_source.hpp"
00013 #include "refine_motion_estimate.hpp"
00014 #include "tictoc.hpp"
00015 #include "internal_utils.hpp"
00016 #include "sad.hpp"
00017 #include "visual_odometry.hpp"
00018 #include "refine_feature_match.hpp"
00019 
00020 #include "stereo_depth.hpp"
00021 
00022 #define USE_HORN_ABSOLUTE_ORIENTATION
00023 #define USE_ROBUST_STEREO_COMPATIBILITY
00024 #define USE_BIDIRECTIONAL_REFINEMENT
00025 
00026 #define dbg(...) fprintf(stderr, __VA_ARGS__)
00027 #define dump(var) (std::cerr<<" "#var<<" =[\n"<< std::setprecision (12)<<var<<"]"<<std::endl)
00028 
00029 namespace fovis {
00030 
00031 const char* MotionEstimateStatusCodeStrings[] = {
00032   "NO_DATA",
00033   "SUCCESS",
00034   "INSUFFICIENT_INLIERS",
00035   "OPTIMIZATION_FAILURE",
00036   "REPROJECTION_ERROR"
00037 };
00038 
00039 MotionEstimator::MotionEstimator(const Rectification* rectification,
00040     const VisualOdometryOptions& options)
00041 {
00042   _rectification = rectification;
00043 
00044   _ref_frame = NULL;
00045   _target_frame = NULL;
00046 
00047   _num_inliers = 0;
00048   _motion_estimate = new Eigen::Isometry3d();
00049   _motion_estimate_covariance = new Eigen::MatrixXd();
00050   _motion_estimate->setIdentity();
00051   _estimate_status = NO_DATA;
00052   _motion_estimate_covariance->setIdentity(6,6);
00053 
00054   _matches = NULL;
00055   _num_matches = 0;
00056   _matches_capacity = 0;
00057   _num_tracks = 0;
00058   _num_frames = 0;
00059 
00060   // extract options
00061   VisualOdometryOptions defaults = VisualOdometry::getDefaultOptions();
00062   _inlier_max_reprojection_error = optionsGetDoubleOrFromDefault(options, "inlier-max-reprojection-error", defaults);
00063   _clique_inlier_threshold = optionsGetDoubleOrFromDefault(options, "clique-inlier-threshold", defaults);
00064   _min_features_for_valid_motion_estimate = optionsGetIntOrFromDefault(options, "min-features-for-estimate", defaults);
00065   _max_mean_reprojection_error = optionsGetDoubleOrFromDefault(options, "max-mean-reprojection-error", defaults);
00066   _use_subpixel_refinement = optionsGetBoolOrFromDefault(options, "use-subpixel-refinement", defaults);
00067   _max_feature_motion = optionsGetDoubleOrFromDefault(options, "feature-search-window", defaults);
00068   _update_target_features_with_refined = _use_subpixel_refinement && optionsGetBoolOrFromDefault(options, "update-target-features-with-refined", defaults);
00069 
00070 }
00071 
00072 MotionEstimator::~MotionEstimator()
00073 {
00074   _ref_frame = NULL;
00075   _target_frame = NULL;
00076   delete[] _matches;
00077   _num_matches = 0;
00078   _matches_capacity = 0;
00079   _num_inliers = 0;
00080   delete _motion_estimate_covariance;
00081   delete _motion_estimate;
00082   _motion_estimate_covariance = NULL;
00083   _motion_estimate = NULL;
00084   _estimate_status = NO_DATA;
00085 }
00086 
00087 void
00088 MotionEstimator::estimateMotion(OdometryFrame* ref_frame,
00089                                 OdometryFrame* target_frame,
00090                                 DepthSource* depth_source,
00091                                 const Eigen::Isometry3d &init_motion_est,
00092                                 const Eigen::MatrixXd &init_motion_cov)
00093 {
00094   tictoc("estimateMotion");
00095 
00096   _depth_source = depth_source;
00097 
00098   _ref_frame = ref_frame;
00099   _target_frame = target_frame;
00100   *_motion_estimate = init_motion_est;
00101   *_motion_estimate_covariance = init_motion_cov;
00102 
00103   //  dbg("Process frame\n");
00104 
00105   tictoc("matchFeatures_all_levels");
00106   _num_matches = 0;
00107   int max_num_matches = std::min(_ref_frame->getNumKeypoints(), _target_frame->getNumKeypoints());
00108   if (max_num_matches > _matches_capacity) {
00109     delete[] _matches;
00110     _matches_capacity = static_cast<int>(max_num_matches * 1.2);
00111     _matches = new FeatureMatch[_matches_capacity];
00112   }
00113 
00114   int num_levels = _ref_frame->getNumLevels();
00115   for (int level_ind = 0; level_ind < num_levels; level_ind++) {
00116     PyramidLevel* ref_level = _ref_frame->getLevel(level_ind);
00117     PyramidLevel* target_level = _target_frame->getLevel(level_ind);
00118     matchFeatures(ref_level, target_level);
00119   }
00120   if (_use_subpixel_refinement) {
00121     depth_source->refineXyz(_matches, _num_matches, target_frame);
00122   }
00123   tictoc("matchFeatures_all_levels");
00124 
00125   // assign a 'local' match id for use in inlier detection
00126   for (int i=0; i < _num_matches; ++i) {
00127     _matches[i].id = i;
00128   }
00129 
00130   tictoc("computeMaximallyConsistentClique");
00131   computeMaximallyConsistentClique();
00132   tictoc("computeMaximallyConsistentClique");
00133 
00134   // first pass at motion estimation
00135   tictoc("estimateRigidBodyTransform1");
00136 #ifdef USE_ROBUST_STEREO_COMPATIBILITY
00137   // Horn/SVD doesn't do too well when using robust stereo metric
00138   _estimate_status = SUCCESS;
00139 #else
00140   estimateRigidBodyTransform();
00141 #endif
00142   tictoc("estimateRigidBodyTransform1");
00143 
00144   // refine motion estimate by minimizing reprojection error
00145   tictoc("refineMotionEstimate");
00146   refineMotionEstimate();
00147   tictoc("refineMotionEstimate");
00148 
00149   // compute inlier reprojection error
00150   tictoc("computeReprojectionError");
00151   computeReprojectionError();
00152   tictoc("computeReprojectionError");
00153 
00154   // remove features with a high reprojection error from the inlier set
00155   _num_reprojection_failures = 0;
00156   for (int m_ind = 0; m_ind < _num_matches; m_ind++) {
00157     FeatureMatch& match = _matches[m_ind];
00158     if (!match.inlier)
00159       continue;
00160     if (match.reprojection_error > _inlier_max_reprojection_error) {
00161       match.inlier = false;
00162       _num_inliers--;
00163       _num_reprojection_failures++;
00164     }
00165   }
00166 
00167   // prevent propagation of track id's through outlier matches.
00168   for (int m_ind = 0; m_ind < _num_matches; m_ind++) {
00169     FeatureMatch& match = _matches[m_ind];
00170     if (!match.inlier) {
00171       match.target_keypoint->track_id = -1;
00172     }
00173   }
00174 
00175   // second motion estimate refinement
00176   tictoc("refineMotionEstimate");
00177   refineMotionEstimate();
00178   tictoc("refineMotionEstimate");
00179 
00180   // compute new reprojection error
00181   tictoc("computeReprojectionError");
00182   computeReprojectionError();
00183   tictoc("computeReprojectionError");
00184 
00185   if (_mean_reprojection_error > _max_mean_reprojection_error) {
00186     _estimate_status = REPROJECTION_ERROR;
00187   }
00188 
00189 #if 0
00190   switch (_estimate_status) {
00191   case SUCCESS:
00192     dbg("Inliers: %4d  Rep. fail: %4d Matches: %4d Feats: %4d Mean err: %5.2f ",
00193         _num_inliers,
00194         _num_reprojection_failures,
00195         _num_matches,
00196         (int) _target_frame->getNumKeypoints(),
00197         _mean_reprojection_error);
00198     //    print_isometry(_motion_estimate);
00199     dbg("\n");
00200     break;
00201   case REPROJECTION_ERROR:
00202     dbg("Excessive reprojection error (%f).\n", _mean_reprojection_error);
00203     break;
00204   case OPTIMIZATION_FAILURE:
00205     dbg("Unable to solve for rigid body transform\n");
00206     break;
00207   case INSUFFICIENT_INLIERS:
00208     dbg("Insufficient inliers\n");
00209     break;
00210   default:
00211     dbg("Unknown error (this should never happen)\n");
00212     break;
00213   }
00214 #endif
00215 
00216   if (_update_target_features_with_refined) {
00217     for (int m_ind = 0; m_ind < _num_matches; m_ind++) {
00218       FeatureMatch& match = _matches[m_ind];
00219       match.target_keypoint->copyFrom(match.refined_target_keypoint);
00220     }
00221   }
00222 
00223   _num_frames++;
00224 
00225   tictoc("estimateMotion");
00226 }
00227 
00228 void MotionEstimator::sanityCheck() const
00229 {
00230 #ifndef NDEBUG
00231   for (int m_ind = 0; m_ind < _num_matches; m_ind++) {
00232     const FeatureMatch& match = _matches[m_ind];
00233 
00234     const KeypointData* ref_kp = match.ref_keypoint;
00235     const KeypointData* target_kp = match.target_keypoint;
00236     assert(ref_kp->pyramid_level >= 0 &&
00237            ref_kp->pyramid_level < _ref_frame->getNumLevels());
00238     assert(target_kp->pyramid_level >= 0 &&
00239            target_kp->pyramid_level < _target_frame->getNumLevels());
00240     const PyramidLevel * ref_level = _ref_frame->getLevel(ref_kp->pyramid_level);
00241     const PyramidLevel * target_level = _target_frame->getLevel(target_kp->pyramid_level);
00242     assert(ref_kp->kp.u >= 0 && ref_kp->kp.v >= 0 &&
00243            ref_kp->kp.u < ref_level->getWidth() &&
00244            ref_kp->kp.v < ref_level->getHeight());
00245     assert(target_kp->kp.u >= 0 && target_kp->kp.v >= 0 &&
00246            target_kp->kp.u < target_level->getWidth() &&
00247            target_kp->kp.v < target_level->getHeight());
00248   }
00249 #endif
00250 }
00251 
00252 void MotionEstimator::matchFeatures(PyramidLevel* ref_level, PyramidLevel* target_level)
00253 {
00254   // get the camera projection matrix
00255   Eigen::Matrix<double, 3, 4> xyz_c_to_uvw_c =
00256     _rectification->getRectifiedCameraParameters().toProjectionMatrix();
00257   // get the ref_to_target isometry cuz of order of loops
00258   Eigen::Isometry3d ref_to_target = _motion_estimate->inverse();
00259   Eigen::Matrix<double, 3, 4> reproj_mat = xyz_c_to_uvw_c * ref_to_target.matrix();
00260   int num_ref_features = ref_level->getNumKeypoints();
00261   int num_target_features = target_level->getNumKeypoints();
00262 
00263   std::vector<std::vector<int> > candidates(num_ref_features);
00264   for (int ref_ind = 0; ref_ind < num_ref_features; ref_ind++) {
00265     // constrain the matching to a search-region based on the
00266     // current motion estimate
00267     const Eigen::Vector4d& ref_xyzw = ref_level->getKeypointXYZW(ref_ind);
00268     assert(!isnan(ref_xyzw(0)) && !isnan(ref_xyzw(1)) &&
00269            !isnan(ref_xyzw(2)) && !isnan(ref_xyzw(3)));
00270     Eigen::Vector3d reproj_uv1 = reproj_mat * ref_xyzw;
00271     reproj_uv1 /= reproj_uv1(2);
00272     Eigen::Vector2d ref_uv(ref_level->getKeypointRectBaseU(ref_ind),
00273                            ref_level->getKeypointRectBaseV(ref_ind));
00274     std::vector<int>& ref_candidates(candidates[ref_ind]);
00275     for (int target_ind = 0; target_ind < num_target_features; target_ind++) {
00276       Eigen::Vector2d target_uv(target_level->getKeypointRectBaseU(target_ind),
00277                                 target_level->getKeypointRectBaseV(target_ind));
00278       //TODO: Should adapt based on covariance instead of constant sized window!
00279       //Eigen::Vector2d err = target_uv - ref_uv; //ignore motion est
00280       Eigen::Vector2d err = target_uv - reproj_uv1.head<2>();
00281       if (err.norm() < _max_feature_motion) {
00282         ref_candidates.push_back(target_ind);
00283       }
00284     }
00285   }
00286 
00287   int inserted_matches = 0;
00288   _matcher.matchFeatures(ref_level, target_level, candidates,
00289                          &(_matches[_num_matches]), &inserted_matches);
00290   int old_num_matches = _num_matches;
00291   _num_matches = old_num_matches + inserted_matches;
00292 
00293   if (_use_subpixel_refinement) {
00294     for (int n=old_num_matches; n < _num_matches; ++n) {
00295       //std::cerr << "n = " << n << std::endl;
00296       FeatureMatch& match(_matches[n]);
00297       const KeypointData* ref_kpdata(match.ref_keypoint);
00298       const KeypointData* target_kpdata(match.target_keypoint);
00299       Eigen::Vector2d ref_uv(ref_kpdata->kp.u, ref_kpdata->kp.v);
00300       Eigen::Vector2d init_target_uv(target_kpdata->kp.u, target_kpdata->kp.v);
00301       Eigen::Vector2d final_target_uv;
00302 
00303       float delta_sse = -1;
00304       refineFeatureMatch(ref_level, target_level, ref_uv, init_target_uv,
00305                          &final_target_uv, &delta_sse);
00306       double ds = (init_target_uv - final_target_uv).norm();
00307       if (ds < 1e-9) {
00308         match.refined_target_keypoint.copyFrom(*match.target_keypoint);
00309         match.status = MATCH_OK;
00310       } else if (ds > 1.5) {
00311         // TODO make threshold a parameter. Also, reject or keep?
00312         match.refined_target_keypoint.copyFrom(*match.target_keypoint);
00313         match.status = MATCH_OK;
00314       } else {
00315         match.refined_target_keypoint.kp.u = final_target_uv(0);
00316         match.refined_target_keypoint.kp.v = final_target_uv(1);
00317         match.refined_target_keypoint.base_uv =
00318           final_target_uv * (1 << target_kpdata->pyramid_level);
00319         _rectification->rectifyBilinearLookup(match.refined_target_keypoint.base_uv,
00320             &match.refined_target_keypoint.rect_base_uv);
00321         match.status = MATCH_NEEDS_DEPTH_REFINEMENT;
00322       }
00323     }
00324   }
00325 
00326   // label matches with their track_id
00327   for (int n=old_num_matches; n < _num_matches; ++n) {
00328     FeatureMatch& match(_matches[n]);
00329     KeypointData* ref_kpdata(match.ref_keypoint);
00330     KeypointData* target_kpdata(match.target_keypoint);
00331     if (ref_kpdata->track_id < 0) {
00332       //ref wasn't already part of a track
00333       ref_kpdata->track_id = _num_tracks++;
00334     }
00335     target_kpdata->track_id = ref_kpdata->track_id;
00336     match.track_id = ref_kpdata->track_id;
00337   }
00338 
00339 }
00340 
00341 // used for sorting feature matches.
00342 static bool consistencyCompare(const FeatureMatch &ca, const FeatureMatch& cb)
00343 {
00344   return ca.compatibility_degree > cb.compatibility_degree;
00345 }
00346 
00347 #ifdef USE_ROBUST_STEREO_COMPATIBILITY
00348 // Robust Stereo Compatibility Check from:
00349 // Heiko Hirschmuller, Peter R. Innocent and Jon M. Garibaldi
00350 // "Fast, Unconstrained Camera Motion Estimation from Stereo without Tracking
00351 // and Robust Statistics"
00352 // Paper recommends a De (compatibility thresh) of ~0.2 pixels
00353 
00354 static inline double sqr(double x) { return x * x; }
00355 
00356 static inline
00357 double robustStereoCompatibility_computeDL(double L,
00358                                            const  Eigen::Vector3d & p1,
00359                                            const  Eigen::Vector3d & p2,
00360                                            double t, double f, double De)
00361 {
00362   double A = sqr((p1(0) - p2(0)) * (t - p1(0)) - (p1(1) - p2(1)) * p1(1) - (p1(2) - p2(2)) * p1(2));
00363   double B = sqr((p1(0) - p2(0)) * p1(0) + (p1(1) - p2(1)) * p1(1) + (p1(2) - p2(2)) * p1(2));
00364   double C = 0.5 * sqr(t * (p1(1) - p2(1)));
00365   double D = sqr((p1(0) - p2(0)) * (t - p2(0)) - (p1(1) - p2(1)) * p2(1) - (p1(2) - p2(2)) * p2(2));
00366   double E = sqr((p1(0) - p2(0)) * p2(0) + (p1(1) - p2(1)) * p2(1) + (p1(2) - p2(2)) * p2(2));
00367   double F = 0.5 * sqr(t * (p1(1) - p2(1)));
00368   return De / (L * f * t) * sqrt(sqr(p1(2)) * (A + B + C) + sqr(p2(2)) * (D + E + F));
00369 }
00370 
00371 static inline bool
00372 robustStereoCompatibility(const Eigen::Vector3d & C1,
00373                           const Eigen::Vector3d & C2,
00374                           const Eigen::Vector3d & P1,
00375                           const Eigen::Vector3d & P2,
00376                           double baseline,
00377                           double focal_length,
00378                           double De)
00379 {
00380   //compute the L quantities (ie dist between pairs of points)
00381   double L1 = (C2-C1).norm();
00382   double L2 = (P2-P1).norm();
00383   //compute the DLs (delta L)
00384   double DL1 = robustStereoCompatibility_computeDL(L1, C1, C2, baseline, focal_length, De);
00385   double DL2 = robustStereoCompatibility_computeDL(L2, P1, P2, baseline, focal_length, De);
00386   return (fabs(L1-L2) <= 3*sqrt(sqr(DL1)+sqr(DL2)));
00387 }
00388 #endif
00389 
00390 void MotionEstimator::computeMaximallyConsistentClique()
00391 {
00392   if (!_num_matches)
00393     return;
00394 
00395   for (int m_ind = 0; m_ind < _num_matches; m_ind++) {
00396     FeatureMatch& match = _matches[m_ind];
00397     match.consistency_vec.resize(_num_matches);
00398   }
00399 
00400 #ifdef USE_ROBUST_STEREO_COMPATIBILITY
00401   double baseline = _depth_source->getBaseline();
00402   bool have_baseline = baseline > 0;
00403   // XXX this is not actually correct for kinect/primesense
00404   const CameraIntrinsicsParameters& rparams = _rectification->getRectifiedCameraParameters();
00405   double stereo_focal_length = rparams.fx;
00406 #endif
00407 
00408   // For each pair of matches, compute the distance between features in the
00409   // reference frame, and the distance between features in the target frame.
00410   // Rigid body transformations (isometries) preserve distance, so the distance
00411   // should not change significantly if the two feature matches are
00412   // "compatible".
00413   //
00414   // If the depth comes from a stereo camera, then apply a consistency metric that
00415   // allows for disparity error resulting from the stereo baseline.
00416 
00417   // FIXME using both homogeneous and cartesian coordinates is a bit gross here...
00418   for (int m_ind = 0; m_ind < _num_matches; m_ind++) {
00419     FeatureMatch& match = _matches[m_ind];
00420 
00421     const Eigen::Vector4d& ref_xyzw_1 = match.ref_keypoint->xyzw;
00422     const Eigen::Vector4d& target_xyzw_1 = match.refined_target_keypoint.xyzw;
00423     const Eigen::Vector3d& ref_xyz_1 = match.ref_keypoint->xyz;
00424     const Eigen::Vector3d& target_xyz_1 = match.refined_target_keypoint.xyz;
00425     assert(match.id == m_ind);
00426 
00427     // are the features points at infinity?
00428     bool ref_infinity = ref_xyzw_1.w() < 1e-9;
00429     bool target_infinity = target_xyzw_1.w() < 1e-9;
00430 
00431     for (int m_ind2 = m_ind + 1; m_ind2 < _num_matches; m_ind2++) {
00432       FeatureMatch& match2 = _matches[m_ind2];
00433       assert(match2.id == m_ind2);
00434       const Eigen::Vector4d& ref_xyzw_2 = match2.ref_keypoint->xyzw;
00435       const Eigen::Vector4d& target_xyzw_2 = match2.refined_target_keypoint.xyzw;
00436       const Eigen::Vector3d& ref_xyz_2 = match2.ref_keypoint->xyz;
00437       const Eigen::Vector3d& target_xyz_2 = match2.refined_target_keypoint.xyz;
00438 
00439       bool consistent;
00440       // special case:  if either of the features are points at infinity, then
00441       // we can't compare their distances.
00442       if((ref_infinity && ref_xyzw_2.w() < 1e-9) ||
00443          (target_infinity && target_xyzw_2.w() < 1e-9)) {
00444         consistent = true;
00445       } else {
00446 #ifdef USE_ROBUST_STEREO_COMPATIBILITY
00447         if (have_baseline) {
00448           consistent = robustStereoCompatibility(ref_xyz_1, ref_xyz_2,
00449                                                  target_xyz_1 ,target_xyz_2,
00450                                                  baseline, stereo_focal_length,
00451                                                  _clique_inlier_threshold);
00452         } else {
00453           double ref_dist = (ref_xyz_2 - ref_xyz_1).norm();
00454           double target_dist = (target_xyz_2 - target_xyz_1).norm();
00455           consistent = fabs(ref_dist - target_dist) < _clique_inlier_threshold;
00456         }
00457 #else
00458         double ref_dist = (ref_xyz_2 - ref_xyz_1).norm();
00459         double target_dist = (target_xyz_2 - target_xyz_1).norm();
00460         consistent = fabs(ref_dist - target_dist) < _clique_inlier_threshold;
00461 #endif
00462       }
00463 
00464       if (consistent) {
00465         match.consistency_vec[match2.id] = 1;
00466         match.compatibility_degree++;
00467         match2.consistency_vec[match.id] = 1;
00468         match2.compatibility_degree++;
00469       }
00470     }
00471   }
00472 
00473   // sort the features based on their consistency with other features
00474   std::sort(_matches, _matches+_num_matches, consistencyCompare);
00475 
00476   // pick the best feature and mark it as an inlier
00477   FeatureMatch &best_candidate = _matches[0];
00478   best_candidate.in_maximal_clique = true;
00479   best_candidate.inlier = true;
00480   _num_inliers = 1;
00481 
00482   // start a list of quick-reject features (features that are known to be
00483   // inconsistent with any of the existing inliers)
00484   int reject[_num_matches];
00485   std::fill(reject, reject+_num_matches, 0);
00486   for (int m_ind = 1; m_ind < _num_matches; m_ind++) {
00487     int other_id = _matches[m_ind].id;
00488     if (!best_candidate.consistency_vec[other_id])
00489       reject[other_id] = 1;
00490   }
00491 
00492   // now start adding inliers that are consistent with all existing
00493   // inliers
00494   for (int m_ind = 1; m_ind < _num_matches; m_ind++) {
00495     FeatureMatch& cand = _matches[m_ind];
00496 
00497     // if this candidate is consistent with fewer than the existing number
00498     // of inliers, then immediately stop iterating since no more features can
00499     // be inliers
00500     if (cand.compatibility_degree < _num_inliers)
00501       break;
00502 
00503     // skip if it's a quick reject
00504     if (reject[cand.id])
00505       continue;
00506 
00507     cand.in_maximal_clique = true;
00508     cand.inlier = true;
00509     _num_inliers++;
00510 
00511     // mark some more features for rejection
00512     for (int r_ind = m_ind + 1; r_ind < _num_matches; r_ind++) {
00513       int other_id = _matches[r_ind].id;
00514       if (!reject[other_id] && !cand.consistency_vec[other_id])
00515         reject[other_id] = 1;
00516     }
00517   }
00518 }
00519 
00520 void MotionEstimator::estimateRigidBodyTransform()
00521 {
00522   _motion_estimate->setIdentity();
00523 
00524   if (_num_inliers < _min_features_for_valid_motion_estimate) {
00525     _estimate_status = INSUFFICIENT_INLIERS;
00526     return;
00527   }
00528 
00529   // gather all the inliers into two big matrices
00530   Eigen::MatrixXd target_xyz(3, _num_inliers);
00531   Eigen::MatrixXd ref_xyz(3, _num_inliers);
00532 
00533   int i = 0;
00534   for (int m_ind = 0; m_ind < _num_matches; m_ind++) {
00535     FeatureMatch& match = _matches[m_ind];
00536     if (!match.inlier)
00537       continue;
00538     // FIXME so that this works with points at infinity
00539     target_xyz.col(i) = match.refined_target_keypoint.xyzw.head<3>() /
00540         match.refined_target_keypoint.xyzw(3) ;
00541     ref_xyz.col(i) = match.ref_keypoint->xyzw.head<3>() /
00542        match.ref_keypoint->xyzw(3);
00543     i++;
00544   }
00545 
00546 #ifdef USE_HORN_ABSOLUTE_ORIENTATION
00547   if (0 != absolute_orientation_horn(target_xyz, ref_xyz, _motion_estimate)) {
00548     _estimate_status = OPTIMIZATION_FAILURE;
00549     return;
00550   }
00551 #else
00552   Eigen::Matrix4d ume_estimate = Eigen::umeyama(target_xyz, ref_xyz);
00553   *_motion_estimate = Eigen::Isometry3d(ume_estimate);
00554 #endif
00555 
00556   _estimate_status = SUCCESS;
00557 }
00558 
00559 void MotionEstimator::refineMotionEstimate()
00560 {
00561 
00562   if (_num_inliers < _min_features_for_valid_motion_estimate) {
00563     _estimate_status = INSUFFICIENT_INLIERS;
00564     return;
00565   }
00566 
00567 #ifdef USE_BIDIRECTIONAL_REFINEMENT
00568   // gather all the inliers into matrices
00569   Eigen::MatrixXd target_xyz(4,_num_inliers);
00570   Eigen::MatrixXd target_projections(2,_num_inliers);
00571   Eigen::MatrixXd ref_xyz(4,_num_inliers);
00572   Eigen::MatrixXd ref_projections(2,_num_inliers);
00573   int i = 0;
00574   for (int m_ind = 0; m_ind < _num_matches; m_ind++) {
00575     FeatureMatch& match = _matches[m_ind];
00576     if (!match.inlier)
00577       continue;
00578     target_xyz.col(i) = match.refined_target_keypoint.xyzw;
00579     target_projections.col(i) = match.refined_target_keypoint.rect_base_uv;
00580 
00581     ref_xyz.col(i) = match.ref_keypoint->xyzw;
00582     ref_projections.col(i) = match.ref_keypoint->rect_base_uv;
00583     i++;
00584   }
00585 
00586   const CameraIntrinsicsParameters& rparams = _rectification->getRectifiedCameraParameters();
00587 
00588   // refine motion estimate by minimizing bidirectional reprojection error.
00589   // bidirectional reprojection error is the error of the target features
00590   // projected into the reference image, along with the reference features
00591   // projected into the target image
00592   refineMotionEstimateBidirectional(ref_xyz,
00593           ref_projections,
00594           target_xyz,
00595           target_projections,
00596           rparams.fx,
00597           rparams.cx,
00598           rparams.cy,
00599           *_motion_estimate,
00600           6,
00601           _motion_estimate,
00602           _motion_estimate_covariance);
00603 
00604   // TODO regularize the motion estimate covariance.
00605 #else
00606   // gather all the inliers into matrices
00607   Eigen::MatrixXd target_xyz(4,_num_inliers);
00608   Eigen::MatrixXd ref_projections(2,_num_inliers);
00609   int i = 0;
00610   for (int m_ind = 0; m_ind < _num_matches; m_ind++) {
00611     FeatureMatch& match = _matches[m_ind];
00612     if (!match.inlier)
00613       continue;
00614     target_xyz.col(i) = match.refined_target_keypoint.xyzw;
00615 
00616     ref_projections.col(i) = match.ref_keypoint->rect_base_uv;
00617     i++;
00618   }
00619 
00620   const CameraIntrinsicsParameters& rparams = _rectification->getRectifiedCameraParameters();
00621   // refine motion estimate by minimizing reprojection error of the
00622   // target features projected into the reference image.
00623   *_motion_estimate = refineMotionEstimate(target_xyz,
00624           ref_projections,
00625           rparams->fx,
00626           rparams->cx,
00627           rparams->cy,
00628           *_motion_estimate,
00629           6);
00630 #endif
00631 }
00632 
00633 void MotionEstimator::computeReprojectionError()
00634 {
00635   if (_estimate_status != SUCCESS)
00636     return;
00637 
00638   Eigen::Matrix<double, 3, 4> proj_matrix =
00639     _rectification->getRectifiedCameraParameters().toProjectionMatrix();
00640   Eigen::Matrix<double, 3, 4> reproj_matrix =
00641       proj_matrix * _motion_estimate->matrix();
00642 
00643   _mean_reprojection_error = 0;
00644 
00645   for (int m_ind = 0; m_ind < _num_matches; m_ind++) {
00646     FeatureMatch& match = _matches[m_ind];
00647     if (!match.inlier) {
00648       continue;
00649     }
00650 
00651     Eigen::Vector3d reproj_homogeneous =
00652         reproj_matrix * match.refined_target_keypoint.xyzw;
00653 
00654     Eigen::Vector2d reproj(reproj_homogeneous(0) / reproj_homogeneous(2),
00655         reproj_homogeneous(1) / reproj_homogeneous(2));
00656 
00657     Eigen::Vector2d err = match.ref_keypoint->rect_base_uv - reproj;
00658 
00659     match.reprojection_error = err.norm();
00660 
00661     //    printf("%3d:  %6.1f, %6.1f, %6.1f -> %6.1f, %6.1f -> %6.2f\n", m_ind,
00662     //        transformed_xyzw(0), transformed_xyzw(1), transformed_xyzw(2),
00663     //        reprojected_x, reprojected_y,
00664     //        match.reprojection_error
00665     //        );
00666     _mean_reprojection_error += match.reprojection_error;
00667   }
00668   _mean_reprojection_error /= _num_inliers;
00669 }
00670 
00671 }


libfovis
Author(s): Albert Huang, Maurice Fallon
autogenerated on Thu Jun 6 2019 20:16:12