Visual Servoing Platform  version 3.3.0 under development (2020-02-17)
vpCameraParameters Class Reference

#include <visp3/core/vpCameraParameters.h>

Public Types

enum  vpCameraParametersProjType { perspectiveProjWithoutDistortion, perspectiveProjWithDistortion }
 

Public Member Functions

 vpCameraParameters ()
 
 vpCameraParameters (const vpCameraParameters &c)
 
 vpCameraParameters (double px, double py, double u0, double v0)
 
 vpCameraParameters (double px, double py, double u0, double v0, double kud, double kdu)
 
vpCameraParametersoperator= (const vpCameraParameters &c)
 
bool operator== (const vpCameraParameters &c) const
 
bool operator!= (const vpCameraParameters &c) const
 
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 (double px, double py, double u0, double v0)
 
void initPersProjWithDistortion (double px, double py, double u0, double v0, double kud, 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 ()
 

Friends

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

Detailed Description

Generic class defining intrinsic camera parameters.

Let us define the pinhole camera model implemented in ViSP. In this model [29], a scene view is formed by projecting 3D points into the image plane using a perspective transformation.

\[ \left[ \begin{array}{c} u \\ v \\ 1 \end{array}\right] = \left[ \begin{array}{ccc} p_x & 0 & u_0 \\ 0 & p_y & v_0 \\ 0 & 0 & 1 \end{array}\right] \left[ \begin{array}{c} x \\ y \\ 1 \end{array}\right] \]

where:

  • $(X_c,Y_c,Z_c)$ are the coordinates of a 3D point in the camera frame
  • $(x,y)$ are the coordinates of the projection of the 3D point in the image plane
  • $(u,v)$ are the coordinates in pixels of the projected 3D point
  • $(u_0,v_0)$ are the coordinates of the principal point (the intersection of the optical axes with the image plane) that is usually near the image center
  • $p_x$ (resp $p_y$) is the ratio between the focal length of the lens $f$ in meters and the size of the pixel $l_x$ in meters: $p_x=f/l_x$ (resp, $l_y$ being the height of a pixel, $p_y=f/l_y$).

When $Z_c \neq 0$, the previous equation is equivalent to the following:

\[ \begin{array}{lcl} x &=& X_c / Z_c \\ y &=& Y_c / Z_c \\ u &=& u_0 + x \; p_x \\ v &=& v_0 + y \; p_y \end{array} \]

Real lenses usually have some radial distortion. So, the above model is extended as:

\[ \begin{array}{lcl} x &=& X_c / Z_c \\ y &=& Y_c / Z_c \\ x^{'} &=& x (1 + k_{ud} r^2) \\ y^{'} &=& y (1 + k_{ud} r^2) \\ r^2 &=& x^2 + y^2 \\ u &=& u_0 + x^{'} \; p_x \\ v &=& v_0 + y^{'} \; p_y \end{array} \]

where $k_{ud}$ is the first order radial distorsion. Higher order distorsion coefficients are not considered in ViSP.

Now in ViSP we consider also the inverse transformation, where from pixel coordinates we want to compute their normalized coordinates in the image plane. Previous equations could be written like:

\[ \begin{array}{lcl} x &=& (u - u_0) / p_x \\ y &=& (v - v_0) / p_y \end{array} \]

Considering radial distortion, the above model is extended as:

\[ \begin{array}{lcl} (u-u_0)^{'} &=& (u-u_0) (1 + k_{du} r^2) \\ (v-v_0)^{'} &=& (v-v_0) (1 + k_{du} r^2) \\ r^2 &=& ((u-u_0)/p_x)^2 + ((v-v_0)/p_y)^2 \\ x &=& (u - u_0)^{'} / p_x \\ y &=& (v - v_0)^{'} / p_y \end{array} \]

Finally, in ViSP 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})$.

Note
The Tutorial: Camera intrinsic calibration shows how to calibrate a camera to estimate the parameters corresponding to the model implemented in this class.
Note also that Tutorial: Bridge over OpenCV gives the correspondance between ViSP and OpenCV camera modelization.
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.

From a practical point of view, two kinds of camera modelisation are implemented in this class:

1. Camera parameters for a perspective projection without distortion model

In this modelisation, only $u_0,v_0,p_x,p_y$ parameters are considered.

Initialization of such a model can be done using:

2. Camera parameters for a perspective projection with distortion model

In this modelisation, all the parameters $u_0,v_0,p_x,p_y,k_{ud},k_{du}$ are considered. Initialization of such a model can be done using:

The selection of the camera model (without or with distorsion) 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.

