StereoCalibration.h
Go to the documentation of this file.
1 // ****************************************************************************
2 // This file is part of the Integrating Vision Toolkit (IVT).
3 //
4 // The IVT is maintained by the Karlsruhe Institute of Technology (KIT)
5 // (www.kit.edu) in cooperation with the company Keyetech (www.keyetech.de).
6 //
7 // Copyright (C) 2014 Karlsruhe Institute of Technology (KIT).
8 // All rights reserved.
9 //
10 // Redistribution and use in source and binary forms, with or without
11 // modification, are permitted provided that the following conditions are met:
12 //
13 // 1. Redistributions of source code must retain the above copyright
14 // notice, this list of conditions and the following disclaimer.
15 //
16 // 2. Redistributions in binary form must reproduce the above copyright
17 // notice, this list of conditions and the following disclaimer in the
18 // documentation and/or other materials provided with the distribution.
19 //
20 // 3. Neither the name of the KIT nor the names of its contributors may be
21 // used to endorse or promote products derived from this software
22 // without specific prior written permission.
23 //
24 // THIS SOFTWARE IS PROVIDED BY THE KIT AND CONTRIBUTORS “AS IS” AND ANY
25 // EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
26 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
27 // DISCLAIMED. IN NO EVENT SHALL THE KIT OR CONTRIBUTORS BE LIABLE FOR ANY
28 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
29 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
31 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
32 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
33 // THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
34 // ****************************************************************************
35 // ****************************************************************************
36 // Filename: StereoCalibration.h
37 // Author: Pedram Azad
38 // Date: 2004
39 // ****************************************************************************
40 
41 
42 #ifndef _STEREO_CALIBRATION_H_
43 #define _STEREO_CALIBRATION_H_
44 
45 
46 // ****************************************************************************
47 // Necessary includes
48 // ****************************************************************************
49 
50 #include "Math/Math3d.h"
51 
52 
53 // ****************************************************************************
54 // Forward declarations
55 // ****************************************************************************
56 
57 class CCalibration;
58 class CByteImage;
59 struct Vec2d;
60 struct Vec3d;
61 struct Mat3d;
62 struct PointPair2d;
63 struct PointPair3d;
64 
65 
66 
67 // ****************************************************************************
68 // CStereoCalibration
69 // ****************************************************************************
70 
88 {
89 public:
99 
104 
108  CStereoCalibration(const CStereoCalibration &stereoCalibration);
109 
110 
115  void Set(const CStereoCalibration &stereoCalibration);
116 
127  void SetSingleCalibrations(const CCalibration &leftCalibration, const CCalibration &rightCalibration, bool bTransformLeftCameraToIdentity = false);
128 
141  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);
142 
157  void SetExtrinsicParameters(const Mat3d& left_rotation, const Vec3d& left_translation, const Mat3d& right_rotation, const Vec3d& right_translation, bool bTransformLeftCameraToIdentity = false);
158 
172  bool LoadCameraParameters(const char *pCameraParameterFileName, bool bTransformLeftCameraToIdentity = true);
173 
207  bool SaveCameraParameters(const char *pCameraParameterFileName) const;
208 
209 
212 
215 
216 
231  void Calculate3DPoint(const Vec2d &cameraPointLeft, const Vec2d &cameraPointRight, Vec3d &worldPoint, bool bInputImagesAreRectified, bool bUseDistortionParameters = true, PointPair3d *pConnectionLine = 0);
232 
245  void CalculateEpipolarLineInLeftImage(const Vec2d &pointInRightImage, Vec3d &l);
246 
255  void CalculateEpipolarLineInLeftImage(const Vec2d &pointInRightImage, PointPair2d &epipolarLine);
256 
265  void CalculateEpipolarLineInLeftImage(const Vec2d &pointInRightImage, float &m, float &c);
266 
279  void CalculateEpipolarLineInRightImage(const Vec2d &pointInLeftImage, Vec3d &l);
280 
289  void CalculateEpipolarLineInRightImage(const Vec2d &pointInLeftImage, PointPair2d &epipolarLine);
290 
299  void CalculateEpipolarLineInRightImage(const Vec2d &pointInLeftImage, float &m, float &c);
300 
301 
311  float CalculateEpipolarLineInLeftImageDistance(const Vec2d &pointInLeftImage, const Vec2d &pointInRightImage);
312 
322  float CalculateEpipolarLineInRightImageDistance(const Vec2d &pointInLeftImage, const Vec2d &pointInRightImage);
323 
341  void GetProjectionMatricesForRectifiedImages(Mat3d &P1Left, Vec3d &p2Left, Mat3d &P1Right, Vec3d &p2Right) const;
342 
343 
344  // public attributes
346  int width;
348  int height;
349 
360 
371 
372 
373 private:
374  // private methods
377 
378  // private attributes
381 
382  Mat3d F, FT; // F = fundamental matrix, FT = transposed fundamental matrix
383 };
384 
385 
386 
387 #endif /* _STEREO_CALIBRATION_H_ */
bool LoadCameraParameters(const char *pCameraParameterFileName, bool bTransformLeftCameraToIdentity=true)
Initializes the stereo camera model, given a file path to a stereo camera parameter file...
Mat3d rectificationHomographyRight
The homography for the rectification mapping of the right image.
CCalibration * m_pRightCalibration
void SetSingleCalibrations(const CCalibration &leftCalibration, const CCalibration &rightCalibration, bool bTransformLeftCameraToIdentity=false)
Initializes the stereo camera model, given two instances of CCalibration.
Data structure for the representation of a 3D vector.
Definition: Math3d.h:73
Data structure for the representation of 8-bit grayscale images and 24-bit RGB (or HSV) color images ...
Definition: ByteImage.h:80
CCalibration * m_pLeftCalibration
void CalculateEpipolarLineInLeftImage(const Vec2d &pointInRightImage, Vec3d &l)
Given an image point in the right image, computes the corresponding epipolar line in the left image...
const CCalibration * GetLeftCalibration() const
Access to the instance of CCalibration for the camera model of the left camera.
float CalculateEpipolarLineInRightImageDistance(const Vec2d &pointInLeftImage, const Vec2d &pointInRightImage)
Given a point correspondence, computes the distance from the epipolar line in the right image...
void Calculate3DPoint(const Vec2d &cameraPointLeft, const Vec2d &cameraPointRight, Vec3d &worldPoint, bool bInputImagesAreRectified, bool bUseDistortionParameters=true, PointPair3d *pConnectionLine=0)
Computes a 3D point, given a point correspondence in both images, by performing stereo triangulation...
const GLubyte * c
Definition: glext.h:5181
float CalculateEpipolarLineInLeftImageDistance(const Vec2d &pointInLeftImage, const Vec2d &pointInRightImage)
Given a point correspondence, computes the distance from the epipolar line in the left image...
int height
The height of the images of the stereo camera system in pixels.
void GetProjectionMatricesForRectifiedImages(Mat3d &P1Left, Vec3d &p2Left, Mat3d &P1Right, Vec3d &p2Right) const
Sets up the projection matrix P for the rectified images.
int width
The width of the images of the stereo camera system in pixels.
Camera model and functions for a stereo camera system.
void SetExtrinsicParameters(const Mat3d &left_rotation, const Vec3d &left_translation, const Mat3d &right_rotation, const Vec3d &right_translation, bool bTransformLeftCameraToIdentity=false)
Sets the extrinsic parameters of both cameras.
~CStereoCalibration()
The destructor.
Mat3d rectificationHomographyLeft
The homography for the rectification mapping of the right image.
bool SaveCameraParameters(const char *pCameraParameterFileName) const
Writes the parameters of the camera model to camera parameter file.
CStereoCalibration()
The default constructor.
Data structure for the representation of a 2D vector.
Definition: Math2d.h:82
void CalculateEpipolarLineInRightImage(const Vec2d &pointInLeftImage, Vec3d &l)
Given an image point in the left image, computes the corresponding epipolar line in the right image...
Data structure for the representation of a 3x3 matrix.
Definition: Math3d.h:93
Camera model parameters and functions for a single camera.
Definition: Calibration.h:125
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)
Sets the distortion parameters of the distortion models of both cameras.
void Set(const CStereoCalibration &stereoCalibration)
Initializes the stereo camera model, given an instance of CStereoCalibration.
const CCalibration * GetRightCalibration() const
Access to the instance of CCalibration for the camera model of the right camera.


asr_ivt
Author(s): Allgeyer Tobias, Hutmacher Robin, Kleinert Daniel, Meißner Pascal, Scholz Jonas, Stöckle Patrick
autogenerated on Mon Dec 2 2019 03:47:28