Visual Servoing Platform
version 3.5.1 under development (2023-09-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) |
Deprecated functions | |
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 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) |
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) |
Tools for perspective camera calibration.
Definition at line 63 of file vpCalibration.h.
Minimization algorithm use to estimate the camera parameters.
Definition at line 69 of file vpCalibration.h.
vpCalibration::vpCalibration | ( | ) |
vpCalibration::vpCalibration | ( | const vpCalibration & | c | ) |
Copy constructor.
Definition at line 70 of file vpCalibration.cpp.
|
virtual |
Destructor : delete the array of point (freed the memory)
Definition at line 77 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 116 of file vpCalibration.cpp.
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 1223 of file vpCalibrationTools.cpp.
References vpHandEyeCalibration::calibrate(), cMo, eMc, and rMe.
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().
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 277 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 362 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().
|
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 1246 of file vpCalibrationTools.cpp.
References vpHandEyeCalibration::calibrate(), vpException::dimensionError, eMc, and eMc_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 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().
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 271 of file vpCalibration.cpp.
References cam, cam_dist, cMo, cMo_dist, and 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.
cMo_est | : the matrix that defines the pose to be tested. |
camera | : camera intrinsic parameters to be tested. |
Definition at line 211 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 567 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 581 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 272 of file vpCalibration.h.
Referenced by computeCalibrationMulti().
|
inlinestatic |
Set the gain for the virtual visual servoing algorithm.
Definition at line 257 of file vpCalibration.h.
|
inline |
Get the residual in pixels.
Definition at line 262 of file vpCalibration.h.
|
inline |
Get the residual for perspective projection with distortion (in pixels).
Definition at line 267 of file vpCalibration.h.
int vpCalibration::init | ( | void | ) |
Basic initialisation (called by the constructors).
Definition at line 48 of file vpCalibration.cpp.
Referenced by vpCalibration().
vpCalibration & vpCalibration::operator= | ( | const vpCalibration & | twinCalibration | ) |
Copy operator.
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.
int vpCalibration::readData | ( | const std::string & | filename | ) |
Read data from disk : data are organized as follow oX oY oZ u v
filename | : Name of the file. |
Definition at line 490 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 | : Additional printings if true (number of points on the calibration grid and their respective coordinates in the object frame). |
Definition at line 522 of file vpCalibration.cpp.
References vpException::badValue.
void vpCalibration::setAspectRatio | ( | double | aspect_ratio | ) |
Set pixel aspect ratio px/py.
[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 629 of file vpCalibration.cpp.
References m_aspect_ratio.
|
inlinestatic |
Set the gain for the virtual visual servoing algorithm.
Definition at line 308 of file vpCalibration.h.
int vpCalibration::writeData | ( | const std::string & | filename | ) |
Write data into a file.
Data are organized as follow oX oY oZ u v
filename | : Name of the file. |
Definition at line 454 of file vpCalibration.cpp.
References vpImagePoint::get_u(), and vpImagePoint::get_v().
vpCameraParameters vpCalibration::cam |
Camera intrinsic parameters for perspective projection model without distortion
Definition at line 98 of file vpCalibration.h.
Referenced by computeCalibration(), computeStdDeviation(), and operator=().
vpCameraParameters vpCalibration::cam_dist |
Camera intrinsic parameters for perspective projection model with distortion
Definition at line 102 of file vpCalibration.h.
Referenced by computeCalibration(), computeStdDeviation(), displayGrid(), and operator=().
vpHomogeneousMatrix vpCalibration::cMo |
Pose computed using camera parameters without distortion (as a 3x4 matrix [R T])
Definition at line 89 of file vpCalibration.h.
Referenced by calibrationTsai(), computeCalibration(), computeCalibrationMulti(), computeStdDeviation(), and operator=().
vpHomogeneousMatrix vpCalibration::cMo_dist |
Pose computed using camera parameters with distortion with distortion model (as a 3x4 matrix [R T])
Definition at line 94 of file vpCalibration.h.
Referenced by computeCalibration(), computeStdDeviation(), displayGrid(), and operator=().
vpHomogeneousMatrix vpCalibration::eMc |
Position of the camera in end-effector frame using camera parameters without distortion
Definition at line 111 of file vpCalibration.h.
Referenced by calibrationTsai(), computeCalibrationTsai(), and operator=().
vpHomogeneousMatrix vpCalibration::eMc_dist |
Position of the camera in end-effector frame using camera parameters with distortion
Definition at line 115 of file vpCalibration.h.
Referenced by computeCalibrationTsai(), and operator=().
double vpCalibration::m_aspect_ratio |
Fix aspect ratio (px/py)
Definition at line 119 of file vpCalibration.h.
Referenced by computeCalibrationMulti(), operator=(), and setAspectRatio().
vpHomogeneousMatrix vpCalibration::rMe |
Position of the effector in relation to the reference coordinates (manipulator base coordinates)
Definition at line 107 of file vpCalibration.h.
Referenced by calibrationTsai(), and operator=().