Examples:
AROgre.cpp, AROgreBasic.cpp, HelloWorldOgre.cpp, HelloWorldOgreAdvanced.cpp, manGeometricFeatures.cpp, manServo4PointsDisplay.cpp, manSimu4Dots.cpp, manSimu4Points.cpp, mbot-apriltag-2D-half-vs.cpp, mbot-apriltag-ibvs.cpp, mbot-apriltag-pbvs.cpp, mbtEdgeKltMultiTracking.cpp, mbtEdgeKltTracking.cpp, mbtEdgeMultiTracking.cpp, mbtEdgeTracking.cpp, mbtGenericTracking.cpp, mbtGenericTracking2.cpp, mbtGenericTrackingDepth.cpp, mbtGenericTrackingDepthOnly.cpp, mbtKltMultiTracking.cpp, mbtKltTracking.cpp, photometricVisualServoing.cpp, poseVirtualVS.cpp, servoAfma4Point2DArtVelocity.cpp, servoAfma4Point2DCamVelocity.cpp, servoAfma4Point2DCamVelocityKalman.cpp, servoAfma62DhalfCamVelocity.cpp, servoAfma6Cylinder2DCamVelocity.cpp, servoAfma6Cylinder2DCamVelocitySecondaryTask.cpp, servoAfma6Ellipse2DCamVelocity.cpp, servoAfma6FourPoints2DArtVelocity.cpp, servoAfma6FourPoints2DCamVelocityLs_cur.cpp, servoAfma6FourPoints2DCamVelocityLs_des.cpp, servoAfma6Line2DCamVelocity.cpp, servoAfma6Point2DArtVelocity.cpp, servoAfma6Point2DCamVelocity.cpp, servoAfma6Points2DCamVelocityEyeToHand.cpp, servoAfma6Segment2DCamVelocity.cpp, servoAfma6SquareLines2DCamVelocity.cpp, servoAfma6TwoLines2DCamVelocity.cpp, servoBebop2.cpp, servoBiclopsPoint2DArtVelocity.cpp, servoFlirPtuIBVS.cpp, servoFrankaIBVS.cpp, servoFrankaPBVS.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, servoSimuSphere2DCamVelocityDisplay.cpp, servoSimuSphere2DCamVelocityDisplaySecondaryTask.cpp, servoSimuSquareLine2DCamVelocityDisplay.cpp, servoSimuViper850FourPoints2DCamVelocity.cpp, servoViper650FourPoints2DArtVelocityLs_cur.cpp, servoViper650FourPoints2DCamVelocityLs_cur-SR300.cpp, servoViper650FourPoints2DCamVelocityLs_cur.cpp, servoViper650Point2DCamVelocity.cpp, servoViper850FourPoints2DArtVelocityLs_cur.cpp, servoViper850FourPoints2DArtVelocityLs_des.cpp, servoViper850FourPoints2DCamVelocityLs_cur.cpp, servoViper850FourPointsKinect.cpp, servoViper850Point2DArtVelocity-jointAvoidance-basic.cpp, servoViper850Point2DArtVelocity-jointAvoidance-gpa.cpp, servoViper850Point2DArtVelocity-jointAvoidance-large.cpp, servoViper850Point2DArtVelocity.cpp, servoViper850Point2DCamVelocity.cpp, servoViper850Point2DCamVelocityKalman.cpp, simulateCircle2DCamVelocity.cpp, simulateFourPoints2DCartesianCamVelocity.cpp, simulateFourPoints2DPolarCamVelocity.cpp, testAfma6.cpp, testAprilTag.cpp, testDisplays.cpp, testFeatureSegment.cpp, testGenericTracker.cpp, testGenericTrackerDepth.cpp, testImageDraw.cpp, testKeyPoint-2.cpp, testKeyPoint-4.cpp, testMomentAlpha.cpp, testRealSense2_D435_align.cpp, testRealSense2_D435_opencv.cpp, testRobotAfma6.cpp, testRobotAfma6Pose.cpp, testRobotViper850.cpp, testRobotViper850Pose.cpp, testTrackDot.cpp, testUndistortImage.cpp, testViper650.cpp, testViper850.cpp, testVirtuoseWithGlove.cpp, trackMeLine.cpp, tutorial-apriltag-detector-live-rgbd-realsense.cpp, tutorial-apriltag-detector-live.cpp, tutorial-apriltag-detector.cpp, tutorial-bridge-opencv.cpp, tutorial-chessboard-pose.cpp, tutorial-detection-object-mbt-deprecated.cpp, tutorial-detection-object-mbt.cpp, tutorial-detection-object-mbt2-deprecated.cpp, tutorial-detection-object-mbt2.cpp, tutorial-flir-ptu-ibvs.cpp, tutorial-franka-acquire-calib-data.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-generic-tracker-apriltag-rs2.cpp, tutorial-mb-generic-tracker-apriltag-webcam.cpp, tutorial-mb-generic-tracker-full.cpp, tutorial-mb-generic-tracker-live.cpp, tutorial-mb-generic-tracker-rgbd-blender.cpp, tutorial-mb-generic-tracker-rgbd-realsense.cpp, tutorial-mb-generic-tracker-rgbd.cpp, tutorial-mb-generic-tracker-stereo-mono.cpp, tutorial-mb-generic-tracker-stereo.cpp, tutorial-mb-generic-tracker.cpp, tutorial-mb-hybrid-tracker.cpp, tutorial-mb-klt-tracker.cpp, tutorial-mb-tracker-full.cpp, tutorial-mb-tracker-stereo-mono.cpp, tutorial-mb-tracker-stereo.cpp, tutorial-mb-tracker.cpp, tutorial-pose-from-points-image.cpp, tutorial-pose-from-points-live.cpp, tutorial-pose-from-qrcode-image.cpp, tutorial-undistort.cpp, and wireframeSimulator.cpp.

