Visual Servoing Platform
version 3.6.1 under development (2025-01-25)
|
#include <visp3/rbt/vpRBSilhouetteMeTracker.h>
Public Member Functions | |
vpRBSilhouetteMeTracker () | |
virtual | ~vpRBSilhouetteMeTracker ()=default |
bool | requiresRGB () const VP_OVERRIDE |
bool | requiresDepth () const VP_OVERRIDE |
bool | requiresSilhouetteCandidates () const VP_OVERRIDE |
void | setMovingEdge (const vpMe &me) |
void | onTrackingIterStart () VP_OVERRIDE |
void | onTrackingIterEnd () VP_OVERRIDE |
void | extractFeatures (const vpRBFeatureTrackerInput &frame, const vpRBFeatureTrackerInput &previousFrame, const vpHomogeneousMatrix &cMo) VP_OVERRIDE |
void | trackFeatures (const vpRBFeatureTrackerInput &frame, const vpRBFeatureTrackerInput &previousFrame, const vpHomogeneousMatrix &cMo) VP_OVERRIDE |
void | initVVS (const vpRBFeatureTrackerInput &frame, const vpRBFeatureTrackerInput &previousFrame, const vpHomogeneousMatrix &cMo) VP_OVERRIDE |
void | computeVVSIter (const vpRBFeatureTrackerInput &frame, const vpHomogeneousMatrix &cMo, unsigned int iteration) VP_OVERRIDE |
void | display (const vpCameraParameters &cam, const vpImage< unsigned char > &I, const vpImage< vpRGBa > &IRGB, const vpImage< unsigned char > &depth) const VP_OVERRIDE |
unsigned | getNumFeatures () const |
bool | vvsHasConverged () const |
virtual double | getVVSTrackerWeight () const |
void | setTrackerWeight (double weight) |
virtual vpMatrix | getLTL () const |
virtual vpColVector | getLTR () const |
const vpColVector & | getWeightedError () const |
Settings | |
const vpMe & | getMe () const |
vpMe & | getMe () |
unsigned int | getNumCandidates () const |
void | setNumCandidates (unsigned int candidates) |
double | getMinRobustThreshold () const |
void | setMinRobustThreshold (double threshold) |
bool | shouldUseMask () const |
void | setShouldUseMask (bool useMask) |
float | getMinimumMaskConfidence () const |
void | setMinimumMaskConfidence (float confidence) |
double | getSinglePointConvergenceThreshold () const |
void | setSinglePointConvergenceThreshold (double threshold) |
double | getGlobalConvergenceMinimumRatio () const |
void | setGlobalConvergenceMinimumRatio (double threshold) |
virtual void | loadJsonConfiguration (const nlohmann::json &j) VP_OVERRIDE |
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) |
Protected Attributes | |
vpMatrix | m_L |
vpMatrix | m_LTL |
vpColVector | m_LTR |
vpMatrix | m_cov |
vpColVector | m_covWeightDiag |
vpColVector | m_error |
vpColVector | m_weighted_error |
vpColVector | m_weights |
unsigned | m_numFeatures |
double | m_userVvsWeight |
bool | m_vvsConverged |
bool | m_enableDisplay |
Moving edge feature tracking from depth-extracted object contours.
Definition at line 48 of file vpRBSilhouetteMeTracker.h.
|
inline |
Definition at line 52 of file vpRBSilhouetteMeTracker.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 vpRBDenseDepthTracker::computeVVSIter(), and computeVVSIter().
|
virtual |
Implements vpRBFeatureTracker.
Definition at line 115 of file vpRBSilhouetteMeTracker.cpp.
References vpMatrix::AtA(), vpException::badValue, vpRBFeatureTrackerInput::cam, vpRBFeatureTracker::computeJTR(), vpRBSilhouetteControlPoint::computeMeInteractionMatrixError(), vpRBSilhouetteControlPoint::computeMeInteractionMatrixErrorMH(), vpCameraParameters::get_px(), vpRBSilhouetteControlPoint::isValid(), vpRBFeatureTracker::m_covWeightDiag, vpRBFeatureTracker::m_error, vpRBFeatureTracker::m_L, vpRBFeatureTracker::m_LTL, vpRBFeatureTracker::m_LTR, vpRBFeatureTracker::m_numFeatures, vpRBFeatureTracker::m_vvsConverged, vpRBFeatureTracker::m_weighted_error, vpRBFeatureTracker::m_weights, vpRobust::MEstimator(), vpRBSilhouetteControlPoint::siteIsValid(), vpArray2D< Type >::size(), and vpRobust::TUKEY.
|
virtual |
Implements vpRBFeatureTracker.
Definition at line 186 of file vpRBSilhouetteMeTracker.cpp.
References vpMeSite::display().
|
virtual |
Extract the geometric features from the list of collected silhouette points.
Implements vpRBFeatureTracker.
Definition at line 40 of file vpRBSilhouetteMeTracker.cpp.
References vpException::badValue, vpRBSilhouetteControlPoint::buildPoint(), vpRBFeatureTrackerInput::cam, vpRBRenderData::cMo, vpCameraParameters::get_px(), vpHomogeneousMatrix::getRotationMatrix(), vpImage< Type >::getSize(), vpRBFeatureTrackerInput::hasMask(), vpRBFeatureTrackerInput::I, vpRBSilhouettePoint::i, vpRBSilhouetteControlPoint::initControlPoint(), vpHomogeneousMatrix::inverse(), vpRBSilhouettePoint::j, vpRBFeatureTracker::m_numFeatures, vpRBFeatureTrackerInput::mask, vpRBSilhouettePoint::normal, vpRBSilhouettePoint::orientation, vpRBFeatureTrackerInput::renders, vpRobust::setMinMedianAbsoluteDeviation(), vpRBSilhouetteControlPoint::setNumCandidates(), vpRBFeatureTrackerInput::silhouettePoints, and vpRBSilhouettePoint::Z.
|
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.
|
inline |
Definition at line 142 of file vpRBSilhouetteMeTracker.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 |
Definition at line 92 of file vpRBSilhouetteMeTracker.h.
|
inline |
Definition at line 91 of file vpRBSilhouetteMeTracker.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 124 of file vpRBSilhouetteMeTracker.h.
|
inline |
Definition at line 103 of file vpRBSilhouetteMeTracker.h.
|
inline |
Definition at line 94 of file vpRBSilhouetteMeTracker.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 133 of file vpRBSilhouetteMeTracker.h.
|
inlinevirtualinherited |
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 in vpRBSilhouetteCCDTracker, and vpRBDenseDepthTracker.
Definition at line 189 of file vpRBFeatureTracker.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.
|
virtual |
Implements vpRBFeatureTracker.
Definition at line 100 of file vpRBSilhouetteMeTracker.cpp.
References vpRBFeatureTracker::m_covWeightDiag, vpRBFeatureTracker::m_error, vpRBFeatureTracker::m_L, vpRBFeatureTracker::m_numFeatures, vpRBFeatureTracker::m_vvsConverged, vpRBFeatureTracker::m_weighted_error, vpRBFeatureTracker::m_weights, vpColVector::resize(), and vpArray2D< Type >::resize().
|
inlinevirtual |
Reimplemented from vpRBFeatureTracker.
Definition at line 152 of file vpRBSilhouetteMeTracker.h.
References vpRBFeatureTracker::loadJsonConfiguration().
|
inlinevirtual |
Method called after the tracking iteration has finished.
Implements vpRBFeatureTracker.
Definition at line 72 of file vpRBSilhouetteMeTracker.h.
|
inlinevirtual |
Method called when starting a tracking iteration.
Implements vpRBFeatureTracker.
Definition at line 67 of file vpRBSilhouetteMeTracker.h.
|
inlinevirtual |
Whether this tracker requires depth image to extract features.
Implements vpRBFeatureTracker.
Definition at line 61 of file vpRBSilhouetteMeTracker.h.
|
inlinevirtual |
Whether this tracker requires RGB image to extract features.
Implements vpRBFeatureTracker.
Definition at line 59 of file vpRBSilhouetteMeTracker.h.
|
inlinevirtual |
Whether this tracker requires Silhouette candidates.
Implements vpRBFeatureTracker.
Definition at line 63 of file vpRBSilhouetteMeTracker.h.
|
inlineinherited |
Definition at line 146 of file vpRBFeatureTracker.h.
|
inline |
Definition at line 143 of file vpRBSilhouetteMeTracker.h.
References vpException::badValue.
|
inline |
Definition at line 125 of file vpRBSilhouetteMeTracker.h.
References vpException::badValue.
|
inline |
Definition at line 104 of file vpRBSilhouetteMeTracker.h.
References vpException::badValue.
|
inline |
Definition at line 65 of file vpRBSilhouetteMeTracker.h.
|
inline |
Definition at line 95 of file vpRBSilhouetteMeTracker.h.
References vpException::badValue.
|
inline |
Definition at line 117 of file vpRBSilhouetteMeTracker.h.
|
inline |
Definition at line 134 of file vpRBSilhouetteMeTracker.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 116 of file vpRBSilhouetteMeTracker.h.
|
virtual |
Track the features.
Implements vpRBFeatureTracker.
Definition at line 86 of file vpRBSilhouetteMeTracker.cpp.
References vpRBFeatureTrackerInput::I.
|
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 vpRBDenseDepthTracker::computeVVSIter(), vpRBDenseDepthTracker::extractFeatures(), vpRBSilhouetteCCDTracker::initVVS(), and vpRBFeatureTracker::updateCovariance().
|
protectedinherited |
Covariance matrix.
Definition at line 226 of file vpRBFeatureTracker.h.
Referenced by vpRBDenseDepthTracker::computeVVSIter(), computeVVSIter(), vpRBDenseDepthTracker::extractFeatures(), initVVS(), and vpRBFeatureTracker::updateCovariance().
|
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(), vpRBDenseDepthTracker::computeVVSIter(), computeVVSIter(), vpRBSilhouetteCCDTracker::display(), vpRBDenseDepthTracker::extractFeatures(), initVVS(), and vpRBFeatureTracker::updateCovariance().
|
protectedinherited |
Definition at line 222 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::computeErrorAndInteractionMatrix(), vpRBDenseDepthTracker::computeVVSIter(), computeVVSIter(), vpRBDenseDepthTracker::extractFeatures(), 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(), vpRBDenseDepthTracker::computeVVSIter(), and computeVVSIter().
|
protectedinherited |
Left side of the Gauss newton minimization.
Definition at line 224 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::computeErrorAndInteractionMatrix(), vpRBDenseDepthTracker::computeVVSIter(), and computeVVSIter().
|
protectedinherited |
Error weights.
Definition at line 233 of file vpRBFeatureTracker.h.
Referenced by vpRBDenseDepthTracker::computeVVSIter(), computeVVSIter(), vpRBDenseDepthTracker::extractFeatures(), extractFeatures(), vpRBSilhouetteCCDTracker::initVVS(), initVVS(), and vpRBFeatureTracker::vpRBFeatureTracker().
|
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 vpRBDenseDepthTracker::computeVVSIter(), vpRBSilhouetteCCDTracker::computeVVSIter(), computeVVSIter(), vpRBSilhouetteCCDTracker::initVVS(), initVVS(), and vpRBFeatureTracker::vpRBFeatureTracker().
|
protectedinherited |
Raw VS Error vector.
Definition at line 229 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::computeErrorAndInteractionMatrix(), vpRBDenseDepthTracker::computeVVSIter(), computeVVSIter(), vpRBDenseDepthTracker::extractFeatures(), and initVVS().
|
protectedinherited |
Weighted VS error.
Definition at line 230 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::computeErrorAndInteractionMatrix(), vpRBDenseDepthTracker::computeVVSIter(), computeVVSIter(), vpRBDenseDepthTracker::display(), vpRBSilhouetteCCDTracker::display(), vpRBDenseDepthTracker::extractFeatures(), vpRBSilhouetteCCDTracker::initVVS(), and initVVS().