Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches

#include <vpRBTracker.h>

Public Member Functions

 vpRBTracker ()
 ~vpRBTracker ()=default
void reset ()
double score (const vpHomogeneousMatrix &cMo, const vpImage< unsigned char > &I, const vpImage< vpRGBa > &IRGB, const vpImage< float > &depth)
template<typename ImageType>
std::enable_if< std::is_same< ImageType, unsignedchar >::value||std::is_same< ImageType, vpRGBa >::value, void >::type initClick (const vpImage< ImageType > &I, const std::string &initFile, bool displayHelp)
Information retrieval
void getPose (vpHomogeneousMatrix &cMo) const
void setPose (const vpHomogeneousMatrix &cMo)
vpObjectCentricRenderergetRenderer ()
const vpRBFeatureTrackerInputgetMostRecentFrame () const
vpMatrix getCovariance () const
Settings
void addTracker (std::shared_ptr< vpRBFeatureTracker > tracker)
std::vector< std::shared_ptr< vpRBFeatureTracker > > getFeatureTrackers () const
std::string getModelPath () const
void setModelPath (const std::string &path)
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)
bool scaleInvariantRegularization () const
void setScaleInvariantRegularization (bool invariant)
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)
void loadConfigurationFile (const std::string &filename)
void loadConfiguration (const nlohmann::json &j)
Tracking
void startTracking ()
vpRBTrackingResult track (const vpImage< unsigned char > &I)
vpRBTrackingResult track (const vpImage< unsigned char > &I, const vpImage< vpRGBa > &IRGB)
vpRBTrackingResult 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)

Public Attributes

friend vpRBInitializationHelper

Protected Member Functions

