ViSP  2.10.0

#include <vpCameraParameters.h>

Public Types

enum  vpCameraParametersProjType { perspectiveProjWithoutDistortion, perspectiveProjWithDistortion }
 

Public Member Functions

 vpCameraParameters ()
 
 vpCameraParameters (const vpCameraParameters &c)
 
 vpCameraParameters (const double px, const double py, const double u0, const double v0)
 
 vpCameraParameters (const double px, const double py, const double u0, const double v0, const double kud, const double kdu)
 
vpCameraParametersoperator= (const vpCameraParameters &c)
 
virtual ~vpCameraParameters ()
 
void init ()
 
void init (const vpCameraParameters &c)
 
void initFromCalibrationMatrix (const vpMatrix &_K)
 
void initFromFov (const unsigned int &w, const unsigned int &h, const double &hfov, const double &vfov)
 
void initPersProjWithoutDistortion (const double px, const double py, const double u0, const double v0)
 
void initPersProjWithDistortion (const double px, const double py, const double u0, const double v0, const double kud, const double kdu)
 
bool isFovComputed () const
 
void computeFov (const unsigned int &w, const unsigned int &h)
 
double getHorizontalFovAngle () const
 
double getVerticalFovAngle () const
 
std::vector< vpColVectorgetFovNormals () const
 
double get_px () const
 
double get_px_inverse () const
 
double get_py_inverse () const
 
double get_py () const
 
double get_u0 () const
 
double get_v0 () const
 
double get_kud () const
 
double get_kdu () const
 
vpCameraParametersProjType get_projModel () const
 
vpMatrix get_K () const
 
vpMatrix get_K_inverse () const
 
void printParameters ()
 
vp_deprecated double getFovAngleX () const
 
vp_deprecated double getFovAngleY () const
 

Friends

class vpMeterPixelConversion
 
class vpPixelMeterConversion
 
VISP_EXPORT std::ostream & operator<< (std::ostream &os, const vpCameraParameters &cam)
 

Detailed Description

Generic class defining intrinsic camera parameters.

Two kinds of camera modelisation are implemented:

  • Camera parameters for a perspective projection without distortion model,
  • Camera parameters for a perspective projection with distortion model.

The main intrinsic camera parameters are $(p_x, p_y)$ the ratio between the focal length and the size of a pixel, and $(u_0, v_0)$ the coordinates of the principal point in pixel. The lens distortion can also be considered by two additional parameters $(k_{ud}, k_{du})$.

1. Camera parameters for a perspective projection without distortion model

In this modelisation, only $u_0,v_0,p_x,p_y$ parameters are used. If we denote $(u,v)$ the position of a pixel in the digitized image, this position is related to the corresponding coordinates $(x,y)$ in the normalized space (in meter) by:

