$search

ipa_CameraSensors::CameraSensorToolbox Class Reference

#include <CameraSensorToolbox.h>

List of all members.

Public Member Functions

 CameraSensorToolbox (const CameraSensorToolbox &cameraSensorToolbox)
 Copy constructor.
 CameraSensorToolbox ()
 Constructor.
virtual cv::Mat GetDistortionMapX (ipa_CameraSensors::t_cameraType cameraType, int cameraIndex)
virtual cv::Mat GetDistortionMapY (ipa_CameraSensors::t_cameraType cameraType, int cameraIndex)
virtual cv::Mat GetDistortionParameters (ipa_CameraSensors::t_cameraType cameraType, int cameraIndex)
virtual cv::Mat GetExtrinsicParameters (ipa_CameraSensors::t_cameraType cameraType, int cameraIndex)
virtual cv::Mat GetIntrinsicMatrix (ipa_CameraSensors::t_cameraType cameraType, int cameraIndex)
virtual unsigned long Init (const std::map< std::string, cv::Mat > *intrinsicMatrices, const std::map< std::string, cv::Mat > *distortionParameters, const std::map< std::string, cv::Mat > *extrinsicMatrices, const std::map< std::string, cv::Mat > *undistortMapsX, const std::map< std::string, cv::Mat > *undistortMapY, const CvSize imageSize)
virtual unsigned long Init (std::string directory, ipa_CameraSensors::t_cameraType cameraType, int cameraIndex, const CvSize imageSize)
CameraSensorToolboxoperator= (const CameraSensorToolbox &cameraSensorToolbox)
 Overwritten assignment operator.
virtual unsigned long Release ()
virtual unsigned long RemoveDistortion (ipa_CameraSensors::t_cameraType cameraType, int cameraIndex, const cv::Mat &src, cv::Mat &dst)
virtual unsigned long ReprojectXYZ (ipa_CameraSensors::t_cameraType cameraType, int cameraIndex, double x, double y, double z, int &u, int &v)
virtual unsigned long SetExtrinsicParameters (std::string key, const cv::Mat &_rotation, const cv::Mat &_translation)
virtual unsigned long SetExtrinsicParameters (ipa_CameraSensors::t_cameraType cameraType, int cameraIndex, const cv::Mat &_rotation, const cv::Mat &_translation)
virtual unsigned long SetIntrinsicParameters (std::string key, const cv::Mat &_intrinsicMatrix, const cv::Mat &_distortion_coeffs)
virtual unsigned long SetIntrinsicParameters (ipa_CameraSensors::t_cameraType cameraType, int cameraIndex, const cv::Mat &_intrinsicMatrix, const cv::Mat &_distortion_coeffs)
 ~CameraSensorToolbox ()
 Destructor.

Private Member Functions

virtual unsigned long ConvertCameraTypeToString (ipa_CameraSensors::t_cameraType cameraType, std::string &cameraTypeString)
virtual unsigned long LoadParameters (const char *filename, ipa_CameraSensors::t_cameraType cameraType, int cameraIndex)

Private Attributes

std::map< std::string, cv::Mat > m_distortionCoeffs
 Distortion coefficients [k1, k2, p1=0, p2=0].
std::map< std::string, cv::Mat > m_extrinsicMatrices
CvSize m_ImageSize
 The size of the image that is returned.
bool m_Initialized
 True, when the camera has sucessfully been initialized.
std::map< std::string, cv::Mat > m_intrinsicMatrices
 Intrinsic parameters [fx 0 cx; 0 fy cy; 0 0 1].
std::map< std::string, cv::Mat > m_undistortMapsX
 where R is a 3x3 rotation matrix and T is a 3x1 translation vector.
std::map< std::string, cv::Mat > m_undistortMapsY
 The output array of Y coordinates for the undistortion map.

Detailed Description

A toolbox for common color cameras. Provides generic functions like image undistortion. Holds essential matrices like distortion, intrinsic and extrinsic matrix. For each camera in the system a separate camera toolbox should be initialized.

Definition at line 87 of file CameraSensorToolbox.h.


Constructor & Destructor Documentation

CameraSensorToolbox::CameraSensorToolbox (  ) 

