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

#include <visp3/rbt/vpRBTracker.h>

Public Member Functions

 vpRBTracker ()
 
 ~vpRBTracker ()=default
 
void reset ()
 
Information retrieval
void getPose (vpHomogeneousMatrix &cMo) const
 
void setPose (const vpHomogeneousMatrix &cMo)
 
vpObjectCentricRenderergetRenderer ()
 
const vpRBFeatureTrackerInputgetMostRecentFrame () const
 
const vpRBTrackerLoggergetLogger () const
 
vpMatrix getCovariance () const
 
Settings
void addTracker (std::shared_ptr< vpRBFeatureTracker > tracker)
 
void setupRenderer (const std::string &file)
 
std::string getModelPath () const
 
void setModelPath (const std::string &path)
 
std::vector< std::shared_ptr< vpRBFeatureTracker > > getFeatureTrackers ()
 
vpCameraParameters getCameraParameters () const
 
void setCameraParameters (const vpCameraParameters &cam, unsigned h, unsigned w)
 
unsigned int getImageWidth () const
 
unsigned int getImageHeight () const
 
vpSilhouettePointsExtractionSettings getSilhouetteExtractionParameters () const
 
void setSilhouetteExtractionParameters (const vpSilhouettePointsExtractionSettings &settings)
 
double getOptimizationGain () const
 
void setOptimizationGain (double lambda)
 
unsigned int getMaxOptimizationIters () const
 
void setMaxOptimizationIters (unsigned int iters)
 
double getOptimizationInitialMu () const
 
void setOptimizationInitialMu (double mu)
 
double getOptimizationMuIterFactor () const
 
void setOptimizationMuIterFactor (double factor)
 
std::shared_ptr< vpRBDriftDetectorgetDriftDetector () const
 
void setDriftDetector (const std::shared_ptr< vpRBDriftDetector > &detector)
 
std::shared_ptr< vpObjectMaskgetObjectSegmentationMethod () const
 
void setObjectSegmentationMethod (const std::shared_ptr< vpObjectMask > &mask)
 
std::shared_ptr< vpRBVisualOdometrygetOdometryMethod () const
 
void setOdometryMethod (const std::shared_ptr< vpRBVisualOdometry > &odometry)
 
bool getVerbose ()
 
void setVerbose (bool verbose)
 
void loadConfigurationFile (const std::string &filename)
 
void loadConfiguration (const nlohmann::json &j)
 
Tracking
void startTracking ()
 
void track (const vpImage< unsigned char > &I)
 
void track (const vpImage< unsigned char > &I, const vpImage< vpRGBa > &IRGB)
 
void track (const vpImage< unsigned char > &I, const vpImage< vpRGBa > &IRGB, const vpImage< float > &depth)
 
Display
void displayMask (vpImage< unsigned char > &Imask) const
 
void display (const vpImage< unsigned char > &I, const vpImage< vpRGBa > &IRGB, const vpImage< unsigned char > &depth)
 

Protected Member Functions

void track (vpRBFeatureTrackerInput &input)
 
void updateRender (vpRBFeatureTrackerInput &frame)
 
std::vector< vpRBSilhouettePointextractSilhouettePoints (const vpImage< vpRGBf > &Inorm, const vpImage< float > &Idepth, const vpImage< vpRGBf > &Ior, const vpImage< unsigned char > &Ivalid, const vpCameraParameters &cam, const vpHomogeneousMatrix &cTcp)
 
template<typename T >
void checkDimensionsOrThrow (const vpImage< T > &I, const std::string &imgType) const
 

Protected Attributes

bool m_firstIteration
 
std::vector< std::shared_ptr< vpRBFeatureTracker > > m_trackers
 
vpRBFeatureTrackerInput m_currentFrame
 
vpRBFeatureTrackerInput m_previousFrame
 
std::string m_modelPath
 
vpHomogeneousMatrix m_cMo
 
vpHomogeneousMatrix m_cMoPrev
 
vpCameraParameters m_cam
 
double m_lambda
 
unsigned m_vvsIterations
 
double m_muInit
 
double m_muIterFactor
 
vpSilhouettePointsExtractionSettings m_depthSilhouetteSettings
 
vpPanda3DRenderParameters m_rendererSettings
 
vpObjectCentricRenderer m_renderer
 
unsigned m_imageHeight
 
unsigned m_imageWidth
 
vpRBTrackerLogger m_logger
 
bool m_verbose
 
std::shared_ptr< vpObjectMaskm_mask
 
std::shared_ptr< vpRBDriftDetectorm_driftDetector
 
