Visual Servoing Platform  version 3.1.0

#include <visp3/vision/vpPose.h>

Public Types

enum  vpPoseMethodType {
  LAGRANGE, DEMENTHON, LOWE, RANSAC,
  LAGRANGE_LOWE, DEMENTHON_LOWE, VIRTUAL_VS, DEMENTHON_VIRTUAL_VS,
  LAGRANGE_VIRTUAL_VS
}
 
enum  FILTERING_RANSAC_FLAGS { PREFILTER_DUPLICATE_POINTS = 0x1, PREFILTER_ALMOST_DUPLICATE_POINTS = 0x2, PREFILTER_DEGENERATE_POINTS = 0x4, CHECK_DEGENERATE_POINTS = 0x8 }
 

Public Member Functions

 vpPose ()
 
virtual ~vpPose ()
 
void addPoint (const vpPoint &P)
 
void addPoints (const std::vector< vpPoint > &lP)
 
void clearPoint ()
 
bool computePose (vpPoseMethodType method, vpHomogeneousMatrix &cMo, bool(*func)(vpHomogeneousMatrix *)=NULL)
 
double computeResidual (const vpHomogeneousMatrix &cMo) const
 
bool coplanar (int &coplanar_plane_type)
 
void displayModel (vpImage< unsigned char > &I, vpCameraParameters &cam, vpColor col=vpColor::none)
 
void displayModel (vpImage< vpRGBa > &I, vpCameraParameters &cam, vpColor col=vpColor::none)
 
void init ()
 
void poseDementhonPlan (vpHomogeneousMatrix &cMo)
 
void poseDementhonNonPlan (vpHomogeneousMatrix &cMo)
 
void poseLagrangePlan (vpHomogeneousMatrix &cMo, const int coplanar_plane_type=0)
 
void poseLagrangeNonPlan (vpHomogeneousMatrix &cMo)
 
void poseLowe (vpHomogeneousMatrix &cMo)
 
bool poseRansac (vpHomogeneousMatrix &cMo, bool(*func)(vpHomogeneousMatrix *)=NULL)
 
void poseVirtualVSrobust (vpHomogeneousMatrix &cMo)
 
void poseVirtualVS (vpHomogeneousMatrix &cMo)
 
void printPoint ()
 
void setDistanceToPlaneForCoplanarityTest (double d)
 
void setLambda (double a)
 
void setVvsEpsilon (const double eps)
 
void setVvsIterMax (int nb)
 
void setRansacNbInliersToReachConsensus (const unsigned int &nbC)
 
void setRansacThreshold (const double &t)
 
void setRansacMaxTrials (const int &rM)
 
unsigned int getRansacNbInliers () const
 
std::vector< unsigned int > getRansacInlierIndex () const
 
std::vector< vpPointgetRansacInliers () const
 
void setCovarianceComputation (const bool &flag)
 
vpMatrix getCovarianceMatrix () const
 
void setRansacFilterFlags (const int flags)
 
int getNbParallelRansacThreads () const
 
void setNbParallelRansacThreads (const int nb)
 
bool getUseParallelRansac () const
 
void setUseParallelRansac (const bool use)
 
std::vector< vpPointgetPoints () const
 

Static Public Member Functions

static void display (vpImage< unsigned char > &I, vpHomogeneousMatrix &cMo, vpCameraParameters &cam, double size, vpColor col=vpColor::none)
 
static void display (vpImage< vpRGBa > &I, vpHomogeneousMatrix &cMo, vpCameraParameters &cam, double size, vpColor col=vpColor::none)
 
static double poseFromRectangle (vpPoint &p1, vpPoint &p2, vpPoint &p3, vpPoint &p4, double lx, vpCameraParameters &cam, vpHomogeneousMatrix &cMo)
 
static int computeRansacIterations (double probability, double epsilon, const int sampleSize=4, int maxIterations=2000)
 
static void findMatch (std::vector< vpPoint > &p2D, std::vector< vpPoint > &p3D, const unsigned int &numberOfInlierToReachAConsensus, const double &threshold, unsigned int &ninliers, std::vector< vpPoint > &listInliers, vpHomogeneousMatrix &cMo, const int &maxNbTrials=10000)
 

