Visual Servoing Platform  version 3.6.1 under development (2024-04-18)
vpCalibration Class Reference

#include <visp3/vision/vpCalibration.h>

Public Types

enum  vpCalibrationMethodType {
  CALIB_LAGRANGE , CALIB_VIRTUAL_VS , CALIB_VIRTUAL_VS_DIST , CALIB_LAGRANGE_VIRTUAL_VS ,
  CALIB_LAGRANGE_VIRTUAL_VS_DIST
}
 

Public Member Functions

 vpCalibration ()
 
 vpCalibration (const vpCalibration &c)
 
virtual ~vpCalibration ()
 
int addPoint (double X, double Y, double Z, vpImagePoint &ip)
 
vpCalibrationoperator= (const vpCalibration &twinCalibration)
 
int clearPoint ()
 
int computeCalibration (vpCalibrationMethodType method, vpHomogeneousMatrix &cMo_est, vpCameraParameters &cam_est, bool verbose=false)
 
void computeStdDeviation (double &deviation, double &deviation_dist)
 
double computeStdDeviation (const vpHomogeneousMatrix &cMo_est, const vpCameraParameters &camera)
 
double computeStdDeviation_dist (const vpHomogeneousMatrix &cMo_est, const vpCameraParameters &camera)
 
int displayData (vpImage< unsigned char > &I, vpColor color=vpColor::red, unsigned int thickness=1, int subsampling_factor=1)
 
int displayGrid (vpImage< unsigned char > &I, vpColor color=vpColor::yellow, unsigned int thickness=1, int subsampling_factor=1)
 
double getResidual (void) const
 
double getResidual_dist (void) const
 
unsigned int get_npt () const
 
int init ()
 
int readData (const std::string &filename)
 
void setAspectRatio (double aspect_ratio)
 
int writeData (const std::string &filename)
 

Static Public Member Functions

static int computeCalibrationMulti (vpCalibrationMethodType method, std::vector< vpCalibration > &table_cal, vpCameraParameters &cam_est, double &globalReprojectionError, bool verbose=false)
 
static double getLambda ()
 
static int readGrid (const std::string &filename, unsigned int &n, std::list< double > &oX, std::list< double > &oY, std::list< double > &oZ, bool verbose=false)
 
static void setLambda (const double &lambda)
 

Public Attributes

vpHomogeneousMatrix cMo
 
vpHomogeneousMatrix cMo_dist
 
vpCameraParameters cam
 
vpCameraParameters cam_dist
 
vpHomogeneousMatrix rMe
 
vpHomogeneousMatrix eMc
 
vpHomogeneousMatrix eMc_dist
 
double m_aspect_ratio
 

Detailed Description

Tools for perspective camera calibration.

Definition at line 60 of file vpCalibration.h.

Member Enumeration Documentation

◆ vpCalibrationMethodType

Minimization algorithm use to estimate the camera parameters.

Enumerator
CALIB_LAGRANGE 

Lagrange approach without estimation of the distortion.

CALIB_VIRTUAL_VS 

Virtual visual servoing approach without estimation of the distortion (results are similar to Lowe approach).

CALIB_VIRTUAL_VS_DIST 

Virtual visual servoing approach with estimation of the distortion.

CALIB_LAGRANGE_VIRTUAL_VS 

Lagrange approach first, than virtual visual servoing approach, without estimation of the distortion.

CALIB_LAGRANGE_VIRTUAL_VS_DIST 

Lagrange approach first, than virtual visual servoing approach, with estimation of the distortion.

Definition at line 66 of file vpCalibration.h.

Constructor & Destructor Documentation

◆ vpCalibration() [1/2]

vpCalibration::vpCalibration ( )

Default constructor.

Definition at line 62 of file vpCalibration.cpp.

References init().

◆ vpCalibration() [2/2]

vpCalibration::vpCalibration ( const vpCalibration c)

Copy constructor.

Definition at line 70 of file vpCalibration.cpp.

◆ ~vpCalibration()

vpCalibration::~vpCalibration ( )
virtual

Destructor : delete the array of point (freed the memory)