std::shared_ptr< vpRBVisualOdometrym_odometry
 

Detailed Description

Constructor & Destructor Documentation

◆ vpRBTracker()

◆ ~vpRBTracker()

vpRBTracker::~vpRBTracker ( )
default

Member Function Documentation

◆ addTracker()

void vpRBTracker::addTracker ( std::shared_ptr< vpRBFeatureTracker tracker)
Examples
catchRBT.cpp.

Definition at line 543 of file vpRBTracker.cpp.

References vpException::badValue, and m_trackers.

◆ checkDimensionsOrThrow()

template<typename T >
void vpRBTracker::checkDimensionsOrThrow ( const vpImage< T > &  I,
const std::string &  imgType 
) const
inlineprotected

Definition at line 234 of file vpRBTracker.h.

References vpException::dimensionError, vpImage< Type >::getCols(), and vpImage< Type >::getRows().

Referenced by track().

◆ display()

void vpRBTracker::display ( const vpImage< unsigned char > &  I,
const vpImage< vpRGBa > &  IRGB,
const vpImage< unsigned char > &  depth 
)

◆ displayMask()

void vpRBTracker::displayMask ( vpImage< unsigned char > &  Imask) const

◆ extractSilhouettePoints()

std::vector< vpRBSilhouettePoint > vpRBTracker::extractSilhouettePoints ( const vpImage< vpRGBf > &  Inorm,
const vpImage< float > &  Idepth,
const vpImage< vpRGBf > &  Ior,
const vpImage< unsigned char > &  Ivalid,
const vpCameraParameters cam,
const vpHomogeneousMatrix cTcp 
)
protected

◆ getCameraParameters()

vpCameraParameters vpRBTracker::getCameraParameters ( ) const
Examples
catchRBT.cpp, and tutorial-rbt-sequence.cpp.

Definition at line 99 of file vpRBTracker.cpp.

References m_cam.

◆ getCovariance()

◆ getDriftDetector()

std::shared_ptr<vpRBDriftDetector> vpRBTracker::getDriftDetector ( ) const
inline

Definition at line 150 of file vpRBTracker.h.

◆ getFeatureTrackers()

std::vector<std::shared_ptr<vpRBFeatureTracker> > vpRBTracker::getFeatureTrackers ( )
inline

Definition at line 100 of file vpRBTracker.h.

◆ getImageHeight()

unsigned int vpRBTracker::getImageHeight ( ) const
inline
Examples
catchRBT.cpp.

Definition at line 106 of file vpRBTracker.h.

◆ getImageWidth()

unsigned int vpRBTracker::getImageWidth ( ) const
inline
Examples
catchRBT.cpp.

Definition at line 105 of file vpRBTracker.h.

◆ getLogger()

const vpRBTrackerLogger& vpRBTracker::getLogger ( ) const
inline

Definition at line 83 of file vpRBTracker.h.

◆ getMaxOptimizationIters()

unsigned int vpRBTracker::getMaxOptimizationIters ( ) const
inline
Examples
catchRBT.cpp.

Definition at line 123 of file vpRBTracker.h.

◆ getModelPath()

std::string vpRBTracker::getModelPath ( ) const
inline
Examples
catchRBT.cpp.

Definition at line 97 of file vpRBTracker.h.

◆ getMostRecentFrame()

const vpRBFeatureTrackerInput& vpRBTracker::getMostRecentFrame ( ) const
inline
Examples
tutorial-rbt-realsense.cpp, and tutorial-rbt-sequence.cpp.

Definition at line 82 of file vpRBTracker.h.

◆ getObjectSegmentationMethod()

std::shared_ptr<vpObjectMask> vpRBTracker::getObjectSegmentationMethod ( ) const
inline

Definition at line 156 of file vpRBTracker.h.

◆ getOdometryMethod()

std::shared_ptr<vpRBVisualOdometry> vpRBTracker::getOdometryMethod ( ) const
inline

Definition at line 162 of file vpRBTracker.h.

◆ getOptimizationGain()

double vpRBTracker::getOptimizationGain ( ) const
inline
Examples
catchRBT.cpp.

Definition at line 115 of file vpRBTracker.h.

◆ getOptimizationInitialMu()

double vpRBTracker::getOptimizationInitialMu ( ) const
inline
Examples
catchRBT.cpp.

Definition at line 132 of file vpRBTracker.h.

◆ getOptimizationMuIterFactor()

double vpRBTracker::getOptimizationMuIterFactor ( ) const
inline
Examples
catchRBT.cpp.

Definition at line 141 of file vpRBTracker.h.

◆ getPose()

