Visual Servoing Platform  version 3.6.1 under development (2025-02-11)

#include <visp3/rbt/vpRBDenseDepthTracker.h>

+ Inheritance diagram for vpRBDenseDepthTracker:

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 vpColVectorgetWeightedError () 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)
 

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
 
std::vector< vpDepthPointm_depthPoints
 
vpRobust m_robust
 
unsigned int m_step
 
bool m_useMask
 
float m_minMaskConfidence
 
void onTrackingIterStart () VP_OVERRIDE
 
void onTrackingIterEnd () VP_OVERRIDE
 
double getVVSTrackerWeight () const VP_OVERRIDE
 
void extractFeatures (const vpRBFeatureTrackerInput &frame, const vpRBFeatureTrackerInput &previousFrame, const vpHomogeneousMatrix &cMo) VP_OVERRIDE
 
void trackFeatures (const vpRBFeatureTrackerInput &, const vpRBFeatureTrackerInput &, const vpHomogeneousMatrix &) VP_OVERRIDE
 
void initVVS (const vpRBFeatureTrackerInput &, const vpRBFeatureTrackerInput &, const vpHomogeneousMatrix &) 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
 
virtual void loadJsonConfiguration (const nlohmann::json &j) VP_OVERRIDE
 

Detailed Description

A tracker based on dense depth point-plane alignment.

Examples
catchRBT.cpp.

Definition at line 67 of file vpRBDenseDepthTracker.h.

Constructor & Destructor Documentation

◆ vpRBDenseDepthTracker()

vpRBDenseDepthTracker::vpRBDenseDepthTracker ( )
inline

Definition at line 71 of file vpRBDenseDepthTracker.h.

◆ ~vpRBDenseDepthTracker()

virtual vpRBDenseDepthTracker::~vpRBDenseDepthTracker ( )
virtualdefault

Member Function Documentation

◆ computeCovarianceMatrix()

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

◆ computeJTR()

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

◆ computeVVSIter()

◆ display()

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

◆ extractFeatures()

◆ featuresShouldBeDisplayed()

bool vpRBFeatureTracker::featuresShouldBeDisplayed ( ) const
inlineinherited

Definition at line 145 of file vpRBFeatureTracker.h.

◆ getCovariance()

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

◆ getLTL()

virtual vpMatrix vpRBFeatureTracker::getLTL ( ) const
inlinevirtualinherited

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

Definition at line 195 of file vpRBFeatureTracker.h.

◆ getLTR()

virtual vpColVector vpRBFeatureTracker::getLTR ( ) const
inlinevirtualinherited

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

Definition at line 200 of file vpRBFeatureTracker.h.

◆ getMinimumMaskConfidence()

float vpRBDenseDepthTracker::getMinimumMaskConfidence ( ) const
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

Examples
catchRBT.cpp.

Definition at line 104 of file vpRBDenseDepthTracker.h.

◆ getNumFeatures()

unsigned vpRBFeatureTracker::getNumFeatures ( ) const
inlineinherited

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 76 of file vpRBFeatureTracker.h.

◆ getStep()

unsigned int vpRBDenseDepthTracker::getStep ( ) const
inline
Examples
catchRBT.cpp.

Definition at line 83 of file vpRBDenseDepthTracker.h.

◆ getVVSTrackerWeight()

double vpRBDenseDepthTracker::getVVSTrackerWeight ( ) 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 from vpRBFeatureTracker.

Definition at line 124 of file vpRBDenseDepthTracker.h.

◆ getWeightedError()

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

◆ initVVS()

void vpRBDenseDepthTracker::initVVS ( const vpRBFeatureTrackerInput ,
const vpRBFeatureTrackerInput ,
const vpHomogeneousMatrix  
)
inlinevirtual

Implements vpRBFeatureTracker.

Definition at line 128 of file vpRBDenseDepthTracker.h.

◆ loadJsonConfiguration()

virtual void vpRBDenseDepthTracker::loadJsonConfiguration ( const nlohmann::json &  j)
inlinevirtual

Reimplemented from vpRBFeatureTracker.

Examples
catchRBT.cpp.

Definition at line 181 of file vpRBDenseDepthTracker.h.

References vpRBFeatureTracker::loadJsonConfiguration().

◆ onTrackingIterEnd()

void vpRBDenseDepthTracker::onTrackingIterEnd ( )
inlinevirtual

Method called after the tracking iteration has finished.

Implements vpRBFeatureTracker.

Definition at line 122 of file vpRBDenseDepthTracker.h.

◆ onTrackingIterStart()

void vpRBDenseDepthTracker::onTrackingIterStart ( )
inlinevirtual

Method called when starting a tracking iteration.

Implements vpRBFeatureTracker.

Definition at line 121 of file vpRBDenseDepthTracker.h.

◆ requiresDepth()

bool vpRBDenseDepthTracker::requiresDepth ( ) const
inlinevirtual

Whether this tracker requires depth image to extract features.

Implements vpRBFeatureTracker.

Definition at line 76 of file vpRBDenseDepthTracker.h.

◆ requiresRGB()

bool vpRBDenseDepthTracker::requiresRGB ( ) const
inlinevirtual

