Visual Servoing Platform  version 3.6.1 under development (2025-01-25)

#include <visp3/rbt/vpRBSilhouetteMeTracker.h>

+ Inheritance diagram for vpRBSilhouetteMeTracker:

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 vpColVectorgetWeightedError () const
 
Settings
const vpMegetMe () const
 
vpMegetMe ()
 
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
 

Detailed Description

Moving edge feature tracking from depth-extracted object contours.

Examples
catchRBT.cpp.

Definition at line 48 of file vpRBSilhouetteMeTracker.h.

Constructor & Destructor Documentation

◆ vpRBSilhouetteMeTracker()

vpRBSilhouetteMeTracker::vpRBSilhouetteMeTracker ( )
inline

Definition at line 52 of file vpRBSilhouetteMeTracker.h.

◆ ~vpRBSilhouetteMeTracker()

virtual vpRBSilhouetteMeTracker::~vpRBSilhouetteMeTracker ( )
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 vpRBSilhouetteMeTracker::display ( const vpCameraParameters cam,
const vpImage< unsigned char > &  I,
const vpImage< vpRGBa > &  IRGB,
const vpImage< unsigned char > &  depth 
) const
virtual

Implements vpRBFeatureTracker.

Definition at line 186 of file vpRBSilhouetteMeTracker.cpp.

References vpMeSite::display().

◆ 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.

◆ getGlobalConvergenceMinimumRatio()

double vpRBSilhouetteMeTracker::getGlobalConvergenceMinimumRatio ( ) const
inline
Examples
catchRBT.cpp.

Definition at line 142 of file vpRBSilhouetteMeTracker.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.

◆ getMe() [1/2]

vpMe& vpRBSilhouetteMeTracker::getMe ( )
inline

Definition at line 92 of file vpRBSilhouetteMeTracker.h.

◆ getMe() [2/2]

const vpMe& vpRBSilhouetteMeTracker::getMe ( ) const
inline
Examples
catchRBT.cpp.

Definition at line 91 of file vpRBSilhouetteMeTracker.h.

◆ getMinimumMaskConfidence()

float vpRBSilhouetteMeTracker::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 124 of file vpRBSilhouetteMeTracker.h.

◆ getMinRobustThreshold()

double vpRBSilhouetteMeTracker::getMinRobustThreshold ( ) const
inline
Examples
catchRBT.cpp.

Definition at line 103 of file vpRBSilhouetteMeTracker.h.

◆ getNumCandidates()

unsigned int vpRBSilhouetteMeTracker::getNumCandidates ( ) const
inline
Examples
catchRBT.cpp.

Definition at line 94 of file vpRBSilhouetteMeTracker.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.

◆ getSinglePointConvergenceThreshold()

double vpRBSilhouetteMeTracker::getSinglePointConvergenceThreshold ( ) const
inline
Examples
catchRBT.cpp.

Definition at line 133 of file vpRBSilhouetteMeTracker.h.

◆ getVVSTrackerWeight()

virtual double vpRBFeatureTracker::getVVSTrackerWeight ( ) const
inlinevirtualinherited

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, and vpRBDenseDepthTracker.

Definition at line 189 of file vpRBFeatureTracker.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()

◆ loadJsonConfiguration()

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

Reimplemented from vpRBFeatureTracker.

Examples
catchRBT.cpp.

Definition at line 152 of file vpRBSilhouetteMeTracker.h.

References vpRBFeatureTracker::loadJsonConfiguration().

◆ onTrackingIterEnd()

void vpRBSilhouetteMeTracker::onTrackingIterEnd ( )
inlinevirtual

Method called after the tracking iteration has finished.

Implements vpRBFeatureTracker.

Definition at line 72 of file vpRBSilhouetteMeTracker.h.

◆ onTrackingIterStart()

void vpRBSilhouetteMeTracker::onTrackingIterStart ( )
inlinevirtual

Method called when starting a tracking iteration.

Implements vpRBFeatureTracker.

Definition at line 67 of file vpRBSilhouetteMeTracker.h.

◆ requiresDepth()

bool vpRBSilhouetteMeTracker::requiresDepth ( ) const
inlinevirtual

Whether this tracker requires depth image to extract features.

Implements vpRBFeatureTracker.

Definition at line 61 of file vpRBSilhouetteMeTracker.h.

◆ requiresRGB()

bool vpRBSilhouetteMeTracker::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 59 of file vpRBSilhouetteMeTracker.h.

◆ requiresSilhouetteCandidates()

bool vpRBSilhouetteMeTracker::requiresSilhouetteCandidates ( ) const
inlinevirtual

Whether this tracker requires Silhouette candidates.

Implements vpRBFeatureTracker.

Definition at line 63 of file vpRBSilhouetteMeTracker.h.

◆ setFeaturesShouldBeDisplayed()

void vpRBFeatureTracker::setFeaturesShouldBeDisplayed ( bool  enableDisplay)
inlineinherited

Definition at line 146 of file vpRBFeatureTracker.h.

◆ setGlobalConvergenceMinimumRatio()

void vpRBSilhouetteMeTracker::setGlobalConvergenceMinimumRatio ( double  threshold)
inline
Examples
catchRBT.cpp.

Definition at line 143 of file vpRBSilhouetteMeTracker.h.

References vpException::badValue.

◆ setMinimumMaskConfidence()

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

Definition at line 125 of file vpRBSilhouetteMeTracker.h.

References vpException::badValue.

◆ setMinRobustThreshold()

void vpRBSilhouetteMeTracker::setMinRobustThreshold ( double  threshold)
inline
Examples
catchRBT.cpp.

Definition at line 104 of file vpRBSilhouetteMeTracker.h.

References vpException::badValue.

◆ setMovingEdge()

void vpRBSilhouetteMeTracker::setMovingEdge ( const vpMe me)
inline

Definition at line 65 of file vpRBSilhouetteMeTracker.h.

◆ setNumCandidates()

void vpRBSilhouetteMeTracker::setNumCandidates ( unsigned int  candidates)
inline
Examples
catchRBT.cpp.

Definition at line 95 of file vpRBSilhouetteMeTracker.h.

References vpException::badValue.

◆ setShouldUseMask()

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

Definition at line 117 of file vpRBSilhouetteMeTracker.h.

◆ setSinglePointConvergenceThreshold()

void vpRBSilhouetteMeTracker::setSinglePointConvergenceThreshold ( double  threshold)
inline
Examples
catchRBT.cpp.

Definition at line 134 of file vpRBSilhouetteMeTracker.h.

References vpException::badValue.

◆ setTrackerWeight()

void vpRBFeatureTracker::setTrackerWeight ( double  weight)
inlineinherited

Definition at line 190 of file vpRBFeatureTracker.h.

◆ shouldUseMask()

bool vpRBSilhouetteMeTracker::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 116 of file vpRBSilhouetteMeTracker.h.

◆ trackFeatures()

void vpRBSilhouetteMeTracker::trackFeatures ( const vpRBFeatureTrackerInput frame,
const vpRBFeatureTrackerInput previousFrame,
const vpHomogeneousMatrix cMo 
)
virtual

Track the features.

Implements vpRBFeatureTracker.

Definition at line 86 of file vpRBSilhouetteMeTracker.cpp.

References vpRBFeatureTrackerInput::I.

◆ 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

◆ m_covWeightDiag

vpColVector vpRBFeatureTracker::m_covWeightDiag
protectedinherited

◆ 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(), vpRBDenseDepthTracker::computeVVSIter(), and 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(), vpRBDenseDepthTracker::computeVVSIter(), and computeVVSIter().

◆ m_numFeatures

◆ 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