00001 #ifndef __fovis_stereo_depth_hpp__ 00002 #define __fovis_stereo_depth_hpp__ 00003 00004 #include <inttypes.h> 00005 00006 #include "stereo_calibration.hpp" 00007 #include "depth_source.hpp" 00008 #include "frame.hpp" 00009 #include "stereo_frame.hpp" 00010 #include "feature_match.hpp" 00011 #include "options.hpp" 00012 00013 #include "motion_estimation.hpp" 00014 00015 namespace fovis 00016 { 00017 00024 class StereoDepth : public DepthSource 00025 { 00026 public: 00027 StereoDepth(const StereoCalibration* calib, 00028 const VisualOdometryOptions& options); 00029 00030 ~StereoDepth(); 00031 00032 void setRightImage(const uint8_t * img); 00033 00034 virtual bool haveXyz(int u, int v); 00035 00036 virtual void getXyz(OdometryFrame * frame); 00037 00038 virtual void refineXyz(FeatureMatch * matches, 00039 int num_matches, 00040 OdometryFrame * frame); 00041 00042 virtual double getBaseline() const { return _calib->getBaseline(); } 00043 00044 private: 00045 typedef std::vector<std::pair<double, double> > Points2d; 00046 00047 void leftRightMatch(PyramidLevel* left_level, 00048 PyramidLevel* right_level, 00049 Points2d* matched_right_keypoints); 00050 00051 const StereoCalibration* _calib; 00052 00053 int _width; 00054 int _height; 00055 00056 int _feature_window_size; 00057 00058 int _num_pyramid_levels; 00059 00060 // params for adaptive feature detector threshold 00061 int _fast_threshold; 00062 int _fast_threshold_min; 00063 int _fast_threshold_max; 00064 int _target_pixels_per_feature; 00065 float _fast_threshold_adaptive_gain; 00066 00067 bool _use_adaptive_threshold; 00068 bool _require_mutual_match; 00069 double _max_dist_epipolar_line; 00070 double _max_refinement_displacement; 00071 00072 StereoFrame* _right_frame; 00073 00074 FeatureMatcher _matcher; 00075 std::vector<Points2d> _matched_right_keypoints_per_level; 00076 std::vector<std::vector<int> > _legal_matches; 00077 00078 Eigen::Matrix4d *_uvd1_to_xyz; 00079 00080 int _max_disparity; 00081 00082 const VisualOdometryOptions _options; 00083 00084 // matches buffer. 00085 FeatureMatch* _matches; 00086 int _num_matches; 00087 int _matches_capacity; 00088 00089 }; 00090 00091 } 00092 00093 #endif