viso_stereo.h
Go to the documentation of this file.
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_STEREO_H
00023 #define VISO_STEREO_H
00024 
00025 #include "viso.h"
00026 
00027 class VisualOdometryStereo : public VisualOdometry {
00028 
00029 public:
00030 
00031   // stereo-specific parameters (mandatory: base)
00032   struct parameters : public VisualOdometry::parameters {
00033     double  base;             // baseline (meters)
00034     int32_t ransac_iters;     // number of RANSAC iterations
00035     double  inlier_threshold; // fundamental matrix inlier threshold
00036     bool    reweighting;      // lower border weights (more robust to calibration errors)
00037     parameters () {
00038       base             = 1.0;
00039       ransac_iters     = 200;
00040       inlier_threshold = 1.5;
00041       reweighting      = true;
00042     }
00043   };
00044 
00045   // constructor, takes as inpute a parameter structure
00046   VisualOdometryStereo (parameters param);
00047   
00048   // deconstructor
00049   ~VisualOdometryStereo ();
00050   
00051   // process a new images, push the images back to an internal ring buffer.
00052   // valid motion estimates are available after calling process for two times.
00053   // inputs: I1 ........ pointer to rectified left image (uint8, row-aligned)
00054   //         I2 ........ pointer to rectified right image (uint8, row-aligned)
00055   //         dims[0] ... width of I1 and I2 (both must be of same size)
00056   //         dims[1] ... height of I1 and I2 (both must be of same size)
00057   //         dims[2] ... bytes per line (often equal to width)
00058   //         replace ... replace current images with I1 and I2, without copying last current
00059   //                     images to previous images internally. this option can be used
00060   //                     when small/no motions are observed to obtain Tr_delta wrt
00061   //                     an older coordinate system / time step than the previous one.
00062   // output: returns false if an error occured
00063   bool process (uint8_t *I1,uint8_t *I2,int32_t* dims,bool replace=false);
00064 
00065 private:
00066 
00067   std::vector<double>  estimateMotion (std::vector<Matcher::p_match> p_matched);
00068   enum                 result { UPDATED, FAILED, CONVERGED };  
00069   result               updateParameters(std::vector<Matcher::p_match> &p_matched,std::vector<int32_t> &active,std::vector<double> &tr,double step_size,double eps);
00070   void                 computeObservations(std::vector<Matcher::p_match> &p_matched,std::vector<int32_t> &active);
00071   void                 computeResidualsAndJacobian(std::vector<double> &tr,std::vector<int32_t> &active);
00072   std::vector<int32_t> getInlier(std::vector<Matcher::p_match> &p_matched,std::vector<double> &tr);
00073 
00074   double *X,*Y,*Z;    // 3d points
00075   double *p_residual; // residuals (p_residual=p_observe-p_predict)
00076   
00077   // parameters
00078   parameters param;
00079 };
00080 
00081 #endif // VISO_STEREO_H
00082 


libviso2
Author(s): Andreas Geiger, Stephan Wirth
autogenerated on Fri Aug 28 2015 13:37:45