![]() |
Visual Servoing Platform version 3.7.0
|
#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) |
| vpObjectCentricRenderer & | getRenderer () |
| const vpRBFeatureTrackerInput & | getMostRecentFrame () 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< vpRBDriftDetector > | getDriftDetector () const |
| void | setDriftDetector (const std::shared_ptr< vpRBDriftDetector > &detector) |
| std::shared_ptr< vpObjectMask > | getObjectSegmentationMethod () const |
| void | setObjectSegmentationMethod (const std::shared_ptr< vpObjectMask > &mask) |
| std::shared_ptr< vpRBVisualOdometry > | getOdometryMethod () 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< vpRBSilhouettePoint > | extractSilhouettePoints (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< vpObjectMask > | m_mask |
| std::shared_ptr< vpRBDriftDetector > | m_driftDetector |
| std::shared_ptr< vpRBVisualOdometry > | m_odometry |
| std::shared_ptr< vpRBConvergenceMetric > | m_convergenceMetric |
| bool | m_displaySilhouette |
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
For a detailed description of the tracker, how to use it and extend it, see:
Definition at line 86 of file vpRBTracker.h.
| BEGIN_VISP_NAMESPACE vpRBTracker::vpRBTracker | ( | ) |
Definition at line 53 of file vpRBTracker.cpp.
References m_convergenceMetric, m_displaySilhouette, m_driftDetector, m_firstIteration, m_imageHeight, m_imageWidth, m_lambda, m_mask, m_modelChanged, m_muInit, m_muIterFactor, m_odometry, m_renderer, m_rendererIsSetup, m_rendererSettings, m_scaleInvariantOptim, m_trackers, and m_vvsIterations.
|
default |
References getPose(), getRenderer(), and setPose().
| void vpRBTracker::addTracker | ( | std::shared_ptr< vpRBFeatureTracker > | tracker | ) |
Add a new feature to track.
| tracker | the feature to add |
| vpException | if the tracker is null |
Definition at line 673 of file vpRBTracker.cpp.
References vpException::badValue, and m_trackers.
|
inlineprotected |
Check that a given image has the correct dimensions, previously specified with setCameraParameters or in the config file.
| T | Pixel type |
| I | Image to check |
| imgType | Helper string to indicat which image type failed. |
Definition at line 508 of file vpRBTracker.h.
References vpException::dimensionError, m_imageHeight, and m_imageWidth.
| 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.
| I | Grayscale display image |
| IRGB | Color display image |
| depth | Depth display image |
Definition at line 688 of file vpRBTracker.cpp.
References displaySilhouette(), m_currentFrame, m_displaySilhouette, and m_trackers.
| 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.
| Imask | the image into which to write the display representation of the mask. |
Definition at line 681 of file vpRBTracker.cpp.
References m_currentFrame, and m_mask.
|
inlineprotected |
Display the object silhouette of the frame in I.
| T | Pixel type of I |
| I | The image where to display the object silhouette |
| frame | Frame 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().
|
protected |
Converts from pixelwise object silhouette representation to an actionable list of silhouette points.
| Inorm | Image containing normals in object frame |
| Idepth | Render image containing depth, in meters |
| Ior | Image containing the silhouette 2D edge orientation data |
| Ivalid | Image contianing whether a pixel is a silhouette point |
| cam | Camera intrinsics |
| cTcp | Pose of the previous camera in the current camera frame. Used when silhouette extraction settings try to reuse the same silhouette points in successive frames. |
Definition at line 635 of file vpRBTracker.cpp.
References vpException::badValue, m_depthSilhouetteSettings, and m_previousFrame.
Referenced by track().
| vpCameraParameters vpRBTracker::getCameraParameters | ( | ) | const |
Get the camera intrinsics that are used to render the 3D object and process the tracked frames.
Definition at line 101 of file vpRBTracker.cpp.
References m_cam.
| vpMatrix vpRBTracker::getCovariance | ( | ) | const |
Definition at line 78 of file vpRBTracker.cpp.
References vpException::dimensionError, vpArray2D< Type >::getCols(), vpArray2D< Type >::getRows(), m_lambda, m_trackers, and vpMatrix::pseudoInverse().
|
inline |
|
inline |
Get the tracked features.
Definition at line 155 of file vpRBTracker.h.
References m_trackers.
|
inline |
Definition at line 188 of file vpRBTracker.h.
References m_imageHeight.
|
inline |
Definition at line 187 of file vpRBTracker.h.
References m_imageWidth.
|
inline |
Definition at line 205 of file vpRBTracker.h.
References m_vvsIterations.
|
inline |
Get the path to the 3D model to track.
Definition at line 160 of file vpRBTracker.h.
References m_modelPath.
|
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.
Definition at line 128 of file vpRBTracker.h.
References m_currentFrame.
|
inline |
Definition at line 257 of file vpRBTracker.h.
References m_mask.
|
inline |
|
inline |
Definition at line 197 of file vpRBTracker.h.
References m_lambda.
|
inline |
Definition at line 214 of file vpRBTracker.h.
References m_muInit.
|
inline |
Definition at line 223 of file vpRBTracker.h.
References m_muIterFactor.
| 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
| cMo | pose to update |
Definition at line 66 of file vpRBTracker.cpp.
References m_cMo.
Referenced by ~vpRBTracker().
| vpObjectCentricRenderer & vpRBTracker::getRenderer | ( | ) |
Get the renderer used to render the object.
Definition at line 705 of file vpRBTracker.cpp.
References m_renderer.
Referenced by ~vpRBTracker().
|
inline |
Definition at line 190 of file vpRBTracker.h.
References m_depthSilhouetteSettings.
|
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) *
| ImageType | The pixel type for I, either unsigned char or vpRGBa |
| I | the image where to click. It should be associated to a vpDisplay |
| initFile | The path to the initialization file. |
| displayHelp | Whether 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.
| void vpRBTracker::loadConfiguration | ( | const nlohmann::json & | j | ) |
Update the tracker with a new json configuration.
| j | the full json configuration |
| if | the parameters are incorrect |
Definition at line 732 of file vpRBTracker.cpp.
References vpException::badValue, vpDynamicFactory< T >::buildFromJson(), vpObjectMaskFactory::getFactory(), vpRBDriftDetectorFactory::getFactory(), vpRBFeatureTrackerFactory::getFactory(), vpRBConvergenceMetric::loadFromJSON(), m_cam, m_convergenceMetric, m_depthSilhouetteSettings, m_displaySilhouette, m_driftDetector, m_firstIteration, m_imageHeight, m_imageWidth, m_lambda, m_mask, m_muInit, m_muIterFactor, m_odometry, m_scaleInvariantOptim, m_trackers, m_vvsIterations, setCameraParameters(), setMaxOptimizationIters(), setModelPath(), setOptimizationGain(), setOptimizationInitialMu(), setOptimizationMuIterFactor(), and setScaleInvariantRegularization().
Referenced by 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.
| filename | The path to the .json file to load |
| if | the file is ill-formed or settings are incorrect |
Definition at line 711 of file vpRBTracker.cpp.
References vpException::ioError, and loadConfiguration().
| void vpRBTracker::reset | ( | ) |
Definition at line 128 of file vpRBTracker.cpp.
References m_cMo, m_cMoPrev, m_currentFrame, m_driftDetector, m_firstIteration, m_mask, m_odometry, m_previousFrame, and m_trackers.
|
inline |
Definition at line 232 of file vpRBTracker.h.
References m_scaleInvariantOptim.
| 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.
| cMo | the pose of the object in the camera frame to be scored |
| I | Grayscale frame |
| IRGB | Color image |
| depth | Depth image |
| if | no 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().
| 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.
| cam | Camera intrinsics for the color (and potential depth) image. It should follow a model without distortion. |
| h | Image height |
| w | Image width |
| vpException | if camera intrinsics have distortion |
| vpException | if 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().
|
inline |
Sets the method to perform drift detection and estimate tracking confidence. Set to null to disable this functionality.
| detector | the algorithm to use |
Definition at line 249 of file vpRBTracker.h.
References m_driftDetector.
|
inline |
Definition at line 206 of file vpRBTracker.h.
References vpException::badValue, and m_vvsIterations.
Referenced by loadConfiguration().
| void vpRBTracker::setModelPath | ( | const std::string & | path | ) |
Set the path to the 3D model to load.
| path | a 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().
|
inline |
Sets the algorithm to use when performing object segmentation. Set to null to disable the use of segmentation.
| mask | the segmentation method |
Definition at line 264 of file vpRBTracker.h.
References m_mask.
|
inline |
Set the method to use when performing visual odometry to preestimate the camera motion before tracking. If null, then odometry is disabled.
| odometry |
Definition at line 279 of file vpRBTracker.h.
References m_odometry.
|
inline |
Definition at line 198 of file vpRBTracker.h.
References vpException::badValue, and m_lambda.
Referenced by loadConfiguration().
|
inline |
Definition at line 215 of file vpRBTracker.h.
References vpException::badValue, and m_muInit.
Referenced by loadConfiguration().
|
inline |
Definition at line 224 of file vpRBTracker.h.
References vpException::badValue, and m_muIterFactor.
Referenced by loadConfiguration().
| 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.
| cMo | the new object pose |
Definition at line 71 of file vpRBTracker.cpp.
References m_cMo, m_cMoPrev, and m_renderer.
Referenced by initClick(), and ~vpRBTracker().
|
inline |
Definition at line 233 of file vpRBTracker.h.
References m_scaleInvariantOptim.
Referenced by loadConfiguration().
| void vpRBTracker::setSilhouetteExtractionParameters | ( | const vpSilhouettePointsExtractionSettings & | settings | ) |
Definition at line 123 of file vpRBTracker.cpp.
References m_depthSilhouetteSettings.
|
protected |
Setup the renderer, and load the 3D model.
| file | path to the 3D model to load and track |
Definition at line 154 of file vpRBTracker.cpp.
References vpException::badValue, vpIoTools::checkFilename(), vpPanda3DFrameworkManager::enableSingleRenderer(), vpPanda3DFrameworkManager::getInstance(), m_modelChanged, m_renderer, m_rendererIsSetup, m_rendererSettings, m_trackers, and vpPanda3DGeometryRenderer::OBJECT_NORMALS.
Referenced by startTracking().
|
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().
| 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().
| 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
| I | Grayscale image |
| if | Image 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().
| 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
| I | Grayscale image |
| IRGB | Grayscale image |
| if | Image 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().
| 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
| I | Grayscale image |
| IRGB | Grayscale image |
| depth | Depth image, in meters. The Depth image should be aligned with the color and grayscale images. |
| if | Image 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().
|
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().
|
protected |
Update the render data with a render at the last tracked pose.
| frame | the frame to update |
Definition at line 546 of file vpRBTracker.cpp.
References m_cMo, and updateRender().
Referenced by score(), startTracking(), track(), and updateRender().
|
protected |
Update the frame data with renders at a given pose.
| frame | the frame to update |
| cMo | the pose of the object at which to perform rendering |
Definition at line 551 of file vpRBTracker.cpp.
References vpRBRenderData::boundingBox, vpRBRenderData::cMo, vpRBRenderData::depth, vpRBRenderData::isSilhouette, m_depthSilhouetteSettings, m_imageHeight, m_imageWidth, m_renderer, m_rendererSettings, vpRBRenderData::normals, vpRBRenderData::objectCenter, vpRBRenderData::objectDiameter, vpRBFeatureTrackerInput::renders, vpImage< Type >::resize(), shouldRenderSilhouette(), vpRBRenderData::silhouetteCanny, vpRBRenderData::zFar, and vpRBRenderData::zNear.
|
protected |
Camera intrinsics.
Definition at line 543 of file vpRBTracker.h.
Referenced by getCameraParameters(), initClick(), loadConfiguration(), setCameraParameters(), track(), track(), track(), and track().
|
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().
|
protected |
Previous pose of the object in the camera frame.
Definition at line 541 of file vpRBTracker.h.
|
protected |
Definition at line 571 of file vpRBTracker.h.
Referenced by loadConfiguration(), startTracking(), track(), and vpRBTracker().
|
protected |
Definition at line 531 of file vpRBTracker.h.
Referenced by display(), displayMask(), getMostRecentFrame(), reset(), and track().
|
protected |
Settings for silhouette extraction.
Definition at line 557 of file vpRBTracker.h.
Referenced by extractSilhouettePoints(), getSilhouetteExtractionParameters(), loadConfiguration(), setSilhouetteExtractionParameters(), and updateRender().
|
protected |
Metric used to compare the motion between different poses.
Definition at line 573 of file vpRBTracker.h.
Referenced by display(), loadConfiguration(), and vpRBTracker().
|
protected |
Definition at line 568 of file vpRBTracker.h.
Referenced by getDriftDetector(), loadConfiguration(), reset(), score(), setDriftDetector(), track(), and vpRBTracker().
|
protected |
Whether this is the first iteration.
Definition at line 527 of file vpRBTracker.h.
Referenced by loadConfiguration(), reset(), track(), and vpRBTracker().
|
protected |
Color and render image dimensions.
Definition at line 565 of file vpRBTracker.h.
Referenced by checkDimensionsOrThrow(), getImageHeight(), loadConfiguration(), setCameraParameters(), updateRender(), and vpRBTracker().
|
protected |
Definition at line 565 of file vpRBTracker.h.
Referenced by checkDimensionsOrThrow(), getImageWidth(), loadConfiguration(), setCameraParameters(), updateRender(), and vpRBTracker().
|
protected |
Optimization gain.
Definition at line 546 of file vpRBTracker.h.
Referenced by getCovariance(), getOptimizationGain(), loadConfiguration(), setOptimizationGain(), track(), and vpRBTracker().
|
protected |
Definition at line 567 of file vpRBTracker.h.
Referenced by displayMask(), getObjectSegmentationMethod(), loadConfiguration(), reset(), setObjectSegmentationMethod(), track(), and vpRBTracker().
|
protected |
Definition at line 536 of file vpRBTracker.h.
Referenced by setModelPath(), setupRenderer(), and vpRBTracker().
|
protected |
Location of the 3D model to load.
Definition at line 535 of file vpRBTracker.h.
Referenced by getModelPath(), setModelPath(), and startTracking().
|
protected |
Initial mu value for Levenberg-Marquardt.
Definition at line 550 of file vpRBTracker.h.
Referenced by getOptimizationInitialMu(), loadConfiguration(), setOptimizationInitialMu(), track(), and vpRBTracker().
|
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().
|
protected |
Definition at line 569 of file vpRBTracker.h.
Referenced by getOdometryMethod(), loadConfiguration(), reset(), setOdometryMethod(), track(), and vpRBTracker().
|
protected |
Definition at line 532 of file vpRBTracker.h.
Referenced by extractSilhouettePoints(), reset(), and track().
|
protected |
3D renderer
Definition at line 561 of file vpRBTracker.h.
Referenced by displaySilhouette(), getRenderer(), setCameraParameters(), setPose(), setupRenderer(), shouldRenderSilhouette(), startTracking(), updateRender(), and vpRBTracker().
|
protected |
Definition at line 562 of file vpRBTracker.h.
Referenced by setupRenderer(), and vpRBTracker().
|
protected |
Camera specific setup for the 3D Panda renderer.
Definition at line 559 of file vpRBTracker.h.
Referenced by setCameraParameters(), setupRenderer(), updateRender(), and vpRBTracker().
|
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().
|
protected |
List of feature trackers.
Definition at line 529 of file vpRBTracker.h.
Referenced by addTracker(), display(), getCovariance(), getFeatureTrackers(), loadConfiguration(), reset(), setupRenderer(), track(), track(), track(), and vpRBTracker().
|
protected |
Maximum number of optimization iterations.
Definition at line 548 of file vpRBTracker.h.
Referenced by getMaxOptimizationIters(), loadConfiguration(), setMaxOptimizationIters(), track(), and vpRBTracker().
| friend vpRBTracker::vpRBInitializationHelper |
Definition at line 435 of file vpRBTracker.h.
Referenced by initClick().