35#ifndef VP_RB_SILHOUETTE_ME_TRACKER_H
36#define VP_RB_SILHOUETTE_ME_TRACKER_H
38#include <visp3/rbt/vpRBFeatureTracker.h>
39#include <visp3/rbt/vpRBSilhouetteControlPoint.h>
40#include <visp3/core/vpRobust.h>
60 vpRBFeatureTracker(), m_me(), m_numCandidates(1), m_robustMadMin(1.0), m_globalVVSConvergenceThreshold(1.0),
61 m_singlePointConvergedThresholdPixels(3), m_useMask(false), m_minMaskConfidence(0.f)
76 m_controlPoints.clear();
104 if (candidates == 0) {
107 m_numCandidates = candidates;
116 m_robustMadMin = threshold;
136 if (confidence > 1.f || confidence < 0.f) {
139 m_minMaskConfidence = confidence;
145 if (threshold < 0.0) {
148 m_singlePointConvergedThresholdPixels = threshold;
154 if (threshold < 0.0 || threshold > 1.0) {
157 m_globalVVSConvergenceThreshold = threshold;
160#if defined(VISP_HAVE_NLOHMANN_JSON)
167 m_me = j.value(
"movingEdge", m_me);
182 std::vector<vpRBSilhouetteControlPoint> m_controlPoints;
184 unsigned int m_numCandidates;
186 double m_robustMadMin;
187 double m_globalVVSConvergenceThreshold;
188 double m_singlePointConvergedThresholdPixels;
190 float m_minMaskConfidence;
Generic class defining intrinsic camera parameters.
error that can be emitted by ViSP classes.
@ badValue
Used to indicate that a value is not in the allowed range.
Implementation of an homogeneous matrix and operations on such kind of matrices.
Definition of the vpImage class member functions.
virtual void extractFeatures(const vpRBFeatureTrackerInput &frame, const vpRBFeatureTrackerInput &previousFrame, const vpHomogeneousMatrix &cMo)=0
Extract features from the frame data and the current pose estimate.
virtual void trackFeatures(const vpRBFeatureTrackerInput &frame, const vpRBFeatureTrackerInput &previousFrame, const vpHomogeneousMatrix &cMo)=0
Track the features.
virtual void display(const vpCameraParameters &cam, const vpImage< unsigned char > &I, const vpImage< vpRGBa > &IRGB, const vpImage< unsigned char > &depth) const =0
virtual void loadJsonConfiguration(const nlohmann::json &j)
virtual void initVVS(const vpRBFeatureTrackerInput &frame, const vpRBFeatureTrackerInput &previousFrame, const vpHomogeneousMatrix &cMo)=0
virtual void computeVVSIter(const vpRBFeatureTrackerInput &frame, const vpHomogeneousMatrix &cMo, unsigned int iteration)=0
bool requiresRGB() const VP_OVERRIDE
Whether this tracker requires RGB image to extract features.
virtual ~vpRBSilhouetteMeTracker()=default
virtual void loadJsonConfiguration(const nlohmann::json &j) VP_OVERRIDE
void setNumCandidates(unsigned int candidates)
double getSinglePointConvergenceThreshold() const
vpRBSilhouetteMeTracker()
const vpMe & getMe() const
void setMinimumMaskConfidence(float confidence)
float getMinimumMaskConfidence() const
Returns the minimum mask confidence that a pixel linked to depth point should have if it should be ke...
void setSinglePointConvergenceThreshold(double threshold)
bool shouldUseMask() const
Returns whether the tracking algorithm should filter out points that are unlikely to be on the object...
double getGlobalConvergenceMinimumRatio() const
void onTrackingIterEnd(const vpHomogeneousMatrix &) VP_OVERRIDE
Method called after the tracking iteration has finished.
void setGlobalConvergenceMinimumRatio(double threshold)
void setMovingEdge(const vpMe &me)
double getMinRobustThreshold() const
bool requiresSilhouetteCandidates() const VP_OVERRIDE
Whether this tracker requires Silhouette candidates.
void setShouldUseMask(bool useMask)
unsigned int getNumCandidates() const
void setMinRobustThreshold(double threshold)
void onTrackingIterStart(const vpRBFeatureTrackerInput &, const vpHomogeneousMatrix &) VP_OVERRIDE
Method called when starting a tracking iteration.
bool requiresDepth() const VP_OVERRIDE
Whether this tracker requires depth image to extract features.
Contains an M-estimator and various influence function.