visual_odometry.hpp
Go to the documentation of this file.
00001 #ifndef __fovis_visual_odometry_hpp__
00002 #define __fovis_visual_odometry_hpp__
00003 
00004 #include <stdint.h>
00005 
00006 #include <Eigen/Geometry>
00007 
00008 #include "keypoint.hpp"
00009 #include "camera_intrinsics.hpp"
00010 #include "frame.hpp"
00011 #include "depth_source.hpp"
00012 #include "motion_estimation.hpp"
00013 #include "options.hpp"
00014 
00015 namespace fovis
00016 {
00017 
00022 class VisualOdometryPriv
00023 {
00024   private:
00025     friend class VisualOdometry;
00026     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00027 
00028     // best estimate for current position and orientation
00029     Eigen::Isometry3d pose;
00030 
00031     // transformation relating reference frame and most recent frame
00032     Eigen::Isometry3d ref_to_prev_frame;
00033 
00034     // best estimate of motion from current to previous frame
00035     Eigen::Isometry3d motion_estimate;
00036     // the 6x6 estimate of the covriance [x-y-z, roll-pitch-yaw];
00037     Eigen::MatrixXd motion_estimate_covariance;
00038 
00039     Eigen::Matrix3d initial_homography_est;
00040     Eigen::Isometry3d initial_motion_estimate;
00041     Eigen::MatrixXd initial_motion_cov;
00042 };
00043 
00067 class VisualOdometry
00068 {
00069   public:
00078     VisualOdometry(const Rectification* rectification,
00079                    const VisualOdometryOptions& options);
00080 
00081     ~VisualOdometry();
00082 
00097     void processFrame(const uint8_t* gray, DepthSource* depth_source);
00098 
00104     const Eigen::Isometry3d& getPose() {
00105       return _p->pose;
00106     }
00107 
00113     const OdometryFrame* getReferenceFrame() const {
00114       return _ref_frame;
00115     }
00116 
00120     const OdometryFrame* getTargetFrame() const {
00121       return _cur_frame;
00122     }
00123 
00128     bool getChangeReferenceFrames() const {
00129       return _change_reference_frames;
00130     }
00131 
00136     MotionEstimateStatusCode getMotionEstimateStatus() const {
00137       return _estimator->getMotionEstimateStatus();
00138     }
00139 
00144     const Eigen::Isometry3d& getMotionEstimate() const {
00145       return _p->motion_estimate;
00146     }
00147 
00152     const Eigen::MatrixXd& getMotionEstimateCov() const {
00153       return _p->motion_estimate_covariance;
00154     }
00155 
00159     const MotionEstimator* getMotionEstimator() const {
00160       return _estimator;
00161     }
00162 
00166     int getFastThreshold() const {
00167       return _fast_threshold;
00168     }
00169 
00173     const Eigen::Matrix3d & getInitialHomography() const {
00174       return _p->initial_homography_est;
00175     }
00176 
00180     const VisualOdometryOptions& getOptions() const {
00181       return _options;
00182     }
00183 
00188     static VisualOdometryOptions getDefaultOptions();
00189 
00194     void sanityCheck() const;
00195 
00196   private:
00197     void prepareFrame(OdometryFrame* frame);
00198 
00199     Eigen::Quaterniond estimateInitialRotation(const OdometryFrame* prev,
00200                                                const OdometryFrame* cur,
00201                                                const Eigen::Isometry3d
00202                                                &init_motion_estimate =
00203                                                Eigen::Isometry3d::Identity());
00204 
00205     const Rectification* _rectification;
00206 
00207     OdometryFrame* _ref_frame;
00208     OdometryFrame* _prev_frame;
00209     OdometryFrame* _cur_frame;
00210 
00211     MotionEstimator* _estimator;
00212 
00213     VisualOdometryPriv* _p;
00214 
00215     bool _change_reference_frames;
00216 
00217     long _frame_count;
00218 
00219     // === tuning parameters ===
00220 
00221     int _feature_window_size;
00222 
00223     int _num_pyramid_levels;
00224 
00225     // initial feature detector threshold
00226     int _fast_threshold;
00227 
00228     // params for adaptive feature detector threshold
00229     int _fast_threshold_min;
00230     int _fast_threshold_max;
00231     int _target_pixels_per_feature;
00232     float _fast_threshold_adaptive_gain;
00233 
00234     bool _use_adaptive_threshold;
00235     bool _use_homography_initialization;
00236 
00237     // if there are least this many inliers in the previous motion estimate,
00238     // don't change reference frames.
00239     int _ref_frame_change_threshold;
00240 
00241     // Which level of the image pyramid to use for initial rotation estimation
00242     int _initial_rotation_pyramid_level;
00243 
00244     VisualOdometryOptions _options;
00245 };
00246 
00247 }
00248 #endif


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