Constructor.

Definition at line 73 of file CameraSensorToolbox.cpp.

CameraSensorToolbox::~CameraSensorToolbox (  ) 

Destructor.

Definition at line 78 of file CameraSensorToolbox.cpp.

CameraSensorToolbox::CameraSensorToolbox ( const CameraSensorToolbox cameraSensorToolbox  ) 

Copy constructor.

Definition at line 97 of file CameraSensorToolbox.cpp.


Member Function Documentation

unsigned long CameraSensorToolbox::ConvertCameraTypeToString ( ipa_CameraSensors::t_cameraType  cameraType,
std::string &  cameraTypeString 
) [private, virtual]

Converts the camera type enumeration value to a string.

Parameters:
cameraType The camera type as enumeration
cameraTypeString The resulting string
Returns:
Retun code

Definition at line 248 of file CameraSensorToolbox.cpp.

cv::Mat CameraSensorToolbox::GetDistortionMapX ( ipa_CameraSensors::t_cameraType  cameraType,
int  cameraIndex 
) [virtual]

Returns the distortion map for x components For each x pixel, the undistorted location is specified within the distortion map.

Parameters:
cameraType The camera type, the parameters are optimized with
cameraIndex Index of the specified camera, the parameters are optimized with
Returns:
The distortion map for x components

Definition at line 479 of file CameraSensorToolbox.cpp.

cv::Mat CameraSensorToolbox::GetDistortionMapY ( ipa_CameraSensors::t_cameraType  cameraType,
int  cameraIndex 
) [virtual]

Returns the distortion map for x components For each y pixel, the undistorted location is specified within the distortion map.

Parameters:
cameraType The camera type, the parameters are optimized with
cameraIndex Index of the specified camera, the parameters are optimized with
Returns:
The distortion map for y components

Definition at line 499 of file CameraSensorToolbox.cpp.

cv::Mat CameraSensorToolbox::GetDistortionParameters ( ipa_CameraSensors::t_cameraType  cameraType,
int  cameraIndex 
) [virtual]

Returns the distortion coefficients. The matrix is given by [k1, k2, p1, p2] where k1, k2 are radial distortion coefficients and p1, p2 are tangential distortion coefficients.

Parameters:
cameraType The camera type, the parameters are optimized with
cameraIndex Index of the specified camera, the parameters are optimized with
Returns:
The OpenCV matrix that refers to the distortion parameters.

Definition at line 459 of file CameraSensorToolbox.cpp.

cv::Mat CameraSensorToolbox::GetExtrinsicParameters ( ipa_CameraSensors::t_cameraType  cameraType,
int  cameraIndex 
) [virtual]

Returns a matrix of the camera's extrinsic parameters. The extrinsic matrix is a 4x3 matrix of the format (R|t), where R desribes a 3x3 rotation matrix and t a 3x1 translation vector.

Parameters:
cameraType The camera type
cameraIndex The camera index
Returns:
The OpenCV matrix that refers to the extrinsic parameters of the camera.

Definition at line 294 of file CameraSensorToolbox.cpp.

cv::Mat CameraSensorToolbox::GetIntrinsicMatrix ( ipa_CameraSensors::t_cameraType  cameraType,
int  cameraIndex 
) [virtual]

Returns a matrix of the camera's intrinsic parameters.

Parameters:
cameraType The camera type, the parameters are optimized with
cameraIndex Index of the specified camera, the parameters are optimized with
Returns:
The OpenCV matrix that should refer to the intrinsic parameters

Definition at line 360 of file CameraSensorToolbox.cpp.

unsigned long CameraSensorToolbox::Init ( const std::map< std::string, cv::Mat > *  intrinsicMatrices,
const std::map< std::string, cv::Mat > *  distortionParameters,
const std::map< std::string, cv::Mat > *  extrinsicMatrices,
const std::map< std::string, cv::Mat > *  undistortMapsX,
const std::map< std::string, cv::Mat > *  undistortMapY,
const CvSize  imageSize 
) [virtual]

Initialize the camera sensor toolbox.