void vpRBTracker::getPose ( vpHomogeneousMatrix cMo) const
Examples
catchRBT.cpp, tutorial-rbt-realsense.cpp, and tutorial-rbt-sequence.cpp.

Definition at line 64 of file vpRBTracker.cpp.

References m_cMo.

◆ getRenderer()

vpObjectCentricRenderer & vpRBTracker::getRenderer ( )

Definition at line 576 of file vpRBTracker.cpp.

References m_renderer.

◆ getSilhouetteExtractionParameters()

vpSilhouettePointsExtractionSettings vpRBTracker::getSilhouetteExtractionParameters ( ) const
inline
Examples
catchRBT.cpp.

Definition at line 108 of file vpRBTracker.h.

◆ getVerbose()

bool vpRBTracker::getVerbose ( )
inline

Get verbosity mode.

Returns
true when verbosity is enabled, false otherwise.

Definition at line 172 of file vpRBTracker.h.

◆ loadConfiguration()

◆ loadConfigurationFile()

void vpRBTracker::loadConfigurationFile ( const std::string &  filename)

◆ reset()

void vpRBTracker::reset ( )

Definition at line 126 of file vpRBTracker.cpp.

References m_firstIteration.

◆ setCameraParameters()

◆ setDriftDetector()

void vpRBTracker::setDriftDetector ( const std::shared_ptr< vpRBDriftDetector > &  detector)
inline

Definition at line 151 of file vpRBTracker.h.

◆ setMaxOptimizationIters()

void vpRBTracker::setMaxOptimizationIters ( unsigned int  iters)
inline
Examples
catchRBT.cpp.

Definition at line 124 of file vpRBTracker.h.

References vpException::badValue.

Referenced by loadConfiguration().

◆ setModelPath()

void vpRBTracker::setModelPath ( const std::string &  path)
Examples
catchRBT.cpp.

Definition at line 131 of file vpRBTracker.cpp.

References m_modelPath.

Referenced by loadConfiguration().

◆ setObjectSegmentationMethod()

void vpRBTracker::setObjectSegmentationMethod ( const std::shared_ptr< vpObjectMask > &  mask)
inline

Definition at line 157 of file vpRBTracker.h.

◆ setOdometryMethod()

void vpRBTracker::setOdometryMethod ( const std::shared_ptr< vpRBVisualOdometry > &  odometry)
inline

Definition at line 163 of file vpRBTracker.h.

◆ setOptimizationGain()

void vpRBTracker::setOptimizationGain ( double  lambda)
inline
Examples
catchRBT.cpp.

Definition at line 116 of file vpRBTracker.h.

References vpException::badValue.

Referenced by loadConfiguration().

◆ setOptimizationInitialMu()

void vpRBTracker::setOptimizationInitialMu ( double  mu)
inline
Examples
catchRBT.cpp.

Definition at line 133 of file vpRBTracker.h.

References vpException::badValue.

Referenced by loadConfiguration().

◆ setOptimizationMuIterFactor()

void vpRBTracker::setOptimizationMuIterFactor ( double  factor)
inline
Examples
catchRBT.cpp.

Definition at line 142 of file vpRBTracker.h.

References vpException::badValue.

Referenced by loadConfiguration().

◆ setPose()

◆ setSilhouetteExtractionParameters()

void vpRBTracker::setSilhouetteExtractionParameters ( const vpSilhouettePointsExtractionSettings settings)
Examples
catchRBT.cpp.

Definition at line 121 of file vpRBTracker.cpp.

References m_depthSilhouetteSettings.

◆ setupRenderer()

◆ setVerbose()

void vpRBTracker::setVerbose ( bool  verbose)
inline

Enable/disable verbosity mode.

Parameters
verbose: When true verbose mode is enabled. When false verbosity is disabled.

Definition at line 181 of file vpRBTracker.h.

◆ startTracking()

void vpRBTracker::startTracking ( )

◆ track() [1/4]

void vpRBTracker::track ( const vpImage< unsigned char > &  I)

◆ track() [2/4]

void vpRBTracker::track ( const vpImage< unsigned char > &  I,
const vpImage< vpRGBa > &  IRGB 
)

◆ track() [3/4]

void vpRBTracker::track ( const vpImage< unsigned char > &  I,
const vpImage< vpRGBa > &  IRGB,
const vpImage< float > &  depth 
)

◆ track() [4/4]

◆ updateRender()

Member Data Documentation

◆ m_cam

vpCameraParameters vpRBTracker::m_cam
protected

Definition at line 255 of file vpRBTracker.h.

Referenced by getCameraParameters(), loadConfiguration(), setCameraParameters(), and track().

