Visual Servoing Platform  version 3.5.0 under development (2022-02-15)
vpPixelMeterConversion Class Reference

#include <visp3/core/vpPixelMeterConversion.h>

Static Public Member Functions

Using ViSP camera parameters
static void convertEllipse (const vpCameraParameters &cam, const vpImagePoint &center_p, double n20_p, double n11_p, double n02_p, double &xc_m, double &yc_m, double &n20_m, double &n11_m, double &n02_m)
 
static void convertLine (const vpCameraParameters &cam, const double &rho_p, const double &theta_p, double &rho_m, double &theta_m)
 
static void convertMoment (const vpCameraParameters &cam, unsigned int order, const vpMatrix &moment_pixel, vpMatrix &moment_meter)
 
static void convertPoint (const vpCameraParameters &cam, const double &u, const double &v, double &x, double &y)
 
static void convertPoint (const vpCameraParameters &cam, const vpImagePoint &iP, double &x, double &y)
 
Using OpenCV camera parameters
static void convertEllipse (const cv::Mat &cameraMatrix, const cv::Mat &distCoeffs, const vpImagePoint &center_p, double n20_p, double n11_p, double n02_p, double &xc_m, double &yc_m, double &n20_m, double &n11_m, double &n02_m)
 
static void convertLine (const cv::Mat &cameraMatrix, const double &rho_p, const double &theta_p, double &rho_m, double &theta_m)
 
static void convertMoment (const cv::Mat &cameraMatrix, unsigned int order, const vpMatrix &moment_pixel, vpMatrix &moment_meter)
 
static void convertPoint (const cv::Mat &cameraMatrix, const cv::Mat &distCoeffs, const double &u, const double &v, double &x, double &y)
 
static void convertPoint (const cv::Mat &cameraMatrix, const cv::Mat &distCoeffs, const vpImagePoint &iP, double &x, double &y)
 

Detailed Description

Various conversion functions to transform primitives (2D line, moments, 2D point) from pixel to normalized coordinates in meter in the image plane.

Tranformation relies either on ViSP camera parameters implemented in vpCameraParameters or on OpenCV camera parameters that are set from a projection matrix and a distorsion coefficients vector.

Definition at line 71 of file vpPixelMeterConversion.h.

Member Function Documentation

◆ convertEllipse() [1/2]

void vpPixelMeterConversion::convertEllipse ( const vpCameraParameters cam,
const vpImagePoint center_p,
double  n20_p,
double  n11_p,
double  n02_p,
double &  xc_m,
double &  yc_m,
double &  n20_m,
double &  n11_m,
double &  n02_m 
)
static

Convert ellipse parameters (ie ellipse center and normalized centered moments) from pixels $(u_c, v_c, n_{{20}_p}, n_{{11}_p}, n_{{02}_p})$ to meters $(x_c, y_c, n_{{20}_m}, n_{{11}_m}, n_{{02}_m})$ in the image plane.

Parameters
[in]cam: Camera parameters.
[in]center_p: Center of the ellipse (uc, vc) with pixel coordinates.
[in]n20_p,n11_p,n02_p: Normalized second order moments of the ellipse in pixels.
[out]xc_m,yc_m: Center of the ellipse with coordinates in meters in the image plane.
[out]n20_m,n11_m,n02_m: Normalized second order moments of the ellipse in meters in the image plane.

Definition at line 60 of file vpPixelMeterConversion.cpp.

References convertPoint(), vpCameraParameters::get_px(), and vpCameraParameters::get_py().

Referenced by vpFeatureBuilder::create().

◆ convertEllipse() [2/2]

void vpPixelMeterConversion::convertEllipse ( const cv::Mat &  cameraMatrix,
const cv::Mat &  distCoeffs,
const vpImagePoint center_p,
double  n20_p,
double  n11_p,
double  n02_p,
double &  xc_m,
double &  yc_m,
double &  n20_m,
double &  n11_m,
double &  n02_m 
)
static

Convert ellipse parameters (ie ellipse center and normalized centered moments) from pixels $(u_c, v_c, n_{{20}_p}, n_{{11}_p}, n_{{02}_p})$ to meters $(x_c, y_c, n_{{20}_m}, n_{{11}_m}, n_{{02}_m})$ in the image plane.

