Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
vpRBFeatureTracker Class Referenceabstract

#include <vpRBFeatureTracker.h>

Inheritance diagram for vpRBFeatureTracker:

Public Member Functions

 vpRBFeatureTracker ()
virtual ~vpRBFeatureTracker ()=default
unsigned getNumFeatures () const
bool vvsHasConverged () const
virtual double getVVSTrackerWeight (double optimizationProgress) const
const std::shared_ptr< vpTemporalWeightinggetTemporalTrackerWeight () const
void setTrackerWeight (double weight)
void setTrackerWeight (const std::shared_ptr< vpTemporalWeighting > &weight)
virtual vpMatrix getLTL () const
virtual vpColVector getLTR () const
const vpColVectorgetWeightedError () 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< vpTemporalWeightingm_weighting
bool m_vvsConverged
bool m_enableDisplay
std::array< bool, 6 > m_estimatedDofs
vpMatrix m_oJo
bool m_jacobianInObjectSpace

Detailed Description

A base class for all features that can be used and tracked in the vpRBTracker.

Tutorials & Examples

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.

Constructor & Destructor Documentation

◆ vpRBFeatureTracker()

◆ ~vpRBFeatureTracker()

virtual vpRBFeatureTracker::~vpRBFeatureTracker ( )
virtualdefault

Member Function Documentation

◆ computeCovarianceMatrix()

vpMatrix vpRBFeatureTracker::computeCovarianceMatrix ( const vpMatrix & A,
const vpColVector & b,
const vpMatrix & W )
static

Definition at line 78 of file vpRBFeatureTracker.cpp.

References vpColVector::t(), and vpMatrix::t().

Referenced by updateCovariance().

◆ computeJTR()

void vpRBFeatureTracker::computeJTR ( const vpMatrix & interaction,
const vpColVector & error,
vpColVector & JTR )
static

◆ computeoJo()

vpMatrix vpRBFeatureTracker::computeoJo ( ) const
inlineprotected

Definition at line 284 of file vpRBFeatureTracker.h.

References m_estimatedDofs.

Referenced by setEstimatedDofs().

◆ computeVVSIter()

virtual void vpRBFeatureTracker::computeVVSIter ( const vpRBFeatureTrackerInput & frame,
const vpHomogeneousMatrix & cMo,
unsigned int iteration )
pure virtual

◆ display()

virtual void vpRBFeatureTracker::display ( const vpCameraParameters & cam,
const vpImage< unsigned char > & I,
const vpImage< vpRGBa > & IRGB,
const vpImage< unsigned char > & depth ) const
pure virtual

◆ extractFeatures()

virtual void vpRBFeatureTracker::extractFeatures ( const vpRBFeatureTrackerInput & frame,
const vpRBFeatureTrackerInput & previousFrame,
const vpHomogeneousMatrix & cMo )
pure virtual

Extract features from the frame data and the current pose estimate.

Implemented in vpRBDenseDepthTracker, vpRBKltTracker, vpRBSilhouetteCCDTracker, and vpRBSilhouetteMeTracker.

◆ featuresShouldBeDisplayed()

bool vpRBFeatureTracker::featuresShouldBeDisplayed ( ) const
inline

Definition at line 163 of file vpRBFeatureTracker.h.

References m_enableDisplay.

◆ getCovariance()

virtual const vpMatrix vpRBFeatureTracker::getCovariance ( ) const
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.

◆ getLTL()

virtual vpMatrix vpRBFeatureTracker::getLTL ( ) const
inlinevirtual

Get the left-side term of the Gauss-Newton optimization term.

Definition at line 215 of file vpRBFeatureTracker.h.

References m_LTL.

◆ getLTR()

virtual vpColVector vpRBFeatureTracker::getLTR ( ) const
inlinevirtual

Get the right-side term of the Gauss-Newton optimization term.

Definition at line 220 of file vpRBFeatureTracker.h.

References m_LTR.

◆ getNumFeatures()

unsigned vpRBFeatureTracker::getNumFeatures ( ) const
inline

Return the type of feature that is used by this tracker.

Returns
vpRBFeatureType

Get the number of features used to compute the pose update

Definition at line 88 of file vpRBFeatureTracker.h.

References m_numFeatures.

◆ getTemporalTrackerWeight()

const std::shared_ptr< vpTemporalWeighting > vpRBFeatureTracker::getTemporalTrackerWeight ( ) const
inline

Definition at line 208 of file vpRBFeatureTracker.h.

References m_weighting.

◆ getVVSTrackerWeight()

virtual double vpRBFeatureTracker::getVVSTrackerWeight ( double optimizationProgress) const
inlinevirtual

Get the importance of this tracker in the optimization step. The default computation is the following: $ w / N $, where $ w$ is the weight defined by setTrackerWeight, and $ N $ is the number of features.

Reimplemented in vpRBSilhouetteCCDTracker.

Definition at line 207 of file vpRBFeatureTracker.h.

References m_numFeatures, and m_weighting.

◆ getWeightedError()

const vpColVector & vpRBFeatureTracker::getWeightedError ( ) const
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.

◆ hasIgnoredDofs()

bool vpRBFeatureTracker::hasIgnoredDofs ( ) const
inline

◆ initVVS()

