Camera model and functions for a stereo camera system. More...
#include <StereoCalibration.h>
Public Member Functions | |
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. | |
void | CalculateEpipolarLineInLeftImage (const Vec2d &pointInRightImage, Vec3d &l) |
Given an image point in the right image, computes the corresponding epipolar line in the left image. | |
void | CalculateEpipolarLineInLeftImage (const Vec2d &pointInRightImage, PointPair2d &epipolarLine) |
Given an image point in the right image, computes the corresponding epipolar line in the left image. | |
void | CalculateEpipolarLineInLeftImage (const Vec2d &pointInRightImage, float &m, float &c) |
Deprecated. | |
float | CalculateEpipolarLineInLeftImageDistance (const Vec2d &pointInLeftImage, const Vec2d &pointInRightImage) |
Given a point correspondence, computes the distance from the epipolar line in the left image. | |
void | CalculateEpipolarLineInRightImage (const Vec2d &pointInLeftImage, Vec3d &l) |
Given an image point in the left image, computes the corresponding epipolar line in the right image. | |
void | CalculateEpipolarLineInRightImage (const Vec2d &pointInLeftImage, PointPair2d &epipolarLine) |
Given an image point in the left image, computes the corresponding epipolar line in the right image. | |
void | CalculateEpipolarLineInRightImage (const Vec2d &pointInLeftImage, float &m, float &c) |
Deprecated. | |
float | CalculateEpipolarLineInRightImageDistance (const Vec2d &pointInLeftImage, const Vec2d &pointInRightImage) |
Given a point correspondence, computes the distance from the epipolar line in the right image. | |
CStereoCalibration () | |
The default constructor. | |
CStereoCalibration (const CStereoCalibration &stereoCalibration) | |
The copy constructor. | |
const CCalibration * | GetLeftCalibration () const |
Access to the instance of CCalibration for the camera model of the left camera. | |
void | GetProjectionMatricesForRectifiedImages (Mat3d &P1Left, Vec3d &p2Left, Mat3d &P1Right, Vec3d &p2Right) const |
Sets up the projection matrix P for the rectified images. | |
const CCalibration * | GetRightCalibration () const |
Access to the instance of CCalibration for the camera model of the right camera. | |
bool | LoadCameraParameters (const char *pCameraParameterFileName, bool bTransformLeftCameraToIdentity=true) |
Initializes the stereo camera model, given a file path to a stereo camera parameter file. | |
bool | SaveCameraParameters (const char *pCameraParameterFileName) const |
Writes the parameters of the camera model to camera parameter file. | |
void | Set (const CStereoCalibration &stereoCalibration) |
Initializes the stereo camera model, given an instance of CStereoCalibration. | |
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 | 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. | |
void | SetSingleCalibrations (const CCalibration &leftCalibration, const CCalibration &rightCalibration, bool bTransformLeftCameraToIdentity=false) |
Initializes the stereo camera model, given two instances of CCalibration. | |
~CStereoCalibration () | |
The destructor. | |
Public Attributes | |
int | height |
The height of the images of the stereo camera system in pixels. | |
Mat3d | rectificationHomographyLeft |
The homography for the rectification mapping of the right image. | |
Mat3d | rectificationHomographyRight |
The homography for the rectification mapping of the right image. | |
int | width |
The width of the images of the stereo camera system in pixels. | |
Private Member Functions | |
void | CalculateFundamentalMatrix () |
void | TransformLeftCameraToIdentity () |
Private Attributes | |
Mat3d | F |
Mat3d | FT |
CCalibration * | m_pLeftCalibration |
CCalibration * | m_pRightCalibration |
Camera model and functions for a stereo camera system.
Handles two instances of CCalibration to model a stereo camera system, computes the epipolar geometriy and performs stereo triangulation.
The camera model that is used for modeling the two individual cameras, including the extrinsic camera parameters, is described in detail in the documentation of the class CCalibration.
The instance can be initialized either by reading a stereo camera parameter file (LoadCameraParameters(const char*, bool) or by assigning two instances of CCalibration (SetSingleCalibrations(const CCalibration&, const CCalibration&, bool). It is possible to adapt the extrinsic parameters, so that the world coordinate system and the camera coordinate system of the left camera become equal.
After initialization, a 3D point can be calculated, given a point correspondence in the left and right camera image (Calculate3DPoint(const Vec2d&, const Vec2d&, Vec3d&, bool, bool, PointPair3d*). Furthermore, access to the epipolar lines is offered.
Definition at line 87 of file StereoCalibration.h.
The default constructor.
The default constructor initializes the stereo camera model with a standard camera setup with a baseline of 100 mm (no orientation difference, i.e. and ), where I denotes the 3x3 identity matrix..
The intrinsic parameters of the cameras are equal and are listed in CCalibration::CCalibration().
Definition at line 66 of file StereoCalibration.cpp.
The destructor.
Definition at line 78 of file StereoCalibration.cpp.
CStereoCalibration::CStereoCalibration | ( | const CStereoCalibration & | stereoCalibration | ) |
The copy constructor.
Definition at line 84 of file StereoCalibration.cpp.
void CStereoCalibration::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.
[in] | cameraPointLeft | The 2D point in the left image. |
[in] | cameraPointRight | The 2D point in the right image. |
[out] | worldPoint | The result 3D point in the world coordinate system. |
[in] | bInputImagesAreRectified | If set to true, cameraPointLeft and cameraPointRight are transformed to the corresponding 2D points in the original images, so that the camera models can be applied. If set to false, cameraPointLeft and cameraPointRight must have been computed on non-rectified images. |
[in] | bUseDistortionParameters | If set to true, the (inverse) distortion model will be applied before linear back projection, i.e. cameraPointLeft and cameraPointRight must contain distorted image coordinates. If set to false, the distortion model is skipped, i.e. cameraPointLeft and cameraPointRight must contain undistorted image coordinates. In other words: If the images in which the coordinates cameraPointLeft and cameraPoint right were calculate were undistorted beforehand then set this parameter to false, otherwise to true. |
[out] | pConnectionLine | Optional output parameter for receiving the two endpoints of the shortest connection line between the two re-projected straight lines. The parameter worldPoint contains the center of this connection line. |
Definition at line 235 of file StereoCalibration.cpp.
void CStereoCalibration::CalculateEpipolarLineInLeftImage | ( | const Vec2d & | pointInRightImage, |
Vec3d & | l | ||
) |
Given an image point in the right image, computes the corresponding epipolar line in the left image.
The representation of the epipolar line is defined as:
.
All image points (u, v) lying on the epipolar line satisfy this equation. Note that is the normal vector the line.
[in] | pointInRightImage | The 2D point in the right image. |
[out] | l | A 3D vector representing the result epipolar line. It is l1 = l.x, l2 = l.y, l3 = l.z. |
Definition at line 304 of file StereoCalibration.cpp.
void CStereoCalibration::CalculateEpipolarLineInLeftImage | ( | const Vec2d & | pointInRightImage, |
PointPair2d & | epipolarLine | ||
) |
Given an image point in the right image, computes the corresponding epipolar line in the left image.
The epipolar line is represented by the two end points of the intersection with the image.
[in] | pointInRightImage | The 2D point in the right image. |
[out] | epipolarLine | Result parameter that contains the two end points. |
Definition at line 319 of file StereoCalibration.cpp.
void CStereoCalibration::CalculateEpipolarLineInLeftImage | ( | const Vec2d & | pointInRightImage, |
float & | m, | ||
float & | c | ||
) |
Deprecated.
This function is deprecated. Use CalculateEpipolarLineInLeftImage(const Vec2d&, Vec3d&) or CalculateEpipolarLineInLeftImage(const Vec2d&, PointPair2d&) instead.
Models the line as . This representation fails for vertical lines.
Definition at line 310 of file StereoCalibration.cpp.
float CStereoCalibration::CalculateEpipolarLineInLeftImageDistance | ( | const Vec2d & | pointInLeftImage, |
const Vec2d & | pointInRightImage | ||
) |
Given a point correspondence, computes the distance from the epipolar line in the left image.
Given pointInRightImage, computes the corresponding epipolar in the left image and the computes the distance of pointInLeftImage to it.
[in] | pointInLeftImage | The 2D point in the left image. |
[in] | pointInRightImage | The 2D point in the right image. |
Definition at line 394 of file StereoCalibration.cpp.
void CStereoCalibration::CalculateEpipolarLineInRightImage | ( | const Vec2d & | pointInLeftImage, |
Vec3d & | l | ||
) |
Given an image point in the left image, computes the corresponding epipolar line in the right image.
The representation of the epipolar line is defined as:
.
All image points (u, v) lying on the epipolar line satisfy this equation. Note that is the normal vector the line.
[in] | pointInLeftImage | The 2D point in the left image. |
[out] | l | A 3D vector representing the result epipolar line. It is l1 = l.x, l2 = l.y, l3 = l.z. |
Definition at line 349 of file StereoCalibration.cpp.
void CStereoCalibration::CalculateEpipolarLineInRightImage | ( | const Vec2d & | pointInLeftImage, |
PointPair2d & | epipolarLine | ||
) |
Given an image point in the left image, computes the corresponding epipolar line in the right image.
The epipolar line is represented by the two end points of the intersection with the image.
[in] | pointInLeftImage | The 2D point in the right image. |
[out] | epipolarLine | Result parameter that contains the two end points. |
Definition at line 364 of file StereoCalibration.cpp.
void CStereoCalibration::CalculateEpipolarLineInRightImage | ( | const Vec2d & | pointInLeftImage, |
float & | m, | ||
float & | c | ||
) |
Deprecated.
This function is deprecated. Use CalculateEpipolarLineInRightImage(const Vec2d&, Vec3d&) or CalculateEpipolarLineInRightImage(const Vec2d&, PointPair2d&) instead.
Models the line as . This representation fails for vertical lines.
Definition at line 355 of file StereoCalibration.cpp.
float CStereoCalibration::CalculateEpipolarLineInRightImageDistance | ( | const Vec2d & | pointInLeftImage, |
const Vec2d & | pointInRightImage | ||
) |
Given a point correspondence, computes the distance from the epipolar line in the right image.
Given pointInLeftImage, computes the corresponding epipolar in the right image and the computes the distance of pointInRightImage to it.
[in] | pointInLeftImage | The 2D point in the left image. |
[in] | pointInRightImage | The 2D point in the right image. |
Definition at line 407 of file StereoCalibration.cpp.
void CStereoCalibration::CalculateFundamentalMatrix | ( | ) | [private] |
Definition at line 211 of file StereoCalibration.cpp.
const CCalibration* CStereoCalibration::GetLeftCalibration | ( | ) | const [inline] |
Access to the instance of CCalibration for the camera model of the left camera.
Definition at line 211 of file StereoCalibration.h.
void CStereoCalibration::GetProjectionMatricesForRectifiedImages | ( | Mat3d & | P1Left, |
Vec3d & | p2Left, | ||
Mat3d & | P1Right, | ||
Vec3d & | p2Right | ||
) | const |
Sets up the projection matrix P for the rectified images.
The projection matrix P for an image that was rectified according to the homography H is a 3x4 matrix defined as:
, where K denotes the calibration matrix (see CCalibration::GetCalibrationMatrix), R and t are the extrinsic parameters, and H is the homography that maps undistorted image coordinates to rectified image coordinates.
Note that in the case of the left camera H is the inverse of CStereoCalibration::rectificationHomographyLeft, and in the case of the right camera H is the inverse of CStereoCalibration::rectificationHomographyRight.
The camera model is described in the general information about the class CCalibration.
[out] | P1Left | The left 3x3 part of the projection matrix for the left camera, i.e. P1Left = H_left K_left R_left. |
[out] | p2Left | The right 3x1 part of the projection matrix for the right camera, i.e. p2Left = H_left K_left t_left. |
[out] | P1Right | The left 3x3 part of the projection matrix for the right camera, i.e. P1Right = H_right K_right R_right. |
[out] | p2Right | The right 3x1 part of the projection matrix for the right camera, i.e. p2Right = H_right K_right t_right. |
Definition at line 583 of file StereoCalibration.cpp.
const CCalibration* CStereoCalibration::GetRightCalibration | ( | ) | const [inline] |
Access to the instance of CCalibration for the camera model of the right camera.
Definition at line 214 of file StereoCalibration.h.
bool CStereoCalibration::LoadCameraParameters | ( | const char * | pCameraParameterFileName, |
bool | bTransformLeftCameraToIdentity = true |
||
) |
Initializes the stereo camera model, given a file path to a stereo camera parameter file.
The format of the file is the same as the one used in OpenCV 1.0. It is...
Camera calibration can be performed with the application found in IVT/examples/CalibrationApp (resp. IVT/win32/CalibrationApp). See also the class CDLTCalibration.
[in] | pCameraParameterFileName | The file path to the camera parameter file to be loaded. |
bTransformLeftCameraToIdentity | If set to true, then the extrinsic parameters will be adapted so that the extrinsic parameters of the left camera become the identiy mapping, i.e. and , where I denotes the 3x3 identity matrix. That means that the world coordinate systems and the camera coordinate system of the left camera become equal. If set to false, the extrinsic parameters are not changed. Note that the internal fundamental matrix for the epipolar geometry is not affected by the choice of this flag. |
Definition at line 421 of file StereoCalibration.cpp.
bool CStereoCalibration::SaveCameraParameters | ( | const char * | pCameraParameterFileName | ) | const |
Writes the parameters of the camera model to camera parameter file.
The format of the file is the same as the one used in OpenCV 1.0. The file format is described in LoadCameraParameters(const char*, bool).
In the following specification of the file format, the first row of each double row contains the parameters of the first, i.e. left, camera, and the second row the parameters of the right camera, respectively. The parameter denotes the number of cameras.
n
w h fx 0 cx 0 fy cy 0 0 1 d1 d2 d3 d4 r1 r2 r3 r4 r5 r6 r7 r8 r9 t1 t2 t3
w h fx 0 cx 0 fy cy 0 0 1 d1 d2 d3 d4 r1 r2 r3 r4 r5 r6 r7 r8 r9 t1 t2 t3
u1 v1 u2 v2 u3 v3 u4 v4
u1 v1 u2 v2 u3 v3 u4 v4
a1 a2 a3 a4 a5 a6 a7 a8 a9
a1 a2 a3 a4 a5 a6 a7 a8 a9
For each camera, the parameters w and h denote the width and height, respectively. The next nine parameters define the calibration matrix (see CCalibration::GetCalibrationMatrix). The parameters d1-d4 denote the distortion parameters of the distortion model, the extrinsic parameters r1-r9 define the rotation matrix R and t1-t3 the translation vector t (see camera model description in the documentation of the class CCalibration). These parameters of both cameras fully describe the epipolar geometry.
The parameters (u1, v1), ..., (u4, v4) define the corner points of the destination quadrangle after rectification. These parameters are not necessary (and redundant) and are therefore not read by the IVT.
Finally, the rectification parameters a1-a9 specify the 3x3 homography matrix A. This homography computes the image coordinates in the original image for given image coordinates in the rectified images. It can thus be directly used to compute a lookup table for the mapping, which is implemented efficiently by the class CRectification.
[in] | pCameraParameterFileName | The file path to the target camera parameter file. |
Definition at line 509 of file StereoCalibration.cpp.
void CStereoCalibration::Set | ( | const CStereoCalibration & | stereoCalibration | ) |
Initializes the stereo camera model, given an instance of CStereoCalibration.
stereoCalibration | The template instance. |
Definition at line 106 of file StereoCalibration.cpp.
void CStereoCalibration::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.
[in] | d1_left | The first radial lens distortion parameter of the left camera. |
[in] | d2_left | The second radial lens distortion parameter of the left camera. |
[in] | d3_left | The first tangential lens distortion parameter of the left camera. |
[in] | d4_left | The second tangential lens distortion parameter of the left camera. |
[in] | d1_right | The first radial lens distortion parameter of the right camera. |
[in] | d2_right | The second radial lens distortion parameter of the right camera. |
[in] | d3_right | The first tangential lens distortion parameter of the right camera. |
[in] | d4_right | The second tangential lens distortion parameter of the right camera. |
Definition at line 121 of file StereoCalibration.cpp.
void CStereoCalibration::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.
The member variables CCalibration::m_rotation_inverse and CCalibration::m_translation_inverse for both cameras are updated automatically.
[in] | left_rotation | The rotation matrix for the left camera as part of the extrinsic camera parameters. |
[in] | left_translation | The translation vector for the left camera as part of the extrinsic camera parameters. |
[in] | right_rotation | The rotation matrix for the right camera as part of the extrinsic camera parameters. |
[in] | right_translation | The translation vector for the right camera as part of the extrinsic camera parameters. |
bTransformLeftCameraToIdentity | If set to true, then the extrinsic parameters will be adapted so that the extrinsic parameters of the left camera become the identiy mapping, i.e. and , where I denotes the 3x3 identity matrix. That means that the world coordinate systems and the camera coordinate system of the left camera become equal. If set to false, the extrinsic parameters are not changed. Note that the internal fundamental matrix for the epipolar geometry is not affected by the choice of this flag. |
Definition at line 165 of file StereoCalibration.cpp.
void CStereoCalibration::SetSingleCalibrations | ( | const CCalibration & | leftCalibration, |
const CCalibration & | rightCalibration, | ||
bool | bTransformLeftCameraToIdentity = false |
||
) |
Initializes the stereo camera model, given two instances of CCalibration.
leftCalibration | The template instance for the left camera. |
rightCalibration | The template instance for the right camera. |
bTransformLeftCameraToIdentity | If set to true, then the extrinsic parameters will be adapted so that the extrinsic parameters of the left camera become the identiy mapping, i.e. and , where I denotes the 3x3 identity matrix. That means that the world coordinate systems and the camera coordinate system of the left camera become equal. If set to false, the extrinsic parameters are not changed. Note that the internal fundamental matrix for the epipolar geometry is not affected by the choice of this flag. |
Definition at line 127 of file StereoCalibration.cpp.
void CStereoCalibration::TransformLeftCameraToIdentity | ( | ) | [private] |
Definition at line 192 of file StereoCalibration.cpp.
Mat3d CStereoCalibration::F [private] |
Definition at line 382 of file StereoCalibration.h.
Mat3d CStereoCalibration::FT [private] |
Definition at line 382 of file StereoCalibration.h.
The height of the images of the stereo camera system in pixels.
Definition at line 348 of file StereoCalibration.h.
Definition at line 379 of file StereoCalibration.h.
Definition at line 380 of file StereoCalibration.h.
The homography for the rectification mapping of the right image.
Given a point in the rectified image, applying this homography computes the corresponding point in the original image (see also Math2d::ApplyHomography).
This member variable is only valid if the method LoadCameraParameters(const char*, bool) was used for initialization.
Use StereoCalibrationCV::CalculateRectificationHomographies if any other method was used for initialization and this member is needed (mainly if the class CRectification is to be used).
Definition at line 359 of file StereoCalibration.h.
The homography for the rectification mapping of the right image.
Given a point in the rectified image, applying this homography computes the corresponding point in the original image (see also Math2d::ApplyHomography).
This member variable is only valid if the method LoadCameraParameters(const char*, bool) was used for initialization.
Use StereoCalibrationCV::CalculateRectificationHomographies if any other method was used for initialization and this member is needed (mainly if the class CRectification is to be used).
Definition at line 370 of file StereoCalibration.h.
The width of the images of the stereo camera system in pixels.
Definition at line 346 of file StereoCalibration.h.