Parameters:
intrinsicMatrices Intrinsic parameters [fx 0 cx; 0 fy cy; 0 0 1]
distortionParameters Distortion coefficients [k1, k2, p1=0, p2=0]
extrinsicMatrices 3x4 matrix of the form (R|t), where R is a 3x3 rotation matrix and t a 3x1 translation vector.
undistortMapsX The output array of x coordinates for the undistortion map
undistortMapY The output array of Y coordinates for the undistortion map
imageSize The Size of the image returned by the camera
Returns:
Return code

Definition at line 201 of file CameraSensorToolbox.cpp.

unsigned long CameraSensorToolbox::Init ( std::string  directory,
ipa_CameraSensors::t_cameraType  cameraType,
int  cameraIndex,
const CvSize  imageSize 
) [virtual]

Initialize the camera sensor toolbox. The matrices are read from the specified xml configuration file.

Parameters:
directory The director where the configuration resides, with ending '/'.
cameraType The camera type
cameraIndex The camera index
imageSize The Size of the image returned by the camera
Returns:
Return code

Definition at line 183 of file CameraSensorToolbox.cpp.

unsigned long CameraSensorToolbox::LoadParameters ( const char *  filename,
ipa_CameraSensors::t_cameraType  cameraType,
int  cameraIndex 
) [private, virtual]

Parses the XML configuration file, that holds the camera settings

Parameters:
filename The file name and path of the configuration file
cameraType The camera type i.e. CAM_AVTPIKE or CAM_IC
cameraIndex The index of the camera within the configuration file i.e. AvtPikeCam_0 or ICCam_1
Returns:
Return value

Definition at line 592 of file CameraSensorToolbox.cpp.

CameraSensorToolbox & CameraSensorToolbox::operator= ( const CameraSensorToolbox cameraSensorToolbox  ) 

Overwritten assignment operator.

Definition at line 136 of file CameraSensorToolbox.cpp.

unsigned long CameraSensorToolbox::Release (  )  [virtual]

Release all allocated memory.

Returns:
Return code

Definition at line 83 of file CameraSensorToolbox.cpp.

unsigned long CameraSensorToolbox::RemoveDistortion ( ipa_CameraSensors::t_cameraType  cameraType,
int  cameraIndex,
const cv::Mat &  src,
cv::Mat &  dst 
) [virtual]

Removes distortion from an image. It is necessary to set the distortion coefficients prior to calling this function.

Parameters:
t_cameraType The camera type
cameraIndex Index of the specified camera, the parameters are optimized with
src The distorted image.
dst The undistorted image.
Returns:
Return code.

Definition at line 519 of file CameraSensorToolbox.cpp.

unsigned long CameraSensorToolbox::ReprojectXYZ ( ipa_CameraSensors::t_cameraType  cameraType,
int  cameraIndex,
double  x,
double  y,
double  z,
int &  u,
int &  v 
) [virtual]

Returns image coordinates (u,v) from (x,y,z) coordinates. (x,y,z) is expressed within the cameras coordinate system.

Parameters:
t_cameraType The camera type
cameraIndex Index of the specified camera, the parameters are optimized with
u image coordinate u
v image coordinate v
x x-coordinates in mm relative to the camera's coodinate system.
y y-coordinates in mm relative to the camera's coodinate system.
z z-coordinates in mm relative to the camera's coodinate system.
Returns:
Return code

Definition at line 545 of file CameraSensorToolbox.cpp.

unsigned long CameraSensorToolbox::SetExtrinsicParameters ( std::string  key,
const cv::Mat &  _rotation,
const cv::Mat &  _translation 
) [virtual]

Sets the camera's extrinsic parameters. The extrinsic matrix is a 4x3 matrix of the format (R|T), where R desribes a 3x3 rotation matrix and T a 3x1 translation vector.

Parameters:
key The key/identifier within the map of extrinsic matrices
_translation 3x1 translation vector.
_rotation 3x3 rotation matrix.
Returns:
Return code.

Definition at line 326 of file CameraSensorToolbox.cpp.

unsigned long CameraSensorToolbox::SetExtrinsicParameters ( ipa_CameraSensors::t_cameraType  cameraType,
int  cameraIndex,
const cv::Mat &  _rotation,
const cv::Mat &  _translation 
) [virtual]