◆ m_cMo

vpHomogeneousMatrix vpRBTracker::m_cMo
protected

Definition at line 253 of file vpRBTracker.h.

Referenced by getPose(), setPose(), track(), and updateRender().

◆ m_cMoPrev

vpHomogeneousMatrix vpRBTracker::m_cMoPrev
protected

Definition at line 254 of file vpRBTracker.h.

Referenced by setPose(), and track().

◆ m_currentFrame

vpRBFeatureTrackerInput vpRBTracker::m_currentFrame
protected

List of trackers.

Definition at line 249 of file vpRBTracker.h.

Referenced by display(), displayMask(), and track().

◆ m_depthSilhouetteSettings

vpSilhouettePointsExtractionSettings vpRBTracker::m_depthSilhouetteSettings
protected

Factor with which to multiply mu at every iteration during VVS.

Definition at line 262 of file vpRBTracker.h.

Referenced by extractSilhouettePoints(), loadConfiguration(), setSilhouetteExtractionParameters(), and updateRender().

◆ m_driftDetector

std::shared_ptr<vpRBDriftDetector> vpRBTracker::m_driftDetector
protected

Definition at line 272 of file vpRBTracker.h.

Referenced by display(), loadConfiguration(), track(), and vpRBTracker().

◆ m_firstIteration

bool vpRBTracker::m_firstIteration
protected

Definition at line 245 of file vpRBTracker.h.

Referenced by loadConfiguration(), reset(), and track().

◆ m_imageHeight

unsigned vpRBTracker::m_imageHeight
protected

Definition at line 266 of file vpRBTracker.h.

Referenced by loadConfiguration(), setCameraParameters(), and updateRender().

◆ m_imageWidth

unsigned vpRBTracker::m_imageWidth
protected

Definition at line 266 of file vpRBTracker.h.

Referenced by loadConfiguration(), setCameraParameters(), and updateRender().

◆ m_lambda

double vpRBTracker::m_lambda
protected

Definition at line 257 of file vpRBTracker.h.

Referenced by getCovariance(), loadConfiguration(), and track().

◆ m_logger

vpRBTrackerLogger vpRBTracker::m_logger
protected

Color and render image dimensions.

Definition at line 268 of file vpRBTracker.h.

Referenced by track().

◆ m_mask

std::shared_ptr<vpObjectMask> vpRBTracker::m_mask
protected

Definition at line 271 of file vpRBTracker.h.

Referenced by displayMask(), loadConfiguration(), track(), and vpRBTracker().

◆ m_modelPath

std::string vpRBTracker::m_modelPath
protected

Definition at line 252 of file vpRBTracker.h.

Referenced by setModelPath(), and startTracking().

◆ m_muInit

double vpRBTracker::m_muInit
protected

Max number of VVS iterations.

Definition at line 259 of file vpRBTracker.h.

Referenced by loadConfiguration(), and track().

◆ m_muIterFactor

double vpRBTracker::m_muIterFactor
protected

Initial mu value for Levenberg-Marquardt.

Definition at line 260 of file vpRBTracker.h.

Referenced by loadConfiguration(), and track().

◆ m_odometry

std::shared_ptr<vpRBVisualOdometry> vpRBTracker::m_odometry
protected

Definition at line 273 of file vpRBTracker.h.

Referenced by track(), and vpRBTracker().

◆ m_previousFrame

vpRBFeatureTrackerInput vpRBTracker::m_previousFrame
protected

Definition at line 250 of file vpRBTracker.h.

Referenced by extractSilhouettePoints(), and track().

◆ m_renderer

vpObjectCentricRenderer vpRBTracker::m_renderer
protected

◆ m_rendererSettings

vpPanda3DRenderParameters vpRBTracker::m_rendererSettings
protected

Definition at line 263 of file vpRBTracker.h.

Referenced by setCameraParameters(), updateRender(), and vpRBTracker().

◆ m_trackers

std::vector<std::shared_ptr<vpRBFeatureTracker> > vpRBTracker::m_trackers
protected

Whether this is the first iteration.

Definition at line 247 of file vpRBTracker.h.

Referenced by addTracker(), display(), getCovariance(), loadConfiguration(), setupRenderer(), and track().

◆ m_verbose

bool vpRBTracker::m_verbose
protected

Definition at line 269 of file vpRBTracker.h.

Referenced by loadConfiguration(), and track().

◆ m_vvsIterations

unsigned vpRBTracker::m_vvsIterations
protected

VVS gain.

Definition at line 258 of file vpRBTracker.h.

Referenced by loadConfiguration(), and track().