Definition at line 233 of file vpCameraParameters.h.

Member Enumeration Documentation

◆ vpCameraParametersProjType

Enumerator
perspectiveProjWithoutDistortion 

Perspective projection without distortion model

perspectiveProjWithDistortion 

Perspective projection with distortion model

Definition at line 239 of file vpCameraParameters.h.

Constructor & Destructor Documentation

◆ vpCameraParameters() [1/4]

vpCameraParameters::vpCameraParameters ( )

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

See also
init()

Definition at line 72 of file vpCameraParameters.cpp.

References init().

◆ vpCameraParameters() [2/4]

vpCameraParameters::vpCameraParameters ( const vpCameraParameters c)

Copy constructor

Definition at line 84 of file vpCameraParameters.cpp.

References init().

◆ vpCameraParameters() [3/4]

vpCameraParameters::vpCameraParameters ( double  cam_px,
double  cam_py,
double  cam_u0,
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 100 of file vpCameraParameters.cpp.

References initPersProjWithoutDistortion().

◆ vpCameraParameters() [4/4]

vpCameraParameters::vpCameraParameters ( double  cam_px,
double  cam_py,
double  cam_u0,
double  cam_v0,
double  cam_kud,
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 118 of file vpCameraParameters.cpp.

References initPersProjWithDistortion().

◆ ~vpCameraParameters()

vpCameraParameters::~vpCameraParameters ( )
virtual

destructor

nothing much to destroy...

Definition at line 277 of file vpCameraParameters.cpp.

Member Function Documentation

◆ computeFov()

◆ get_K()

vpMatrix vpCameraParameters::get_K ( ) const

◆ get_K_inverse()

vpMatrix vpCameraParameters::get_K_inverse ( ) const

Return the inverted camera matrix $K^{-1}$ 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] $

See also
get_K()

Definition at line 514 of file vpCameraParameters.cpp.

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

◆ get_kdu()

double vpCameraParameters::get_kdu ( ) const
inline

Definition at line 335 of file vpCameraParameters.h.

Referenced by vpCalibration::computeStdDeviation_dist().

◆ get_kud()

double vpCameraParameters::get_kud ( ) const
inline

◆ get_projModel()

vpCameraParametersProjType vpCameraParameters::get_projModel ( ) const
inline

Definition at line 337 of file vpCameraParameters.h.

◆ get_px()

double vpCameraParameters::get_px ( ) const
inline

◆ get_px_inverse()

double vpCameraParameters::get_px_inverse ( ) const
inline

Definition at line 329 of file vpCameraParameters.h.

◆ get_py()

◆ get_py_inverse()

double vpCameraParameters::get_py_inverse ( ) const
inline

Definition at line 330 of file vpCameraParameters.h.

◆ get_u0()

◆ get_v0()

◆ getFovNormals()

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 319 of file vpCameraParameters.h.

References vpTRACE.

Referenced by vpPolygon3D::computePolygonClipped().

◆ getHorizontalFovAngle()

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 282 of file vpCameraParameters.h.

References vpTRACE.

◆ getVerticalFovAngle()

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 298 of file vpCameraParameters.h.

References vpTRACE.

◆ init() [1/2]

void vpCameraParameters::init ( )

basic initialization with the default parameters

Examples:
AROgre.cpp, and AROgreBasic.cpp.

Definition at line 131 of file vpCameraParameters.cpp.

References vpException::divideByZeroError, and vpERROR_TRACE.

Referenced by vpCameraParameters().

◆ init() [2/2]

void vpCameraParameters::init ( const vpCameraParameters c)

initialization from another vpCameraParameters object

Definition at line 282 of file vpCameraParameters.cpp.

◆ initFromCalibrationMatrix()

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 298 of file vpCameraParameters.cpp.

References vpException::badValue, vpException::dimensionError, vpArray2D< Type >::getCols(), vpArray2D< Type >::getRows(), and initPersProjWithoutDistortion().

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

◆ initFromFov()

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 <visp3/core/vpCameraParameters.h>
#include <visp3/core/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 342 of file vpCameraParameters.cpp.

References computeFov(), and perspectiveProjWithoutDistortion.

◆ initPersProjWithDistortion()

void vpCameraParameters::initPersProjWithDistortion ( double  cam_px,
double  cam_py,
double  cam_u0,
double  cam_v0,
double  cam_kud,
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 <visp3/core/vpCameraParameters.h>
#include <visp3/core/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 248 of file vpCameraParameters.cpp.

References vpException::divideByZeroError, perspectiveProjWithDistortion, and vpERROR_TRACE.

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

◆ initPersProjWithoutDistortion()

void vpCameraParameters::initPersProjWithoutDistortion ( double  cam_px,
double  cam_py,
double  cam_u0,
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 <visp3/core/vpCameraParameters.h>
#include <visp3/core/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:
mbot-apriltag-2D-half-vs.cpp, mbot-apriltag-ibvs.cpp, mbot-apriltag-pbvs.cpp, mbtEdgeKltMultiTracking.cpp, mbtEdgeKltTracking.cpp, mbtEdgeMultiTracking.cpp, mbtEdgeTracking.cpp, mbtGenericTracking.cpp, mbtGenericTracking2.cpp, mbtGenericTrackingDepth.cpp, mbtGenericTrackingDepthOnly.cpp, mbtKltMultiTracking.cpp, mbtKltTracking.cpp, servoBebop2.cpp, servoPioneerPanSegment3D.cpp, servoPioneerPoint2DDepth.cpp, servoPioneerPoint2DDepthWithoutVpServo.cpp, testAprilTag.cpp, testGenericTracker.cpp, testGenericTrackerDepth.cpp, testKeyPoint-2.cpp, testKeyPoint-4.cpp, tutorial-apriltag-detector-live.cpp, tutorial-apriltag-detector.cpp, tutorial-detection-object-mbt-deprecated.cpp, tutorial-detection-object-mbt.cpp, tutorial-detection-object-mbt2-deprecated.cpp, tutorial-detection-object-mbt2.cpp, tutorial-mb-edge-tracker.cpp, tutorial-mb-generic-tracker-apriltag-webcam.cpp, tutorial-mb-generic-tracker-full.cpp, tutorial-mb-generic-tracker-live.cpp, tutorial-mb-generic-tracker-stereo-mono.cpp, tutorial-mb-generic-tracker.cpp, tutorial-mb-hybrid-tracker.cpp, tutorial-mb-klt-tracker.cpp, tutorial-mb-tracker-full.cpp, tutorial-mb-tracker-stereo-mono.cpp, and tutorial-mb-tracker.cpp.

Definition at line 182 of file vpCameraParameters.cpp.

References vpException::divideByZeroError, perspectiveProjWithoutDistortion, and vpERROR_TRACE.

Referenced by VispDetector::detectAprilTag:px:py:, vpServolens::getCameraParameters(), vpViper650::getCameraParameters(), vpViper850::getCameraParameters(), vpAfma6::getCameraParameters(), vpSimulatorAfma6::getCameraParameters(), vpSimulatorViper850::getCameraParameters(), vpRealSense2::getCameraParameters(), vpRealSense::getCameraParameters(), vpSimulatorAfma6::initDisplay(), vpSimulatorViper850::initDisplay(), initFromCalibrationMatrix(), and vpCameraParameters().

◆ isFovComputed()

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 271 of file vpCameraParameters.h.

Referenced by vpPolygon3D::computePolygonClipped().

◆ operator!=()

bool vpCameraParameters::operator!= ( const vpCameraParameters c) const

False if the two objects are absolutely identical.

Definition at line 422 of file vpCameraParameters.cpp.

◆ operator=()

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

copy operator

Definition at line 360 of file vpCameraParameters.cpp.

◆ operator==()

bool vpCameraParameters::operator== ( const vpCameraParameters c) const

True if the two objects are absolutely identical.

Definition at line 386 of file vpCameraParameters.cpp.

References vpMath::equal().

◆ printParameters()

Friends And Related Function Documentation

◆ operator<<

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 560 of file vpCameraParameters.cpp.

◆ vpMeterPixelConversion

friend class vpMeterPixelConversion
friend

Definition at line 235 of file vpCameraParameters.h.

◆ vpPixelMeterConversion

friend class vpPixelMeterConversion
friend

Definition at line 236 of file vpCameraParameters.h.