Sets the camera's extrinsic parameters. The extrinsic matrix is a 4x3 matrix of the format (R|T), where R desribes a 3x3 rotation matrix and T a 3x1 translation vector.

Parameters:
t_cameraType The camera type
cameraIndex The camera index
_translation 3x1 translation vector.
_rotation 3x3 rotation matrix.
Returns:
Return code.

Definition at line 314 of file CameraSensorToolbox.cpp.

unsigned long CameraSensorToolbox::SetIntrinsicParameters ( std::string  key,
const cv::Mat &  _intrinsicMatrix,
const cv::Mat &  _distortion_coeffs 
) [virtual]

Initializes the distortion parameters. The following equations apply: (x,y,z) = R*(X,Y,Z) + t and x' = x/z, y' = y/z and u = fx*x' + cx, v = fy*y' + cy. The model might be extended with distortion coefficients to replace x' and y' with x'' = x'*(1 + k1*r^2 + k2*r^4) + 2*p1*x'*y' + p2(r^2+2*x'^2) y'' = y'*(1 + k1*r^2 + k2*r^4) + p1(r^2+2*y'^2) + 2*p2*x'*y'

Parameters:
key The key/identifier within the map of extrinsic matrices
_intrinsicMatrix The cameras intrinsic matrix
_distortion_coeffs radial and tangential distortion coefficient
Returns:
Return code.

Definition at line 392 of file CameraSensorToolbox.cpp.

unsigned long CameraSensorToolbox::SetIntrinsicParameters ( ipa_CameraSensors::t_cameraType  cameraType,
int  cameraIndex,
const cv::Mat &  _intrinsicMatrix,
const cv::Mat &  _distortion_coeffs 
) [virtual]

Initializes the distortion parameters. The following equations apply: (x,y,z) = R*(X,Y,Z) + t and x' = x/z, y' = y/z and u = fx*x' + cx, v = fy*y' + cy. The model might be extended with distortion coefficients to replace x' and y' with x'' = x'*(1 + k1*r^2 + k2*r^4) + 2*p1*x'*y' + p2(r^2+2*x'^2) y'' = y'*(1 + k1*r^2 + k2*r^4) + p1(r^2+2*y'^2) + 2*p2*x'*y'

Parameters:
cameraType The camera type, the parameters are optimized with
cameraIndex Index of the specified camera, the parameters are optimized with
_intrinsicMatrix The cameras intrinsic matrix
_distortion_coeffs radial and tangential distortion coefficient
Returns:
Return code.

Definition at line 380 of file CameraSensorToolbox.cpp.


Member Data Documentation

std::map<std::string, cv::Mat> ipa_CameraSensors::CameraSensorToolbox::m_distortionCoeffs [private]

Distortion coefficients [k1, k2, p1=0, p2=0].

Definition at line 252 of file CameraSensorToolbox.h.

std::map<std::string, cv::Mat> ipa_CameraSensors::CameraSensorToolbox::m_extrinsicMatrices [private]

a map of 3x4 matrix of the form (R|T),

Definition at line 253 of file CameraSensorToolbox.h.

The size of the image that is returned.

Definition at line 259 of file CameraSensorToolbox.h.

True, when the camera has sucessfully been initialized.

Definition at line 249 of file CameraSensorToolbox.h.

std::map<std::string, cv::Mat> ipa_CameraSensors::CameraSensorToolbox::m_intrinsicMatrices [private]

Intrinsic parameters [fx 0 cx; 0 fy cy; 0 0 1].

Definition at line 251 of file CameraSensorToolbox.h.

std::map<std::string, cv::Mat> ipa_CameraSensors::CameraSensorToolbox::m_undistortMapsX [private]

where R is a 3x3 rotation matrix and T is a 3x1 translation vector.

The output array of x coordinates for the undistortion map

Definition at line 256 of file CameraSensorToolbox.h.

std::map<std::string, cv::Mat> ipa_CameraSensors::CameraSensorToolbox::m_undistortMapsY [private]

The output array of Y coordinates for the undistortion map.

Definition at line 257 of file CameraSensorToolbox.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


cob_vision_utils
Author(s): Jan Fischer
autogenerated on Fri Mar 1 14:55:44 2013