Definition at line 77 of file vpCalibration.cpp.

References clearPoint().

Member Function Documentation

◆ addPoint()

int vpCalibration::addPoint ( double  X,
double  Y,
double  Z,
vpImagePoint ip 
)

Add a new point in the array of points.

Parameters
X,Y,Z: 3D coordinates of a point in the object frame
ip: 2D Coordinates of the point in the camera frame.

Definition at line 116 of file vpCalibration.cpp.

Referenced by readData().

◆ clearPoint()

int vpCalibration::clearPoint ( )

Suppress all the point in the array of point.

Definition at line 105 of file vpCalibration.cpp.

Referenced by readData(), and ~vpCalibration().

◆ computeCalibration()

int vpCalibration::computeCalibration ( vpCalibrationMethodType  method,
vpHomogeneousMatrix cMo_est,
vpCameraParameters cam_est,
bool  verbose = false 
)

Compute the calibration according to the desired method using one pose.

Parameters
method: Method that will be used to estimate the parameters.
cMo_est: estimated homogeneous matrix that defines the pose.
cam_est: estimated intrinsic camera parameters.
verbose: set at true if information about the residual at each loop of the algorithm is hoped.
Returns
EXIT_SUCCESS if the calibration succeed, EXIT_FAILURE otherwise.

Definition at line 275 of file vpCalibration.cpp.

References CALIB_LAGRANGE, CALIB_LAGRANGE_VIRTUAL_VS, CALIB_LAGRANGE_VIRTUAL_VS_DIST, CALIB_VIRTUAL_VS, CALIB_VIRTUAL_VS_DIST, cam, cam_dist, cMo, cMo_dist, vpCameraParameters::get_px(), vpCameraParameters::get_py(), vpCameraParameters::get_u0(), vpCameraParameters::get_v0(), and vpCameraParameters::printParameters().

◆ computeCalibrationMulti()

int vpCalibration::computeCalibrationMulti ( vpCalibrationMethodType  method,
std::vector< vpCalibration > &  table_cal,
vpCameraParameters cam_est,
double &  globalReprojectionError,
bool  verbose = false 
)
static

Compute the multi-images calibration according to the desired method using many poses.

Parameters
method: Method used to estimate the camera parameters.
table_cal: Vector of vpCalibration.
cam_est: Estimated intrinsic camera parameters.
globalReprojectionError: Global reprojection error or global residual.
verbose: Set at true if information about the residual at each loop of the algorithm is hoped.
Returns
EXIT_SUCCESS if the calibration succeed, EXIT_FAILURE otherwise.

Definition at line 360 of file vpCalibration.cpp.

References CALIB_LAGRANGE, CALIB_LAGRANGE_VIRTUAL_VS, CALIB_LAGRANGE_VIRTUAL_VS_DIST, CALIB_VIRTUAL_VS, CALIB_VIRTUAL_VS_DIST, cMo, get_npt(), vpCameraParameters::get_px(), vpCameraParameters::get_py(), vpCameraParameters::get_u0(), vpCameraParameters::get_v0(), m_aspect_ratio, and vpCameraParameters::printParameters().

◆ computeStdDeviation() [1/2]

double vpCalibration::computeStdDeviation ( const vpHomogeneousMatrix cMo_est,
const vpCameraParameters camera 
)

Compute and return the standard deviation expressed in pixel for pose matrix and camera intrinsic parameters for model without distortion.

Parameters
cMo_est: the matrix that defines the pose to be tested.
camera: camera intrinsic parameters to be tested.
Returns
the standard deviation by point of the error in pixel .

Definition at line 166 of file vpCalibration.cpp.

References vpCameraParameters::get_px(), vpCameraParameters::get_py(), vpImagePoint::get_u(), vpCameraParameters::get_u0(), vpImagePoint::get_v(), vpCameraParameters::get_v0(), and vpMath::sqr().

◆ computeStdDeviation() [2/2]

void vpCalibration::computeStdDeviation ( double &  deviation,
double &  deviation_dist 
)

Compute and return the standard deviation expressed in pixel for pose matrix and camera intrinsic parameters.