Parameters
[in]cameraMatrix: Camera Matrix $\begin{bmatrix} f_x & 0 & c_x \\ 0 & f_y & c_y \\ 0 & 0 & 1\end{bmatrix}$
[in]distCoeffs: Input vector of distortion coefficients $(k_1, k_2, p_1, p_2[, k_3[, k_4, k_5, k_6 [, s_1, s_2, s_3, s_4[, \tau_x, \tau_y]]]])$ of 4, 5, 8, 12 or 14 elements. If the vector is NULL/empty, the zero distortion coefficients are assumed.
[in]center_p: Center of the ellipse (uc, vc) with pixel coordinates.
[in]n20_p,n11_p,n02_p: Normalized second order moments of the ellipse in pixels.
[out]xc_m,yc_m: Center of the ellipse with coordinates in meters in the image plane.
[out]n20_m,n11_m,n02_m: Normalized second order moments of the ellipse in meters in the image plane.

Definition at line 188 of file vpPixelMeterConversion.cpp.

References convertPoint().

◆ convertLine() [1/2]

void vpPixelMeterConversion::convertLine ( const vpCameraParameters cam,
const double &  rho_p,
const double &  theta_p,
double &  rho_m,
double &  theta_m 
)
static

Line parameters conversion from pixel $(\rho_p,\theta_p)$ to normalized coordinates $(\rho_m,\theta_m)$ in meter using ViSP camera parameters. This function doesn't use distorsion coefficients.

Parameters
[in]cam: camera parameters.
[in]rho_p,theta_p: Line parameters expressed in pixels.
[out]rho_m,theta_m: Line parameters expressed in meters in the image plane.

Definition at line 82 of file vpPixelMeterConversion.cpp.

References vpException::divideByZeroError, vpMath::sqr(), and vpERROR_TRACE.

Referenced by vpFeatureBuilder::create().

◆ convertLine() [2/2]

void vpPixelMeterConversion::convertLine ( const cv::Mat &  cameraMatrix,
const double &  rho_p,
const double &  theta_p,
double &  rho_m,
double &  theta_m 
)
static

Line parameters conversion from pixel $(\rho_p,\theta_p)$ to normalized coordinates $(\rho_m,\theta_m)$ in meter using OpenCV camera parameters. This function doesn't use distorsion coefficients.

Parameters
[in]cameraMatrix: Camera Matrix $\begin{bmatrix} f_x & 0 & c_x \\ 0 & f_y & c_y \\ 0 & 0 & 1\end{bmatrix}$
[in]rho_p,theta_p: Line parameters expressed in pixels.
[out]rho_m,theta_m: Line parameters expressed in meters in the image plane.

Definition at line 210 of file vpPixelMeterConversion.cpp.

References vpException::divideByZeroError, vpMath::sqr(), and vpERROR_TRACE.

◆ convertMoment() [1/2]

void vpPixelMeterConversion::convertMoment ( const vpCameraParameters cam,
unsigned int  order,
const vpMatrix moment_pixel,
vpMatrix moment_meter 
)
static

Moments conversion from pixel to normalized coordinates in meter using ViSP camera parameters. This function doesn't use distorsion coefficients.

Parameters
[in]cam: camera parameters.
[in]order: Moment order.
[in]moment_pixel: Moment values in pixels.
[out]moment_meter: Moment values in meters in the image plane.

The following example show how to use this function.

unsigned int order = 3;
vpMatrix M_p(order, order); // 3-by-3 matrix with mij moments expressed in pixels
M_p = 0;
vpMatrix M_m(order, order); // 3-by-3 matrix with mij moments expressed in meters
M_m = 0;
// Fill input Matrix with mij moments in pixels
M_p[0][0] = m00_p;
M_p[1][0] = m10_p;
M_p[0][1] = m01_p;
M_p[2][0] = m20_p;
M_p[1][1] = m11_p;
M_p[0][2] = m02_p;
// Moments mij in meters
double m00 = M_m[0][0];
double m01 = M_m[0][1];
double m10 = M_m[1][0];
double m02 = M_m[0][2];
double m11 = M_m[1][1];
double m20 = M_m[2][0];

Definition at line 135 of file vpPixelMeterConversion.cpp.

References vpMath::comb().

◆ convertMoment() [2/2]