Whether this tracker requires RGB image to extract features.

Returns
true if the tracker requires an RGB image
false otherwise

Implements vpRBFeatureTracker.

Definition at line 75 of file vpRBDenseDepthTracker.h.

◆ requiresSilhouetteCandidates()

bool vpRBDenseDepthTracker::requiresSilhouetteCandidates ( ) const
inlinevirtual

Whether this tracker requires Silhouette candidates.

Implements vpRBFeatureTracker.

Definition at line 77 of file vpRBDenseDepthTracker.h.

◆ setFeaturesShouldBeDisplayed()

void vpRBFeatureTracker::setFeaturesShouldBeDisplayed ( bool  enableDisplay)
inlineinherited

Definition at line 146 of file vpRBFeatureTracker.h.

◆ setMinimumMaskConfidence()

void vpRBDenseDepthTracker::setMinimumMaskConfidence ( float  confidence)
inline
Examples
catchRBT.cpp.

Definition at line 105 of file vpRBDenseDepthTracker.h.

References vpException::badValue.

◆ setShouldUseMask()

void vpRBDenseDepthTracker::setShouldUseMask ( bool  useMask)
inline
Examples
catchRBT.cpp.

Definition at line 97 of file vpRBDenseDepthTracker.h.

◆ setStep()

void vpRBDenseDepthTracker::setStep ( unsigned int  step)
inline
Examples
catchRBT.cpp.

Definition at line 84 of file vpRBDenseDepthTracker.h.

References vpException::badValue.

◆ setTrackerWeight()

void vpRBFeatureTracker::setTrackerWeight ( double  weight)
inlineinherited

Definition at line 190 of file vpRBFeatureTracker.h.

◆ shouldUseMask()

bool vpRBDenseDepthTracker::shouldUseMask ( ) const
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.

Examples
catchRBT.cpp.

Definition at line 96 of file vpRBDenseDepthTracker.h.

◆ trackFeatures()

void vpRBDenseDepthTracker::trackFeatures ( const vpRBFeatureTrackerInput frame,
const vpRBFeatureTrackerInput previousFrame,
const vpHomogeneousMatrix cMo 
)
inlinevirtual

Track the features.

Implements vpRBFeatureTracker.

Definition at line 127 of file vpRBDenseDepthTracker.h.

◆ updateCovariance()

void vpRBFeatureTracker::updateCovariance ( const double  lambda)
virtualinherited

Update the covariance matrix.

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

◆ vvsHasConverged()

bool vpRBFeatureTracker::vvsHasConverged ( ) const
inlineinherited

Returns whether the tracker is considered as having converged to the desired pose.

Definition at line 182 of file vpRBFeatureTracker.h.

Member Data Documentation

◆ m_cov

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

◆ m_covWeightDiag

vpColVector vpRBFeatureTracker::m_covWeightDiag
protectedinherited

◆ m_depthPoints

std::vector<vpDepthPoint> vpRBDenseDepthTracker::m_depthPoints
protected

Definition at line 193 of file vpRBDenseDepthTracker.h.

Referenced by computeVVSIter(), display(), and extractFeatures().

◆ m_enableDisplay

bool vpRBFeatureTracker::m_enableDisplay
protectedinherited

Whether VVS has converged, should be updated every VVS iteration.

Definition at line 238 of file vpRBFeatureTracker.h.

Referenced by vpRBFeatureTracker::vpRBFeatureTracker().

◆ m_error

◆ m_L

◆ m_LTL

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

◆ m_LTR

vpColVector vpRBFeatureTracker::m_LTR
protectedinherited

Left side of the Gauss newton minimization.

Definition at line 224 of file vpRBFeatureTracker.h.

Referenced by vpRBSilhouetteCCDTracker::computeErrorAndInteractionMatrix(), computeVVSIter(), and vpRBSilhouetteMeTracker::computeVVSIter().

◆ m_minMaskConfidence

float vpRBDenseDepthTracker::m_minMaskConfidence
protected

Definition at line 197 of file vpRBDenseDepthTracker.h.

Referenced by extractFeatures().

◆ m_numFeatures

◆ m_robust

vpRobust vpRBDenseDepthTracker::m_robust
protected

Definition at line 194 of file vpRBDenseDepthTracker.h.

Referenced by computeVVSIter().

◆ m_step

unsigned int vpRBDenseDepthTracker::m_step
protected

Definition at line 195 of file vpRBDenseDepthTracker.h.

Referenced by extractFeatures().

◆ m_useMask

bool vpRBDenseDepthTracker::m_useMask
protected

Definition at line 196 of file vpRBDenseDepthTracker.h.

Referenced by extractFeatures().

◆ m_userVvsWeight

double vpRBFeatureTracker::m_userVvsWeight
protectedinherited

Number of considered features.

Definition at line 234 of file vpRBFeatureTracker.h.

Referenced by vpRBFeatureTracker::vpRBFeatureTracker().

◆ m_vvsConverged

bool vpRBFeatureTracker::m_vvsConverged
protectedinherited

◆ m_weighted_error

vpColVector vpRBFeatureTracker::m_weighted_error
protectedinherited

◆ m_weights