Parameters
deviation: the standard deviation computed for the model without distortion.
deviation_dist: the standard deviation computed for the model with distortion.

Definition at line 269 of file vpCalibration.cpp.

References cam, cam_dist, cMo, cMo_dist, and computeStdDeviation_dist().

◆ computeStdDeviation_dist()

double vpCalibration::computeStdDeviation_dist ( const vpHomogeneousMatrix cMo_est,
const vpCameraParameters camera 
)

Compute and return the standard deviation expressed in pixel for pose matrix and camera intrinsic parameters with pixel to meter model.

Parameters
cMo_est: the matrix that defines the pose to be tested.
camera: camera intrinsic parameters to be tested.
Returns
the standard deviation by point of the error in pixel .

Definition at line 210 of file vpCalibration.cpp.

References vpCameraParameters::get_kdu(), vpCameraParameters::get_kud(), vpCameraParameters::get_px(), vpCameraParameters::get_py(), vpImagePoint::get_u(), vpCameraParameters::get_u0(), vpImagePoint::get_v(), vpCameraParameters::get_v0(), and vpMath::sqr().

Referenced by computeStdDeviation().

◆ displayData()

int vpCalibration::displayData ( vpImage< unsigned char > &  I,
vpColor  color = vpColor::red,
unsigned int  thickness = 1,
int  subsampling_factor = 1 
)

Display the data of the calibration (center of the tracked dots).

Parameters
I: Image where to display data.
color: Color of the data.
thickness: Thickness of the displayed data.
subsampling_factor: Subsampling factor. Default value is 1. Admissible values are multiple of 2. Divide by this parameter the coordinates of the data points resulting from image processing.

Definition at line 565 of file vpCalibration.cpp.

References vpDisplay::displayCross(), vpImagePoint::get_u(), vpImagePoint::get_v(), vpImagePoint::set_u(), and vpImagePoint::set_v().

◆ displayGrid()

int vpCalibration::displayGrid ( vpImage< unsigned char > &  I,
vpColor  color = vpColor::yellow,
unsigned int  thickness = 1,
int  subsampling_factor = 1 
)

Display estimated centers of dots using intrinsic camera parameters with model with distortion and the computed pose.

Parameters
I: Image where to display grid data.
color: Color of the data.
thickness: Thickness of the displayed data.
subsampling_factor: Subsampling factor. Default value is 1. Admissible values are multiple of 2. Divide by this parameter the values of the camera parameters.

Definition at line 579 of file vpCalibration.cpp.

References cam_dist, cMo_dist, vpDisplay::displayCross(), vpCameraParameters::get_kud(), vpCameraParameters::get_px(), vpCameraParameters::get_py(), vpCameraParameters::get_u0(), vpCameraParameters::get_v0(), vpImagePoint::set_u(), and vpMath::sqr().

◆ get_npt()

unsigned int vpCalibration::get_npt ( ) const
inline

Get the number of points.

Definition at line 257 of file vpCalibration.h.

Referenced by computeCalibrationMulti().

◆ getLambda()

static double vpCalibration::getLambda ( )
inlinestatic

Get the gain of the virtual visual servoing algorithm.

Definition at line 242 of file vpCalibration.h.

◆ getResidual()

double vpCalibration::getResidual ( void  ) const
inline

Get the residual in pixels.

Definition at line 247 of file vpCalibration.h.

◆ getResidual_dist()

double vpCalibration::getResidual_dist ( void  ) const
inline

Get the residual for perspective projection with distortion (in pixels).

Definition at line 252 of file vpCalibration.h.

◆ init()

int vpCalibration::init ( void  )

Basic initialisation (called by the constructors).

Definition at line 48 of file vpCalibration.cpp.

Referenced by vpCalibration().

◆ operator=()

vpCalibration & vpCalibration::operator= ( const vpCalibration twinCalibration)

Copy operator.

Parameters
twinCalibration: object to be copied

Definition at line 79 of file vpCalibration.cpp.

References cam, cam_dist, cMo, cMo_dist, eMc, eMc_dist, m_aspect_ratio, and rMe.

