![]() |
Visual Servoing Platform
version 3.5.1 under development (2023-05-30)
|
#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 , DEMENTHON_LAGRANGE_VIRTUAL_VS } |
enum | RANSAC_FILTER_FLAGS { NO_FILTER , PREFILTER_DEGENERATE_POINTS , CHECK_DEGENERATE_POINTS } |
Public Member Functions | |
vpPose () | |
vpPose (const std::vector< vpPoint > &lP) | |
virtual | ~vpPose () |
void | addPoint (const vpPoint &P) |
void | addPoints (const std::vector< vpPoint > &lP) |
void | clearPoint () |
bool | computePose (vpPoseMethodType method, vpHomogeneousMatrix &cMo, bool(*func)(const vpHomogeneousMatrix &)=NULL) |
bool | computePoseDementhonLagrangeVVS (vpHomogeneousMatrix &cMo) |
double | computeResidual (const vpHomogeneousMatrix &cMo) const |
bool | coplanar (int &coplanar_plane_type, double *p_a=NULL, double *p_b=NULL, double *p_c=NULL, double *p_d=NULL) |
void | displayModel (vpImage< unsigned char > &I, vpCameraParameters &cam, vpColor col=vpColor::none) |
void | displayModel (vpImage< vpRGBa > &I, vpCameraParameters &cam, vpColor col=vpColor::none) |
void | poseDementhonPlan (vpHomogeneousMatrix &cMo) |
void | poseDementhonNonPlan (vpHomogeneousMatrix &cMo) |
void | poseLagrangePlan (vpHomogeneousMatrix &cMo, bool *p_isPlan=NULL, double *p_a=NULL, double *p_b=NULL, double *p_c=NULL, double *p_d=NULL) |
void | poseLagrangeNonPlan (vpHomogeneousMatrix &cMo) |
void | poseLowe (vpHomogeneousMatrix &cMo) |
bool | poseRansac (vpHomogeneousMatrix &cMo, bool(*func)(const vpHomogeneousMatrix &)=NULL) |
void | poseVirtualVSrobust (vpHomogeneousMatrix &cMo) |
void | poseVirtualVS (vpHomogeneousMatrix &cMo) |
void | printPoint () |
void | setDementhonSvThreshold (const double &svThresh) |
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< vpPoint > | getRansacInliers () const |
void | setCovarianceComputation (const bool &flag) |
vpMatrix | getCovarianceMatrix () const |
void | setRansacFilterFlag (const RANSAC_FILTER_FLAGS &flag) |
int | getNbParallelRansacThreads () const |
void | setNbParallelRansacThreads (int nb) |
bool | getUseParallelRansac () const |
void | setUseParallelRansac (bool use) |
std::vector< vpPoint > | getPoints () const |
Deprecated functions | |
vp_deprecated void | init () |
Static Public Member Functions | |
static bool | computePlanarObjectPoseFromRGBD (const vpImage< float > &depthMap, const std::vector< vpImagePoint > &corners, const vpCameraParameters &colorIntrinsics, const std::vector< vpPoint > &point3d, vpHomogeneousMatrix &cMo, double *confidence_index=NULL) |
static bool | computePlanarObjectPoseFromRGBD (const vpImage< float > &depthMap, const std::vector< std::vector< vpImagePoint > > &corners, const vpCameraParameters &colorIntrinsics, const std::vector< std::vector< vpPoint > > &point3d, vpHomogeneousMatrix &cMo, double *confidence_index=NULL, bool coplanar_points=true) |
static int | computeRansacIterations (double probability, double epsilon, const int sampleSize=4, int maxIterations=2000) |
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 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, bool useParallelRansac=true, unsigned int nthreads=0, bool(*func)(const vpHomogeneousMatrix &)=NULL) |
static double | poseFromRectangle (vpPoint &p1, vpPoint &p2, vpPoint &p3, vpPoint &p4, double lx, vpCameraParameters &cam, vpHomogeneousMatrix &cMo) |
template<typename DataId > | |
static std::optional< vpHomogeneousMatrix > | computePlanarObjectPoseWithAtLeast3Points (const vpPlane &plane_in_camera_frame, const std::map< DataId, vpPoint > &pts, const std::map< DataId, vpImagePoint > &ips, const vpCameraParameters &camera_intrinsics, std::optional< vpHomogeneousMatrix > cMo_init=std::nullopt, bool enable_vvs=true) |
static std::optional< vpHomogeneousMatrix > | poseVirtualVSWithDepth (const std::vector< vpPoint > &points, const vpHomogeneousMatrix &cMo) |
Public Attributes | |
unsigned int | npt |
std::list< vpPoint > | listP |
double | residual |
Protected Member Functions | |
double | computeResidualDementhon (const vpHomogeneousMatrix &cMo) |
int | calculArbreDementhon (vpMatrix &b, vpColVector &U, vpHomogeneousMatrix &cMo) |
Protected Attributes | |
double | lambda |
double | dementhonSvThresh |
Class used for pose computation from N points (pose from point only). Some of the algorithms implemented in this class are described in [33].
To see how to use this class you can follow the Tutorial: Pose estimation from points.
Methods that could be used to estimate the pose from points.
vpPose::vpPose | ( | ) |
Default constructor.
Definition at line 97 of file vpPose.cpp.
vpPose::vpPose | ( | const std::vector< vpPoint > & | lP | ) |
Definition at line 106 of file vpPose.cpp.
|
virtual |
Destructor that deletes the array of point (freed the memory).
Definition at line 119 of file vpPose.cpp.
References listP.
void vpPose::addPoint | ( | const vpPoint & | newP | ) |
Add a new point in the array of points.
newP | : New point to add in the array of point. |
Definition at line 149 of file vpPose.cpp.
Referenced by vpKeyPoint::computePose(), findMatch(), vpMbTracker::initClick(), vpMbTracker::initFromPoints(), poseFromRectangle(), and poseRansac().
void vpPose::addPoints | ( | const std::vector< vpPoint > & | lP | ) |
Add (append) a list of points in the array of points.
lP | : List of points to add (append). |
Definition at line 164 of file vpPose.cpp.
Referenced by computePlanarObjectPoseFromRGBD().
|
protected |
Return 0 if success, -1 if failure.
Definition at line 301 of file vpPoseDementhon.cpp.
References computeResidualDementhon(), vpMath::deg(), vpHomogeneousMatrix::extract(), and npt.
Referenced by poseDementhonPlan().
void vpPose::clearPoint | ( | ) |
Delete the array of point
Definition at line 134 of file vpPose.cpp.
Referenced by vpMbTracker::initClick().
|
static |
Compute the pose of multiple planar object from corresponding 2D-3D point coordinates and depth map. Depth map is here used to estimate the 3D plane of each planar object.
This implementation is reserved for the case where multiple planar objects are considered and where an object like robot arm obstruct the view and interfere with plane equation estimation for each single object. Therefore this function considers only the 3D point inside the visible tags.
[in] | depthMap | : Depth map aligned to the color image from where corners are extracted. |
[in] | corners | : Vector where each element is a vector containing 2D pixel coordinates of the 2D polygon that defines the object edges in an image. |
[in] | colorIntrinsics | : Camera parameters used to convert corners from pixel to meters. |
[in] | point3d | : Vector where each element is a vector containing 3D points coordinates of the 3D polygon that defines the model of the planar object. |
[out] | cMo | : Computed pose. |
[out] | confidence_index | : Confidence index in range [0, 1]. When values are close to 1, it means that pose estimation confidence is high. Values close to 0 indicate that pose is not well estimated. This confidence index corresponds to the product between the normalized number of depth data covering the tag and the normalized M-estimator weights returned by the robust estimation of the tag 3D plane. |
[in] | coplanar_points | : There are cases where all the planar objects are not in the same plane. In order to differentiate these cases, this parameter will be used to compute the common plane for all objects if its value is true and compute the plane invidually for each object otherwise. |
Definition at line 291 of file vpPoseRGBD.cpp.
References addPoints(), vpHomogeneousMatrix::compute3d3dTransformation(), computePose(), vpPlane::computeZ(), vpPixelMeterConversion::convertPoint(), vpException::fatalError, vpImagePoint::get_u(), vpImagePoint::get_v(), vpPolygon::getArea(), vpRect::getBottom(), vpPolygon::getBoundingBox(), vpImage< Type >::getHeight(), vpRect::getLeft(), vpRect::getRight(), vpRect::getTop(), vpImage< Type >::getWidth(), vpImage< Type >::insert(), vpPolygon::isInside(), vpHomogeneousMatrix::isValid(), and VIRTUAL_VS.
|
static |
Compute the pose of a planar object from corresponding 2D-3D point coordinates and depth map. Depth map is here used to estimate the 3D plane of the object.
[in] | depthMap | : Depth map aligned to the color image from where corners are extracted. |
[in] | corners | : Vector of 2D pixel coordinates of the object in an image. |
[in] | colorIntrinsics | : Camera parameters used to convert corners from pixel to meters. |
[in] | point3d | : Vector of 3D points corresponding to the model of the planar object. |
[out] | cMo | : Computed pose. |
[out] | confidence_index | : Confidence index in range [0, 1]. When values are close to 1, it means that pose estimation confidence is high. Values close to 0 indicate that pose is not well estimated. This confidence index corresponds to the product between the normalized number of depth data covering the tag and the normalized M-estimator weights returned by the robust estimation of the tag 3D plane. |
The following code snippet implemented in tutorial-apriltag-detector-live-rgbd-realsense.cpp shows how to use this function to estimate the pose of an AprilTag using this method:
Definition at line 169 of file vpPoseRGBD.cpp.
References addPoints(), vpHomogeneousMatrix::compute3d3dTransformation(), computePose(), vpPlane::computeZ(), vpPixelMeterConversion::convertPoint(), vpException::fatalError, vpImagePoint::get_u(), vpImagePoint::get_v(), vpPolygon::getArea(), vpRect::getBottom(), vpPolygon::getBoundingBox(), vpImage< Type >::getHeight(), vpRect::getLeft(), vpRect::getRight(), vpRect::getTop(), vpImage< Type >::getWidth(), vpPolygon::isInside(), vpHomogeneousMatrix::isValid(), and VIRTUAL_VS.
|
inlinestatic |
Compute the pose of a planar object from corresponding 2D-3D point coordinates and plane equation. Here at least 3 points are required.
[in] | plane_in_camera_frame | : Plane in camera frame. |
[in] | pts | : Object points. |
[in] | ips | : Points in the image. |
[in] | camera_intrinsics | : Camera parameters. |
[in] | cMo_init | : Camera to object frame transformation used as initialization. When set to std::nullopt , this transformation is computed internally. |
[in] | enable_vvs | : When true, refine estimated pose using a virtual visual servoing scheme. |
Definition at line 392 of file vpPose.h.
References vpHomogeneousMatrix::compute3d3dTransformation(), vpPlane::computeZ(), vpPixelMeterConversion::convertPoint(), vpException::fatalError, vpHomogeneousMatrix::isValid(), poseVirtualVSWithDepth(), vpPoint::set_x(), vpPoint::set_y(), and vpPoint::set_Z().
bool vpPose::computePose | ( | vpPoseMethodType | method, |
vpHomogeneousMatrix & | cMo, | ||
bool(*)(const vpHomogeneousMatrix &) | func = NULL |
||
) |
Compute the pose according to the desired method which are:
Definition at line 414 of file vpPose.cpp.
References computePoseDementhonLagrangeVVS(), coplanar(), DEMENTHON, DEMENTHON_LAGRANGE_VIRTUAL_VS, DEMENTHON_LOWE, DEMENTHON_VIRTUAL_VS, LAGRANGE, LAGRANGE_LOWE, LAGRANGE_VIRTUAL_VS, LOWE, vpPoseException::notEnoughPointError, npt, poseDementhonNonPlan(), poseDementhonPlan(), poseLagrangeNonPlan(), poseLagrangePlan(), poseLowe(), poseRansac(), poseVirtualVS(), RANSAC, and VIRTUAL_VS.
Referenced by computePlanarObjectPoseFromRGBD(), vpKeyPoint::computePose(), computePoseDementhonLagrangeVVS(), findMatch(), vpMbTracker::initClick(), vpMbTracker::initFromPoints(), poseFromRectangle(), and poseRansac().
bool vpPose::computePoseDementhonLagrangeVVS | ( | vpHomogeneousMatrix & | cMo | ) |
Method that first computes the pose cMo using the linear approaches of Dementhon and Lagrange and then uses the non-linear Virtual Visual Servoing approach to affine the pose which had the lowest residual.
cMo | the pose of the object with regard to the camera. |
Definition at line 525 of file vpPose.cpp.
References computePose(), computeResidual(), coplanar(), poseDementhonNonPlan(), poseDementhonPlan(), poseLagrangeNonPlan(), poseLagrangePlan(), and VIRTUAL_VS.
Referenced by computePose().
|
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.
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. |
maxIterations
if it exceeds the desired upper bound or INT_MAX if maxIterations=-1. Definition at line 525 of file vpPoseRansac.cpp.
References vpMath::nul().
double vpPose::computeResidual | ( | const vpHomogeneousMatrix & | cMo | ) | const |
Compute and return the sum of squared residuals expressed in meter^2 for the pose matrix cMo.
cMo | : Input pose. The matrix that defines the pose to be tested. |
Definition at line 373 of file vpPose.cpp.
References vpPoint::get_x(), vpPoint::get_y(), listP, vpMath::sqr(), and vpForwardProjection::track().
Referenced by computePoseDementhonLagrangeVVS().
|
protected |
Compute and return the residual corresponding to the sum of squared residuals in meter^2 for the pose matrix cMo.
cMo | : the matrix that defines the pose to be tested. |
Definition at line 591 of file vpPoseDementhon.cpp.
References npt, and vpMath::sqr().
Referenced by calculArbreDementhon(), poseDementhonNonPlan(), and poseDementhonPlan().
bool vpPose::coplanar | ( | int & | coplanar_plane_type, |
double * | p_a = NULL , |
||
double * | p_b = NULL , |
||
double * | p_c = NULL , |
||
double * | p_d = NULL |
||
) |
Test the coplanarity of the set of points
coplanar_plane_type | 1: if plane x=cst 2: if plane y=cst 3: if plane z=cst 4: if the points are collinear. 0: any other plane |
p_a | if different from null, it will be set to equal the a coefficient of the potential plan. |
p_b | if different from null, it will be set to equal the b coefficient of the potential plan. |
p_c | if different from null, it will be set to equal the c coefficient of the potential plan. |
p_d | if different from null, it will be set to equal the d coefficient of the potential plan. |
Definition at line 196 of file vpPose.cpp.
References vpColVector::crossProd(), vpPoint::get_oX(), vpPoint::get_oY(), vpPoint::get_oZ(), vpPoseException::notEnoughPointError, npt, vpMath::sqr(), vpColVector::sumSquare(), vpDEBUG_TRACE, and vpERROR_TRACE.
Referenced by computePose(), computePoseDementhonLagrangeVVS(), and poseLagrangePlan().
|
static |
Display in the image I the pose represented by its homogenous transformation cMo as a 3 axis frame.
I | Image where the pose is displayed in overlay. |
cMo | Considered pose to display. |
cam | Camera parameters associated to image I. |
size | length in meter of the axis that will be displayed |
col | Color 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 655 of file vpPose.cpp.
References vpDisplay::displayFrame().
|
static |
Display in the image I the pose represented by its homogenous transformation cMo as a 3 axis frame.
I | Image where the pose is displayed in overlay. |
cMo | Considered pose to display. |
cam | Camera parameters associated to image I. |
size | length in meter of the axis that will be displayed |
col | Color 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 670 of file vpPose.cpp.
References vpDisplay::displayFrame().
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 679 of file vpPose.cpp.
References vpMeterPixelConversion::convertPoint(), vpDisplay::displayCross(), listP, and vpTracker::p.
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 697 of file vpPose.cpp.
References vpMeterPixelConversion::convertPoint(), vpDisplay::displayCross(), listP, and vpTracker::p.
|
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.
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. |
useParallelRansac | : If true, use parallel RANSAC version (if C++11 is available). |
nthreads | : Number of threads to use, if 0 the number of CPU threads will be determined. |
func | : Pointer to a function that takes in parameter a vpHomogeneousMatrix and returns true if the pose check is OK or false otherwise |
Definition at line 593 of file vpPoseRansac.cpp.
References addPoint(), CHECK_DEGENERATE_POINTS, computePose(), getRansacInliers(), getRansacNbInliers(), listP, vpPoseException::notEnoughPointError, RANSAC, vpPoint::set_x(), vpPoint::set_y(), setNbParallelRansacThreads(), setRansacFilterFlag(), setRansacMaxTrials(), setRansacNbInliersToReachConsensus(), setRansacThreshold(), setUseParallelRansac(), and vpERROR_TRACE.
|
inline |
Get the covariance matrix computed in the Virtual Visual Servoing approach.
Definition at line 282 of file vpPose.h.
References vpTRACE.
Referenced by vpKeyPoint::computePose().
|
inline |
Get the number of threads for the parallel RANSAC implementation.
|
inline |
|
inline |
Definition at line 262 of file vpPose.h.
Referenced by vpKeyPoint::computePose().
|
inline |
Definition at line 263 of file vpPose.h.
Referenced by vpKeyPoint::computePose(), and findMatch().
|
inline |
Definition at line 261 of file vpPose.h.
Referenced by findMatch().
|
inline |
void vpPose::init | ( | void | ) |
Definition at line 64 of file vpPose.cpp.
References vpMatrix::clear(), lambda, listP, NO_FILTER, npt, and residual.
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 [14].
Definition at line 108 of file vpPoseDementhon.cpp.
References computeResidualDementhon(), vpMath::deg(), dementhonSvThresh, vpHomogeneousMatrix::extract(), vpException::fatalError, vpPoint::get_oX(), vpPoint::get_oY(), vpPoint::get_oZ(), listP, npt, vpMatrix::pseudoInverse(), vpPoint::set_oX(), vpPoint::set_oY(), and vpPoint::set_oZ().
Referenced by computePose(), and computePoseDementhonLagrangeVVS().
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.
Definition at line 429 of file vpPoseDementhon.cpp.
References calculArbreDementhon(), computeResidualDementhon(), vpMath::deg(), dementhonSvThresh, vpHomogeneousMatrix::extract(), vpException::fatalError, vpPoint::get_oX(), vpPoint::get_oY(), vpPoint::get_oZ(), listP, npt, vpMatrix::pseudoInverse(), vpPoint::set_oX(), vpPoint::set_oY(), vpPoint::set_oZ(), and vpColVector::t().
Referenced by computePose(), and computePoseDementhonLagrangeVVS().
|
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
p1,p2,p3,p4 | the image of the corners of the rectangle (respectively the image of (0,0),(lx,0),(lx,lx/s) and (0,lx/s)) (input) |
cam | the camera used (input) |
lx | the rectangle size on the x axis (input) |
cMo | the camera pose (output) |
Definition at line 730 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().
void vpPose::poseLagrangeNonPlan | ( | vpHomogeneousMatrix & | cMo | ) |
Definition at line 475 of file vpPoseLagrange.cpp.
References vpException::dimensionError, 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(), and computePoseDementhonLagrangeVVS().
void vpPose::poseLagrangePlan | ( | vpHomogeneousMatrix & | cMo, |
bool * | p_isPlan = NULL , |
||
double * | p_a = NULL , |
||
double * | p_b = NULL , |
||
double * | p_c = NULL , |
||
double * | p_d = NULL |
||
) |
Compute the pose of a planar object using Lagrange approach.
cMo | : Estimated pose. No initialisation is requested to estimate cMo. |
p_isPlan | : if different from NULL, indicates if the object is planar or not. |
p_a | : if different from NULL, the a coefficient of the plan formed by the points. |
p_b | : if different from NULL, the b coefficient of the plan formed by the points. |
p_c | : if different from NULL, the c coefficient of the plan formed by the points. |
p_d | : if different from NULL, the d coefficient of the plan formed by the points. |
Definition at line 261 of file vpPoseLagrange.cpp.
References coplanar(), vpColVector::crossProd(), vpException::divideByZeroError, vpException::fatalError, vpPoint::get_oX(), vpPoint::get_oY(), vpPoint::get_oZ(), vpPoint::get_x(), vpPoint::get_y(), listP, npt, and vpColVector::sumSquare().
Referenced by computePose(), and computePoseDementhonLagrangeVVS().
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 [25].
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(), listP, and npt.
Referenced by computePose().
bool vpPose::poseRansac | ( | vpHomogeneousMatrix & | cMo, |
bool(*)(const vpHomogeneousMatrix &) | func = NULL |
||
) |
Compute the pose using the Ransac approach.
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 |
Definition at line 299 of file vpPoseRansac.cpp.
References addPoint(), CHECK_DEGENERATE_POINTS, computePose(), DEMENTHON_LAGRANGE_VIRTUAL_VS, listP, vpPoseException::notInitializedError, PREFILTER_DEGENERATE_POINTS, and setCovarianceComputation().
Referenced by computePose().
void vpPose::poseVirtualVS | ( | vpHomogeneousMatrix & | cMo | ) |
Compute the pose using virtual visual servoing approach.
This approach is described in [30].
Definition at line 53 of file vpPoseVirtualVisualServoing.cpp.
References vpMatrix::computeCovarianceMatrixVVS(), vpExponentialMap::direct(), vpPoint::get_x(), vpPoint::get_y(), vpPoint::get_Z(), vpHomogeneousMatrix::inverse(), lambda, listP, vpColVector::sumSquare(), vpForwardProjection::track(), and vpERROR_TRACE.
Referenced by computePose().
void vpPose::poseVirtualVSrobust | ( | vpHomogeneousMatrix & | cMo | ) |
Compute the pose using virtual visual servoing approach and a robust control law.
This approach is described in [8].
Definition at line 158 of file vpPoseVirtualVisualServoing.cpp.
References vpMatrix::computeCovarianceMatrix(), vpExponentialMap::direct(), vpPoint::get_x(), vpPoint::get_y(), vpPoint::get_Z(), vpArray2D< Type >::getRows(), vpHomogeneousMatrix::inverse(), lambda, listP, vpRobust::MEstimator(), vpColVector::resize(), vpArray2D< Type >::resize(), vpRobust::setMinMedianAbsoluteDeviation(), vpMath::sqr(), vpColVector::sumSquare(), vpForwardProjection::track(), vpRobust::TUKEY, and vpERROR_TRACE.
|
static |
Compute the pose by virtual visual servoing using x,y and Z point coordinates as visual features. We recall that x,y are the coordinates of a point in the image plane which are obtained by perspective projection, while Z is the 3D coordinate of the point along the camera frame Z-axis.
[in] | cMo | : Pose initial value used to initialize the non linear pose estimation algorithm. |
[in] | points | : A vector of points with [x,y,Z] values used as visual features. |
Definition at line 276 of file vpPoseVirtualVisualServoing.cpp.
References vpExponentialMap::direct(), vpHomogeneousMatrix::inverse(), lambda, vpMath::sqr(), and vpColVector::sumSquare().
Referenced by computePlanarObjectPoseWithAtLeast3Points().
void vpPose::printPoint | ( | ) |
Definition at line 634 of file vpPose.cpp.
References vpTracker::cP, listP, vpForwardProjection::oP, vpTracker::p, and vpColVector::t().
|
inline |
Set if the covariance matrix has to be computed in the Virtual Visual Servoing approach.
flag | : True if the covariance has to be computed, false otherwise. |
Definition at line 271 of file vpPose.h.
Referenced by vpKeyPoint::computePose(), and poseRansac().
void vpPose::setDementhonSvThreshold | ( | const double & | svThresh | ) |
Definition at line 173 of file vpPose.cpp.
References vpException::badValue, and dementhonSvThresh.
void vpPose::setDistanceToPlaneForCoplanarityTest | ( | double | d | ) |
Definition at line 171 of file vpPose.cpp.
|
inline |
Set the number of threads for the parallel RANSAC implementation.
Definition at line 319 of file vpPose.h.
Referenced by vpKeyPoint::computePose(), and findMatch().
|
inline |
Set RANSAC filter flag.
flag | : RANSAC flag to use to prefilter or perform degenerate configuration check. |
Definition at line 302 of file vpPose.h.
Referenced by vpKeyPoint::computePose(), and findMatch().
|
inline |
Definition at line 260 of file vpPose.h.
Referenced by vpKeyPoint::computePose(), and findMatch().
|
inline |
Definition at line 250 of file vpPose.h.
Referenced by vpKeyPoint::computePose(), and findMatch().
|
inline |
Definition at line 251 of file vpPose.h.
References vpException::badValue.
Referenced by vpKeyPoint::computePose(), and findMatch().
|
inline |
Set if parallel RANSAC version should be used or not (only if C++11).
Definition at line 333 of file vpPose.h.
Referenced by vpKeyPoint::computePose(), and findMatch().
|
inline |
Definition at line 240 of file vpPose.h.
References vpException::badValue.
|
protected |
SVD threshold use for the pseudo-inverse computation in poseDementhonPlan.
Definition at line 207 of file vpPose.h.
Referenced by poseDementhonNonPlan(), poseDementhonPlan(), and setDementhonSvThreshold().
|
protected |
parameters use for the virtual visual servoing approach
Definition at line 127 of file vpPose.h.
Referenced by init(), poseVirtualVS(), poseVirtualVSrobust(), and poseVirtualVSWithDepth().
std::list<vpPoint> vpPose::listP |
Array of point (use here class vpPoint)
Definition at line 122 of file vpPose.h.
Referenced by addPoint(), addPoints(), clearPoint(), computeResidual(), displayModel(), findMatch(), init(), poseDementhonNonPlan(), poseDementhonPlan(), poseLagrangeNonPlan(), poseLagrangePlan(), poseLowe(), poseRansac(), poseVirtualVS(), poseVirtualVSrobust(), printPoint(), and ~vpPose().
unsigned int vpPose::npt |
Number of point used in pose computation.
Definition at line 121 of file vpPose.h.
Referenced by addPoint(), addPoints(), calculArbreDementhon(), clearPoint(), computePose(), computeResidualDementhon(), coplanar(), init(), poseDementhonNonPlan(), poseDementhonPlan(), poseLagrangeNonPlan(), poseLagrangePlan(), and poseLowe().