![]() |
Visual Servoing Platform version 3.7.0
|
#include <vpRBFeatureTracker.h>
Public Member Functions | |
| vpRBFeatureTracker () | |
| virtual | ~vpRBFeatureTracker ()=default |
| unsigned | getNumFeatures () const |
| bool | vvsHasConverged () const |
| virtual double | getVVSTrackerWeight (double optimizationProgress) const |
| const std::shared_ptr< vpTemporalWeighting > | getTemporalTrackerWeight () const |
| void | setTrackerWeight (double weight) |
| void | setTrackerWeight (const std::shared_ptr< vpTemporalWeighting > &weight) |
| virtual vpMatrix | getLTL () const |
| virtual vpColVector | getLTR () const |
| const vpColVector & | getWeightedError () const |
| virtual void | loadJsonConfiguration (const nlohmann::json &j) |
| void | setComputeJacobianObjectSpace (bool inObjectSpace) |
| bool | hasIgnoredDofs () const |
| void | setEstimatedDofs (const std::array< bool, 6 > &dofs) |
| void | updateOptimizerTerms (const vpHomogeneousMatrix &cMo) |
Required inputs | |
| virtual bool | requiresRGB () const =0 |
| virtual bool | requiresDepth () const =0 |
| virtual bool | requiresSilhouetteCandidates () const =0 |
Core Tracking methods | |
| virtual void | onTrackingIterStart (const vpRBFeatureTrackerInput &frame, const vpHomogeneousMatrix &cMo)=0 |
| virtual void | onTrackingIterEnd (const vpHomogeneousMatrix &cMo)=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 |
| virtual void | reset () |
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 Member Functions | |
| vpMatrix | computeoJo () const |
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 |
| std::shared_ptr< vpTemporalWeighting > | m_weighting |
| bool | m_vvsConverged |
| bool | m_enableDisplay |
| std::array< bool, 6 > | m_estimatedDofs |
| vpMatrix | m_oJo |
| bool | m_jacobianInObjectSpace |
A base class for all features that can be used and tracked in the vpRBTracker.
Tutorials
If you want to have an in-depth presentation of the Render-Based Tracker (RBT), you may have a look at:
Definition at line 70 of file vpRBFeatureTracker.h.
| BEGIN_VISP_NAMESPACE vpRBFeatureTracker::vpRBFeatureTracker | ( | ) |
Definition at line 39 of file vpRBFeatureTracker.cpp.
References m_enableDisplay, m_jacobianInObjectSpace, m_numFeatures, m_vvsConverged, m_weighting, and setEstimatedDofs().
Referenced by vpRBDenseDepthTracker::vpRBDenseDepthTracker(), vpRBSilhouetteCCDTracker::vpRBSilhouetteCCDTracker(), and vpRBSilhouetteMeTracker::vpRBSilhouetteMeTracker().
|
virtualdefault |
|
static |
Definition at line 78 of file vpRBFeatureTracker.cpp.
References vpColVector::t(), and vpMatrix::t().
Referenced by updateCovariance().
|
static |
Definition at line 56 of file vpRBFeatureTracker.cpp.
References vpArray2D< Type >::data, vpArray2D< Type >::getCols(), vpArray2D< Type >::getRows(), vpMatrixException::incorrectMatrixSizeError, and vpColVector::resize().
Referenced by updateOptimizerTerms().
|
inlineprotected |
Definition at line 284 of file vpRBFeatureTracker.h.
References m_estimatedDofs.
Referenced by setEstimatedDofs().
|
pure virtual |
Implemented in vpRBDenseDepthTracker, vpRBKltTracker, vpRBSilhouetteCCDTracker, and vpRBSilhouetteMeTracker.
|
pure virtual |
Implemented in vpRBDenseDepthTracker, vpRBKltTracker, vpRBSilhouetteCCDTracker, and vpRBSilhouetteMeTracker.
|
pure virtual |
Extract features from the frame data and the current pose estimate.
Implemented in vpRBDenseDepthTracker, vpRBKltTracker, vpRBSilhouetteCCDTracker, and vpRBSilhouetteMeTracker.
|
inline |
Definition at line 163 of file vpRBFeatureTracker.h.
References m_enableDisplay.
|
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 186 of file vpRBFeatureTracker.h.
References m_cov.
|
inlinevirtual |
Get the left-side term of the Gauss-Newton optimization term.
Definition at line 215 of file vpRBFeatureTracker.h.
References m_LTL.
|
inlinevirtual |
Get the right-side term of the Gauss-Newton optimization term.
Definition at line 220 of file vpRBFeatureTracker.h.
References m_LTR.
|
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 88 of file vpRBFeatureTracker.h.
References m_numFeatures.
|
inline |
Definition at line 208 of file vpRBFeatureTracker.h.
References m_weighting.
|
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.
Definition at line 207 of file vpRBFeatureTracker.h.
References m_numFeatures, and m_weighting.
|
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 226 of file vpRBFeatureTracker.h.
References m_weighted_error.
|
inline |
Definition at line 246 of file vpRBFeatureTracker.h.
References m_estimatedDofs.
Referenced by vpRBSilhouetteCCDTracker::computeErrorAndInteractionMatrix().
|
pure virtual |
Implemented in vpRBDenseDepthTracker, vpRBKltTracker, vpRBSilhouetteCCDTracker, and vpRBSilhouetteMeTracker.
|
inlinevirtual |
Reimplemented in vpRBDenseDepthTracker, vpRBKltTracker, vpRBSilhouetteCCDTracker, and vpRBSilhouetteMeTracker.
Definition at line 229 of file vpRBFeatureTracker.h.
References m_enableDisplay, m_weighting, vpTemporalWeighting::parseTemporalWeighting(), and setEstimatedDofs().
Referenced by vpRBDenseDepthTracker::loadJsonConfiguration(), vpRBKltTracker::loadJsonConfiguration(), vpRBSilhouetteCCDTracker::loadJsonConfiguration(), and vpRBSilhouetteMeTracker::loadJsonConfiguration().
|
pure virtual |
Method called after the tracking iteration has finished.
Implemented in vpRBDenseDepthTracker, vpRBKltTracker, vpRBSilhouetteCCDTracker, and vpRBSilhouetteMeTracker.
|
pure virtual |
Method called when starting a tracking iteration.
Implemented in vpRBDenseDepthTracker, vpRBKltTracker, vpRBSilhouetteCCDTracker, and vpRBSilhouetteMeTracker.
|
pure virtual |
Whether this tracker requires depth image to extract features.
Implemented in vpRBDenseDepthTracker, vpRBKltTracker, vpRBSilhouetteCCDTracker, and vpRBSilhouetteMeTracker.
|
pure virtual |
Whether this tracker requires RGB image to extract features.
Implemented in vpRBDenseDepthTracker, vpRBKltTracker, vpRBSilhouetteCCDTracker, and vpRBSilhouetteMeTracker.
|
pure virtual |
Whether this tracker requires Silhouette candidates.
Implemented in vpRBDenseDepthTracker, vpRBKltTracker, vpRBSilhouetteCCDTracker, and vpRBSilhouetteMeTracker.
|
inlinevirtual |
Resets feature state. Can be called when the object changes or is lost, Ensuring that prior data does not influence the tracking behaviour.
Reimplemented in vpRBSilhouetteCCDTracker.
Definition at line 152 of file vpRBFeatureTracker.h.
|
inline |
Definition at line 238 of file vpRBFeatureTracker.h.
References m_jacobianInObjectSpace.
|
inline |
Definition at line 255 of file vpRBFeatureTracker.h.
References computeoJo(), m_estimatedDofs, and m_oJo.
Referenced by loadJsonConfiguration(), and vpRBFeatureTracker().
|
inline |
Definition at line 164 of file vpRBFeatureTracker.h.
References m_enableDisplay.
Referenced by visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker::load_settings().
|
inline |
Definition at line 210 of file vpRBFeatureTracker.h.
References m_weighting.
Referenced by visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker::load_settings().
|
inline |
Definition at line 209 of file vpRBFeatureTracker.h.
References m_weighting.
Referenced by visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker::load_settings().
|
pure virtual |
Track the features.
Implemented in vpRBDenseDepthTracker, vpRBKltTracker, vpRBSilhouetteCCDTracker, and vpRBSilhouetteMeTracker.
|
virtual |
Update the covariance matrix.
| lambda | the visual servoing gain |
Reimplemented in vpRBSilhouetteCCDTracker.
Definition at line 49 of file vpRBFeatureTracker.cpp.
References computeCovarianceMatrix(), vpMatrix::diag(), m_cov, m_covWeightDiag, m_error, and m_L.
|
inline |
Definition at line 262 of file vpRBFeatureTracker.h.
References computeJTR(), m_covWeightDiag, m_error, m_jacobianInObjectSpace, m_L, m_LTL, m_LTR, m_oJo, m_weighted_error, and m_weights.
Referenced by vpRBDenseDepthTracker::computeVVSIter(), and vpRBSilhouetteMeTracker::computeVVSIter().
|
inline |
Returns whether the tracker is considered as having converged to the desired pose.
Definition at line 200 of file vpRBFeatureTracker.h.
References m_vvsConverged.
|
protected |
Right side of the Gauss Newton minimization.
Definition at line 301 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::changeScale(), vpRBDenseDepthTracker::computeVVSIter(), vpRBDenseDepthTracker::extractFeatures(), getCovariance(), vpRBSilhouetteCCDTracker::initVVS(), updateCovariance(), and vpRBSilhouetteCCDTracker::updateCovariance().
|
protected |
Covariance matrix.
Definition at line 302 of file vpRBFeatureTracker.h.
Referenced by vpRBDenseDepthTracker::computeVVSIter(), vpRBDenseDepthTracker::extractFeatures(), vpRBSilhouetteMeTracker::initVVS(), updateCovariance(), and updateOptimizerTerms().
|
protected |
Whether VVS has converged, should be updated every VVS iteration.
Definition at line 314 of file vpRBFeatureTracker.h.
Referenced by featuresShouldBeDisplayed(), loadJsonConfiguration(), setFeaturesShouldBeDisplayed(), and vpRBFeatureTracker().
|
protected |
Definition at line 304 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::computeErrorAndInteractionMatrix(), vpRBDenseDepthTracker::computeVVSIter(), vpRBSilhouetteMeTracker::computeVVSIter(), vpRBDenseDepthTracker::display(), vpRBSilhouetteCCDTracker::display(), vpRBDenseDepthTracker::extractFeatures(), vpRBSilhouetteCCDTracker::getVVSTrackerWeight(), vpRBSilhouetteMeTracker::initVVS(), vpRBSilhouetteCCDTracker::reset(), updateCovariance(), and updateOptimizerTerms().
|
protected |
Whether the tracked features should be displayed.
Definition at line 315 of file vpRBFeatureTracker.h.
Referenced by computeoJo(), hasIgnoredDofs(), and setEstimatedDofs().
|
protected |
Matrix representation of the estimated DOFS.
Definition at line 317 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::computeErrorAndInteractionMatrix(), setComputeJacobianObjectSpace(), updateOptimizerTerms(), and vpRBFeatureTracker().
|
protected |
Definition at line 298 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::computeErrorAndInteractionMatrix(), vpRBDenseDepthTracker::computeVVSIter(), vpRBSilhouetteMeTracker::computeVVSIter(), vpRBDenseDepthTracker::extractFeatures(), vpRBSilhouetteMeTracker::initVVS(), updateCovariance(), and updateOptimizerTerms().
|
protected |
Error jacobian (In VS terms, the interaction matrix).
Definition at line 299 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::computeErrorAndInteractionMatrix(), vpRBDenseDepthTracker::computeVVSIter(), getLTL(), and updateOptimizerTerms().
|
protected |
Left side of the Gauss newton minimization.
Definition at line 300 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::computeErrorAndInteractionMatrix(), vpRBDenseDepthTracker::computeVVSIter(), vpRBSilhouetteMeTracker::computeVVSIter(), getLTR(), and updateOptimizerTerms().
|
protected |
Error weights.
Definition at line 309 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::changeScale(), vpRBDenseDepthTracker::computeVVSIter(), vpRBSilhouetteCCDTracker::computeVVSIter(), vpRBSilhouetteMeTracker::computeVVSIter(), vpRBDenseDepthTracker::extractFeatures(), vpRBSilhouetteMeTracker::extractFeatures(), getNumFeatures(), getVVSTrackerWeight(), vpRBSilhouetteCCDTracker::initVVS(), vpRBSilhouetteMeTracker::initVVS(), and vpRBFeatureTracker().
|
protected |
Definition at line 316 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::computeErrorAndInteractionMatrix(), setEstimatedDofs(), and updateOptimizerTerms().
|
protected |
User-defined weight for this specific type of feature.
Definition at line 312 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::computeVVSIter(), vpRBSilhouetteMeTracker::computeVVSIter(), vpRBSilhouetteCCDTracker::initVVS(), vpRBSilhouetteMeTracker::initVVS(), vpRBSilhouetteCCDTracker::reset(), vpRBFeatureTracker(), and vvsHasConverged().
|
protected |
Raw VS Error vector.
Definition at line 305 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::computeErrorAndInteractionMatrix(), vpRBDenseDepthTracker::computeVVSIter(), vpRBDenseDepthTracker::extractFeatures(), getWeightedError(), vpRBSilhouetteMeTracker::initVVS(), and updateOptimizerTerms().
|
protected |
Number of considered features.
Definition at line 310 of file vpRBFeatureTracker.h.
Referenced by getTemporalTrackerWeight(), getVVSTrackerWeight(), vpRBSilhouetteCCDTracker::getVVSTrackerWeight(), loadJsonConfiguration(), setTrackerWeight(), setTrackerWeight(), and vpRBFeatureTracker().
|
protected |
Weighted VS error.
Definition at line 306 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::changeScale(), vpRBSilhouetteCCDTracker::computeErrorAndInteractionMatrix(), vpRBDenseDepthTracker::computeVVSIter(), vpRBSilhouetteMeTracker::computeVVSIter(), vpRBDenseDepthTracker::display(), vpRBSilhouetteCCDTracker::display(), vpRBDenseDepthTracker::extractFeatures(), vpRBSilhouetteCCDTracker::initVVS(), vpRBSilhouetteMeTracker::initVVS(), and updateOptimizerTerms().