00001 /* 00002 Copyright 2011. All rights reserved. 00003 Institute of Measurement and Control Systems 00004 Karlsruhe Institute of Technology, Germany 00005 00006 This file is part of libviso2. 00007 Authors: Andreas Geiger 00008 00009 libviso2 is free software; you can redistribute it and/or modify it under the 00010 terms of the GNU General Public License as published by the Free Software 00011 Foundation; either version 2 of the License, or any later version. 00012 00013 libviso2 is distributed in the hope that it will be useful, but WITHOUT ANY 00014 WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A 00015 PARTICULAR PURPOSE. See the GNU General Public License for more details. 00016 00017 You should have received a copy of the GNU General Public License along with 00018 libviso2; if not, write to the Free Software Foundation, Inc., 51 Franklin 00019 Street, Fifth Floor, Boston, MA 02110-1301, USA 00020 */ 00021 00022 #ifndef VISO_H 00023 #define VISO_H 00024 00025 #include "matrix.h" 00026 #include "matcher.h" 00027 00028 class VisualOdometry { 00029 00030 public: 00031 00032 // camera parameters (all are mandatory / need to be supplied) 00033 struct calibration { 00034 double f; // focal length (in pixels) 00035 double cu; // principal point (u-coordinate) 00036 double cv; // principal point (v-coordinate) 00037 calibration () { 00038 f = 1; 00039 cu = 0; 00040 cv = 0; 00041 } 00042 }; 00043 00044 // bucketing parameters 00045 struct bucketing { 00046 int32_t max_features; // maximal number of features per bucket 00047 double bucket_width; // width of bucket 00048 double bucket_height; // height of bucket 00049 bucketing () { 00050 max_features = 2; 00051 bucket_width = 50; 00052 bucket_height = 50; 00053 } 00054 }; 00055 00056 // general parameters 00057 struct parameters { 00058 Matcher::parameters match; // matching parameters 00059 VisualOdometry::bucketing bucket; // bucketing parameters 00060 VisualOdometry::calibration calib; // camera calibration parameters 00061 }; 00062 00063 // constructor, takes as input a parameter structure: 00064 // do not instanciate this class directly, instanciate VisualOdometryMono 00065 // or VisualOdometryStereo instead! 00066 VisualOdometry (parameters param); 00067 00068 // deconstructor 00069 ~VisualOdometry (); 00070 00071 // call this function instead of the specialized ones, if you already have 00072 // feature matches, and simply want to compute visual odometry from them, without 00073 // using the internal matching functions. 00074 bool process (std::vector<Matcher::p_match> p_matched_) { 00075 p_matched = p_matched_; 00076 return updateMotion(); 00077 } 00078 00079 // returns transformation from previous to current coordinates as a 4x4 00080 // homogeneous transformation matrix Tr_delta, with the following semantics: 00081 // p_t = Tr_delta * p_ {t-1} takes a point in the camera coordinate system 00082 // at time t_1 and maps it to the camera coordinate system at time t. 00083 // note: getMotion() returns the last transformation even when process() 00084 // has failed. this is useful if you wish to linearly extrapolate occasional 00085 // frames for which no correspondences have been found 00086 Matrix getMotion () { return Tr_delta; } 00087 00088 // returns previous to current feature matches from internal matcher 00089 std::vector<Matcher::p_match> getMatches () { return matcher->getMatches(); } 00090 00091 // returns the number of successfully matched points, after bucketing 00092 int32_t getNumberOfMatches () { return p_matched.size(); } 00093 00094 // returns the number of inliers: num_inliers <= num_matched 00095 int32_t getNumberOfInliers () { return inliers.size(); } 00096 00097 // returns the indices of all inliers 00098 std::vector<int32_t> getInlierIndices () { return inliers; } 00099 00100 // given a vector of inliers computes gain factor between the current and 00101 // the previous frame. this function is useful if you want to reconstruct 3d 00102 // and you want to cancel the change of (unknown) camera gain. 00103 float getGain (std::vector<int32_t> inliers_) { return matcher->getGain(inliers_); } 00104 00105 // streams out the current transformation matrix Tr_delta 00106 friend std::ostream& operator<< (std::ostream &os,VisualOdometry &viso) { 00107 Matrix p = viso.getMotion(); 00108 os << p.val[0][0] << " " << p.val[0][1] << " " << p.val[0][2] << " " << p.val[0][3] << " "; 00109 os << p.val[1][0] << " " << p.val[1][1] << " " << p.val[1][2] << " " << p.val[1][3] << " "; 00110 os << p.val[2][0] << " " << p.val[2][1] << " " << p.val[2][2] << " " << p.val[2][3]; 00111 return os; 00112 } 00113 00114 protected: 00115 00116 // calls bucketing and motion estimation 00117 bool updateMotion (); 00118 00119 // compute transformation matrix from transformation vector 00120 Matrix transformationVectorToMatrix (std::vector<double> tr); 00121 00122 // compute motion from previous to current coordinate system 00123 // if motion could not be computed, resulting vector will be of size 0 00124 virtual std::vector<double> estimateMotion (std::vector<Matcher::p_match> p_matched) = 0; 00125 00126 // get random and unique sample of num numbers from 1:N 00127 std::vector<int32_t> getRandomSample (int32_t N,int32_t num); 00128 00129 Matrix Tr_delta; // transformation (previous -> current frame) 00130 bool Tr_valid; // motion estimate exists? 00131 Matcher *matcher; // feature matcher 00132 std::vector<int32_t> inliers; // inlier set 00133 double *J; // jacobian 00134 double *p_observe; // observed 2d points 00135 double *p_predict; // predicted 2d points 00136 std::vector<Matcher::p_match> p_matched; // feature point matches 00137 00138 private: 00139 00140 parameters param; // common parameters 00141 }; 00142 00143 #endif // VISO_H 00144