Go to the documentation of this file.00001 #ifndef __fovis_motion_estimation_hpp__
00002 #define __fovis_motion_estimation_hpp__
00003
00004 #include <stdint.h>
00005
00006 #include <Eigen/Dense>
00007 #include <Eigen/Geometry>
00008
00009 #include "keypoint.hpp"
00010 #include "frame.hpp"
00011 #include "camera_intrinsics.hpp"
00012 #include "feature_match.hpp"
00013 #include "feature_matcher.hpp"
00014 #include "rectification.hpp"
00015 #include "options.hpp"
00016
00017 namespace fovis
00018 {
00019
00020 enum MotionEstimateStatusCode
00021 {
00022 NO_DATA,
00023 SUCCESS,
00024 INSUFFICIENT_INLIERS,
00025 OPTIMIZATION_FAILURE,
00026 REPROJECTION_ERROR
00027 };
00028
00029 extern const char* MotionEstimateStatusCodeStrings[];
00030
00037 class MotionEstimator
00038 {
00039 public:
00040 MotionEstimator(const Rectification* rectification, const VisualOdometryOptions& options);
00041 ~MotionEstimator();
00042
00043 void estimateMotion(OdometryFrame* reference_frame,
00044 OdometryFrame* target_frame,
00045 DepthSource* depth_source,
00046 const Eigen::Isometry3d &init_motion_est,
00047 const Eigen::MatrixXd &init_motion_cov);
00048
00049 bool isMotionEstimateValid() const {
00050 return _estimate_status == SUCCESS;
00051 }
00052
00053 MotionEstimateStatusCode getMotionEstimateStatus() const {
00054 return _estimate_status;
00055 }
00056
00057 const Eigen::Isometry3d& getMotionEstimate() const {
00058 return *_motion_estimate;
00059 }
00060
00061 const Eigen::MatrixXd& getMotionEstimateCov() const {
00062 return *_motion_estimate_covariance;
00063 }
00064
00065 const FeatureMatch* getMatches() const {
00066 return _matches;
00067 }
00068
00069 int getNumMatches() const {
00070 return _num_matches;
00071 }
00072
00073 int getNumInliers() const {
00074 return _num_inliers;
00075 }
00076
00077 int getNumReprojectionFailures() const {
00078 return _num_reprojection_failures;
00079 }
00080
00081 double getMeanInlierReprojectionError() const {
00082 return _mean_reprojection_error;
00083 }
00084
00085 void sanityCheck() const;
00086
00087 private:
00088 void matchFeatures(PyramidLevel* ref_level, PyramidLevel* target_level);
00089 void computeMaximallyConsistentClique();
00090 void estimateRigidBodyTransform();
00091 void refineMotionEstimate();
00092 void computeReprojectionError();
00093
00094
00095 DepthSource* _depth_source;
00096
00097 FeatureMatcher _matcher;
00098
00099
00100 FeatureMatch* _matches;
00101 int _num_matches;
00102 int _matches_capacity;
00103
00104
00105 int _num_tracks;
00106
00107
00108 int _num_frames;
00109
00110
00111 int _num_inliers;
00112
00113
00114 double _mean_reprojection_error;
00115
00116
00117 int _num_reprojection_failures;
00118
00119 const Rectification* _rectification;
00120
00121 OdometryFrame* _ref_frame;
00122 OdometryFrame* _target_frame;
00123
00124
00125
00126
00127 Eigen::Isometry3d* _motion_estimate;
00128
00129 Eigen::MatrixXd* _motion_estimate_covariance;
00130
00131
00132
00133 double _max_mean_reprojection_error;
00134
00135
00136
00137 double _inlier_max_reprojection_error;
00138
00139
00140
00141 double _clique_inlier_threshold;
00142
00143
00144
00145 int _min_features_for_valid_motion_estimate;
00146
00147
00148
00149
00150
00151 double _max_feature_motion;
00152
00153
00154 int _use_subpixel_refinement;
00155
00156
00157
00158
00159 bool _update_target_features_with_refined;
00160
00161 MotionEstimateStatusCode _estimate_status;
00162 };
00163
00164 }
00165
00166 #endif