vpRBTrackingResult track (vpRBFeatureTrackerInput &input)
void setupRenderer (const std::string &file)
void updateRender (vpRBFeatureTrackerInput &frame)
void updateRender (vpRBFeatureTrackerInput &frame, const vpHomogeneousMatrix &cMo)
template<typename T>
void displaySilhouette (const vpImage< T > &I, const vpRBFeatureTrackerInput &frame)
std::vector< vpRBSilhouettePointextractSilhouettePoints (const vpImage< vpRGBf > &Inorm, const vpImage< float > &Idepth, const vpImage< float > &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
bool shouldRenderSilhouette ()

Protected Attributes

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

Detailed Description

Class implementing the Render-Based Tracker (RBT).

The RBT is an extension and rework of [45] and of the Model-Based Tracker.

Tracking is framed as a non-linear optimization problem where a visual error (formulated by comparing renders with images) should be minimized.

The RBT supports a various set of features, from tracked 2D points to dense depth information. For a list of base features, see Trackable features.

The RBT can be extended and you can add your own features and other functionalities to the pipeline.

Tutorials & Examples

Tutorials
For a detailed description of the tracker, how to use it and extend it, see:

Examples
catchRBT.cpp, catchRBTDataset.cpp, tutorial-rbt-realsense.cpp, and tutorial-rbt-sequence.cpp.

Definition at line 86 of file vpRBTracker.h.

Constructor & Destructor Documentation

◆ vpRBTracker()

◆ ~vpRBTracker()

vpRBTracker::~vpRBTracker ( )
default

References getPose(), getRenderer(), and setPose().

Member Function Documentation

◆ addTracker()

void vpRBTracker::addTracker ( std::shared_ptr< vpRBFeatureTracker > tracker)

Add a new feature to track.

Parameters
trackerthe feature to add
Exceptions
vpExceptionif the tracker is null

Definition at line 673 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

Check that a given image has the correct dimensions, previously specified with setCameraParameters or in the config file.

Template Parameters
TPixel type
Parameters
IImage to check
imgTypeHelper string to indicat which image type failed.

Definition at line 508 of file vpRBTracker.h.

References vpException::dimensionError, m_imageHeight, and m_imageWidth.

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

◆ display()

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

Displays tracker information such as current pose, object silhouette and tracked features on display images.

Parameters
IGrayscale display image
IRGBColor display image
depthDepth display image

Definition at line 688 of file vpRBTracker.cpp.

References displaySilhouette(), m_currentFrame, m_displaySilhouette, and m_trackers.

◆ displayMask()

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

Convert the mask output by the object segmentation method to a displayable representation. If no object segmentation method is set, then this method has no effect.

Parameters
Imaskthe image into which to write the display representation of the mask.
See also
setObjectSegmentationMethod, display

Definition at line 681 of file vpRBTracker.cpp.

References m_currentFrame, and m_mask.

◆ displaySilhouette()

template<typename T>
void vpRBTracker::displaySilhouette ( const vpImage< T > & I,
const vpRBFeatureTrackerInput & frame )
inlineprotected

Display the object silhouette of the frame in I.

Template Parameters
TPixel type of I
Parameters
IThe image where to display the object silhouette
frameFrame containing the rendered data. Does not have to be last pose or associated to the estimated pose of I.

Definition at line 468 of file vpRBTracker.h.

References vpDisplay::displayPoint(), vpColor::green, vpRBRenderData::isSilhouette, m_renderer, vpRBFeatureTrackerInput::renders, and shouldRenderSilhouette().

Referenced by display().

◆ extractSilhouettePoints()

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

Converts from pixelwise object silhouette representation to an actionable list of silhouette points.

Parameters
InormImage containing normals in object frame
IdepthRender image containing depth, in meters
IorImage containing the silhouette 2D edge orientation data
IvalidImage contianing whether a pixel is a silhouette point
camCamera intrinsics
cTcpPose of the previous camera in the current camera frame. Used when silhouette extraction settings try to reuse the same silhouette points in successive frames.
Returns
std::vector<vpRBSilhouettePoint>

Definition at line 635 of file vpRBTracker.cpp.

References vpException::badValue, m_depthSilhouetteSettings, and m_previousFrame.

Referenced by track().

◆ getCameraParameters()

vpCameraParameters vpRBTracker::getCameraParameters ( ) const

Get the camera intrinsics that are used to render the 3D object and process the tracked frames.

Returns
vpCameraParameters

Definition at line 101 of file vpRBTracker.cpp.

References m_cam.

◆ getCovariance()

◆ getDriftDetector()

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

Definition at line 242 of file vpRBTracker.h.

References m_driftDetector.

◆ getFeatureTrackers()

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

Get the tracked features.

Returns
std::vector<std::shared_ptr<vpRBFeatureTracker>>

Definition at line 155 of file vpRBTracker.h.

References m_trackers.

◆ getImageHeight()

unsigned int vpRBTracker::getImageHeight ( ) const
inline

Definition at line 188 of file vpRBTracker.h.

References m_imageHeight.

◆ getImageWidth()

unsigned int vpRBTracker::getImageWidth ( ) const
inline

Definition at line 187 of file vpRBTracker.h.

References m_imageWidth.

◆ getMaxOptimizationIters()

unsigned int vpRBTracker::getMaxOptimizationIters ( ) const
inline

Definition at line 205 of file vpRBTracker.h.

References m_vvsIterations.

◆ getModelPath()

std::string vpRBTracker::getModelPath ( ) const
inline

Get the path to the 3D model to track.

Definition at line 160 of file vpRBTracker.h.

References m_modelPath.

◆ getMostRecentFrame()

const vpRBFeatureTrackerInput & vpRBTracker::getMostRecentFrame ( ) const
inline

Retrieve the most recent frame that was used when tracking the object. The renders may not correspond to the latest pose that can be retrieved with getPose To retrieve the render pose see vpRBRenderData::cMo.

Returns
const vpRBFeatureTrackerInput&

Definition at line 128 of file vpRBTracker.h.

References m_currentFrame.

◆ getObjectSegmentationMethod()

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

Definition at line 257 of file vpRBTracker.h.

References m_mask.

◆ getOdometryMethod()

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

Definition at line 272 of file vpRBTracker.h.

References m_odometry.

◆ getOptimizationGain()

double vpRBTracker::getOptimizationGain ( ) const
inline

Definition at line 197 of file vpRBTracker.h.

References m_lambda.

◆ getOptimizationInitialMu()

double vpRBTracker::getOptimizationInitialMu ( ) const
inline

Definition at line 214 of file vpRBTracker.h.

References m_muInit.

◆ getOptimizationMuIterFactor()

double vpRBTracker::getOptimizationMuIterFactor ( ) const
inline

Definition at line 223 of file vpRBTracker.h.

References m_muIterFactor.

◆ getPose()

void vpRBTracker::getPose ( vpHomogeneousMatrix & cMo) const

Get the estimated pose of the object in the camera frame.

You should call vpRBTracker::track to update the retrieved pose

Parameters
cMopose to update

Definition at line 66 of file vpRBTracker.cpp.

References m_cMo.

Referenced by ~vpRBTracker().

◆ getRenderer()

vpObjectCentricRenderer & vpRBTracker::getRenderer ( )

Get the renderer used to render the object.

Returns
vpObjectCentricRenderer&

Definition at line 705 of file vpRBTracker.cpp.

References m_renderer.

Referenced by ~vpRBTracker().

◆ getSilhouetteExtractionParameters()

vpSilhouettePointsExtractionSettings vpRBTracker::getSilhouetteExtractionParameters ( ) const
inline

Definition at line 190 of file vpRBTracker.h.

References m_depthSilhouetteSettings.

◆ initClick()

template<typename ImageType>
std::enable_if< std::is_same< ImageType, unsignedchar >::value||std::is_same< ImageType, vpRGBa >::value, void >::type vpRBTracker::initClick ( const vpImage< ImageType > & I,
const std::string & initFile,
bool displayHelp )
inline

Perform Pose initialization by asking the user to click on predefined 3D points. This method is similar to the one provided in the MBT.

The 3D points (in the object frame) are defined in a .init file which should look like:

* 4 # Number of points
* 0.0 0.0 0.0 # Point 1 (In object frame coordinates)
* 0.0 0.0 0.1 # Point 2 (In object frame coordinates)
* 0.0 0.1 0.1 # Point 3 (In object frame coordinates)
* 0.1 0.1 0.1 # Point 4 (In object frame coordinates)
* 
Template Parameters
ImageTypeThe pixel type for I, either unsigned char or vpRGBa
Parameters
Ithe image where to click. It should be associated to a vpDisplay
initFileThe path to the initialization file.
displayHelpWhether to display an image to help with initialization. If true and the init file is "path/to/object.init", then the function will look for an image "path/to/object.{png, jpg, jpeg, ppm}".

Definition at line 426 of file vpRBTracker.h.

References vpRBInitializationHelper::getPose(), m_cam, vpRBInitializationHelper::setCameraParameters(), setPose(), and vpRBInitializationHelper.

◆ loadConfiguration()

◆ loadConfigurationFile()

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

Update tracker settings from a .json file. See the tutorials for a full description of the json format.

Parameters
filenameThe path to the .json file to load
Exceptions
ifthe file is ill-formed or settings are incorrect

Definition at line 711 of file vpRBTracker.cpp.

References vpException::ioError, and loadConfiguration().

◆ reset()

void vpRBTracker::reset ( )

◆ scaleInvariantRegularization()

bool vpRBTracker::scaleInvariantRegularization ( ) const
inline

Definition at line 232 of file vpRBTracker.h.

References m_scaleInvariantOptim.

◆ score()

double vpRBTracker::score ( const vpHomogeneousMatrix & cMo,
const vpImage< unsigned char > & I,
const vpImage< vpRGBa > & IRGB,
const vpImage< float > & depth )

Using the preconfigured drift detector, score a given pose by comparing the render with the given frame information.

Parameters
cMothe pose of the object in the camera frame to be scored
IGrayscale frame
IRGBColor image
depthDepth image
Returns
The tracking confidence score estimated by the drift detector.
Exceptions
ifno vpRBDriftDetector is specified, then scoring cannot be performed.

Definition at line 530 of file vpRBTracker.cpp.

References vpRBFeatureTrackerInput::depth, vpException::functionNotImplementedError, vpRBFeatureTrackerInput::I, vpRBFeatureTrackerInput::IRGB, m_driftDetector, and updateRender().

◆ setCameraParameters()

void vpRBTracker::setCameraParameters ( const vpCameraParameters & cam,
unsigned h,
unsigned w )

Sets the camera intrinsics and image resolution for the images where the object will be tracked.

Parameters
camCamera intrinsics for the color (and potential depth) image. It should follow a model without distortion.
hImage height
wImage width
Exceptions
vpExceptionif camera intrinsics have distortion
vpExceptionif image resolution is incorrect

Definition at line 103 of file vpRBTracker.cpp.

References vpException::badValue, m_cam, m_imageHeight, m_imageWidth, m_renderer, m_rendererSettings, and vpCameraParameters::perspectiveProjWithoutDistortion.

Referenced by loadConfiguration().

◆ setDriftDetector()

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

Sets the method to perform drift detection and estimate tracking confidence. Set to null to disable this functionality.

Parameters
detectorthe algorithm to use

Definition at line 249 of file vpRBTracker.h.

References m_driftDetector.

◆ setMaxOptimizationIters()

void vpRBTracker::setMaxOptimizationIters ( unsigned int iters)
inline

Definition at line 206 of file vpRBTracker.h.

References vpException::badValue, and m_vvsIterations.

Referenced by loadConfiguration().

◆ setModelPath()

void vpRBTracker::setModelPath ( const std::string & path)

Set the path to the 3D model to load.

Parameters
patha path to an existing file containing a 3D mesh that can be read by Panda3D

Definition at line 148 of file vpRBTracker.cpp.

References m_modelChanged, and m_modelPath.

Referenced by loadConfiguration().

◆ setObjectSegmentationMethod()

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

Sets the algorithm to use when performing object segmentation. Set to null to disable the use of segmentation.

Parameters
maskthe segmentation method

Definition at line 264 of file vpRBTracker.h.

References m_mask.

◆ setOdometryMethod()

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

Set the method to use when performing visual odometry to preestimate the camera motion before tracking. If null, then odometry is disabled.

Parameters
odometry

Definition at line 279 of file vpRBTracker.h.

References m_odometry.

◆ setOptimizationGain()

void vpRBTracker::setOptimizationGain ( double lambda)
inline

Definition at line 198 of file vpRBTracker.h.

References vpException::badValue, and m_lambda.

Referenced by loadConfiguration().

◆ setOptimizationInitialMu()

void vpRBTracker::setOptimizationInitialMu ( double mu)
inline

Definition at line 215 of file vpRBTracker.h.

References vpException::badValue, and m_muInit.

Referenced by loadConfiguration().

◆ setOptimizationMuIterFactor()

void vpRBTracker::setOptimizationMuIterFactor ( double factor)
inline

Definition at line 224 of file vpRBTracker.h.

References vpException::badValue, and m_muIterFactor.

Referenced by loadConfiguration().

◆ setPose()

void vpRBTracker::setPose ( const vpHomogeneousMatrix & cMo)

Sets the pose of the object in the camera frame. Should be called when initializing the tracker or when reinitializing after tracking failure.

Parameters
cMothe new object pose

Definition at line 71 of file vpRBTracker.cpp.

References m_cMo, m_cMoPrev, and m_renderer.

Referenced by initClick(), and ~vpRBTracker().

◆ setScaleInvariantRegularization()

void vpRBTracker::setScaleInvariantRegularization ( bool invariant)
inline

Definition at line 233 of file vpRBTracker.h.

References m_scaleInvariantOptim.

Referenced by loadConfiguration().

◆ setSilhouetteExtractionParameters()

void vpRBTracker::setSilhouetteExtractionParameters ( const vpSilhouettePointsExtractionSettings & settings)

Definition at line 123 of file vpRBTracker.cpp.

References m_depthSilhouetteSettings.

◆ setupRenderer()

void vpRBTracker::setupRenderer ( const std::string & file)
protected

◆ shouldRenderSilhouette()

bool vpRBTracker::shouldRenderSilhouette ( )
inlineprotected

Returns whether the renderer should render the silhouette information.

Definition at line 522 of file vpRBTracker.h.

References m_renderer.

Referenced by displaySilhouette(), and updateRender().

◆ startTracking()

void vpRBTracker::startTracking ( )

Method that should be called before starting tracking.

Initializes the renderer, loads the 3D model and ensures that the parameters are correct

Definition at line 228 of file vpRBTracker.cpp.

References m_convergenceMetric, m_modelPath, m_renderer, setupRenderer(), and updateRender().

◆ track() [1/4]

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

track and re-estimate the pose of the object in this frame, given only a grayscale image The pose after tracking should be retrieved using getPose. You should use the returned vpRBTrackingResult to check that tracking was successful

Parameters
IGrayscale image
Returns
vpRBTrackingResult
Exceptions
ifImage dimensions are incorrect or if one of the used features requires additional data, such as color or depth information

Definition at line 198 of file vpRBTracker.cpp.

References vpException::badValue, vpRBFeatureTrackerInput::cam, checkDimensionsOrThrow(), vpRBFeatureTrackerInput::I, m_cam, m_trackers, and track().

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

◆ track() [2/4]

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

track and re-estimate the pose of the object in this frame, given only a grayscale image The pose after tracking should be retrieved using getPose. You should use the returned vpRBTrackingResult to check that tracking was successful

Parameters
IGrayscale image
IRGBGrayscale image
Returns
vpRBTrackingResult
Exceptions
ifImage dimensions are incorrect or if one of the used features requires additional data, such as depth information

Definition at line 212 of file vpRBTracker.cpp.

References vpException::badValue, vpRBFeatureTrackerInput::cam, checkDimensionsOrThrow(), vpRBFeatureTrackerInput::I, vpRBFeatureTrackerInput::IRGB, m_cam, m_trackers, and track().

◆ track() [3/4]

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

track and re-estimate the pose of the object in this frame, given only a grayscale image The pose after tracking should be retrieved using getPose. You should use the returned vpRBTrackingResult to check that tracking was successful

Parameters
IGrayscale image
IRGBGrayscale image
depthDepth image, in meters. The Depth image should be aligned with the color and grayscale images.
Returns
vpRBTrackingResult
Exceptions
ifImage dimensions are incorrect

Definition at line 239 of file vpRBTracker.cpp.

References vpRBFeatureTrackerInput::cam, checkDimensionsOrThrow(), vpRBFeatureTrackerInput::depth, vpRBFeatureTrackerInput::I, vpRBFeatureTrackerInput::IRGB, m_cam, and track().

◆ track() [4/4]

vpRBTrackingResult vpRBTracker::track ( vpRBFeatureTrackerInput & input)
protected

Definition at line 252 of file vpRBTracker.cpp.

References vpRBTrackingTimings::addTrackerVVSTime(), vpRBTrackingResult::beforeIter(), vpRBFeatureTrackerInput::cam, vpRBRenderData::depth, vpExponentialMap::direct(), vpRBTrackingTimings::endTimer(), extractSilhouettePoints(), vpMatrix::eye(), vpArray2D< Type >::getRows(), vpRBFeatureTrackerInput::I, vpHomogeneousMatrix::inverse(), vpRBFeatureTrackerInput::IRGB, vpArray2D< Type >::isFinite(), vpMath::isFinite(), vpRBRenderData::isSilhouette, vpRBTrackingResult::logFeatures(), m_cam, m_cMo, m_cMoPrev, m_convergenceMetric, m_currentFrame, m_driftDetector, m_firstIteration, m_lambda, m_mask, m_muInit, m_muIterFactor, m_odometry, m_previousFrame, m_scaleInvariantOptim, m_trackers, m_vvsIterations, vpRBFeatureTrackerInput::mask, vpRBRenderData::normals, vpRBTrackingResult::onEndIter(), vpRBFeatureTrackerInput::renders, vpRBTrackingTimings::reset(), vpRBTrackingTimings::setDriftDetectionTime(), vpRBTrackingTimings::setInitVVSTime(), vpRBTrackingTimings::setMaskTime(), vpRBTrackingResult::setOdometryMetricAndThreshold(), vpRBTrackingResult::setOdometryMotion(), vpRBTrackingTimings::setOdometryTime(), vpRBTrackingTimings::setRenderTime(), vpRBTrackingTimings::setSilhouetteTime(), vpRBTrackingResult::setStoppingReason(), vpRBTrackingTimings::setTrackerFeatureExtractionTime(), vpRBTrackingTimings::setTrackerFeatureTrackingTime(), vpRBTrackingTimings::setTrackerIterStartTime(), vpRBRenderData::silhouetteCanny, vpRBFeatureTrackerInput::silhouettePoints, vpRBTrackingTimings::startTimer(), vpRBTrackingResult::timer(), and updateRender().

◆ updateRender() [1/2]

void vpRBTracker::updateRender ( vpRBFeatureTrackerInput & frame)
protected

Update the render data with a render at the last tracked pose.

Parameters
framethe frame to update

Definition at line 546 of file vpRBTracker.cpp.

References m_cMo, and updateRender().

Referenced by score(), startTracking(), track(), and updateRender().

◆ updateRender() [2/2]

Member Data Documentation

◆ m_cam

vpCameraParameters vpRBTracker::m_cam
protected

Camera intrinsics.

Definition at line 543 of file vpRBTracker.h.

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

◆ m_cMo

vpHomogeneousMatrix vpRBTracker::m_cMo
protected

Current pose of the object in the camera frame.

Definition at line 539 of file vpRBTracker.h.

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

◆ m_cMoPrev

vpHomogeneousMatrix vpRBTracker::m_cMoPrev
protected

Previous pose of the object in the camera frame.

Definition at line 541 of file vpRBTracker.h.

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

◆ m_convergenceMetric

std::shared_ptr<vpRBConvergenceMetric> vpRBTracker::m_convergenceMetric
protected

Definition at line 571 of file vpRBTracker.h.

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

◆ m_currentFrame

vpRBFeatureTrackerInput vpRBTracker::m_currentFrame
protected

Definition at line 531 of file vpRBTracker.h.

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

◆ m_depthSilhouetteSettings

vpSilhouettePointsExtractionSettings vpRBTracker::m_depthSilhouetteSettings
protected

◆ m_displaySilhouette

bool vpRBTracker::m_displaySilhouette
protected

Metric used to compare the motion between different poses.

Definition at line 573 of file vpRBTracker.h.

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

◆ m_driftDetector

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

◆ m_firstIteration

bool vpRBTracker::m_firstIteration
protected

Whether this is the first iteration.

Definition at line 527 of file vpRBTracker.h.

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

◆ m_imageHeight

unsigned vpRBTracker::m_imageHeight
protected

Color and render image dimensions.

Definition at line 565 of file vpRBTracker.h.

Referenced by checkDimensionsOrThrow(), getImageHeight(), loadConfiguration(), setCameraParameters(), updateRender(), and vpRBTracker().

◆ m_imageWidth

unsigned vpRBTracker::m_imageWidth
protected

◆ m_lambda

double vpRBTracker::m_lambda
protected

Optimization gain.

Definition at line 546 of file vpRBTracker.h.

Referenced by getCovariance(), getOptimizationGain(), loadConfiguration(), setOptimizationGain(), track(), and vpRBTracker().

◆ m_mask

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

◆ m_modelChanged

bool vpRBTracker::m_modelChanged
protected

Definition at line 536 of file vpRBTracker.h.

Referenced by setModelPath(), setupRenderer(), and vpRBTracker().

◆ m_modelPath

std::string vpRBTracker::m_modelPath
protected

Location of the 3D model to load.

Definition at line 535 of file vpRBTracker.h.

Referenced by getModelPath(), setModelPath(), and startTracking().

◆ m_muInit

double vpRBTracker::m_muInit
protected

Initial mu value for Levenberg-Marquardt.

Definition at line 550 of file vpRBTracker.h.

Referenced by getOptimizationInitialMu(), loadConfiguration(), setOptimizationInitialMu(), track(), and vpRBTracker().

◆ m_muIterFactor

double vpRBTracker::m_muIterFactor
protected

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

Definition at line 552 of file vpRBTracker.h.

Referenced by getOptimizationMuIterFactor(), loadConfiguration(), setOptimizationMuIterFactor(), track(), and vpRBTracker().

◆ m_odometry

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

◆ m_previousFrame

vpRBFeatureTrackerInput vpRBTracker::m_previousFrame
protected

Definition at line 532 of file vpRBTracker.h.

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

◆ m_renderer

◆ m_rendererIsSetup

bool vpRBTracker::m_rendererIsSetup
protected

Definition at line 562 of file vpRBTracker.h.

Referenced by setupRenderer(), and vpRBTracker().

◆ m_rendererSettings

vpPanda3DRenderParameters vpRBTracker::m_rendererSettings
protected

Camera specific setup for the 3D Panda renderer.

Definition at line 559 of file vpRBTracker.h.

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

◆ m_scaleInvariantOptim

bool vpRBTracker::m_scaleInvariantOptim
protected

Whether to use diagonal scaling in Levenberg-Marquardt regularization.

Definition at line 554 of file vpRBTracker.h.

Referenced by loadConfiguration(), scaleInvariantRegularization(), setScaleInvariantRegularization(), track(), and vpRBTracker().

◆ m_trackers

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

◆ m_vvsIterations

unsigned vpRBTracker::m_vvsIterations
protected

Maximum number of optimization iterations.

Definition at line 548 of file vpRBTracker.h.

Referenced by getMaxOptimizationIters(), loadConfiguration(), setMaxOptimizationIters(), track(), and vpRBTracker().

◆ vpRBInitializationHelper

friend vpRBTracker::vpRBInitializationHelper

Definition at line 435 of file vpRBTracker.h.

Referenced by initClick().