![]() |
Visual Servoing Platform
version 3.6.1 under development (2025-02-17)
|
#include <visp3/rbt/vpRBFeatureTracker.h>
Public Member Functions | |
vpRBFeatureTracker () | |
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 |
virtual void | loadJsonConfiguration (const nlohmann::json &j) |
Required inputs | |
virtual bool | requiresRGB () const =0 |
virtual bool | requiresDepth () const =0 |
virtual bool | requiresSilhouetteCandidates () const =0 |
Core Tracking methods | |
virtual void | onTrackingIterStart ()=0 |
virtual void | onTrackingIterEnd ()=0 |
virtual void | extractFeatures (const vpRBFeatureTrackerInput &frame, const vpRBFeatureTrackerInput &previousFrame, const vpHomogeneousMatrix &cMo)=0 |
virtual void | trackFeatures (const vpRBFeatureTrackerInput &frame, const vpRBFeatureTrackerInput &previousFrame, const vpHomogeneousMatrix &cMo)=0 |
virtual void | initVVS (const vpRBFeatureTrackerInput &frame, const vpRBFeatureTrackerInput &previousFrame, const vpHomogeneousMatrix &cMo)=0 |
virtual void | computeVVSIter (const vpRBFeatureTrackerInput &frame, const vpHomogeneousMatrix &cMo, unsigned int iteration)=0 |
Display | |
bool | featuresShouldBeDisplayed () const |
void | setFeaturesShouldBeDisplayed (bool enableDisplay) |
virtual void | display (const vpCameraParameters &cam, const vpImage< unsigned char > &I, const vpImage< vpRGBa > &IRGB, const vpImage< unsigned char > &depth) const =0 |
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 |
A base class for all features that can be used and tracked in the vpRBTracker.
Definition at line 60 of file vpRBFeatureTracker.h.
BEGIN_VISP_NAMESPACE vpRBFeatureTracker::vpRBFeatureTracker | ( | ) |
Definition at line 39 of file vpRBFeatureTracker.cpp.
References m_enableDisplay, m_numFeatures, m_userVvsWeight, and m_vvsConverged.
|
static |
Definition at line 76 of file vpRBFeatureTracker.cpp.
References vpArray2D< Type >::getRows(), vpColVector::t(), and vpMatrix::t().
Referenced by updateCovariance().
|
static |
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 vpRBSilhouetteMeTracker::computeVVSIter().
|
pure virtual |
Implemented in vpRBSilhouetteMeTracker, vpRBSilhouetteCCDTracker, and vpRBDenseDepthTracker.
|
pure virtual |
Implemented in vpRBSilhouetteMeTracker, vpRBSilhouetteCCDTracker, and vpRBDenseDepthTracker.
|
pure virtual |
Extract features from the frame data and the current pose estimate.
Implemented in vpRBSilhouetteMeTracker, vpRBSilhouetteCCDTracker, and vpRBDenseDepthTracker.
|
inline |
Definition at line 145 of file vpRBFeatureTracker.h.
|
inlinevirtual |
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.
|
inlinevirtual |
Get the left-side term of the Gauss-Newton optimization term.
Definition at line 195 of file vpRBFeatureTracker.h.
|
inlinevirtual |
Get the right-side term of the Gauss-Newton optimization term.
Definition at line 200 of file vpRBFeatureTracker.h.
|
inline |
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.
|
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 in vpRBSilhouetteCCDTracker, and vpRBDenseDepthTracker.
Definition at line 189 of file vpRBFeatureTracker.h.
|
inline |
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.
|
pure virtual |
Implemented in vpRBSilhouetteMeTracker, vpRBSilhouetteCCDTracker, and vpRBDenseDepthTracker.
|
inlinevirtual |
Reimplemented in vpRBSilhouetteMeTracker, vpRBSilhouetteCCDTracker, and vpRBDenseDepthTracker.
Definition at line 209 of file vpRBFeatureTracker.h.
Referenced by vpRBDenseDepthTracker::loadJsonConfiguration(), vpRBSilhouetteCCDTracker::loadJsonConfiguration(), and vpRBSilhouetteMeTracker::loadJsonConfiguration().
|
pure virtual |
Method called after the tracking iteration has finished.
Implemented in vpRBSilhouetteMeTracker, vpRBSilhouetteCCDTracker, and vpRBDenseDepthTracker.
|
pure virtual |
Method called when starting a tracking iteration.
Implemented in vpRBSilhouetteMeTracker, vpRBSilhouetteCCDTracker, and vpRBDenseDepthTracker.
|
pure virtual |
Whether this tracker requires depth image to extract features.
Implemented in vpRBSilhouetteMeTracker, vpRBSilhouetteCCDTracker, and vpRBDenseDepthTracker.
|
pure virtual |
Whether this tracker requires RGB image to extract features.
Implemented in vpRBSilhouetteMeTracker, vpRBSilhouetteCCDTracker, and vpRBDenseDepthTracker.
|
pure virtual |
Whether this tracker requires Silhouette candidates.
Implemented in vpRBSilhouetteMeTracker, vpRBSilhouetteCCDTracker, and vpRBDenseDepthTracker.
|
inline |
Definition at line 146 of file vpRBFeatureTracker.h.
|
inline |
Definition at line 190 of file vpRBFeatureTracker.h.
|
pure virtual |
Track the features.
Implemented in vpRBSilhouetteMeTracker, vpRBSilhouetteCCDTracker, and vpRBDenseDepthTracker.
|
virtual |
Update the covariance matrix.
lambda | the visual servoing gain |
Reimplemented in vpRBSilhouetteCCDTracker.
Definition at line 47 of file vpRBFeatureTracker.cpp.
References computeCovarianceMatrix(), m_cov, m_covWeightDiag, m_error, and m_L.
|
inline |
Returns whether the tracker is considered as having converged to the desired pose.
Definition at line 182 of file vpRBFeatureTracker.h.
|
protected |
Right side of the Gauss Newton minimization.
Definition at line 225 of file vpRBFeatureTracker.h.
Referenced by vpRBDenseDepthTracker::computeVVSIter(), vpRBDenseDepthTracker::extractFeatures(), vpRBSilhouetteCCDTracker::initVVS(), and updateCovariance().
|
protected |
Covariance matrix.
Definition at line 226 of file vpRBFeatureTracker.h.
Referenced by vpRBDenseDepthTracker::computeVVSIter(), vpRBSilhouetteMeTracker::computeVVSIter(), vpRBDenseDepthTracker::extractFeatures(), vpRBSilhouetteMeTracker::initVVS(), and updateCovariance().
|
protected |
Whether VVS has converged, should be updated every VVS iteration.
Definition at line 238 of file vpRBFeatureTracker.h.
Referenced by vpRBFeatureTracker().
|
protected |
Definition at line 228 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::computeErrorAndInteractionMatrix(), vpRBDenseDepthTracker::computeVVSIter(), vpRBSilhouetteMeTracker::computeVVSIter(), vpRBSilhouetteCCDTracker::display(), vpRBDenseDepthTracker::extractFeatures(), vpRBSilhouetteMeTracker::initVVS(), and updateCovariance().
|
protected |
Definition at line 222 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::computeErrorAndInteractionMatrix(), vpRBDenseDepthTracker::computeVVSIter(), vpRBSilhouetteMeTracker::computeVVSIter(), vpRBDenseDepthTracker::extractFeatures(), vpRBSilhouetteMeTracker::initVVS(), and updateCovariance().
|
protected |
Error jacobian (In VS terms, the interaction matrix)
Definition at line 223 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::computeErrorAndInteractionMatrix(), vpRBDenseDepthTracker::computeVVSIter(), and vpRBSilhouetteMeTracker::computeVVSIter().
|
protected |
Left side of the Gauss newton minimization.
Definition at line 224 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::computeErrorAndInteractionMatrix(), vpRBDenseDepthTracker::computeVVSIter(), and vpRBSilhouetteMeTracker::computeVVSIter().
|
protected |
Error weights.
Definition at line 233 of file vpRBFeatureTracker.h.
Referenced by vpRBDenseDepthTracker::computeVVSIter(), vpRBSilhouetteMeTracker::computeVVSIter(), vpRBDenseDepthTracker::extractFeatures(), vpRBSilhouetteMeTracker::extractFeatures(), vpRBSilhouetteCCDTracker::initVVS(), vpRBSilhouetteMeTracker::initVVS(), and vpRBFeatureTracker().
|
protected |
Number of considered features.
Definition at line 234 of file vpRBFeatureTracker.h.
Referenced by vpRBFeatureTracker().
|
protected |
User-defined weight for this specific type of feature.
Definition at line 236 of file vpRBFeatureTracker.h.
Referenced by vpRBDenseDepthTracker::computeVVSIter(), vpRBSilhouetteCCDTracker::computeVVSIter(), vpRBSilhouetteMeTracker::computeVVSIter(), vpRBSilhouetteCCDTracker::initVVS(), vpRBSilhouetteMeTracker::initVVS(), and vpRBFeatureTracker().
|
protected |
Raw VS Error vector.
Definition at line 229 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::computeErrorAndInteractionMatrix(), vpRBDenseDepthTracker::computeVVSIter(), vpRBSilhouetteMeTracker::computeVVSIter(), vpRBDenseDepthTracker::extractFeatures(), and vpRBSilhouetteMeTracker::initVVS().
|
protected |
Weighted VS error.
Definition at line 230 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::computeErrorAndInteractionMatrix(), vpRBDenseDepthTracker::computeVVSIter(), vpRBSilhouetteMeTracker::computeVVSIter(), vpRBDenseDepthTracker::display(), vpRBSilhouetteCCDTracker::display(), vpRBDenseDepthTracker::extractFeatures(), vpRBSilhouetteCCDTracker::initVVS(), and vpRBSilhouetteMeTracker::initVVS().