void vpPixelMeterConversion::convertMoment ( const cv::Mat &  cameraMatrix,
unsigned int  order,
const vpMatrix moment_pixel,
vpMatrix moment_meter 
)
static

Moments conversion from pixel to normalized coordinates in meter using OpenCV camera parameters. This function doesn't use distorsion coefficients.

Parameters
[in]cameraMatrix: Camera Matrix $\begin{bmatrix} f_x & 0 & c_x \\ 0 & f_y & c_y \\ 0 & 0 & 1\end{bmatrix}$
[in]order: Moment order.
[in]moment_pixel: Moment values in pixels.
[out]moment_meter: Moment values in meters in the image plane.

Definition at line 241 of file vpPixelMeterConversion.cpp.

References vpMath::comb().

◆ convertPoint() [1/4]

static void vpPixelMeterConversion::convertPoint ( const vpCameraParameters cam,
const double &  u,
const double &  v,
double &  x,
double &  y 
)
inlinestatic

Point coordinates conversion from pixel coordinates $(u,v)$ to normalized coordinates $(x,y)$ in meter using ViSP camera parameters.

The used formula depends on the projection model of the camera. To know the currently used projection model use vpCameraParameter::get_projModel()

Parameters
[in]cam: camera parameters.
[in]u: input coordinate in pixels along image horizontal axis.
[in]v: input coordinate in pixels along image vertical axis.
[out]x: output coordinate in meter along image plane x-axis.
[out]y: output coordinate in meter along image plane y-axis.

$ x = (u-u_0)/p_x $ and $ y = (v-v_0)/p_y $ in the case of perspective projection without distortion.

$ x = (u-u_0)*(1+k_{du}*r^2)/p_x $ and $ y = (v-v_0)*(1+k_{du}*r^2)/p_y $ with $ r^2=((u - u_0)/p_x)^2+((v-v_0)/p_y)^2 $ in the case of perspective projection with distortion.

In the case of a projection with Kannala-Brandt distortion, refer to [22].

Examples:
AROgre.cpp, AROgreBasic.cpp, mbot-apriltag-ibvs.cpp, poseVirtualVS.cpp, servoAfma62DhalfCamVelocity.cpp, servoAfma6FourPoints2DCamVelocityLs_cur.cpp, servoAfma6Points2DCamVelocityEyeToHand.cpp, servoBebop2.cpp, servoFlirPtuIBVS.cpp, servoViper650FourPoints2DArtVelocityLs_cur.cpp, servoViper650FourPoints2DCamVelocityLs_cur-SR300.cpp, servoViper650FourPoints2DCamVelocityLs_cur.cpp, servoViper850FourPoints2DArtVelocityLs_cur.cpp, servoViper850FourPoints2DCamVelocityLs_cur.cpp, servoViper850FourPointsKinect.cpp, testAprilTag.cpp, testGenericTracker.cpp, testGenericTrackerDepth.cpp, testKeyPoint-4.cpp, testRobotAfma6Pose.cpp, testRobotViper850Pose.cpp, tutorial-chessboard-pose.cpp, tutorial-flir-ptu-ibvs.cpp, tutorial-matching-keypoint-homography.cpp, tutorial-matching-surf-homography-deprecated.cpp, and tutorial-mb-generic-tracker-rgbd-blender.cpp.

Definition at line 109 of file vpPixelMeterConversion.h.

References vpCameraParameters::perspectiveProjWithDistortion, vpCameraParameters::perspectiveProjWithoutDistortion, and vpCameraParameters::ProjWithKannalaBrandtDistortion.

Referenced by vpCalibration::addPoint(), vpFeatureLuminance::buildFrom(), vpKeyPoint::compute3D(), vpKeyPoint::compute3DForPointsOnCylinders(), vpMbtFaceDepthNormal::computeDesiredFeatures(), vpMbtDistanceKltCylinder::computeInteractionMatrixAndResidu(), vpMbtDistanceKltPoints::computeInteractionMatrixAndResidu(), vpMbtDistanceCircle::computeInteractionMatrixError(), vpPose::computePlanarObjectPoseFromRGBD(), convertEllipse(), vpFeatureBuilder::create(), vpMomentObject::fromImage(), vpImageSimulator::getImage(), vpMbtDistanceKltCylinder::init(), vpMbTracker::initClick(), vpMbTracker::initFromPoints(), vpKeyPoint::matchPoint(), and vpKinect::warpRGBFrame().

