Visual Servoing Platform
version 3.6.1 under development (2025-02-11)
|
#include <visp3/rbt/vpRBDenseDepthTracker.h>
Classes | |
struct | vpDepthPoint |
Public Member Functions | |
vpRBDenseDepthTracker () | |
virtual | ~vpRBDenseDepthTracker ()=default |
bool | requiresRGB () const VP_OVERRIDE |
bool | requiresDepth () const VP_OVERRIDE |
bool | requiresSilhouetteCandidates () const VP_OVERRIDE |
unsigned | getNumFeatures () const |
bool | vvsHasConverged () const |
void | setTrackerWeight (double weight) |
virtual vpMatrix | getLTL () const |
virtual vpColVector | getLTR () const |
const vpColVector & | getWeightedError () const |
Settings | |
unsigned int | getStep () const |
void | setStep (unsigned int step) |
bool | shouldUseMask () const |
void | setShouldUseMask (bool useMask) |
float | getMinimumMaskConfidence () const |
void | setMinimumMaskConfidence (float confidence) |
Display | |
bool | featuresShouldBeDisplayed () const |
void | setFeaturesShouldBeDisplayed (bool enableDisplay) |
Covariance computation | |
virtual const vpMatrix | getCovariance () const |
virtual void | updateCovariance (const double lambda) |
Static Public Member Functions | |
static void | computeJTR (const vpMatrix &interaction, const vpColVector &error, vpColVector &JTR) |
static vpMatrix | computeCovarianceMatrix (const vpMatrix &A, const vpColVector &b, const vpMatrix &W) |
A tracker based on dense depth point-plane alignment.
Definition at line 67 of file vpRBDenseDepthTracker.h.
|
inline |
Definition at line 71 of file vpRBDenseDepthTracker.h.
|
virtualdefault |
|
staticinherited |
Definition at line 76 of file vpRBFeatureTracker.cpp.
References vpArray2D< Type >::getRows(), vpColVector::t(), and vpMatrix::t().
Referenced by vpRBFeatureTracker::updateCovariance().
|
staticinherited |
Definition at line 54 of file vpRBFeatureTracker.cpp.
References vpArray2D< Type >::data, vpArray2D< Type >::getCols(), vpArray2D< Type >::getRows(), vpMatrixException::incorrectMatrixSizeError, and vpColVector::resize().
Referenced by computeVVSIter(), and vpRBSilhouetteMeTracker::computeVVSIter().
|
virtual |
Implements vpRBFeatureTracker.
Definition at line 115 of file vpRBDenseDepthTracker.cpp.
References vpMatrix::AtA(), vpRBFeatureTracker::computeJTR(), vpRBDenseDepthTracker::vpDepthPoint::error(), vpHomogeneousMatrix::getRotationMatrix(), vpRBDenseDepthTracker::vpDepthPoint::interaction(), vpRBFeatureTracker::m_cov, vpRBFeatureTracker::m_covWeightDiag, m_depthPoints, vpRBFeatureTracker::m_error, vpRBFeatureTracker::m_L, vpRBFeatureTracker::m_LTL, vpRBFeatureTracker::m_LTR, vpRBFeatureTracker::m_numFeatures, m_robust, vpRBFeatureTracker::m_vvsConverged, vpRBFeatureTracker::m_weighted_error, vpRBFeatureTracker::m_weights, vpRobust::MEstimator(), vpRobust::TUKEY, and vpRBDenseDepthTracker::vpDepthPoint::update().
|
virtual |
Implements vpRBFeatureTracker.
Definition at line 154 of file vpRBDenseDepthTracker.cpp.
References vpDisplay::displayPoint(), m_depthPoints, vpRBFeatureTracker::m_weights, and vpRBDenseDepthTracker::vpDepthPoint::pixelPos.
|
virtual |
Extract features from the frame data and the current pose estimate.
Implements vpRBFeatureTracker.
Definition at line 55 of file vpRBDenseDepthTracker.cpp.
References vpRBRenderData::boundingBox, vpRBFeatureTrackerInput::cam, vpRBRenderData::cMo, vpPixelMeterConversion::convertPoint(), vpRBDenseDepthTracker::vpDepthPoint::currentPoint, vpRBRenderData::depth, vpRBFeatureTrackerInput::depth, vpRect::getArea(), vpRect::getBottom(), vpRect::getLeft(), vpRect::getRight(), vpHomogeneousMatrix::getRotationMatrix(), vpArray2D< Type >::getRows(), vpRect::getTop(), vpRBFeatureTrackerInput::hasMask(), vpHomogeneousMatrix::inverse(), vpRBFeatureTracker::m_cov, vpRBFeatureTracker::m_covWeightDiag, m_depthPoints, vpRBFeatureTracker::m_error, vpRBFeatureTracker::m_L, m_minMaskConfidence, vpRBFeatureTracker::m_numFeatures, m_step, m_useMask, vpRBFeatureTracker::m_weighted_error, vpRBFeatureTracker::m_weights, vpRBFeatureTrackerInput::mask, vpRBRenderData::normals, vpRBDenseDepthTracker::vpDepthPoint::objectNormal, vpRBDenseDepthTracker::vpDepthPoint::oP, vpRBDenseDepthTracker::vpDepthPoint::pixelPos, vpRBFeatureTrackerInput::renders, vpColVector::resize(), vpArray2D< Type >::resize(), and vpImagePoint::set_ij().
|
inlineinherited |
Definition at line 145 of file vpRBFeatureTracker.h.
|
inlinevirtualinherited |
Retrieve the 6 x 6 pose covariance matrix, computed from the weights associated to each feature.
The updateCovariance method should have been called before
Definition at line 168 of file vpRBFeatureTracker.h.
|
inlinevirtualinherited |
Get the left-side term of the Gauss-Newton optimization term.
Definition at line 195 of file vpRBFeatureTracker.h.
|
inlinevirtualinherited |
Get the right-side term of the Gauss-Newton optimization term.
Definition at line 200 of file vpRBFeatureTracker.h.
|
inline |
Returns the minimum mask confidence that a pixel linked to depth point should have if it should be kept during tracking.
This value is between 0 and 1
Definition at line 104 of file vpRBDenseDepthTracker.h.
|
inlineinherited |
Return the type of feature that is used by this tracker.
Get the number of features used to compute the pose update
Definition at line 76 of file vpRBFeatureTracker.h.
|
inline |
Definition at line 83 of file vpRBDenseDepthTracker.h.
|
inlinevirtual |
Get the importance of this tracker in the optimization step. The default computation is the following: , where is the weight defined by setTrackerWeight, and is the number of features.
Reimplemented from vpRBFeatureTracker.
Definition at line 124 of file vpRBDenseDepthTracker.h.
|
inlineinherited |
Get a weighted version of the error vector. This should not include the userVVSWeight, but may include reweighting to remove outliers, occlusions, etc.
Definition at line 206 of file vpRBFeatureTracker.h.
|
inlinevirtual |
Implements vpRBFeatureTracker.
Definition at line 128 of file vpRBDenseDepthTracker.h.
|
inlinevirtual |
Reimplemented from vpRBFeatureTracker.
Definition at line 181 of file vpRBDenseDepthTracker.h.
References vpRBFeatureTracker::loadJsonConfiguration().
|
inlinevirtual |
Method called after the tracking iteration has finished.
Implements vpRBFeatureTracker.
Definition at line 122 of file vpRBDenseDepthTracker.h.
|
inlinevirtual |
Method called when starting a tracking iteration.
Implements vpRBFeatureTracker.
Definition at line 121 of file vpRBDenseDepthTracker.h.
|
inlinevirtual |
Whether this tracker requires depth image to extract features.
Implements vpRBFeatureTracker.
Definition at line 76 of file vpRBDenseDepthTracker.h.
|
inlinevirtual |
Whether this tracker requires RGB image to extract features.
Implements vpRBFeatureTracker.
Definition at line 75 of file vpRBDenseDepthTracker.h.
|
inlinevirtual |
Whether this tracker requires Silhouette candidates.
Implements vpRBFeatureTracker.
Definition at line 77 of file vpRBDenseDepthTracker.h.
|
inlineinherited |
Definition at line 146 of file vpRBFeatureTracker.h.
|
inline |
Definition at line 105 of file vpRBDenseDepthTracker.h.
References vpException::badValue.
|
inline |
Definition at line 97 of file vpRBDenseDepthTracker.h.
|
inline |
Definition at line 84 of file vpRBDenseDepthTracker.h.
References vpException::badValue.
|
inlineinherited |
Definition at line 190 of file vpRBFeatureTracker.h.
|
inline |
Returns whether the tracking algorithm should filter out points that are unlikely to be on the object according to the mask. If the mask is not computed beforehand, then it has no effect.
Definition at line 96 of file vpRBDenseDepthTracker.h.
|
inlinevirtual |
Track the features.
Implements vpRBFeatureTracker.
Definition at line 127 of file vpRBDenseDepthTracker.h.
|
virtualinherited |
Update the covariance matrix.
lambda | the visual servoing gain |
Reimplemented in vpRBSilhouetteCCDTracker.
Definition at line 47 of file vpRBFeatureTracker.cpp.
References vpRBFeatureTracker::computeCovarianceMatrix(), vpRBFeatureTracker::m_cov, vpRBFeatureTracker::m_covWeightDiag, vpRBFeatureTracker::m_error, and vpRBFeatureTracker::m_L.
|
inlineinherited |
Returns whether the tracker is considered as having converged to the desired pose.
Definition at line 182 of file vpRBFeatureTracker.h.
|
protectedinherited |
Right side of the Gauss Newton minimization.
Definition at line 225 of file vpRBFeatureTracker.h.
Referenced by computeVVSIter(), extractFeatures(), vpRBSilhouetteCCDTracker::initVVS(), and vpRBFeatureTracker::updateCovariance().
|
protectedinherited |
Covariance matrix.
Definition at line 226 of file vpRBFeatureTracker.h.
Referenced by computeVVSIter(), vpRBSilhouetteMeTracker::computeVVSIter(), extractFeatures(), vpRBSilhouetteMeTracker::initVVS(), and vpRBFeatureTracker::updateCovariance().
|
protected |
Definition at line 193 of file vpRBDenseDepthTracker.h.
Referenced by computeVVSIter(), display(), and extractFeatures().
|
protectedinherited |
Whether VVS has converged, should be updated every VVS iteration.
Definition at line 238 of file vpRBFeatureTracker.h.
Referenced by vpRBFeatureTracker::vpRBFeatureTracker().
|
protectedinherited |
Definition at line 228 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::computeErrorAndInteractionMatrix(), computeVVSIter(), vpRBSilhouetteMeTracker::computeVVSIter(), vpRBSilhouetteCCDTracker::display(), extractFeatures(), vpRBSilhouetteMeTracker::initVVS(), and vpRBFeatureTracker::updateCovariance().
|
protectedinherited |
Definition at line 222 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::computeErrorAndInteractionMatrix(), computeVVSIter(), vpRBSilhouetteMeTracker::computeVVSIter(), extractFeatures(), vpRBSilhouetteMeTracker::initVVS(), and vpRBFeatureTracker::updateCovariance().
|
protectedinherited |
Error jacobian (In VS terms, the interaction matrix)
Definition at line 223 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::computeErrorAndInteractionMatrix(), computeVVSIter(), and vpRBSilhouetteMeTracker::computeVVSIter().
|
protectedinherited |
Left side of the Gauss newton minimization.
Definition at line 224 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::computeErrorAndInteractionMatrix(), computeVVSIter(), and vpRBSilhouetteMeTracker::computeVVSIter().
|
protected |
Definition at line 197 of file vpRBDenseDepthTracker.h.
Referenced by extractFeatures().
|
protectedinherited |
Error weights.
Definition at line 233 of file vpRBFeatureTracker.h.
Referenced by computeVVSIter(), vpRBSilhouetteMeTracker::computeVVSIter(), extractFeatures(), vpRBSilhouetteMeTracker::extractFeatures(), vpRBSilhouetteCCDTracker::initVVS(), vpRBSilhouetteMeTracker::initVVS(), and vpRBFeatureTracker::vpRBFeatureTracker().
|
protected |
Definition at line 194 of file vpRBDenseDepthTracker.h.
Referenced by computeVVSIter().
|
protected |
Definition at line 195 of file vpRBDenseDepthTracker.h.
Referenced by extractFeatures().
|
protected |
Definition at line 196 of file vpRBDenseDepthTracker.h.
Referenced by extractFeatures().
|
protectedinherited |
Number of considered features.
Definition at line 234 of file vpRBFeatureTracker.h.
Referenced by vpRBFeatureTracker::vpRBFeatureTracker().
|
protectedinherited |
User-defined weight for this specific type of feature.
Definition at line 236 of file vpRBFeatureTracker.h.
Referenced by computeVVSIter(), vpRBSilhouetteCCDTracker::computeVVSIter(), vpRBSilhouetteMeTracker::computeVVSIter(), vpRBSilhouetteCCDTracker::initVVS(), vpRBSilhouetteMeTracker::initVVS(), and vpRBFeatureTracker::vpRBFeatureTracker().
|
protectedinherited |
Raw VS Error vector.
Definition at line 229 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::computeErrorAndInteractionMatrix(), computeVVSIter(), vpRBSilhouetteMeTracker::computeVVSIter(), extractFeatures(), and vpRBSilhouetteMeTracker::initVVS().
|
protectedinherited |
Weighted VS error.
Definition at line 230 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::computeErrorAndInteractionMatrix(), computeVVSIter(), vpRBSilhouetteMeTracker::computeVVSIter(), display(), vpRBSilhouetteCCDTracker::display(), extractFeatures(), vpRBSilhouetteCCDTracker::initVVS(), and vpRBSilhouetteMeTracker::initVVS().