Visual Servoing Platform
version 3.2.0 under development (2019-01-22)
|
#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) |
vpCalibration & | operator= (const vpCalibration &twinCalibration) |
int | clearPoint () |
void | computeStdDeviation (double &deviation, double &deviation_dist) |
int | computeCalibration (vpCalibrationMethodType method, vpHomogeneousMatrix &cMo_est, vpCameraParameters &cam_est, bool verbose=false) |
double | computeStdDeviation (const vpHomogeneousMatrix &cMo_est, const vpCameraParameters &camera) |
double | computeStdDeviation_dist (const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam) |
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 char *filename) |
int | writeData (const char *filename) |
Static Public Member Functions | |
static int | computeCalibrationMulti (vpCalibrationMethodType method, std::vector< vpCalibration > &table_cal, vpCameraParameters &cam, double &globalReprojectionError, bool verbose=false) |
static double | getLambda () |
static int | readGrid (const char *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) |
Deprecated functions | |
static vp_deprecated void | calibrationTsai (const std::vector< vpHomogeneousMatrix > &cMo, const std::vector< vpHomogeneousMatrix > &rMe, vpHomogeneousMatrix &eMc) |
static vp_deprecated int | computeCalibrationTsai (const std::vector< vpCalibration > &table_cal, vpHomogeneousMatrix &eMc, vpHomogeneousMatrix &eMc_dist) |
Public Attributes | |
vpHomogeneousMatrix | cMo |
vpHomogeneousMatrix | cMo_dist |
vpCameraParameters | cam |
vpCameraParameters | cam_dist |
vpHomogeneousMatrix | rMe |
vpHomogeneousMatrix | eMc |
vpHomogeneousMatrix | eMc_dist |
Tools for perspective camera calibration.
Definition at line 71 of file vpCalibration.h.
Minimization algorithm use to estimate the camera parameters.
Definition at line 77 of file vpCalibration.h.
vpCalibration::vpCalibration | ( | ) |
vpCalibration::vpCalibration | ( | const vpCalibration & | c | ) |
Copy constructor.
Definition at line 83 of file vpCalibration.cpp.
|
virtual |
Destructor : delete the array of point (freed the memory)
Definition at line 93 of file vpCalibration.cpp.
References clearPoint().
int vpCalibration::addPoint | ( | double | X, |
double | Y, | ||
double | Z, | ||
vpImagePoint & | ip | ||
) |
Add a new point in the array of points.
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 144 of file vpCalibration.cpp.
References vpPose::addPoint(), vpPose::clearPoint(), vpPose::computePose(), vpPose::computeResidual(), vpPixelMeterConversion::convertPoint(), vpPose::DEMENTHON, vpPose::LAGRANGE, vpPoint::set_x(), vpPoint::set_y(), and vpPose::VIRTUAL_VS.
Referenced by readData().
|
static |
Compute extrinsic camera parameters : the constant transformation from the effector to the camera frames (eMc).
cMo | : vector of homogeneous matrices representing the transformation between the camera and the scene (input) |
rMe | : vector of homogeneous matrices representing the transformation between the effector (where the camera is fixed) and the reference coordinates (base of the manipulator) (input). Must be the same size as cMo. |
eMc | : homogeneous matrix representing the transformation between the effector and the camera (output) |
Definition at line 1538 of file vpCalibrationTools.cpp.
References vpHandEyeCalibration::calibrate().
int vpCalibration::clearPoint | ( | ) |
Suppress all the point in the array of point.
Delete the array of points.
Definition at line 127 of file vpCalibration.cpp.
Referenced by readData(), and ~vpCalibration().
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.
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. |
Definition at line 356 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().
|
static |
Compute the multi-images calibration according to the desired method using many poses.
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. |
Definition at line 452 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(), and vpCameraParameters::printParameters().
|
static |
Compute extrinsic camera parameters : the constant transformation from the end-effector to the camera frame considering the camera model with or without distortion.
[in] | table_cal | : Vector of vpCalibration that contains for each index a couple of (world to end-effector) and (camera to object) transformations. |
[out] | eMc | : Estimated pose of the camera in relation to the end-effector considering the camera model without distortion. |
[out] | eMc_dist | : Estimated pose of the camera in relation to the end-effector considering the model with distortion. |
Definition at line 1561 of file vpCalibrationTools.cpp.
References vpHandEyeCalibration::calibrate(), and vpException::dimensionError.
void vpCalibration::computeStdDeviation | ( | double & | deviation, |
double & | deviation_dist | ||
) |
Compute and return the standard deviation expressed in pixel for pose matrix and camera intrinsic 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 339 of file vpCalibration.cpp.
References cam, cam_dist, cMo, cMo_dist, and computeStdDeviation_dist().
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.
cMo_est | : the matrix that defines the pose to be tested. |
camera | : camera intrinsic parameters to be tested. |
Definition at line 221 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().
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.
cMo_est | : the matrix that defines the pose to be tested. |
camera | : camera intrinsic parameters to be tested. |
Definition at line 272 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().
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)
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 687 of file vpCalibration.cpp.
References vpDisplay::displayCross(), vpImagePoint::get_u(), vpImagePoint::get_v(), vpImagePoint::set_u(), and vpImagePoint::set_v().
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.
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 711 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().
|
inline |
get the number of points
Definition at line 159 of file vpCalibration.h.
Referenced by computeCalibrationMulti().
|
inlinestatic |
Set the gain for the virtual visual servoing algorithm.
Definition at line 152 of file vpCalibration.h.
|
inline |
get the residual in pixels
Definition at line 155 of file vpCalibration.h.
|
inline |
get the residual for perspective projection with distortion (in pixels)
Definition at line 157 of file vpCalibration.h.
int vpCalibration::init | ( | void | ) |
Basic initialisation (called by the constructors)
Definition at line 57 of file vpCalibration.cpp.
Referenced by vpCalibration().
vpCalibration & vpCalibration::operator= | ( | const vpCalibration & | twinCalibration | ) |
int vpCalibration::readData | ( | const char * | filename | ) |
Read data from disk : data are organized as follow oX oY oZ u v
filename | : name of the file |
Definition at line 588 of file vpCalibration.cpp.
References addPoint(), vpException::badValue, clearPoint(), vpImagePoint::set_u(), and vpImagePoint::set_v().
|
static |
Read calibration grid coordinates from disk : data are organized as follow oX oY oZ
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 | : Additionnal printings if true (number of points on the calibration grid and their respective coordinates in the object frame). |
Definition at line 634 of file vpCalibration.cpp.
References vpException::badValue.
|
inlinestatic |
set the gain for the virtual visual servoing algorithm
Definition at line 168 of file vpCalibration.h.
int vpCalibration::writeData | ( | const char * | filename | ) |
Write data into a file.
data are organized as follow oX oY oZ u v
filename | : name of the file |
Definition at line 546 of file vpCalibration.cpp.
References vpImagePoint::get_u(), and vpImagePoint::get_v().
vpCameraParameters vpCalibration::cam |
projection model without distortion
camera intrinsic parameters for perspective
Definition at line 98 of file vpCalibration.h.
Referenced by computeCalibration(), computeStdDeviation(), and operator=().
vpCameraParameters vpCalibration::cam_dist |
projection model with distortion
camera intrinsic parameters for perspective
Definition at line 100 of file vpCalibration.h.
Referenced by computeCalibration(), computeStdDeviation(), displayGrid(), and operator=().
vpHomogeneousMatrix vpCalibration::cMo |
(as a 3x4 matrix [R T])
the pose computed for the model without distortion
Definition at line 93 of file vpCalibration.h.
Referenced by computeCalibration(), computeCalibrationMulti(), computeStdDeviation(), and operator=().
vpHomogeneousMatrix vpCalibration::cMo_dist |
the pose computed for perspective projection with distortion model (as a 3x4 matrix [R T])
Definition at line 95 of file vpCalibration.h.
Referenced by computeCalibration(), computeStdDeviation(), displayGrid(), and operator=().
vpHomogeneousMatrix vpCalibration::eMc |
position of the camera in relation to the effector
Definition at line 105 of file vpCalibration.h.
Referenced by operator=().
vpHomogeneousMatrix vpCalibration::eMc_dist |
Definition at line 106 of file vpCalibration.h.
Referenced by operator=().
vpHomogeneousMatrix vpCalibration::rMe |
reference coordinates (manipulator base coordinates)
position of the effector in relation to the
Definition at line 103 of file vpCalibration.h.
Referenced by operator=().