stereo_calibration.hpp
Go to the documentation of this file.
00001 #ifndef __fovis_stereo_calibration_hpp__
00002 #define __fovis_stereo_calibration_hpp__
00003 
00004 #include <inttypes.h>
00005 
00006 #include "camera_intrinsics.hpp"
00007 #include "rectification.hpp"
00008 
00009 namespace fovis
00010 {
00011 
00016 struct StereoCalibrationParameters
00017 {
00021   double right_to_left_translation[3];
00025   double right_to_left_rotation[4];
00026 
00030   CameraIntrinsicsParameters left_parameters;
00031 
00035   CameraIntrinsicsParameters right_parameters;
00036 };
00037 
00042 class StereoCalibration
00043 {
00044   public:
00045     StereoCalibration(const StereoCalibrationParameters& params);
00046     ~StereoCalibration();
00047 
00053     Eigen::Matrix4d getUvdToXyz() const {
00054       double fx_inv = 1./_rectified_parameters.fx;
00055       double base_inv = 1./getBaseline();
00056       double cx = _rectified_parameters.cx;
00057       double cy = _rectified_parameters.cy;
00058       Eigen::Matrix4d result;
00059       result <<
00060       fx_inv    , 0      , 0               , -cx * fx_inv ,
00061       0         , fx_inv , 0               , -cy * fx_inv ,
00062       0         , 0      , 0               , 1            ,
00063       0         , 0      , fx_inv*base_inv , 0;
00064       return result;
00065     }
00066 
00070     int getWidth() const {
00071       return _rectified_parameters.width;
00072     }
00073 
00077     int getHeight() const {
00078       return _rectified_parameters.height;
00079     }
00080 
00081     double getBaseline() const {
00082       return -_parameters.right_to_left_translation[0];
00083     }
00084 
00085     const Rectification* getLeftRectification() const {
00086       return _left_rectification;
00087     }
00088 
00089     const Rectification* getRightRectification() const {
00090       return _right_rectification;
00091     }
00092 
00093     const CameraIntrinsicsParameters& getRectifiedParameters() const {
00094       return _rectified_parameters;
00095     }
00096 
00100     StereoCalibration* makeCopy() const;
00101 
00102   private:
00103     StereoCalibration() { }
00104     void initialize();
00105 
00106     StereoCalibrationParameters _parameters;
00107     CameraIntrinsicsParameters _rectified_parameters;
00108     Rectification* _left_rectification;
00109     Rectification* _right_rectification;
00110 };
00111 
00112 }
00113 
00114 #endif


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