![]() |
Visual Servoing Platform version 3.7.0
|
#include <vpRBSilhouetteCCDTracker.h>
Public Types | |
| enum | vpDisplayType { DT_SIMPLE = 0 , DT_WEIGHT = 1 , DT_ERROR = 2 , DT_WEIGHT_AND_ERROR = 3 , DT_INVALID = 4 } |
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 Member Functions | |
| void | updateCCDPoints (const vpHomogeneousMatrix &cMo) |
| void | computeLocalStatistics (const vpImage< vpRGBa > &I, vpCCDStatistics &stats) |
| template<bool hasTemporalSmoothing> | |
| void | computeErrorAndInteractionMatrix (const vpHomogeneousMatrix &cMo) |
| vpMatrix | computeoJo () const |
Protected Attributes | |
| vpCCDParameters | m_ccdParameters |
| std::vector< vpRBSilhouetteControlPoint > | m_controlPoints |
| vpRobust | m_robust |
| vpCCDStatistics | m_stats |
| vpCCDStatistics | m_prevStats |
| vpMatrix | m_sigma |
| double | m_vvsConvergenceThreshold |
| double | tol |
| std::vector< double > | m_gradientData |
| std::vector< double > | m_hessianData |
| std::vector< vpColVector > | m_gradients |
| std::vector< vpMatrix > | m_hessians |
| vpColVector | m_gradient |
| vpMatrix | m_hessian |
| double | m_temporalSmoothingFac |
| bool | m_useMask |
| double | m_minMaskConfidence |
| unsigned int | m_maxPoints |
| vpUniRand | m_random |
| vpDisplayType | m_displayType |
| const vpRBFeatureTrackerInput * | m_previousFrame |
| 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 |
| std::shared_ptr< vpTemporalWeighting > | m_weighting |
| bool | m_vvsConverged |
| bool | m_enableDisplay |
| std::array< bool, 6 > | m_estimatedDofs |
| vpMatrix | m_oJo |
| bool | m_jacobianInObjectSpace |
Static Protected Attributes | |
| static const unsigned int | BASE_SEED = 421 |
Tracking based on the Contracting Curve Density algorithm.
Tutorials
If you want to have an in-depth presentation of the Render-Based Tracker (RBT), you may have a look at:
Definition at line 212 of file vpRBSilhouetteCCDTracker.h.
| Enumerator | |
|---|---|
| DT_SIMPLE | |
| DT_WEIGHT | |
| DT_ERROR | |
| DT_WEIGHT_AND_ERROR | |
| DT_INVALID | |
Definition at line 216 of file vpRBSilhouetteCCDTracker.h.
| vpRBSilhouetteCCDTracker::vpRBSilhouetteCCDTracker | ( | ) |
Definition at line 143 of file vpRBSilhouetteCCDTracker.cpp.
References BASE_SEED, DT_SIMPLE, m_displayType, m_maxPoints, m_minMaskConfidence, m_random, m_temporalSmoothingFac, m_useMask, m_vvsConvergenceThreshold, vpRBFeatureTracker::vpRBFeatureTracker(), and vpRBSilhouetteCCDTracker().
Referenced by vpRBSilhouetteCCDTracker().
|
virtualdefault |
| void vpRBSilhouetteCCDTracker::buildGradientAndHessianStorageViews | ( | unsigned int | normalsPerPoint, |
| bool | clear ) |
Update the gradient and hessian storage views. Reserve new memory if required and ensure that gradients and hessians point on correct memory.
| normalsPerPoint | the size of the normal vector (one side) |
Definition at line 244 of file vpRBSilhouetteCCDTracker.cpp.
References m_controlPoints, m_gradientData, m_gradients, m_hessianData, m_hessians, vpColVector::view(), and vpMatrix::view().
Referenced by changeScale(), and initVVS().
| void vpRBSilhouetteCCDTracker::changeScale | ( | ) |
To be called when the scale of the normal vectors is changed.
Definition at line 297 of file vpRBSilhouetteCCDTracker.cpp.
References buildGradientAndHessianStorageViews(), computeLocalStatistics(), m_ccdParameters, m_controlPoints, vpRBFeatureTracker::m_cov, vpRBFeatureTracker::m_numFeatures, m_previousFrame, m_prevStats, m_sigma, m_stats, m_temporalSmoothingFac, and vpRBFeatureTracker::m_weights.
Referenced by computeVVSIter().
|
staticinherited |
Definition at line 78 of file vpRBFeatureTracker.cpp.
References vpColVector::t(), and vpMatrix::t().
Referenced by updateCovariance().
|
protected |
Definition at line 813 of file vpRBSilhouetteCCDTracker.cpp.
References FastMat63< T >::data, vpArray2D< Type >::getRows(), vpRBFeatureTracker::hasIgnoredDofs(), FastMat33< T >::inverse(), m_ccdParameters, m_controlPoints, vpRBFeatureTracker::m_error, m_gradient, m_gradients, m_hessian, m_hessians, vpRBFeatureTracker::m_jacobianInObjectSpace, vpRBFeatureTracker::m_L, vpRBFeatureTracker::m_LTL, vpRBFeatureTracker::m_LTR, vpRBFeatureTracker::m_oJo, m_prevStats, m_robust, m_sigma, m_stats, m_temporalSmoothingFac, vpRBFeatureTracker::m_weighted_error, vpRBFeatureTracker::m_weights, FastMat63< T >::multiply(), FastVec3< T >::multiply(), FastMat63< T >::multiplyBTranspose(), and vpRobust::TUKEY.
Referenced by computeVVSIter().
|
staticinherited |
Definition at line 56 of file vpRBFeatureTracker.cpp.
References vpArray2D< Type >::data, vpArray2D< Type >::getCols(), vpArray2D< Type >::getRows(), vpMatrixException::incorrectMatrixSizeError, and vpColVector::resize().
Referenced by updateOptimizerTerms().
|
protected |
Definition at line 500 of file vpRBSilhouetteCCDTracker.cpp.
References vpRGBa::B, vpException::badValue, vpCCDStatistics::cov_vic, vpException::fatalError, vpRGBa::G, vpCCDStatistics::imgPoints, m_ccdParameters, m_controlPoints, vpCCDStatistics::mean_vic, vpCCDStatistics::nv, vpRGBa::R, and vpCCDStatistics::vic.
Referenced by changeScale(), computeVVSIter(), and initVVS().
|
inlineprotectedinherited |
Definition at line 284 of file vpRBFeatureTracker.h.
References m_estimatedDofs.
Referenced by setEstimatedDofs().
|
virtual |
Implements vpRBFeatureTracker.
Definition at line 317 of file vpRBSilhouetteCCDTracker.cpp.
References changeScale(), computeErrorAndInteractionMatrix(), computeLocalStatistics(), vpRBFeatureTrackerInput::IRGB, m_ccdParameters, m_controlPoints, vpRBFeatureTracker::m_numFeatures, m_stats, m_temporalSmoothingFac, vpRBFeatureTracker::m_vvsConverged, m_vvsConvergenceThreshold, tol, and updateCCDPoints().
|
virtual |
Implements vpRBFeatureTracker.
Definition at line 371 of file vpRBSilhouetteCCDTracker.cpp.
References vpRGBa::B, vpException::badValue, vpDisplay::displayCross(), vpDisplay::displayPoint(), DT_ERROR, DT_SIMPLE, DT_WEIGHT, DT_WEIGHT_AND_ERROR, vpRGBa::G, vpArray2D< Type >::getMaxValue(), vpColor::green, m_ccdParameters, m_controlPoints, m_displayType, vpRBFeatureTracker::m_error, vpRBFeatureTracker::m_weights, vpRGBa::R, and vpColor::red.
|
virtual |
Extract features from the frame data and the current pose estimate.
Implements vpRBFeatureTracker.
Definition at line 155 of file vpRBSilhouetteCCDTracker.cpp.
References vpRBSilhouetteControlPoint::buildSilhouettePoint(), vpRBFeatureTrackerInput::cam, vpRBRenderData::cMo, vpImage< Type >::getHeight(), vpRBSilhouetteControlPoint::getMaxMaskGradientAlongLine(), vpImage< Type >::getWidth(), vpRBFeatureTrackerInput::hasMask(), vpRBFeatureTrackerInput::I, vpRBSilhouettePoint::i, vpRBSilhouettePoint::isSilhouette, vpRBSilhouetteControlPoint::isValid(), vpRBSilhouettePoint::j, m_ccdParameters, m_controlPoints, m_maxPoints, m_minMaskConfidence, m_random, m_useMask, vpRBFeatureTrackerInput::mask, vpRBSilhouettePoint::normal, vpRBSilhouettePoint::orientation, vpRBFeatureTrackerInput::renders, vpRBFeatureTrackerInput::silhouettePoints, and vpRBSilhouettePoint::Z.
|
inlineinherited |
Definition at line 163 of file vpRBFeatureTracker.h.
References m_enableDisplay.
|
inline |
Definition at line 237 of file vpRBSilhouetteCCDTracker.h.
References m_ccdParameters.
|
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 186 of file vpRBFeatureTracker.h.
References m_cov.
|
inlinevirtualinherited |
Get the left-side term of the Gauss-Newton optimization term.
Definition at line 215 of file vpRBFeatureTracker.h.
References m_LTL.
|
inlinevirtualinherited |
Get the right-side term of the Gauss-Newton optimization term.
Definition at line 220 of file vpRBFeatureTracker.h.
References m_LTR.
|
inline |
Get the maximum number of silhouette control points that will be used by the tracker at a given iteration. If there are more control points on the silhouette than getMaxNumPoints(), they will be subsampled randomly. If maxNumPoints is zero, then all points are used.
Definition at line 287 of file vpRBSilhouetteCCDTracker.h.
References m_maxPoints.
|
inline |
Returns the minimum mask gradient required for a silhouette point to be considered.
This value is between 0 and 1.
Definition at line 276 of file vpRBSilhouetteCCDTracker.h.
References m_minMaskConfidence.
|
inlineinherited |
Return the type of feature that is used by this tracker.
Get the number of features used to compute the pose update
Definition at line 88 of file vpRBFeatureTracker.h.
References m_numFeatures.
|
inline |
Returns the amount of temporal smoothing applied when computing the tracking error and its jacobian. This factor is used to interpolate with the error computed on the previous frame for the features selected at the current iteration. Temporal smoothing may help smooth out the motion and reduce jitter.
Definition at line 246 of file vpRBSilhouetteCCDTracker.h.
References m_temporalSmoothingFac.
|
inlineinherited |
Definition at line 208 of file vpRBFeatureTracker.h.
References m_weighting.
|
inlinevirtual |
Get the importance of this tracker in the optimization step. The default computation is the following:
, where
is the weight defined by setTrackerWeight, and
is the number of features.
Reimplemented from vpRBFeatureTracker.
Definition at line 319 of file vpRBSilhouetteCCDTracker.h.
References vpRBFeatureTracker::m_error, and vpRBFeatureTracker::m_weighting.
|
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 226 of file vpRBFeatureTracker.h.
References m_weighted_error.
|
inlineinherited |
Definition at line 246 of file vpRBFeatureTracker.h.
References m_estimatedDofs.
Referenced by vpRBSilhouetteCCDTracker::computeErrorAndInteractionMatrix().
|
virtual |
Implements vpRBFeatureTracker.
Definition at line 272 of file vpRBSilhouetteCCDTracker.cpp.
References buildGradientAndHessianStorageViews(), computeLocalStatistics(), vpRBFeatureTrackerInput::IRGB, m_ccdParameters, m_controlPoints, vpRBFeatureTracker::m_cov, m_gradient, m_hessian, vpRBFeatureTracker::m_numFeatures, m_previousFrame, m_prevStats, m_sigma, m_stats, m_temporalSmoothingFac, vpRBFeatureTracker::m_vvsConverged, and vpRBFeatureTracker::m_weights.
|
inlinevirtual |
Reimplemented from vpRBFeatureTracker.
Definition at line 362 of file vpRBSilhouetteCCDTracker.h.
References vpRBFeatureTracker::loadJsonConfiguration(), m_ccdParameters, m_displayType, m_maxPoints, m_minMaskConfidence, m_temporalSmoothingFac, m_useMask, m_vvsConvergenceThreshold, setDisplayType(), setMaxNumPoints(), setMinimumMaskConfidence(), setShouldUseMask(), and setTemporalSmoothingFactor().
| vpRBSilhouetteCCDTracker::NLOHMANN_JSON_SERIALIZE_ENUM | ( | vpRBSilhouetteCCDTracker::vpDisplayType | , |
| { {vpRBSilhouetteCCDTracker::vpDisplayType::DT_INVALID, nullptr}, {vpRBSilhouetteCCDTracker::vpDisplayType::DT_SIMPLE, "simple"}, {vpRBSilhouetteCCDTracker::vpDisplayType::DT_WEIGHT, "weight"}, {vpRBSilhouetteCCDTracker::vpDisplayType::DT_ERROR, "error"}, {vpRBSilhouetteCCDTracker::vpDisplayType::DT_WEIGHT_AND_ERROR, "weightAndError"} } | ) |
References DT_ERROR, DT_INVALID, DT_SIMPLE, DT_WEIGHT, and DT_WEIGHT_AND_ERROR.
|
inlinevirtual |
Method called after the tracking iteration has finished.
Implements vpRBFeatureTracker.
Definition at line 303 of file vpRBSilhouetteCCDTracker.h.
|
virtual |
Method called when starting a tracking iteration.
Implements vpRBFeatureTracker.
Definition at line 147 of file vpRBSilhouetteCCDTracker.cpp.
References m_ccdParameters, and m_controlPoints.
|
inlinevirtual |
Whether this tracker requires depth image to extract features.
Implements vpRBFeatureTracker.
Definition at line 229 of file vpRBSilhouetteCCDTracker.h.
|
inlinevirtual |
Whether this tracker requires RGB image to extract features.
Implements vpRBFeatureTracker.
Definition at line 228 of file vpRBSilhouetteCCDTracker.h.
|
inlinevirtual |
Whether this tracker requires Silhouette candidates.
Implements vpRBFeatureTracker.
Definition at line 230 of file vpRBSilhouetteCCDTracker.h.
|
inlinevirtual |
Resets feature state. Can be called when the object changes or is lost, Ensuring that prior data does not influence the tracking behaviour.
Reimplemented from vpRBFeatureTracker.
Definition at line 304 of file vpRBSilhouetteCCDTracker.h.
References BASE_SEED, m_controlPoints, vpRBFeatureTracker::m_error, m_gradientData, m_gradients, m_hessian, m_hessianData, m_previousFrame, m_prevStats, m_random, m_stats, and vpRBFeatureTracker::m_vvsConverged.
|
inline |
Definition at line 236 of file vpRBSilhouetteCCDTracker.h.
References m_ccdParameters.
|
inlineinherited |
Definition at line 238 of file vpRBFeatureTracker.h.
References m_jacobianInObjectSpace.
|
inline |
Definition at line 290 of file vpRBSilhouetteCCDTracker.h.
References vpException::badValue, DT_INVALID, and m_displayType.
Referenced by loadJsonConfiguration().
|
inlineinherited |
Definition at line 255 of file vpRBFeatureTracker.h.
References computeoJo(), m_estimatedDofs, and m_oJo.
Referenced by loadJsonConfiguration(), and vpRBFeatureTracker().
|
inlineinherited |
Definition at line 164 of file vpRBFeatureTracker.h.
References m_enableDisplay.
Referenced by visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker::load_settings().
|
inline |
Definition at line 288 of file vpRBSilhouetteCCDTracker.h.
References m_maxPoints.
Referenced by loadJsonConfiguration().
|
inline |
Definition at line 277 of file vpRBSilhouetteCCDTracker.h.
References m_minMaskConfidence.
Referenced by loadJsonConfiguration().
|
inline |
Definition at line 269 of file vpRBSilhouetteCCDTracker.h.
References m_useMask.
Referenced by loadJsonConfiguration().
|
inline |
Sets the temporal smoothing factor.
| factor | the new temporal smoothing factor. Should be greater than 0 |
Definition at line 255 of file vpRBSilhouetteCCDTracker.h.
References vpException::badValue, and m_temporalSmoothingFac.
Referenced by loadJsonConfiguration().
|
inlineinherited |
Definition at line 210 of file vpRBFeatureTracker.h.
References m_weighting.
Referenced by visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker::load_settings().
|
inlineinherited |
Definition at line 209 of file vpRBFeatureTracker.h.
References m_weighting.
Referenced by visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker::load_settings().
|
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.
Definition at line 268 of file vpRBSilhouetteCCDTracker.h.
References m_useMask.
|
inlinevirtual |
Track the features.
Implements vpRBFeatureTracker.
Definition at line 325 of file vpRBSilhouetteCCDTracker.h.
|
protected |
Definition at line 472 of file vpRBSilhouetteCCDTracker.cpp.
References m_controlPoints.
Referenced by computeVVSIter().
|
inlinevirtual |
Update the covariance matrix.
| lambda | the visual servoing gain |
Reimplemented from vpRBFeatureTracker.
Definition at line 329 of file vpRBSilhouetteCCDTracker.h.
References vpRBFeatureTracker::m_cov, and m_sigma.
|
inlineinherited |
Definition at line 262 of file vpRBFeatureTracker.h.
References computeJTR(), m_covWeightDiag, m_error, m_jacobianInObjectSpace, m_L, m_LTL, m_LTR, m_oJo, m_weighted_error, and m_weights.
Referenced by vpRBDenseDepthTracker::computeVVSIter(), and vpRBSilhouetteMeTracker::computeVVSIter().
|
inlineinherited |
Returns whether the tracker is considered as having converged to the desired pose.
Definition at line 200 of file vpRBFeatureTracker.h.
References m_vvsConverged.
|
staticprotected |
Definition at line 414 of file vpRBSilhouetteCCDTracker.h.
Referenced by reset(), and vpRBSilhouetteCCDTracker().
|
protected |
Definition at line 388 of file vpRBSilhouetteCCDTracker.h.
Referenced by changeScale(), computeErrorAndInteractionMatrix(), computeLocalStatistics(), computeVVSIter(), display(), extractFeatures(), getCCDParameters(), initVVS(), loadJsonConfiguration(), onTrackingIterStart(), and setCCDParameters().
|
protected |
Definition at line 390 of file vpRBSilhouetteCCDTracker.h.
Referenced by buildGradientAndHessianStorageViews(), changeScale(), computeErrorAndInteractionMatrix(), computeLocalStatistics(), computeVVSIter(), display(), extractFeatures(), initVVS(), onTrackingIterStart(), reset(), and updateCCDPoints().
|
protectedinherited |
Right side of the Gauss Newton minimization.
Definition at line 301 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::changeScale(), vpRBDenseDepthTracker::computeVVSIter(), vpRBDenseDepthTracker::extractFeatures(), getCovariance(), vpRBSilhouetteCCDTracker::initVVS(), updateCovariance(), and vpRBSilhouetteCCDTracker::updateCovariance().
|
protectedinherited |
Covariance matrix.
Definition at line 302 of file vpRBFeatureTracker.h.
Referenced by vpRBDenseDepthTracker::computeVVSIter(), vpRBDenseDepthTracker::extractFeatures(), vpRBSilhouetteMeTracker::initVVS(), updateCovariance(), and updateOptimizerTerms().
|
protected |
Definition at line 417 of file vpRBSilhouetteCCDTracker.h.
Referenced by display(), loadJsonConfiguration(), setDisplayType(), and vpRBSilhouetteCCDTracker().
|
protectedinherited |
Whether VVS has converged, should be updated every VVS iteration.
Definition at line 314 of file vpRBFeatureTracker.h.
Referenced by featuresShouldBeDisplayed(), loadJsonConfiguration(), setFeaturesShouldBeDisplayed(), and vpRBFeatureTracker().
|
protectedinherited |
Definition at line 304 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::computeErrorAndInteractionMatrix(), vpRBDenseDepthTracker::computeVVSIter(), vpRBSilhouetteMeTracker::computeVVSIter(), vpRBDenseDepthTracker::display(), vpRBSilhouetteCCDTracker::display(), vpRBDenseDepthTracker::extractFeatures(), vpRBSilhouetteCCDTracker::getVVSTrackerWeight(), vpRBSilhouetteMeTracker::initVVS(), vpRBSilhouetteCCDTracker::reset(), updateCovariance(), and updateOptimizerTerms().
|
protectedinherited |
Whether the tracked features should be displayed.
Definition at line 315 of file vpRBFeatureTracker.h.
Referenced by computeoJo(), hasIgnoredDofs(), and setEstimatedDofs().
|
protected |
Definition at line 406 of file vpRBSilhouetteCCDTracker.h.
Referenced by computeErrorAndInteractionMatrix(), and initVVS().
|
protected |
Definition at line 401 of file vpRBSilhouetteCCDTracker.h.
Referenced by buildGradientAndHessianStorageViews(), and reset().
|
protected |
Definition at line 404 of file vpRBSilhouetteCCDTracker.h.
Referenced by buildGradientAndHessianStorageViews(), computeErrorAndInteractionMatrix(), and reset().
|
protected |
Sum of local gradients.
Definition at line 407 of file vpRBSilhouetteCCDTracker.h.
Referenced by computeErrorAndInteractionMatrix(), initVVS(), and reset().
|
protected |
Definition at line 402 of file vpRBSilhouetteCCDTracker.h.
Referenced by buildGradientAndHessianStorageViews(), and reset().
|
protected |
Definition at line 405 of file vpRBSilhouetteCCDTracker.h.
Referenced by buildGradientAndHessianStorageViews(), and computeErrorAndInteractionMatrix().
|
protectedinherited |
Matrix representation of the estimated DOFS.
Definition at line 317 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::computeErrorAndInteractionMatrix(), setComputeJacobianObjectSpace(), updateOptimizerTerms(), and vpRBFeatureTracker().
|
protectedinherited |
Definition at line 298 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::computeErrorAndInteractionMatrix(), vpRBDenseDepthTracker::computeVVSIter(), vpRBSilhouetteMeTracker::computeVVSIter(), vpRBDenseDepthTracker::extractFeatures(), vpRBSilhouetteMeTracker::initVVS(), updateCovariance(), and updateOptimizerTerms().
|
protectedinherited |
Error jacobian (In VS terms, the interaction matrix).
Definition at line 299 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::computeErrorAndInteractionMatrix(), vpRBDenseDepthTracker::computeVVSIter(), getLTL(), and updateOptimizerTerms().
|
protectedinherited |
Left side of the Gauss newton minimization.
Definition at line 300 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::computeErrorAndInteractionMatrix(), vpRBDenseDepthTracker::computeVVSIter(), vpRBSilhouetteMeTracker::computeVVSIter(), getLTR(), and updateOptimizerTerms().
|
protected |
Definition at line 413 of file vpRBSilhouetteCCDTracker.h.
Referenced by extractFeatures(), getMaxNumPoints(), loadJsonConfiguration(), setMaxNumPoints(), and vpRBSilhouetteCCDTracker().
|
protected |
Definition at line 411 of file vpRBSilhouetteCCDTracker.h.
Referenced by extractFeatures(), getMinimumMaskConfidence(), loadJsonConfiguration(), setMinimumMaskConfidence(), and vpRBSilhouetteCCDTracker().
|
protectedinherited |
Error weights.
Definition at line 309 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::changeScale(), vpRBDenseDepthTracker::computeVVSIter(), vpRBSilhouetteCCDTracker::computeVVSIter(), vpRBSilhouetteMeTracker::computeVVSIter(), vpRBDenseDepthTracker::extractFeatures(), vpRBSilhouetteMeTracker::extractFeatures(), getNumFeatures(), getVVSTrackerWeight(), vpRBSilhouetteCCDTracker::initVVS(), vpRBSilhouetteMeTracker::initVVS(), and vpRBFeatureTracker().
|
protectedinherited |
Definition at line 316 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::computeErrorAndInteractionMatrix(), setEstimatedDofs(), and updateOptimizerTerms().
|
protected |
Definition at line 418 of file vpRBSilhouetteCCDTracker.h.
Referenced by changeScale(), initVVS(), and reset().
|
protected |
Definition at line 394 of file vpRBSilhouetteCCDTracker.h.
Referenced by changeScale(), computeErrorAndInteractionMatrix(), initVVS(), and reset().
|
protected |
Definition at line 415 of file vpRBSilhouetteCCDTracker.h.
Referenced by extractFeatures(), reset(), and vpRBSilhouetteCCDTracker().
|
protected |
Silhouette points where to compute CCD statistics.
Definition at line 391 of file vpRBSilhouetteCCDTracker.h.
Referenced by computeErrorAndInteractionMatrix().
|
protected |
Definition at line 396 of file vpRBSilhouetteCCDTracker.h.
Referenced by changeScale(), computeErrorAndInteractionMatrix(), initVVS(), and updateCovariance().
|
protected |
Definition at line 393 of file vpRBSilhouetteCCDTracker.h.
Referenced by changeScale(), computeErrorAndInteractionMatrix(), computeVVSIter(), initVVS(), and reset().
|
protected |
Sum of local hessians.
Definition at line 408 of file vpRBSilhouetteCCDTracker.h.
Referenced by changeScale(), computeErrorAndInteractionMatrix(), computeVVSIter(), getTemporalSmoothingFactor(), initVVS(), loadJsonConfiguration(), setTemporalSmoothingFactor(), and vpRBSilhouetteCCDTracker().
|
protected |
Smoothing factor used to integrate data from the previous frame.
Definition at line 410 of file vpRBSilhouetteCCDTracker.h.
Referenced by extractFeatures(), loadJsonConfiguration(), setShouldUseMask(), shouldUseMask(), and vpRBSilhouetteCCDTracker().
|
protectedinherited |
User-defined weight for this specific type of feature.
Definition at line 312 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::computeVVSIter(), vpRBSilhouetteMeTracker::computeVVSIter(), vpRBSilhouetteCCDTracker::initVVS(), vpRBSilhouetteMeTracker::initVVS(), vpRBSilhouetteCCDTracker::reset(), vpRBFeatureTracker(), and vvsHasConverged().
|
protected |
Definition at line 398 of file vpRBSilhouetteCCDTracker.h.
Referenced by computeVVSIter(), loadJsonConfiguration(), and vpRBSilhouetteCCDTracker().
|
protectedinherited |
Raw VS Error vector.
Definition at line 305 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::computeErrorAndInteractionMatrix(), vpRBDenseDepthTracker::computeVVSIter(), vpRBDenseDepthTracker::extractFeatures(), getWeightedError(), vpRBSilhouetteMeTracker::initVVS(), and updateOptimizerTerms().
|
protectedinherited |
Number of considered features.
Definition at line 310 of file vpRBFeatureTracker.h.
Referenced by getTemporalTrackerWeight(), getVVSTrackerWeight(), vpRBSilhouetteCCDTracker::getVVSTrackerWeight(), loadJsonConfiguration(), setTrackerWeight(), setTrackerWeight(), and vpRBFeatureTracker().
|
protectedinherited |
Weighted VS error.
Definition at line 306 of file vpRBFeatureTracker.h.
Referenced by vpRBSilhouetteCCDTracker::changeScale(), vpRBSilhouetteCCDTracker::computeErrorAndInteractionMatrix(), vpRBDenseDepthTracker::computeVVSIter(), vpRBSilhouetteMeTracker::computeVVSIter(), vpRBDenseDepthTracker::display(), vpRBSilhouetteCCDTracker::display(), vpRBDenseDepthTracker::extractFeatures(), vpRBSilhouetteCCDTracker::initVVS(), vpRBSilhouetteMeTracker::initVVS(), and updateOptimizerTerms().
|
protected |
Definition at line 399 of file vpRBSilhouetteCCDTracker.h.
Referenced by computeVVSIter().