Public Attributes

unsigned int npt
 
std::list< vpPointlistP
 
double residual
 

Protected Member Functions

double computeResidualDementhon (const vpHomogeneousMatrix &cMo)
 
int calculArbreDementhon (vpMatrix &b, vpColVector &U, vpHomogeneousMatrix &cMo)
 

Protected Attributes

double lambda
 

Detailed Description

Member Enumeration Documentation

◆ FILTERING_RANSAC_FLAGS

Enumerator
PREFILTER_DUPLICATE_POINTS 

Remove duplicate points before the RANSAC.

PREFILTER_ALMOST_DUPLICATE_POINTS 

Remove almost duplicate points (up to a tolerance) before the RANSAC.

PREFILTER_DEGENERATE_POINTS 

Remove degenerate points (same 3D or 2D coordinates) before the RANSAC.

CHECK_DEGENERATE_POINTS 

Check for degenerate points during the RANSAC.

Definition at line 103 of file vpPose.h.

◆ vpPoseMethodType

Methods that could be used to estimate the pose from points.

Enumerator
LAGRANGE 

Linear Lagrange approach (does't need an initialization)

DEMENTHON 

Linear Dementhon aproach (does't need an initialization)

LOWE 

Lowe aproach based on a Levenberg Marquartd non linear minimization scheme that needs an initialization from Lagrange or Dementhon aproach

RANSAC 

Robust Ransac aproach (does't need an initialization)

LAGRANGE_LOWE 

Non linear Lowe aproach initialized by Lagrange approach

DEMENTHON_LOWE 

Non linear Lowe aproach initialized by Dementhon approach

VIRTUAL_VS 

Non linear virtual visual servoing approach that needs an initialization from Lagrange or Dementhon aproach

DEMENTHON_VIRTUAL_VS 

Non linear virtual visual servoing approach initialized by Dementhon approach

LAGRANGE_VIRTUAL_VS 

Non linear virtual visual servoing approach initialized by Lagrange approach

Definition at line 83 of file vpPose.h.

Constructor & Destructor Documentation

◆ vpPose()

vpPose::vpPose ( )

Default constructor.

Definition at line 94 of file vpPose.cpp.

◆ ~vpPose()

vpPose::~vpPose ( )
virtual

Destructor that deletes the array of point (freed the memory).

Definition at line 107 of file vpPose.cpp.

References listP.

Member Function Documentation

◆ addPoint()

◆ addPoints()

void vpPose::addPoints ( const std::vector< vpPoint > &  lP)

Add (append) a list of points in the array of points.

Parameters
lP: List of points to add (append).
Warning
Considering a point from the class vpPoint, oX, oY, and oZ will represent the 3D coordinates of the point in the object frame and x and y its 2D coordinates in the image plane. These 5 fields must be initialized to be used within this function.
Examples:
testPoseRansac2.cpp.

Definition at line 152 of file vpPose.cpp.

References listP, and npt.

◆ calculArbreDementhon()

int vpPose::calculArbreDementhon ( vpMatrix b,
vpColVector U,
vpHomogeneousMatrix cMo 
)
protected

◆ clearPoint()

void vpPose::clearPoint ( )

◆ computePose()

bool vpPose::computePose ( vpPoseMethodType  method,
vpHomogeneousMatrix cMo,
bool(*)(vpHomogeneousMatrix *)  func = NULL 
)

Compute the pose according to the desired method which are:

  • vpPose::LAGRANGE: Linear Lagrange approach (test is done to switch between planar and non planar algorithm)
  • vpPose::DEMENTHON: Linear Dementhon approach (test is done to switch between planar and non planar algorithm)
  • vpPose::LOWE: Lowe aproach based on a Levenberg Marquartd non linear minimization scheme that needs an initialization from Lagrange or Dementhon aproach
  • vpPose::LAGRANGE_LOWE: Non linear Lowe aproach initialized by Lagrange approach
  • vpPose::DEMENTHON_LOWE: Non linear Lowe aproach initialized by Dementhon approach
  • vpPose::VIRTUAL_VS: Non linear virtual visual servoing approach that needs an initialization from Lagrange or Dementhon aproach
  • vpPose::DEMENTHON_VIRTUAL_VS: Non linear virtual visual servoing approach initialized by Dementhon approach
  • vpPose::LAGRANGE_VIRTUAL_VS: Non linear virtual visual servoing approach initialized by Lagrange approach
  • vpPose::RANSAC: Robust Ransac aproach (does't need an initialization)
Examples:
AROgre.cpp, AROgreBasic.cpp, poseVirtualVS.cpp, servoAfma62DhalfCamVelocity.cpp, servoAfma6FourPoints2DCamVelocityInteractionCurrent.cpp, servoAfma6Points2DCamVelocityEyeToHand.cpp, servoViper650FourPoints2DArtVelocityInteractionCurrent.cpp, servoViper650FourPoints2DCamVelocityInteractionCurrent-SR300.cpp, servoViper650FourPoints2DCamVelocityInteractionCurrent.cpp, servoViper850FourPoints2DArtVelocityInteractionCurrent.cpp, servoViper850FourPoints2DCamVelocityInteractionCurrent.cpp, servoViper850FourPointsKinect.cpp, testKeyPoint-4.cpp, testPose.cpp, testPoseRansac.cpp, testPoseRansac2.cpp, testRobotAfma6Pose.cpp, testRobotViper850Pose.cpp, tutorial-pose-from-points-image.cpp, tutorial-pose-from-points-tracking.cpp, and tutorial-pose-from-qrcode-image.cpp.

Definition at line 362 of file vpPose.cpp.

References coplanar(), DEMENTHON, DEMENTHON_LOWE, DEMENTHON_VIRTUAL_VS, LAGRANGE, LAGRANGE_LOWE, LAGRANGE_VIRTUAL_VS, LOWE, vpPoseException::notEnoughPointError, npt, poseDementhonNonPlan(), poseDementhonPlan(), poseLagrangeNonPlan(), poseLagrangePlan(), poseLowe(), poseRansac(), poseVirtualVS(), RANSAC, VIRTUAL_VS, and vpERROR_TRACE.

Referenced by vpCalibration::addPoint(), vpKeyPoint::computePose(), findMatch(), vpMbTracker::initClick(), vpMbTracker::initFromPoints(), poseFromRectangle(), and poseRansac().

◆ computeRansacIterations()

int vpPose::computeRansacIterations ( double  probability,
double  epsilon,
const int  sampleSize = 4,
int  maxIterations = 2000 
)
static

Compute the number of RANSAC iterations to ensure with a probability p that at least one of the random samples of s points is free from outliers.

Note
See: Hartley and Zisserman, Multiple View Geometry in Computer Vision, p119 (2. How many samples?).
Parameters
probability: Probability that at least one of the random samples is free from outliers (typically p=0.99).
epsilon: Probability that a selected point is an outlier (between 0 and 1).
sampleSize: Minimum number of points to estimate the model (4 for a pose estimation).
maxIterations: Upper bound on the number of iterations or -1 for INT_MAX.
Returns
The number of RANSAC iterations to ensure with a probability p that at least one of the random samples of s points is free from outliers or maxIterations if it exceeds the desired upper bound or INT_MAX if maxIterations=-1.
Examples:
testPoseRansac2.cpp.

Definition at line 984 of file vpPoseRansac.cpp.

References vpMath::nul().

◆ computeResidual()

◆ computeResidualDementhon()

double vpPose::computeResidualDementhon ( const vpHomogeneousMatrix cMo)
protected

Compute and return the residual expressed in meter for the pose matrix 'pose'.

Parameters
cMo: the matrix that defines the pose to be tested.
Returns
the value of he residual in meter

Definition at line 643 of file vpPoseDementhon.cpp.

References npt, and vpMath::sqr().

Referenced by calculArbreDementhon(), and poseDementhonPlan().

◆ coplanar()

bool vpPose::coplanar ( int &  coplanar_plane_type)

Test the coplanarity of the set of points

Parameters
coplanar_plane_type1: if plane x=cst 2: if plane y=cst 3: if plane z=cst 4: if the points are collinear. 0: any other plane
Returns
true if points are coplanar false otherwise.

Definition at line 172 of file vpPose.cpp.

References vpColVector::crossProd(), vpPoint::get_oX(), vpPoint::get_oY(), vpPoint::get_oZ(), listP, vpPoseException::notEnoughPointError, npt, vpMath::sqr(), vpColVector::sumSquare(), vpDEBUG_TRACE, and vpERROR_TRACE.

Referenced by computePose().

◆ display() [1/2]

void vpPose::display ( vpImage< unsigned char > &  I,
vpHomogeneousMatrix cMo,
vpCameraParameters cam,
double  size,
vpColor  col = vpColor::none 
)
static

Display in the image I the pose represented by its homogenous transformation cMo as a 3 axis frame.

Parameters
IImage where the pose is displayed in overlay.
cMoConsidered pose to display.
camCamera parameters associated to image I.
sizelength in meter of the axis that will be displayed
colColor used to display the 3 axis. If vpColor::none, red, green and blue will represent x-axiw, y-axis and z-axis respectively.
Examples:
AROgre.cpp, AROgreBasic.cpp, and poseVirtualVS.cpp.

Definition at line 516 of file vpPose.cpp.

References vpDisplay::displayFrame().

◆ display() [2/2]

void vpPose::display ( vpImage< vpRGBa > &  I,
vpHomogeneousMatrix cMo,
vpCameraParameters cam,
double  size,
vpColor  col = vpColor::none 
)
static

Display in the image I the pose represented by its homogenous transformation cMo as a 3 axis frame.

Parameters
IImage where the pose is displayed in overlay.
cMoConsidered pose to display.
camCamera parameters associated to image I.
sizelength in meter of the axis that will be displayed
colColor used to display the 3 axis. If vpColor::none, red, green and blue will represent x-axiw, y-axis and z-axis respectively.

Definition at line 531 of file vpPose.cpp.

References vpDisplay::displayFrame().

◆ displayModel() [1/2]

void vpPose::displayModel ( vpImage< unsigned char > &  I,
vpCameraParameters cam,
vpColor  col = vpColor::none 
)

Display the coordinates of the points in the image plane that are used to compute the pose in image I.

Definition at line 540 of file vpPose.cpp.

References vpMeterPixelConversion::convertPoint(), vpDisplay::displayCross(), listP, and vpTracker::p.

◆ displayModel() [2/2]

void vpPose::displayModel ( vpImage< vpRGBa > &  I,
vpCameraParameters cam,
vpColor  col = vpColor::none 
)

Display the coordinates of the points in the image plane that are used to compute the pose in image I.

Definition at line 558 of file vpPose.cpp.

References vpMeterPixelConversion::convertPoint(), vpDisplay::displayCross(), listP, and vpTracker::p.

◆ findMatch()

void vpPose::findMatch ( std::vector< vpPoint > &  p2D,
std::vector< vpPoint > &  p3D,
const unsigned int &  numberOfInlierToReachAConsensus,
const double &  threshold,
unsigned int &  ninliers,
std::vector< vpPoint > &  listInliers,
vpHomogeneousMatrix cMo,
const int &  maxNbTrials = 10000 
)
static

Match a vector p2D of 2D point (x,y) and a vector p3D of 3D points (X,Y,Z) using the Ransac algorithm.

At least numberOfInlierToReachAConsensus of true correspondance are required to validate the pose

The inliers are given in a vector of vpPoint listInliers.

The pose is returned in cMo.

Parameters
p2D: Vector of 2d points (x and y attributes are used).
p3D: Vector of 3d points (oX, oY and oZ attributes are used).
numberOfInlierToReachAConsensus: The minimum number of inlier to have to consider a trial as correct.
threshold: The maximum error allowed between the 2d points and the reprojection of its associated 3d points by the current pose (in meter).
ninliers: Number of inliers found for the best solution.
listInliers: Vector of points (2d and 3d) that are inliers for the best solution.
cMo: The computed pose (best solution).
maxNbTrials: Maximum number of trials before considering a solution fitting the required numberOfInlierToReachAConsensus and threshold cannot be found.
Examples:
testFindMatch.cpp.

Definition at line 1045 of file vpPoseRansac.cpp.

References addPoint(), computePose(), getRansacInliers(), getRansacNbInliers(), listP, vpPoseException::notEnoughPointError, RANSAC, vpPoint::set_x(), vpPoint::set_y(), setRansacMaxTrials(), setRansacNbInliersToReachConsensus(), setRansacThreshold(), and vpERROR_TRACE.

◆ getCovarianceMatrix()

vpMatrix vpPose::getCovarianceMatrix ( ) const
inline

Get the covariance matrix computed in the Virtual Visual Servoing approach.

Warning
The compute covariance flag has to be true if you want to compute the covariance matrix.
See also
setCovarianceComputation

Definition at line 283 of file vpPose.h.

References vpTRACE.

Referenced by vpKeyPoint::computePose().

◆ getNbParallelRansacThreads()

int vpPose::getNbParallelRansacThreads ( ) const
inline

Get the number of threads for the parallel RANSAC implementation.

See also
setNbParallelRansacThreads

Definition at line 306 of file vpPose.h.

◆ getPoints()

std::vector<vpPoint> vpPose::getPoints ( ) const
inline

Get the vector of points.

Returns
The vector of points.

Definition at line 336 of file vpPose.h.

References vpColor::none.

◆ getRansacInlierIndex()

std::vector<unsigned int> vpPose::getRansacInlierIndex ( ) const
inline
Examples:
testPoseRansac2.cpp.

Definition at line 263 of file vpPose.h.

Referenced by vpKeyPoint::computePose().

◆ getRansacInliers()

std::vector<vpPoint> vpPose::getRansacInliers ( ) const
inline
Examples:
testPoseRansac.cpp, and testPoseRansac2.cpp.

Definition at line 264 of file vpPose.h.

Referenced by vpKeyPoint::computePose(), and findMatch().

◆ getRansacNbInliers()

unsigned int vpPose::getRansacNbInliers ( ) const
inline

Definition at line 262 of file vpPose.h.

Referenced by findMatch().

◆ getUseParallelRansac()

bool vpPose::getUseParallelRansac ( ) const
inline
Returns
True if the parallel RANSAC version should be used.
See also
setUseParallelRansac

Definition at line 322 of file vpPose.h.

◆ init()

void vpPose::init ( void  )

Basic initialisation that is called by the constructors.

Definition at line 62 of file vpPose.cpp.

References vpMatrix::clear(), lambda, listP, npt, PREFILTER_DUPLICATE_POINTS, and residual.

◆ poseDementhonNonPlan()

void vpPose::poseDementhonNonPlan ( vpHomogeneousMatrix cMo)

Compute the pose using Dementhon approach for non planar objects this is a direct implementation of the algorithm proposed by Dementhon and Davis in their 1995 paper [12].

Definition at line 60 of file vpPoseDementhon.cpp.

References vpColVector::cross(), vpException::divideByZeroError, vpPoint::get_oX(), vpPoint::get_oY(), vpPoint::get_oZ(), listP, vpColVector::normalize(), npt, vpMatrix::pseudoInverse(), vpColVector::resize(), vpPoint::set_oX(), vpPoint::set_oY(), vpPoint::set_oZ(), vpColVector::sumSquare(), and vpMatrix::t().

Referenced by computePose().

◆ poseDementhonPlan()

void vpPose::poseDementhonPlan ( vpHomogeneousMatrix cMo)

Compute the pose using Dementhon approach for planar objects this is a direct implementation of the algorithm proposed by Dementhon in his PhD.

Author
Francois Chaumette (simplified by Eric Marchand)

Definition at line 427 of file vpPoseDementhon.cpp.

References calculArbreDementhon(), computeResidualDementhon(), vpColVector::dotProd(), vpPoint::get_oX(), vpPoint::get_oY(), vpPoint::get_oZ(), vpMatrix::getCol(), vpArray2D< Type >::getCols(), vpArray2D< Type >::getRows(), listP, npt, vpArray2D< Type >::resize(), vpPoint::set_oX(), vpPoint::set_oY(), vpPoint::set_oZ(), vpColVector::sumSquare(), vpMatrix::svd(), vpColVector::t(), vpMatrix::t(), and vpERROR_TRACE.

Referenced by computePose().

◆ poseFromRectangle()

double vpPose::poseFromRectangle ( vpPoint p1,
vpPoint p2,
vpPoint p3,
vpPoint p4,
double  lx,
vpCameraParameters cam,
vpHomogeneousMatrix cMo 
)
static

Carries out the camera pose the image of a rectangle and the intrinsec parameters, the length on x axis is known but the proprtion of the rectangle are unknown.

This method is taken from "Markerless Tracking using Planar Structures in the Scene" by Gilles Simon. The idea is to compute the homography H giving the image point of the rectangle by associating them with the coordinates (0,0)(1,0)(1,1/s)(0,1/s) (the rectangle is on the Z=0 plane). If K is the intrinsec parameters matrix, we have s = ||Kh1||/ ||Kh2||. s gives us the proportion of the rectangle

Parameters
p1,p2,p3,p4the image of the corners of the rectangle (respectively the image of (0,0),(lx,0),(lx,lx/s) and (0,lx/s)) (input)
camthe camera used (input)
lxthe rectangle size on the x axis (input)
cMothe camera pose (output)
Returns
int : OK if no pb occurs

Definition at line 591 of file vpPose.cpp.

References addPoint(), computePose(), DEMENTHON_LOWE, vpMatrix::eye(), vpCameraParameters::get_K(), vpPoint::get_x(), vpPoint::get_y(), vpMatrix::getCol(), vpHomography::HLM(), vpMatrix::pseudoInverse(), vpPoint::setWorldCoordinates(), and vpColVector::sumSquare().

◆ poseLagrangeNonPlan()

◆ poseLagrangePlan()

void vpPose::poseLagrangePlan ( vpHomogeneousMatrix cMo,
const int  coplanar_plane_type = 0 
)

Compute the pose of a planar object using Lagrange approach.

Parameters
cMo: Estimated pose. No initialisation is requested to estimate cMo.
coplanar_plane_type: Type of coplanar plane: 1: if plane x=cst 2: if plane y=cst 3: if plane z=cst 0: any other plane

Definition at line 260 of file vpPoseLagrange.cpp.

References vpException::divideByZeroError, vpPoint::get_oX(), vpPoint::get_oY(), vpPoint::get_oZ(), vpPoint::get_x(), vpPoint::get_y(), listP, npt, and vpColVector::sumSquare().

Referenced by computePose().

◆ poseLowe()

void vpPose::poseLowe ( vpHomogeneousMatrix cMo)

Compute the pose using the Lowe non linear approach it consider the minimization of a residual using the levenberg marquartd approach.

The approach has been proposed by D.G Lowe in 1992 paper [22].

Definition at line 262 of file vpPoseLowe.cpp.

References vpHomogeneousMatrix::extract(), vpPoint::get_oX(), vpPoint::get_oY(), vpPoint::get_oZ(), vpPoint::get_x(), vpPoint::get_y(), vpHomogeneousMatrix::insert(), and listP.

Referenced by computePose().

◆ poseRansac()

bool vpPose::poseRansac ( vpHomogeneousMatrix cMo,
bool(*)(vpHomogeneousMatrix *)  func = NULL 
)

Compute the pose using the Ransac approach.

Parameters
cMo: Computed pose
func: Pointer to a function that takes in parameter a vpHomogeneousMatrix and returns true if the pose check is OK or false otherwise
Returns
True if we found at least 4 points with a reprojection error below ransacThreshold.

Definition at line 440 of file vpPoseRansac.cpp.

References addPoint(), computePose(), computeResidual(), DEMENTHON, vpPoint::get_x(), vpPoint::get_y(), vpMath::isNaN(), LAGRANGE, vpPoseException::notInitializedError, npt, setCovarianceComputation(), vpPoint::setWorldCoordinates(), vpArray2D< Type >::size(), vpMath::sqr(), vpForwardProjection::track(), and VIRTUAL_VS.

Referenced by computePose().

◆ poseVirtualVS()

void vpPose::poseVirtualVS ( vpHomogeneousMatrix cMo)

◆ poseVirtualVSrobust()

◆ printPoint()

void vpPose::printPoint ( )

Definition at line 495 of file vpPose.cpp.

References vpTracker::cP, listP, vpForwardProjection::oP, vpTracker::p, and vpColVector::t().

◆ setCovarianceComputation()

void vpPose::setCovarianceComputation ( const bool &  flag)
inline

Set if the covariance matrix has to be computed in the Virtual Visual Servoing approach.

Parameters
flag: True if the covariance has to be computed, false otherwise.

Definition at line 272 of file vpPose.h.

Referenced by vpKeyPoint::computePose(), and poseRansac().

◆ setDistanceToPlaneForCoplanarityTest()

void vpPose::setDistanceToPlaneForCoplanarityTest ( double  d)

Definition at line 159 of file vpPose.cpp.

◆ setLambda()

void vpPose::setLambda ( double  a)
inline

Definition at line 240 of file vpPose.h.

◆ setNbParallelRansacThreads()

void vpPose::setNbParallelRansacThreads ( const int  nb)
inline

Set the number of threads for the parallel RANSAC implementation.

Note
You have to enable the parallel version with setUseParallelRansac(). If the number of threads is 0, the number of threads to use is automatically determined with OpenMP.
See also
setUseParallelRansac
Examples:
testPoseRansac2.cpp.

Definition at line 315 of file vpPose.h.

◆ setRansacFilterFlags()

void vpPose::setRansacFilterFlags ( const int  flags)
inline

Set RANSAC filtering flags.

Parameters
flags: Flags to use, e.g. setRansacFilterFlags(PREFILTER_DUPLICATE_POINTS + CHECK_DEGENERATE_POINTS).
See also
FILTERING_RANSAC_FLAGS
Examples:
testPoseRansac2.cpp.

Definition at line 299 of file vpPose.h.

◆ setRansacMaxTrials()

void vpPose::setRansacMaxTrials ( const int &  rM)
inline
Examples:
testKeyPoint-4.cpp, and testPoseRansac2.cpp.

Definition at line 261 of file vpPose.h.

Referenced by vpKeyPoint::computePose(), and findMatch().

◆ setRansacNbInliersToReachConsensus()

void vpPose::setRansacNbInliersToReachConsensus ( const unsigned int &  nbC)
inline

◆ setRansacThreshold()

void vpPose::setRansacThreshold ( const double &  t)
inline

◆ setUseParallelRansac()

void vpPose::setUseParallelRansac ( const bool  use)
inline

Set if parallel RANSAC version should be used or not.

Note
Need Pthread.
Examples:
testPoseRansac2.cpp.

Definition at line 329 of file vpPose.h.

◆ setVvsEpsilon()

void vpPose::setVvsEpsilon ( const double  eps)
inline

Definition at line 241 of file vpPose.h.

References vpException::badValue.

◆ setVvsIterMax()

void vpPose::setVvsIterMax ( int  nb)
inline

Definition at line 249 of file vpPose.h.

Member Data Documentation

◆ lambda

double vpPose::lambda
protected

parameters use for the virtual visual servoing approach

Definition at line 120 of file vpPose.h.

Referenced by init(), poseVirtualVS(), and poseVirtualVSrobust().

◆ listP

◆ npt

unsigned int vpPose::npt

◆ residual

double vpPose::residual

Residual in meter.

Definition at line 117 of file vpPose.h.

Referenced by init().