virtual void vpRBFeatureTracker::initVVS ( const vpRBFeatureTrackerInput & frame,
const vpRBFeatureTrackerInput & previousFrame,
const vpHomogeneousMatrix & cMo )
pure virtual

◆ loadJsonConfiguration()

◆ onTrackingIterEnd()

virtual void vpRBFeatureTracker::onTrackingIterEnd ( const vpHomogeneousMatrix & cMo)
pure virtual

Method called after the tracking iteration has finished.

Implemented in vpRBDenseDepthTracker, vpRBKltTracker, vpRBSilhouetteCCDTracker, and vpRBSilhouetteMeTracker.

◆ onTrackingIterStart()

virtual void vpRBFeatureTracker::onTrackingIterStart ( const vpRBFeatureTrackerInput & frame,
const vpHomogeneousMatrix & cMo )
pure virtual

Method called when starting a tracking iteration.

Implemented in vpRBDenseDepthTracker, vpRBKltTracker, vpRBSilhouetteCCDTracker, and vpRBSilhouetteMeTracker.

◆ requiresDepth()

virtual bool vpRBFeatureTracker::requiresDepth ( ) const
pure virtual

Whether this tracker requires depth image to extract features.

Implemented in vpRBDenseDepthTracker, vpRBKltTracker, vpRBSilhouetteCCDTracker, and vpRBSilhouetteMeTracker.

◆ requiresRGB()

virtual bool vpRBFeatureTracker::requiresRGB ( ) const
pure virtual

Whether this tracker requires RGB image to extract features.

Returns
true if the tracker requires an RGB image
false otherwise

Implemented in vpRBDenseDepthTracker, vpRBKltTracker, vpRBSilhouetteCCDTracker, and vpRBSilhouetteMeTracker.

◆ requiresSilhouetteCandidates()

virtual bool vpRBFeatureTracker::requiresSilhouetteCandidates ( ) const
pure virtual

Whether this tracker requires Silhouette candidates.

Implemented in vpRBDenseDepthTracker, vpRBKltTracker, vpRBSilhouetteCCDTracker, and vpRBSilhouetteMeTracker.

◆ reset()

virtual void vpRBFeatureTracker::reset ( )
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.

◆ setComputeJacobianObjectSpace()

void vpRBFeatureTracker::setComputeJacobianObjectSpace ( bool inObjectSpace)
inline

Definition at line 238 of file vpRBFeatureTracker.h.

References m_jacobianInObjectSpace.

◆ setEstimatedDofs()

void vpRBFeatureTracker::setEstimatedDofs ( const std::array< bool, 6 > & dofs)
inline

Definition at line 255 of file vpRBFeatureTracker.h.

References computeoJo(), m_estimatedDofs, and m_oJo.

Referenced by loadJsonConfiguration(), and vpRBFeatureTracker().

◆ setFeaturesShouldBeDisplayed()

void vpRBFeatureTracker::setFeaturesShouldBeDisplayed ( bool enableDisplay)
inline

◆ setTrackerWeight() [1/2]

void vpRBFeatureTracker::setTrackerWeight ( const std::shared_ptr< vpTemporalWeighting > & weight)
inline

◆ setTrackerWeight() [2/2]

void vpRBFeatureTracker::setTrackerWeight ( double weight)
inline

◆ trackFeatures()

virtual void vpRBFeatureTracker::trackFeatures ( const vpRBFeatureTrackerInput & frame,
const vpRBFeatureTrackerInput & previousFrame,
const vpHomogeneousMatrix & cMo )
pure virtual

◆ updateCovariance()

void vpRBFeatureTracker::updateCovariance ( const double lambda)
virtual

Update the covariance matrix.

Parameters
lambdathe 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.

◆ updateOptimizerTerms()

void vpRBFeatureTracker::updateOptimizerTerms ( const vpHomogeneousMatrix & cMo)
inline

◆ vvsHasConverged()

bool vpRBFeatureTracker::vvsHasConverged ( ) const
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.

Member Data Documentation

◆ m_cov

◆ m_covWeightDiag

vpColVector vpRBFeatureTracker::m_covWeightDiag
protected

◆ m_enableDisplay

bool vpRBFeatureTracker::m_enableDisplay
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().

◆ m_error

◆ m_estimatedDofs

std::array<bool, 6> vpRBFeatureTracker::m_estimatedDofs
protected

Whether the tracked features should be displayed.

Definition at line 315 of file vpRBFeatureTracker.h.

Referenced by computeoJo(), hasIgnoredDofs(), and setEstimatedDofs().

◆ m_jacobianInObjectSpace

bool vpRBFeatureTracker::m_jacobianInObjectSpace
protected

◆ m_L

◆ m_LTL

vpMatrix vpRBFeatureTracker::m_LTL
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().

◆ m_LTR

vpColVector vpRBFeatureTracker::m_LTR
protected

◆ m_numFeatures

◆ m_oJo

vpMatrix vpRBFeatureTracker::m_oJo
protected

◆ m_vvsConverged

bool vpRBFeatureTracker::m_vvsConverged
protected

◆ m_weighted_error

◆ m_weighting

std::shared_ptr<vpTemporalWeighting> vpRBFeatureTracker::m_weighting
protected

◆ m_weights