◆ convertPoint() [2/4]

static void vpPixelMeterConversion::convertPoint ( const vpCameraParameters cam,
const vpImagePoint iP,
double &  x,
double &  y 
)
inlinestatic

Point coordinates conversion from pixel coordinates Coordinates in pixel to normalized coordinates $(x,y)$ in meter using ViSP camera parameters.

The used formula depends on the projection model of the camera. To know the currently used projection model use vpCameraParameter::get_projModel()

Parameters
[in]cam: camera parameters.
[in]iP: input coordinates in pixels.
[out]x: output coordinate in meter along image plane x-axis.
[out]y: output coordinate in meter along image plane y-axis.

Thanks to the pixel coordinates in the frame (u,v), the meter coordinates are given by :

$ x = (u-u_0)/p_x $ and $ y = (v-v_0)/p_y $ in the case of perspective projection without distortion.

$ x = (u-u_0)*(1+k_{du}*r^2)/p_x $ and $ y = (v-v_0)*(1+k_{du}*r^2)/p_y $ with $ r^2=((u - u_0)/p_x)^2+((v-v_0)/p_y)^2 $ in the case of perspective projection with distortion.

In the case of a projection with Kannala-Brandt distortion, refer to [22].

Definition at line 152 of file vpPixelMeterConversion.h.

References vpImagePoint::get_u(), vpImagePoint::get_v(), vpCameraParameters::getKannalaBrandtDistortionCoefficients(), vpCameraParameters::perspectiveProjWithDistortion, vpCameraParameters::perspectiveProjWithoutDistortion, vpCameraParameters::ProjWithKannalaBrandtDistortion, and vpMath::sqr().

◆ convertPoint() [3/4]

void vpPixelMeterConversion::convertPoint ( const cv::Mat &  cameraMatrix,
const cv::Mat &  distCoeffs,
const double &  u,
const double &  v,
double &  x,
double &  y 
)
static

Point coordinates conversion from pixel coordinates $(u,v)$ to normalized coordinates $(x,y)$ in meter using OpenCV camera parameters.

Parameters
[in]cameraMatrix: Camera Matrix $\begin{bmatrix} f_x & 0 & c_x \\ 0 & f_y & c_y \\ 0 & 0 & 1\end{bmatrix}$
[in]distCoeffs: Input vector of distortion coefficients $(k_1, k_2, p_1, p_2[, k_3[, k_4, k_5, k_6 [, s_1, s_2, s_3, s_4[, \tau_x, \tau_y]]]])$ of 4, 5, 8, 12 or 14 elements. If the vector is NULL/empty, the zero distortion coefficients are assumed.
[in]u: input coordinate in pixels along image horizontal axis.
[in]v: input coordinate in pixels along image vertical axis.
[out]x: output coordinate in meter along image plane x-axis.
[out]y: output coordinate in meter along image plane y-axis.

Definition at line 299 of file vpPixelMeterConversion.cpp.

◆ convertPoint() [4/4]

void vpPixelMeterConversion::convertPoint ( const cv::Mat &  cameraMatrix,
const cv::Mat &  distCoeffs,
const vpImagePoint iP,
double &  x,
double &  y 
)
static

Point coordinates conversion from pixel coordinates $(u,v)$ to normalized coordinates $(x,y)$ in meter using OpenCV camera parameters.

Parameters
[in]cameraMatrix: Camera Matrix $\begin{bmatrix} f_x & 0 & c_x \\ 0 & f_y & c_y \\ 0 & 0 & 1\end{bmatrix}$
[in]distCoeffs: Input vector of distortion coefficients $(k_1, k_2, p_1, p_2[, k_3[, k_4, k_5, k_6 [, s_1, s_2, s_3, s_4[, \tau_x, \tau_y]]]])$ of 4, 5, 8, 12 or 14 elements. If the vector is NULL/empty, the zero distortion coefficients are assumed.
[in]iP: input coordinates in pixels.
[out]x: output coordinate in meter along image plane x-axis.
[out]y: output coordinate in meter along image plane y-axis.

Definition at line 323 of file vpPixelMeterConversion.cpp.

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