\[ \left\{ \begin{array}{l} u = u_0 + p_x x \\ v = v_0 + p_y y \end{array}\right. \]

The initialization of such a model can be done using:

2. Camera parameters for a perspective projection with distortion model

In this modelisation, $u_0,v_0,p_x,p_y,k_{ud},k_{du}$ parameters are used. If a model with distortion is considered, we got:

\[ \left\{ \begin{array}{l} u = u_0 + p_x x + \delta_u \\ v = v_0 + p_y y + \delta_v \end{array}\right. \]

where $\delta_u$ and $\delta_v$ are geometrical distortions introduced in the camera model. These distortions are due to imperfections in the lenses design and assembly there usually are some positional errors that have to be taken into account. $\delta_u$ and $\delta_v$ can be modeled as follow:

  • with an undistorted to distorted model

    \[ \left\{ \begin{array}{l} \delta_u(x,y) = k_{ud} \;r^2\; p_x x \\ \\ \delta_v(x,y) = k_{ud}\; r^2\; p_y y \end{array}\right. \]

    with

    \[ r^2 = x^2 + y^2 \]

    This model is useful to convert meter to pixel coordinates because in this case :

    \[ \left\{ \begin{array}{l} u = f_u(x,y) = u_0 + p_x x\left(1+k_{ud}\left(x^2 + y^2\right)\right) \\ \\ v = f_v(x,y) = v_0 + p_y y\left(1+k_{ud}\left(x^2 + y^2\right)\right) \end{array}\right. \]

    The conversion from normalized coordinates $(x,y)$ into pixel $(u,v)$ is implemented in vpMeterPixelConversion.
  • or with a distorted to undistorted model

    \[ \left\{ \begin{array}{l} \delta_u(u,v) = -k_{du} \;r^2\; \left(u-u_0\right) \\ \\ \delta_v(u,v) = -k_{du}\; r^2\; \left(v-v_0\right) \end{array}\right. \]

    with

    \[ r^2 = {\left(\frac{u-u_0}{p_{x}}\right)}^2 + {\left(\frac{v-v_0}{p_{y}}\right)}^2 \]

    This model is useful to convert pixel to meter coordinates because in this case :

    \[ \left\{ \begin{array}{l} x = f_x(u,v) = \frac{u-u_0}{p_x}\left(1+k_{du}\left( {\left(\frac{u-u_0}{p_{x}}\right)}^2 + {\left(\frac{v-v_0}{p_{y}}\right)}^2 \right)\right) \\ \\ y = f_y(u,v) = \frac{v-v_0}{p_y}\left(1+k_{du}\left( {\left(\frac{u-u_0}{p_{x}}\right)}^2 + {\left(\frac{v-v_0}{p_{y}}\right)}^2 \right)\right) \end{array}\right. \]

The initialization of such a model can be done using:

Note
The conversion from pixel coordinates $(u,v)$ in the normalized space $(x,y)$ is implemented in vpPixelMeterConversion, whereas the conversion from normalized coordinates into pixel is implemented in vpMeterPixelConversion.

The selection of one of these modelisations is done during vpCameraParameters initialisation.

Here an example of camera initialisation, for a model without distortion. A complete example is given in initPersProjWithoutDistortion().

double px = 600;
double py = 600;
double u0 = 320;
double v0 = 240;
// Create a camera parameter container
// Camera initialization with a perspective projection without distortion model
// It is also possible to print the current camera parameters
std::cout << cam << std::endl;

Here an example of camera initialisation, for a model with distortion. A complete example is given in initPersProjWithDistortion().

double px = 600;
double py = 600;
double u0 = 320;
double v0 = 240;
double kud = -0.19;
double kdu = 0.20;
// Create a camera parameter container
// Camera initialization with a perspective projection without distortion model
cam.initPersProjWithDistortion(px,py,u0,v0,kud,kdu);

The code below shows how to know the currently used projection model:

...
vpCameraParameters::vpCameraParametersProjType projModel;
projModel = cam.get_projModel(); // Get the projection model type

An XML parser for camera parameters is also provided in vpXmlParserCamera.

Note also that the Tutorial: Camera calibration shows how to calibrate a camera to obtain the parameters corresponding to both models implemented in this class.

Examples:
AROgre.cpp, AROgreBasic.cpp, HelloWorldOgre.cpp, HelloWorldOgreAdvanced.cpp, manGeometricFeatures.cpp, manServo4PointsDisplay.cpp, manSimu4Dots.cpp, manSimu4Points.cpp, mbtEdgeKltTracking.cpp, mbtEdgeTracking.cpp, mbtKltTracking.cpp, photometricVisualServoing.cpp, poseVirtualVS.cpp, servoAfma4Point2DArtVelocity.cpp, servoAfma4Point2DCamVelocity.cpp, servoAfma4Point2DCamVelocityKalman.cpp, servoAfma62DhalfCamVelocity.cpp, servoAfma6Cylinder2DCamVelocity.cpp, servoAfma6Cylinder2DCamVelocitySecondaryTask.cpp, servoAfma6Ellipse2DCamVelocity.cpp, servoAfma6FourPoints2DArtVelocity.cpp, servoAfma6FourPoints2DCamVelocityInteractionCurrent.cpp, servoAfma6FourPoints2DCamVelocityInteractionDesired.cpp, servoAfma6Line2DCamVelocity.cpp, servoAfma6Point2DArtVelocity.cpp, servoAfma6Point2DCamVelocity.cpp, servoAfma6Points2DCamVelocityEyeToHand.cpp, servoAfma6Segment2DCamVelocity.cpp, servoAfma6SquareLines2DCamVelocity.cpp, servoAfma6TwoLines2DCamVelocity.cpp, servoBiclopsPoint2DArtVelocity.cpp, servoMomentImage.cpp, servoMomentPoints.cpp, servoMomentPolygon.cpp, servoPioneerPanSegment3D.cpp, servoPioneerPoint2DDepth.cpp, servoPioneerPoint2DDepthWithoutVpServo.cpp, servoPtu46Point2DArtVelocity.cpp, servoSimu4Points.cpp, servoSimuAfma6FourPoints2DCamVelocity.cpp, servoSimuCircle2DCamVelocityDisplay.cpp, servoSimuCylinder.cpp, servoSimuCylinder2DCamVelocityDisplay.cpp, servoSimuCylinder2DCamVelocityDisplaySecondaryTask.cpp, servoSimuFourPoints2DCamVelocityDisplay.cpp, servoSimuFourPoints2DPolarCamVelocityDisplay.cpp, servoSimuLine2DCamVelocityDisplay.cpp, servoSimuSphere.cpp, servoSimuSquareLine2DCamVelocityDisplay.cpp, servoSimuViper850FourPoints2DCamVelocity.cpp, servoViper650FourPoints2DArtVelocityInteractionCurrent.cpp, servoViper650FourPoints2DCamVelocityInteractionCurrent.cpp, servoViper650Point2DCamVelocity.cpp, servoViper850FourPoints2DArtVelocityInteractionCurrent.cpp, servoViper850FourPoints2DArtVelocityInteractionDesired.cpp, servoViper850FourPoints2DCamVelocityInteractionCurrent.cpp, servoViper850FourPointsKinect.cpp, servoViper850Point2DArtVelocity-jointAvoidance-basic.cpp, servoViper850Point2DArtVelocity-jointAvoidance-gpa.cpp, servoViper850Point2DArtVelocity.cpp, servoViper850Point2DCamVelocity.cpp, servoViper850Point2DCamVelocityKalman.cpp, simulateCircle2DCamVelocity.cpp, simulateFourPoints2DCartesianCamVelocity.cpp, simulateFourPoints2DPolarCamVelocity.cpp, testAfma6.cpp, testFeatureSegment.cpp, testRobotAfma6.cpp, testRobotAfma6Pose.cpp, testRobotViper850.cpp, testRobotViper850Pose.cpp, testTrackDot.cpp, testUndistortImage.cpp, testViper850.cpp, trackMeLine.cpp, tutorial-detection-object-mbt.cpp, tutorial-homography-from-points.cpp, tutorial-ibvs-4pts-display.cpp, tutorial-ibvs-4pts-image-tracking.cpp, tutorial-ibvs-4pts-ogre-tracking.cpp, tutorial-ibvs-4pts-ogre.cpp, tutorial-ibvs-4pts-wireframe-camera.cpp, tutorial-ibvs-4pts-wireframe-robot-afma6.cpp, tutorial-ibvs-4pts-wireframe-robot-viper.cpp, tutorial-image-simulator.cpp, tutorial-matching-keypoint-homography.cpp, tutorial-matching-surf-homography-deprecated.cpp, tutorial-mb-edge-tracker.cpp, tutorial-mb-hybrid-tracker.cpp, tutorial-mb-klt-tracker.cpp, tutorial-pose-from-points-image.cpp, tutorial-pose-from-points-tracking.cpp, tutorial-undistort.cpp, and wireframeSimulator.cpp.

Definition at line 210 of file vpCameraParameters.h.

Member Enumeration Documentation

Enumerator
perspectiveProjWithoutDistortion 

Perspective projection without distortion model.

perspectiveProjWithDistortion 

Perspective projection with distortion model.

Definition at line 215 of file vpCameraParameters.h.

Constructor & Destructor Documentation

vpCameraParameters::vpCameraParameters ( )

Default constructor. By default, a perspective projection without distortion model is set.

See also
init()

Definition at line 77 of file vpCameraParameters.cpp.

References init().

vpCameraParameters::vpCameraParameters ( const vpCameraParameters c)

Copy constructor

Definition at line 93 of file vpCameraParameters.cpp.

References init().

vpCameraParameters::vpCameraParameters ( const double  cam_px,
const double  cam_py,
const double  cam_u0,
const double  cam_v0 
)

Constructor for perspective projection without distortion model

Parameters
cam_px,cam_py: pixel size
cam_u0,cam_v0: principal points

Definition at line 113 of file vpCameraParameters.cpp.

References initPersProjWithoutDistortion().

vpCameraParameters::vpCameraParameters ( const double  cam_px,
const double  cam_py,
const double  cam_u0,
const double  cam_v0,
const double  cam_kud,
const double  cam_kdu 
)

Constructor for perspective projection with distortion model

Parameters
cam_px,cam_py: pixel size
cam_u0,cam_v0: principal points
cam_kud: undistorted to distorted radial distortion
cam_kdu: distorted to undistorted radial distortion

Definition at line 136 of file vpCameraParameters.cpp.

References initPersProjWithDistortion().

vpCameraParameters::~vpCameraParameters ( )
virtual

destructor

nothing much to destroy...

Definition at line 313 of file vpCameraParameters.cpp.

Member Function Documentation

void vpCameraParameters::computeFov ( const unsigned int &  w,
const unsigned int &  h 
)

Compute angles and normals of the FOV.

Parameters
w: Width of the image
h: Height of the image.

Definition at line 436 of file vpCameraParameters.cpp.

References vpColVector::normalize().

Referenced by vpMbtDistanceLine::display(), vpMbKltTracker::display(), initFromFov(), vpMbtDistanceLine::initMovingEdge(), vpMbtPolygon::isVisible(), vpMbKltTracker::reinit(), and vpMbtDistanceLine::updateMovingEdge().

vpMatrix vpCameraParameters::get_K ( ) const

Return the calibration matrix $K$.

$K$ is 3x3 matrix given by:

$ K = \left(\begin{array}{ccc} p_x & 0 & u_0 \\ 0 & p_y & v_0 \\ 0 & 0 & 1 \end{array} \right) $

Warning
: this function is useful only in the case of perspective projection without distortion.
See also
get_K_inverse()

Definition at line 501 of file vpCameraParameters.cpp.

References vpException::notImplementedError, perspectiveProjWithDistortion, perspectiveProjWithoutDistortion, vpMatrix::resize(), and vpERROR_TRACE.

Referenced by vpMbEdgeTracker::downScale(), vpPose::poseFromRectangle(), vpHomography::project(), vpMbKltTracker::setPose(), and vpMbEdgeTracker::upScale().

vpMatrix vpCameraParameters::get_K_inverse ( ) const

Return the calibration matrix $K^{-1}$.

$K^{-1}$ is 3x3 matrix given by:

$ K^{-1} = \left(\begin{array}{ccc} 1/p_x & 0 & -u_0/p_x \\ 0 & 1/p_y & -v_0/p_y \\ 0 & 0 & 1 \end{array} \right) $

Warning
: this function is useful only in the case of perspective projection without distortion.
See also
get_K()

Definition at line 541 of file vpCameraParameters.cpp.

References vpException::notImplementedError, perspectiveProjWithDistortion, perspectiveProjWithoutDistortion, vpMatrix::resize(), and vpERROR_TRACE.

Referenced by vpHomography::project(), and vpMbKltTracker::setPose().

double vpCameraParameters::get_kdu ( ) const
inline

Definition at line 299 of file vpCameraParameters.h.

Referenced by vpCalibration::computeStdDeviation_dist().

double vpCameraParameters::get_kud ( ) const
inline
vpCameraParametersProjType vpCameraParameters::get_projModel ( ) const
inline

Definition at line 301 of file vpCameraParameters.h.

Referenced by vpXmlParserCamera::save().

double vpCameraParameters::get_px_inverse ( ) const
inline

Definition at line 293 of file vpCameraParameters.h.

double vpCameraParameters::get_py_inverse ( ) const
inline

Definition at line 294 of file vpCameraParameters.h.

vp_deprecated double vpCameraParameters::getFovAngleX ( ) const
inline
Deprecated:
This function is deprecated. Use rather getHorizontalFovAngle(). Get the horizontal angle of the field of view.
See also
computeFov()
Returns
AngleX computed with px and width.

Definition at line 320 of file vpCameraParameters.h.

References vpTRACE.

vp_deprecated double vpCameraParameters::getFovAngleY ( ) const
inline
Deprecated:
This function is deprecated. Use rather getVerticalFovAngle(). Get the vertical angle in radian of the field of view.
See also
computeFov()
Returns
FOV vertical angle computed with py and height.

Definition at line 333 of file vpCameraParameters.h.

References vpTRACE.

std::vector<vpColVector> vpCameraParameters::getFovNormals ( ) const
inline

Get the list of the normals corresponding to planes describing the field of view.

  • vector[0] : Left Normal.
  • vector[1] : Right Normal.
  • vector[2] : Up Normal.
  • vector[3] : Down Normal.
See also
computeFov()
Returns
List of the normals.

Definition at line 287 of file vpCameraParameters.h.

References vpTRACE.

Referenced by vpMbtPolygon::computeRoiClipped().

double vpCameraParameters::getHorizontalFovAngle ( ) const
inline

Get the horizontal angle in radian of the field of view.

Returns
FOV horizontal angle computed with px and width.
See also
computeFov(), getVerticalFovAngle()

Definition at line 259 of file vpCameraParameters.h.

References vpTRACE.

double vpCameraParameters::getVerticalFovAngle ( ) const
inline

Get the vertical angle in radian of the field of view.

Returns
FOV vertical angle computed with py and height.
See also
computeFov(), getHorizontalFovAngle()

Definition at line 271 of file vpCameraParameters.h.

References vpTRACE.

void vpCameraParameters::init ( )

basic initialization with the default parameters

Examples:
AROgre.cpp, and AROgreBasic.cpp.

Definition at line 155 of file vpCameraParameters.cpp.

References vpException::divideByZeroError, and vpERROR_TRACE.

Referenced by vpCameraParameters().

void vpCameraParameters::init ( const vpCameraParameters c)

initialization from another vpCameraParameters object

Definition at line 321 of file vpCameraParameters.cpp.

void vpCameraParameters::initFromCalibrationMatrix ( const vpMatrix _K)

initialise the camera from a calibration matrix. Using a calibration matrix leads to a camera without distortion

The K matrix in parameters must be like:

$ K = \left(\begin{array}{ccc} p_x & 0 & u_0 \\ 0 & p_y & v_0 \\ 0 & 0 & 1 \end{array} \right) $

Parameters
_K: the 3by3 calibration matrix

Definition at line 342 of file vpCameraParameters.cpp.

References vpException::badValue, vpException::dimensionError, vpMatrix::getCols(), vpMatrix::getRows(), and initPersProjWithoutDistortion().

Referenced by vpMbEdgeTracker::downScale(), and vpMbEdgeTracker::upScale().

void vpCameraParameters::initFromFov ( const unsigned int &  w,
const unsigned int &  h,
const double &  hfov,
const double &  vfov 
)

Initialize the camera model without distorsion from the image dimension and the camera field of view.

Parameters
w: Image width.
h: Image height.
hfov: Camera horizontal field of view angle expressed in radians.
vfov: Camera vertical field of view angle expressed in radians.

The following sample code shows how to use this function:

#include <visp/vpCameraParameters.h>
#include <visp/vpImage.h>
int main()
{
double hfov = vpMath::rad(56);
double vfov = vpMath::rad(43);
cam.initFromFov(I.getWidth(), I.getHeight(), hfov, vfov);
std::cout << cam << std::endl;
std::cout << "Field of view (horizontal: " << vpMath::deg(cam.getHorizontalFovAngle())
<< " and vertical: " << vpMath::deg(cam.getVerticalFovAngle()) << " degrees)" << std::endl;
}

It produces the following output:

Camera parameters for perspective projection without distortion:
px = 601.832 py = 609.275
u0 = 320 v0 = 240
Field of view (horizontal: 56 and vertical: 43 degrees)

Definition at line 388 of file vpCameraParameters.cpp.

References computeFov(), and perspectiveProjWithoutDistortion.

void vpCameraParameters::initPersProjWithDistortion ( const double  cam_px,
const double  cam_py,
const double  cam_u0,
const double  cam_v0,
const double  cam_kud,
const double  cam_kdu 
)

Initialization with specific parameters using perpective projection with distortion model.

Parameters
cam_px,cam_py: the ratio between the focal length and the size of a pixel.
cam_u0,cam_v0: principal points coordinates in pixels.
cam_kud: undistorted to distorted radial distortion.
cam_kdu: distorted to undistorted radial distortion.

The following sample code shows how to use this function:

#include <visp/vpCameraParameters.h>
#include <visp/vpImage.h>
int main()
{
double u0 = I.getWidth() / 2.;
double v0 = I.getHeight() / 2.;
double px = 600;
double py = 600;
double kud = -0.19;
double kdu = 0.20;
cam.initPersProjWithDistortion(px, py, u0, v0, kud, kdu);
cam.computeFov(I.getWidth(), I.getHeight());
std::cout << cam << std::endl;
std::cout << "Field of view (horizontal: " << vpMath::deg(cam.getHorizontalFovAngle())
<< " and vertical: " << vpMath::deg(cam.getVerticalFovAngle()) << " degrees)" << std::endl;
}

It produces the following output:

Camera parameters for perspective projection with distortion:
px = 600 py = 600
u0 = 320 v0 = 240
kud = -0.19
kdu = 0.2
Field of view (horizontal: 56.14497387 and vertical: 43.60281897 degrees)
Examples:
testUndistortImage.cpp, and tutorial-undistort.cpp.

Definition at line 279 of file vpCameraParameters.cpp.

References vpException::divideByZeroError, perspectiveProjWithDistortion, and vpERROR_TRACE.

Referenced by vpViper650::getCameraParameters(), vpViper850::getCameraParameters(), vpAfma6::getCameraParameters(), vpKinect::start(), and vpCameraParameters().

void vpCameraParameters::initPersProjWithoutDistortion ( const double  cam_px,
const double  cam_py,
const double  cam_u0,
const double  cam_v0 
)

Initialization with specific parameters using perpective projection without distortion model.

Parameters
cam_px,cam_py: the ratio between the focal length and the size of a pixel.
cam_u0,cam_v0: principal point coordinates in pixels.

The following sample code shows how to use this function:

#include <visp/vpCameraParameters.h>
#include <visp/vpImage.h>
int main()
{
double u0 = I.getWidth() / 2.;
double v0 = I.getHeight() / 2.;
double px = 600;
double py = 600;
cam.initPersProjWithoutDistortion(px, py, u0, v0);
cam.computeFov(I.getWidth(), I.getHeight());
std::cout << cam << std::endl;
std::cout << "Field of view (horizontal: " << vpMath::deg(cam.getHorizontalFovAngle())
<< " and vertical: " << vpMath::deg(cam.getVerticalFovAngle()) << " degrees)" << std::endl;
}

It produces the following output:

Camera parameters for perspective projection without distortion:
px = 600 py = 600
u0 = 320 v0 = 240
Field of view (horizontal: 56.145 and vertical: 43.6028 degrees)
Examples:
mbtEdgeKltTracking.cpp, mbtEdgeTracking.cpp, mbtKltTracking.cpp, servoPioneerPanSegment3D.cpp, servoPioneerPoint2DDepth.cpp, servoPioneerPoint2DDepthWithoutVpServo.cpp, tutorial-detection-object-mbt.cpp, tutorial-mb-edge-tracker.cpp, tutorial-mb-hybrid-tracker.cpp, and tutorial-mb-klt-tracker.cpp.

Definition at line 210 of file vpCameraParameters.cpp.

References vpException::divideByZeroError, perspectiveProjWithoutDistortion, and vpERROR_TRACE.

Referenced by vpViper650::getCameraParameters(), vpViper850::getCameraParameters(), vpAfma6::getCameraParameters(), vpSimulatorAfma6::getCameraParameters(), vpSimulatorViper850::getCameraParameters(), vpSimulatorAfma6::initDisplay(), vpSimulatorViper850::initDisplay(), initFromCalibrationMatrix(), vpMbXmlParser::read_camera(), and vpCameraParameters().

bool vpCameraParameters::isFovComputed ( ) const
inline

Specify if the fov has been computed.

See also
computeFov()
Returns
True if the fov has been computed, False otherwise.

Definition at line 248 of file vpCameraParameters.h.

Referenced by vpMbtPolygon::computeRoiClipped().

vpCameraParameters & vpCameraParameters::operator= ( const vpCameraParameters cam)

copy operator

Definition at line 406 of file vpCameraParameters.cpp.

Friends And Related Function Documentation

VISP_EXPORT std::ostream& operator<< ( std::ostream &  os,
const vpCameraParameters cam 
)
friend

Print on the output stream os the camera parameters.

Parameters
os: Output stream.
cam: Camera parameters.

Definition at line 603 of file vpCameraParameters.cpp.

friend class vpMeterPixelConversion
friend

Definition at line 212 of file vpCameraParameters.h.

friend class vpPixelMeterConversion
friend

Definition at line 213 of file vpCameraParameters.h.