◆ readData()

int vpCalibration::readData ( const std::string &  filename)

Read data from disk : data are organized as follow oX oY oZ u v

Parameters
filename: Name of the file.

Definition at line 488 of file vpCalibration.cpp.

References addPoint(), vpException::badValue, clearPoint(), vpImagePoint::set_u(), and vpImagePoint::set_v().

◆ readGrid()

int vpCalibration::readGrid ( const std::string &  filename,
unsigned int &  n,
std::list< double > &  oX,
std::list< double > &  oY,
std::list< double > &  oZ,
bool  verbose = false 
)
static

Read calibration grid coordinates from disk. Data are organized as follow oX oY oZ

Parameters
filename: Name of the file.
n: Number of points in the calibration grid.
oX: List of oX coordinates.
oY: List of oY coordinates.
oZ: List of oZ coordinates.
verbose: Additional printings if true (number of points on the calibration grid and their respective coordinates in the object frame).
Returns
0 if success, -1 if an error occurs.

Definition at line 520 of file vpCalibration.cpp.

References vpException::badValue.

◆ setAspectRatio()

void vpCalibration::setAspectRatio ( double  aspect_ratio)

Set pixel aspect ratio px/py.

Parameters
[in]aspect_ratio: px/py aspect ratio. Value need to be positive. To estimate a model where px=py set 1 as aspect ratio.

Definition at line 627 of file vpCalibration.cpp.

References m_aspect_ratio.

◆ setLambda()

static void vpCalibration::setLambda ( const double &  lambda)
inlinestatic

Set the gain for the virtual visual servoing algorithm.

Definition at line 293 of file vpCalibration.h.

◆ writeData()

int vpCalibration::writeData ( const std::string &  filename)

Write data into a file.

Data are organized as follow oX oY oZ u v

Parameters
filename: Name of the file.

Definition at line 452 of file vpCalibration.cpp.

References vpImagePoint::get_u(), and vpImagePoint::get_v().

Member Data Documentation

◆ cam

vpCameraParameters vpCalibration::cam

Camera intrinsic parameters for perspective projection model without distortion

Definition at line 95 of file vpCalibration.h.

Referenced by computeCalibration(), computeStdDeviation(), and operator=().

◆ cam_dist

vpCameraParameters vpCalibration::cam_dist

Camera intrinsic parameters for perspective projection model with distortion

Definition at line 99 of file vpCalibration.h.

Referenced by computeCalibration(), computeStdDeviation(), displayGrid(), and operator=().

◆ cMo

vpHomogeneousMatrix vpCalibration::cMo

Pose computed using camera parameters without distortion (as a 3x4 matrix [R T])

Definition at line 86 of file vpCalibration.h.

Referenced by computeCalibration(), computeCalibrationMulti(), computeStdDeviation(), and operator=().

◆ cMo_dist

vpHomogeneousMatrix vpCalibration::cMo_dist

Pose computed using camera parameters with distortion with distortion model (as a 3x4 matrix [R T])

Definition at line 91 of file vpCalibration.h.

Referenced by computeCalibration(), computeStdDeviation(), displayGrid(), and operator=().

◆ eMc

vpHomogeneousMatrix vpCalibration::eMc

Position of the camera in end-effector frame using camera parameters without distortion

Definition at line 108 of file vpCalibration.h.

Referenced by operator=().

◆ eMc_dist

vpHomogeneousMatrix vpCalibration::eMc_dist

Position of the camera in end-effector frame using camera parameters with distortion

Definition at line 112 of file vpCalibration.h.

Referenced by operator=().

◆ m_aspect_ratio

double vpCalibration::m_aspect_ratio

Fix aspect ratio (px/py)

Definition at line 117 of file vpCalibration.h.

Referenced by computeCalibrationMulti(), operator=(), and setAspectRatio().

◆ rMe

vpHomogeneousMatrix vpCalibration::rMe

Position of the effector in relation to the reference coordinates (manipulator base coordinates)

Definition at line 104 of file vpCalibration.h.

Referenced by operator=().