StereoCalibration.h
Go to the documentation of this file.
00001 // ****************************************************************************
00002 // This file is part of the Integrating Vision Toolkit (IVT).
00003 //
00004 // The IVT is maintained by the Karlsruhe Institute of Technology (KIT)
00005 // (www.kit.edu) in cooperation with the company Keyetech (www.keyetech.de).
00006 //
00007 // Copyright (C) 2014 Karlsruhe Institute of Technology (KIT).
00008 // All rights reserved.
00009 //
00010 // Redistribution and use in source and binary forms, with or without
00011 // modification, are permitted provided that the following conditions are met:
00012 //
00013 // 1. Redistributions of source code must retain the above copyright
00014 //    notice, this list of conditions and the following disclaimer.
00015 //
00016 // 2. Redistributions in binary form must reproduce the above copyright
00017 //    notice, this list of conditions and the following disclaimer in the
00018 //    documentation and/or other materials provided with the distribution.
00019 //
00020 // 3. Neither the name of the KIT nor the names of its contributors may be
00021 //    used to endorse or promote products derived from this software
00022 //    without specific prior written permission.
00023 //
00024 // THIS SOFTWARE IS PROVIDED BY THE KIT AND CONTRIBUTORS “AS IS” AND ANY
00025 // EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00026 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00027 // DISCLAIMED. IN NO EVENT SHALL THE KIT OR CONTRIBUTORS BE LIABLE FOR ANY
00028 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00029 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00031 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00032 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
00033 // THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00034 // ****************************************************************************
00035 // ****************************************************************************
00036 // Filename:  StereoCalibration.h
00037 // Author:    Pedram Azad
00038 // Date:      2004
00039 // ****************************************************************************
00040 
00041 
00042 #ifndef _STEREO_CALIBRATION_H_
00043 #define _STEREO_CALIBRATION_H_
00044 
00045 
00046 // ****************************************************************************
00047 // Necessary includes
00048 // ****************************************************************************
00049 
00050 #include "Math/Math3d.h"
00051 
00052 
00053 // ****************************************************************************
00054 // Forward declarations
00055 // ****************************************************************************
00056 
00057 class CCalibration;
00058 class CByteImage;
00059 struct Vec2d;
00060 struct Vec3d;
00061 struct Mat3d;
00062 struct PointPair2d;
00063 struct PointPair3d;
00064 
00065 
00066 
00067 // ****************************************************************************
00068 // CStereoCalibration
00069 // ****************************************************************************
00070 
00087 class CStereoCalibration
00088 {
00089 public:
00098         CStereoCalibration();
00099 
00103         ~CStereoCalibration();
00104         
00108         CStereoCalibration(const CStereoCalibration &stereoCalibration);
00109 
00110         
00115         void Set(const CStereoCalibration &stereoCalibration);
00116         
00127         void SetSingleCalibrations(const CCalibration &leftCalibration, const CCalibration &rightCalibration, bool bTransformLeftCameraToIdentity = false);
00128         
00141         void SetDistortionParameters(float d1_left, float d2_left, float d3_left, float d4_left, float d1_right, float d2_right, float d3_right, float d4_right);
00142 
00157         void SetExtrinsicParameters(const Mat3d& left_rotation, const Vec3d& left_translation, const Mat3d& right_rotation, const Vec3d& right_translation, bool bTransformLeftCameraToIdentity = false);
00158         
00172         bool LoadCameraParameters(const char *pCameraParameterFileName, bool bTransformLeftCameraToIdentity = true);
00173                 
00207         bool SaveCameraParameters(const char *pCameraParameterFileName) const;
00208 
00209         
00211         const CCalibration* GetLeftCalibration() const { return m_pLeftCalibration; }
00212         
00214         const CCalibration* GetRightCalibration() const { return m_pRightCalibration; }
00215 
00216         
00231         void Calculate3DPoint(const Vec2d &cameraPointLeft, const Vec2d &cameraPointRight, Vec3d &worldPoint, bool bInputImagesAreRectified, bool bUseDistortionParameters = true, PointPair3d *pConnectionLine = 0);
00232         
00245         void CalculateEpipolarLineInLeftImage(const Vec2d &pointInRightImage, Vec3d &l);
00246         
00255         void CalculateEpipolarLineInLeftImage(const Vec2d &pointInRightImage, PointPair2d &epipolarLine);
00256         
00265         void CalculateEpipolarLineInLeftImage(const Vec2d &pointInRightImage, float &m, float &c);
00266         
00279         void CalculateEpipolarLineInRightImage(const Vec2d &pointInLeftImage, Vec3d &l);
00280         
00289         void CalculateEpipolarLineInRightImage(const Vec2d &pointInLeftImage, PointPair2d &epipolarLine);
00290         
00299         void CalculateEpipolarLineInRightImage(const Vec2d &pointInLeftImage, float &m, float &c);
00300         
00301         
00311         float CalculateEpipolarLineInLeftImageDistance(const Vec2d &pointInLeftImage, const Vec2d &pointInRightImage);
00312         
00322         float CalculateEpipolarLineInRightImageDistance(const Vec2d &pointInLeftImage, const Vec2d &pointInRightImage);
00323         
00341         void GetProjectionMatricesForRectifiedImages(Mat3d &P1Left, Vec3d &p2Left, Mat3d &P1Right, Vec3d &p2Right) const;
00342         
00343         
00344         // public attributes
00346         int width;
00348         int height;
00349         
00359         Mat3d rectificationHomographyLeft;
00360         
00370         Mat3d rectificationHomographyRight;
00371                 
00372 
00373 private:
00374         // private methods
00375         void TransformLeftCameraToIdentity();
00376         void CalculateFundamentalMatrix();
00377 
00378         // private attributes
00379         CCalibration *m_pLeftCalibration;
00380         CCalibration *m_pRightCalibration;
00381         
00382         Mat3d F, FT; // F = fundamental matrix, FT = transposed fundamental matrix
00383 };
00384 
00385 
00386 
00387 #endif /* _STEREO_CALIBRATION_H_ */


asr_ivt
Author(s): Allgeyer Tobias, Hutmacher Robin, Kleinert Daniel, Meißner Pascal, Scholz Jonas, Stöckle Patrick
autogenerated on Thu Jun 6 2019 21:46:58