Visual Servoing Platform  version 3.6.1 under development (2024-07-27)

#include <visp3/me/vpMe.h>

Public Types

enum  vpLikelihoodThresholdType { OLD_THRESHOLD = 0 , NORMALIZED_THRESHOLD = 1 }
 

Public Member Functions

 vpMe ()
 
 vpMe (const vpMe &me)
 
virtual ~vpMe ()
 
vpMeoperator= (const vpMe &me)
 
vpMeoperator= (const vpMe &&me)
 
void checkSamplestep (double &sample_step)
 
unsigned int getAngleStep () const
 
vpMatrixgetMask () const
 
unsigned int getMaskNumber () const
 
int getMaskSign () const
 
unsigned int getMaskSize () const
 
double getMinSampleStep () const
 
double getMu1 () const
 
double getMu2 () const
 
int getNbTotalSample () const
 
int getPointsToTrack () const
 
unsigned int getRange () const
 
double getSampleStep () const
 
int getStrip () const
 
double getThreshold () const
 
double getThresholdMarginRatio () const
 
double getMinThreshold () const
 
bool getUseAutomaticThreshold () const
 
vpLikelihoodThresholdType getLikelihoodThresholdType () const
 
void initMask ()
 
void print ()
 
void setAngleStep (const unsigned int &anglestep)
 
void setMaskNumber (const unsigned int &mask_number)
 
void setMaskSign (const int &mask_sign)
 
void setMaskSize (const unsigned int &mask_size)
 
void setMinSampleStep (const double &min_samplestep)
 
void setMu1 (const double &mu_1)
 
void setMu2 (const double &mu_2)
 
void setNbTotalSample (const int &ntotal_sample)
 
void setPointsToTrack (const int &points_to_track)
 
void setRange (const unsigned int &range)
 
void setSampleStep (const double &sample_step)
 
void setStrip (const int &strip)
 
void setThreshold (const double &threshold)
 
void setThresholdMarginRatio (const double &thresholdMarginRatio)
 
void setMinThreshold (const double &minThreshold)
 
void setLikelihoodThresholdType (const vpLikelihoodThresholdType likelihood_threshold_type)
 

Friends

void to_json (nlohmann::json &j, const vpMe &me)
 
void from_json (const nlohmann::json &j, vpMe &me)
 

Detailed Description

This class defines predetermined masks for sites and holds moving edges tracking parameters.

JSON serialization

Since ViSP 3.6.0, if ViSP is build with JSON for modern C++ 3rd-party we introduce JSON serialization capabilities for vpMe. The following sample code shows how to save moving-edges settings in a file named me.json and reload the values from this JSON file.

#include <visp3/me/vpMe.h>
#ifdef ENABLE_VISP_NAMESPACE
using namespace VISP_NAMESPACE_NAME;
#endif
int main()
{
#if defined(VISP_HAVE_NLOHMANN_JSON)
std::string filename = "me.json";
{
vpMe me;
me.setThreshold(20); // Value in range [0 ; 255]
me.setThresholdMarginRatio(-1.); // Deactivate automatic thresholding
me.setMinThreshold(-1.); // Deactivate automatic thresholding
me.setMaskNumber(180);
me.setMaskSign(0);
me.setMu1(0.5);
me.setMu2(0.5);
me.setRange(5);
me.setStrip(2);
std::ofstream file(filename);
const nlohmann::json j = me;
file << j;
file.close();
}
{
std::ifstream file(filename);
const nlohmann::json j = nlohmann::json::parse(file);
vpMe me;
me = j;
file.close();
std::cout << "Read moving-edges settings from " << filename << ":" << std::endl;
me.print();
}
#endif
}
Definition: vpMe.h:134
void setMu1(const double &mu_1)
Definition: vpMe.h:385
void setMinThreshold(const double &minThreshold)
Definition: vpMe.h:491
void setPointsToTrack(const int &points_to_track)
Definition: vpMe.h:408
void print()
Definition: vpMe.cpp:404
void setMaskSign(const int &mask_sign)
Definition: vpMe.h:361
void setRange(const unsigned int &range)
Definition: vpMe.h:415
void setLikelihoodThresholdType(const vpLikelihoodThresholdType likelihood_threshold_type)
Definition: vpMe.h:505
void setNbTotalSample(const int &ntotal_sample)
Definition: vpMe.h:399
void setMaskNumber(const unsigned int &mask_number)
Definition: vpMe.cpp:552
void setThreshold(const double &threshold)
Definition: vpMe.h:466
void setStrip(const int &strip)
Definition: vpMe.h:429
void setThresholdMarginRatio(const double &thresholdMarginRatio)
Definition: vpMe.h:475
void setMu2(const double &mu_2)
Definition: vpMe.h:392
@ NORMALIZED_THRESHOLD
Definition: vpMe.h:145

If you build and execute the sample code, it will produce the following output:

Read moving-edges settings from me.json:
Moving edges settings
Size of the convolution masks....5x5 pixels
Number of masks..................180
Query range +/- J................5 pixels
Likelihood threshold type........normalized
Likelihood threshold.............20
Likelihood margin ratio..........unused
Minimum likelihood threshold.....unused
Contrast tolerance +/-...........50% and 50%
Sample step......................10 pixels
Strip............................2 pixels
Min sample step..................4 pixels

The content of the me.json file is the following:

$ cat me.json
{"maskSign":0,"maskSize":5,"minSampleStep":4.0,"mu":[0.5,0.5],"nMask":180,"ntotalSample":0,"pointsToTrack":200,
"range":5,"sampleStep":10.0,"strip":2,"threshold":20.0,"thresholdMarginRatio":-1.0,"minThreshold":-1.0,"thresholdType":"normalized"}
Examples
mbtEdgeKltTracking.cpp, mbtEdgeTracking.cpp, mbtGenericTracking.cpp, mbtGenericTracking2.cpp, mbtGenericTrackingDepth.cpp, perfGenericTracker.cpp, servoAfma62DhalfCamVelocity.cpp, servoAfma6Cylinder2DCamVelocity.cpp, servoAfma6Cylinder2DCamVelocitySecondaryTask.cpp, servoAfma6Line2DCamVelocity.cpp, servoAfma6SquareLines2DCamVelocity.cpp, servoAfma6TwoLines2DCamVelocity.cpp, testGenericTracker.cpp, testGenericTrackerDeterminist.cpp, testKeyPoint-2.cpp, testKeyPoint-4.cpp, trackMeCircle.cpp, trackMeEllipse.cpp, trackMeLine.cpp, trackMeNurbs.cpp, tutorial-detection-object-mbt-deprecated.cpp, tutorial-detection-object-mbt.cpp, tutorial-detection-object-mbt2-deprecated.cpp, tutorial-detection-object-mbt2.cpp, tutorial-mb-edge-tracker.cpp, tutorial-mb-generic-tracker-apriltag-rs2.cpp, tutorial-mb-generic-tracker-apriltag-webcam.cpp, tutorial-mb-generic-tracker-full.cpp, tutorial-mb-generic-tracker-live.cpp, tutorial-mb-generic-tracker-rgbd.cpp, tutorial-mb-generic-tracker-stereo-mono.cpp, tutorial-mb-generic-tracker.cpp, tutorial-mb-hybrid-tracker.cpp, tutorial-mb-tracker-full.cpp, tutorial-mb-tracker.cpp, tutorial-me-ellipse-tracker.cpp, and tutorial-me-line-tracker.cpp.

Definition at line 133 of file vpMe.h.

Member Enumeration Documentation

◆ vpLikelihoodThresholdType

Type of likelihood threshold to use.

Enumerator
OLD_THRESHOLD 

Old likelihood ratio threshold (to be avoided).

NORMALIZED_THRESHOLD 

Easy-to-use normalized likelihood threshold corresponding to the minimal luminance contrast to consider with values in [0 ; 255].

Definition at line 139 of file vpMe.h.

Constructor & Destructor Documentation

◆ vpMe() [1/2]

vpMe::vpMe ( )

Default constructor.

Definition at line 432 of file vpMe.cpp.

References initMask().

◆ vpMe() [2/2]

vpMe::vpMe ( const vpMe me)

Copy constructor.

Definition at line 460 of file vpMe.cpp.

◆ ~vpMe()

vpMe::~vpMe ( )
virtual

Destructor.

Definition at line 544 of file vpMe.cpp.

Member Function Documentation

◆ checkSamplestep()

void vpMe::checkSamplestep ( double &  sample_step)
inline

Check sample step wrt min value.

Parameters
[in,out]sample_step: When this value is lower than the min sample step value, it is modified to the min sample step value.

Definition at line 181 of file vpMe.h.

◆ getAngleStep()

unsigned int vpMe::getAngleStep ( ) const
inline

Return the angle step.

Returns
Value of angle step.

Definition at line 193 of file vpMe.h.

Referenced by vpMeSite::convolution().

◆ getLikelihoodThresholdType()

vpLikelihoodThresholdType vpMe::getLikelihoodThresholdType ( ) const
inline

Return the selected choice for the likelihood threshold.

Returns
The likelihood threshold type to consider.
See also
setLikelihoodThresholdType(), setThreshold(), getThreshold()
Examples
trackMeEllipse.cpp.

Definition at line 327 of file vpMe.h.

Referenced by vpMeSite::track().

◆ getMask()

vpMatrix* vpMe::getMask ( ) const
inline

Get the matrix of the mask.

Returns
the value of mask.

Definition at line 200 of file vpMe.h.

Referenced by vpMeSite::convolution().

◆ getMaskNumber()

unsigned int vpMe::getMaskNumber ( ) const
inline

Return the number of mask applied to determine the object contour. The number of mask determines the precision of the normal of the edge for every sample. If precision is 2deg, then there are 360/2 = 180 masks.

Returns
the current number of mask.

Definition at line 209 of file vpMe.h.

◆ getMaskSign()

int vpMe::getMaskSign ( ) const
inline

Return the mask sign.

Returns
Value of mask_sign.

Definition at line 216 of file vpMe.h.

◆ getMaskSize()

unsigned int vpMe::getMaskSize ( ) const
inline

Return the actual mask size (in pixel) used to compute the image gradient and determine the object contour. The mask size defines the size of the convolution mask used to detect an edge.

Returns
the current mask size.

Definition at line 225 of file vpMe.h.

Referenced by vpMeSite::convolution(), and vpMeSite::track().

◆ getMinSampleStep()

double vpMe::getMinSampleStep ( ) const
inline

Get the minimum allowed sample step. Useful to specify a lower bound when the sample step is changed.

Returns
Value of min sample step.

Definition at line 233 of file vpMe.h.

◆ getMinThreshold()

double vpMe::getMinThreshold ( ) const
inline

Return the minimum contrast threshold of the vpMeSite that can be used when using the automatic threshold computation.

Returns
Value of the minimum contrast threshold.
See also
setThresholdMarginRatio(), getThresholdMarginRatio(), setMinThreshold(), getLikelihoodThresholdType(), setLikelihoodThresholdType()

Definition at line 310 of file vpMe.h.

Referenced by vpMeSite::setContrastThreshold().

◆ getMu1()

double vpMe::getMu1 ( ) const
inline

Get the minimum image contrast allowed to detect a contour.

Returns
Value of mu1.

Definition at line 240 of file vpMe.h.

Referenced by vpMeSite::track().

◆ getMu2()

double vpMe::getMu2 ( ) const
inline

Get the maximum image contrast allowed to detect a contour.

Returns
Value of mu2.

Definition at line 247 of file vpMe.h.

Referenced by vpMeSite::track().

◆ getNbTotalSample()

int vpMe::getNbTotalSample ( ) const
inline

Get how many discretized points are used to track the feature.

Returns
Value of ntotal_sample.

Definition at line 254 of file vpMe.h.

◆ getPointsToTrack()

int vpMe::getPointsToTrack ( ) const
inline

Return the number of points to track.

Returns
Value of points_to_track.

Definition at line 261 of file vpMe.h.

Referenced by vpMeNurbs::localReSample(), and vpMeNurbs::sample().

◆ getRange()

unsigned int vpMe::getRange ( ) const
inline

◆ getSampleStep()

◆ getStrip()

int vpMe::getStrip ( ) const
inline

Get the number of pixels that are ignored around the image borders.

Returns
the value of strip.

Definition at line 282 of file vpMe.h.

Referenced by vpMeSite::convolution().

◆ getThreshold()

double vpMe::getThreshold ( ) const
inline

Return the likelihood threshold used to determine if the moving edge is valid or not.

Returns
Value of the likelihood threshold.
See also
setThreshold(), getLikelihoodThresholdType(), setLikelihoodThresholdType()
Examples
trackMeEllipse.cpp.

Definition at line 291 of file vpMe.h.

Referenced by vpMeSite::setContrastThreshold().

◆ getThresholdMarginRatio()

double vpMe::getThresholdMarginRatio ( ) const
inline

Return the ratio of the initial contrast to use to initialize the contrast threshold of the vpMeSite.

Returns
Value of the likelihood threshold ratio, between 0 and 1.
See also
setThresholdMarginRatio(), setMinThreshold(), getMinThreshold(), getLikelihoodThresholdType(), setLikelihoodThresholdType()

Definition at line 300 of file vpMe.h.

Referenced by vpMeEllipse::plugHoles(), vpMeEllipse::sample(), and vpMeLine::sample().

◆ getUseAutomaticThreshold()

bool vpMe::getUseAutomaticThreshold ( ) const
inline

Indicates if the contrast threshold of the vpMeSite is automatically computed.

Returns
true The contrast threshold of the vpMeSite is automatically computed.
false The vpMe::m_threshold is used as a global threshold.

Definition at line 318 of file vpMe.h.

Referenced by vpMeSite::setContrastThreshold().

◆ initMask()

BEGIN_VISP_NAMESPACE void vpMe::initMask ( )

Initialise the array of matrices with the defined size and the number of matrices to create.

Definition at line 383 of file vpMe.cpp.

Referenced by operator=(), setMaskNumber(), setMaskSize(), and vpMe().

◆ operator=() [1/2]

vpMe & vpMe::operator= ( const vpMe &&  me)

Move operator.

Definition at line 515 of file vpMe.cpp.

References initMask().

◆ operator=() [2/2]

vpMe & vpMe::operator= ( const vpMe me)

Copy operator.

Definition at line 485 of file vpMe.cpp.

References initMask().

◆ print()

void vpMe::print ( )

Print using std::cout moving edges settings.

Examples
tutorial-mb-generic-tracker.cpp.

Definition at line 404 of file vpMe.cpp.

References NORMALIZED_THRESHOLD.

◆ setAngleStep()

void vpMe::setAngleStep ( const unsigned int &  anglestep)
inline

Set the angle step.

Parameters
anglestep: New angle step value.

Definition at line 345 of file vpMe.h.

◆ setLikelihoodThresholdType()

void vpMe::setLikelihoodThresholdType ( const vpLikelihoodThresholdType  likelihood_threshold_type)
inline

Set the likelihood threshold type used to determine if the moving edge is valid or not.

Parameters
likelihood_threshold_type: Likelihood threshold type. It is recommended to use NORMALIZED_THRESHOLD and set the threshold using setThreshold() with a value corresponding to the minimal luminance contrast to consider that can handle values in range [0 ; 255].
See also
setThreshold()
Examples
mbtEdgeKltTracking.cpp, mbtEdgeTracking.cpp, mbtGenericTracking.cpp, mbtGenericTracking2.cpp, mbtGenericTrackingDepth.cpp, perfGenericTracker.cpp, servoAfma62DhalfCamVelocity.cpp, servoAfma6Cylinder2DCamVelocity.cpp, servoAfma6Cylinder2DCamVelocitySecondaryTask.cpp, servoAfma6Line2DCamVelocity.cpp, servoAfma6SquareLines2DCamVelocity.cpp, servoAfma6TwoLines2DCamVelocity.cpp, testGenericTracker.cpp, testGenericTrackerDeterminist.cpp, testKeyPoint-2.cpp, testKeyPoint-4.cpp, trackMeCircle.cpp, trackMeEllipse.cpp, trackMeLine.cpp, trackMeNurbs.cpp, tutorial-detection-object-mbt-deprecated.cpp, tutorial-detection-object-mbt.cpp, tutorial-detection-object-mbt2-deprecated.cpp, tutorial-detection-object-mbt2.cpp, tutorial-mb-edge-tracker.cpp, tutorial-mb-generic-tracker-apriltag-rs2.cpp, tutorial-mb-generic-tracker-apriltag-webcam.cpp, tutorial-mb-generic-tracker-full.cpp, tutorial-mb-generic-tracker-live.cpp, tutorial-mb-generic-tracker-rgbd.cpp, tutorial-mb-generic-tracker-stereo-mono.cpp, tutorial-mb-generic-tracker.cpp, tutorial-mb-hybrid-tracker.cpp, tutorial-mb-tracker-full.cpp, tutorial-mb-tracker.cpp, tutorial-me-ellipse-tracker.cpp, and tutorial-me-line-tracker.cpp.

Definition at line 505 of file vpMe.h.

◆ setMaskNumber()

◆ setMaskSign()

void vpMe::setMaskSign ( const int &  mask_sign)
inline

Set the mask sign.

Parameters
mask_sign: New mask sign.

Definition at line 361 of file vpMe.h.

◆ setMaskSize()

◆ setMinSampleStep()

void vpMe::setMinSampleStep ( const double &  min_samplestep)
inline

Set the minimum allowed sample step. Useful to specify a lower bound when the sample step is changed.

Parameters
min_samplestep: New minimum sample step.

Definition at line 378 of file vpMe.h.

◆ setMinThreshold()

void vpMe::setMinThreshold ( const double &  minThreshold)
inline

Set the minimum value of the contrast threshold of the vpMeSite.

Parameters
minThresholdMinimum value of the contrast threshold.
See also
getMinThreshold(), setThresholdMarginRatio(), getThresholdMarginRatio(), getLikelihoodThresholdType(), setLikelihoodThresholdType()

Definition at line 491 of file vpMe.h.

◆ setMu1()

◆ setMu2()

◆ setNbTotalSample()

void vpMe::setNbTotalSample ( const int &  ntotal_sample)
inline

Set how many discretized points are used to track the feature.

Parameters
ntotal_sample: New total number of sample.
Examples
testKeyPoint-2.cpp, testKeyPoint-4.cpp, tutorial-detection-object-mbt-deprecated.cpp, tutorial-detection-object-mbt.cpp, tutorial-detection-object-mbt2-deprecated.cpp, and tutorial-detection-object-mbt2.cpp.

Definition at line 399 of file vpMe.h.

◆ setPointsToTrack()

void vpMe::setPointsToTrack ( const int &  points_to_track)
inline

Set the number of points to track.

Parameters
points_to_track: New number of points to track.
Warning
This method is useful only for the vpMeNurbsTracker.
Examples
servoAfma62DhalfCamVelocity.cpp, servoAfma6Cylinder2DCamVelocity.cpp, servoAfma6Cylinder2DCamVelocitySecondaryTask.cpp, servoAfma6Line2DCamVelocity.cpp, servoAfma6SquareLines2DCamVelocity.cpp, servoAfma6TwoLines2DCamVelocity.cpp, trackMeLine.cpp, and trackMeNurbs.cpp.

Definition at line 408 of file vpMe.h.

◆ setRange()

void vpMe::setRange ( const unsigned int &  range)
inline

Set the seek range on both sides of the reference pixel.

Parameters
range: New range.
Examples
mbtEdgeKltTracking.cpp, mbtEdgeTracking.cpp, mbtGenericTracking.cpp, mbtGenericTracking2.cpp, mbtGenericTrackingDepth.cpp, perfGenericTracker.cpp, servoAfma62DhalfCamVelocity.cpp, servoAfma6Cylinder2DCamVelocity.cpp, servoAfma6Cylinder2DCamVelocitySecondaryTask.cpp, servoAfma6Line2DCamVelocity.cpp, servoAfma6SquareLines2DCamVelocity.cpp, servoAfma6TwoLines2DCamVelocity.cpp, testGenericTracker.cpp, testGenericTrackerDeterminist.cpp, testKeyPoint-2.cpp, testKeyPoint-4.cpp, trackMeCircle.cpp, trackMeEllipse.cpp, trackMeLine.cpp, trackMeNurbs.cpp, tutorial-detection-object-mbt-deprecated.cpp, tutorial-detection-object-mbt.cpp, tutorial-detection-object-mbt2-deprecated.cpp, tutorial-detection-object-mbt2.cpp, tutorial-mb-edge-tracker.cpp, tutorial-mb-generic-tracker-apriltag-rs2.cpp, tutorial-mb-generic-tracker-apriltag-webcam.cpp, tutorial-mb-generic-tracker-full.cpp, tutorial-mb-generic-tracker-live.cpp, tutorial-mb-generic-tracker-rgbd.cpp, tutorial-mb-generic-tracker-stereo-mono.cpp, tutorial-mb-generic-tracker.cpp, tutorial-mb-hybrid-tracker.cpp, tutorial-mb-tracker-full.cpp, tutorial-mb-tracker.cpp, tutorial-me-ellipse-tracker.cpp, and tutorial-me-line-tracker.cpp.

Definition at line 415 of file vpMe.h.

Referenced by vpMeTracker::initTracking(), vpMeNurbs::localReSample(), vpMeEllipse::plugHoles(), vpMeLine::seekExtremities(), vpMeNurbs::seekExtremities(), and vpMeNurbs::seekExtremitiesCanny().

◆ setSampleStep()

◆ setStrip()

void vpMe::setStrip ( const int &  strip)
inline

Set the number of pixels that are ignored around the image borders.

Parameters
strip: New strip.

Definition at line 429 of file vpMe.h.

◆ setThreshold()

void vpMe::setThreshold ( const double &  threshold)
inline

Set the likelihood threshold used to determined if the moving edge is valid or not.

Parameters
threshold: Threshold to consider. Two different cases need to be considered depending on the likelihood threshold type that can be set using setLikelihoodThresholdType() or get using getLikelihoodThresholdType(). The default likelihood threshold type is set to OLD_THRESHOLD to keep compatibility with ViSP previous releases, but it is recommended to use rather the NORMALIZED_THRESHOLD type like in the following sample code. When doing so, the threshold is more easy to set since it corresponds to the minimal luminance contrast to consider with values in range [0 ; 255].
vpMe me;
me.setThreshold(20); // Value in range [0 ; 255]
me.setThresholdMarginRatio(-1.); // Deactivate automatic thresholding
me.setMinThreshold(-1.); // Deactivate automatic thresholding

When the likelihood threshold type is set by default to OLD_THRESHOLD like in the next example, values of the likelihood threshold depends on the minimal luminance contrast to consider and the mask size that can be set using setMaskSize() and retrieved using getMaskSize().

vpMe me; // By default the constructor set the threshold type to OLD_THRESHOLD
me.setThreshold(10000); // Value that depends on the minimal luminance contrast to consider and the mask size.
me.setThresholdMarginRatio(-1.); // Deactivate automatic thresholding
me.setMinThreshold(-1.); // Deactivate automatic thresholding

The previous sample code is similar to the next one:

vpMe me;
me.setThreshold(10000); // Value that depends on the minimal luminance contrast to consider and the mask size.
me.setThresholdMarginRatio(-1.); // Deactivate automatic thresholding
me.setMinThreshold(-1.); // Deactivate automatic thresholding
@ OLD_THRESHOLD
Old likelihood ratio threshold (to be avoided).
Definition: vpMe.h:142
See also
getThreshold(), getLikelihoodThresholdType()
Examples
mbtEdgeKltTracking.cpp, mbtEdgeTracking.cpp, mbtGenericTracking.cpp, mbtGenericTracking2.cpp, mbtGenericTrackingDepth.cpp, perfGenericTracker.cpp, servoAfma62DhalfCamVelocity.cpp, servoAfma6Cylinder2DCamVelocity.cpp, servoAfma6Cylinder2DCamVelocitySecondaryTask.cpp, servoAfma6Line2DCamVelocity.cpp, servoAfma6SquareLines2DCamVelocity.cpp, servoAfma6TwoLines2DCamVelocity.cpp, testGenericTracker.cpp, testGenericTrackerDeterminist.cpp, testKeyPoint-2.cpp, testKeyPoint-4.cpp, trackMeCircle.cpp, trackMeEllipse.cpp, trackMeLine.cpp, trackMeNurbs.cpp, tutorial-detection-object-mbt-deprecated.cpp, tutorial-detection-object-mbt.cpp, tutorial-detection-object-mbt2-deprecated.cpp, tutorial-detection-object-mbt2.cpp, tutorial-mb-edge-tracker.cpp, tutorial-mb-generic-tracker-apriltag-rs2.cpp, tutorial-mb-generic-tracker-apriltag-webcam.cpp, tutorial-mb-generic-tracker-full.cpp, tutorial-mb-generic-tracker-live.cpp, tutorial-mb-generic-tracker-rgbd.cpp, tutorial-mb-generic-tracker-stereo-mono.cpp, tutorial-mb-generic-tracker.cpp, tutorial-mb-hybrid-tracker.cpp, tutorial-mb-tracker-full.cpp, tutorial-mb-tracker.cpp, tutorial-me-ellipse-tracker.cpp, and tutorial-me-line-tracker.cpp.

Definition at line 466 of file vpMe.h.

◆ setThresholdMarginRatio()

void vpMe::setThresholdMarginRatio ( const double &  thresholdMarginRatio)
inline

Set the the ratio of the initial contrast to use to initialize the contrast threshold of the vpMeSite.

Parameters
thresholdMarginRatioValue of the likelihood threshold ratio, between 0 and 1.
See also
getThresholdMarginRatio(), setMinThreshold(), getMinThreshold(), getLikelihoodThresholdType(), setLikelihoodThresholdType()

Definition at line 475 of file vpMe.h.

References vpException::badValue.

Friends And Related Function Documentation

◆ from_json

void from_json ( const nlohmann::json &  j,
vpMe me 
)
friend

Retrieve a vpMe object from a JSON representation.

JSON content (key: type):

Example:

{
"angleStep": 1,
"maskSign": 0,
"maskSize": 5,
"minSampleStep": 4.0,
"mu": [
0.5,
0.5
],
"nMask": 180,
"ntotal_sample": 0,
"pointsToTrack": 500,
"range": 7,
"sampleStep": 4.0,
"strip": 2,
"thresholdType": "normalized",
"threshold": 20.0,
"thresholdMarginRatio": 0.75,
"minThreshold": 20.0,
}
Parameters
jJSON representation to convert
meconverted object

Definition at line 618 of file vpMe.h.

◆ to_json

void to_json ( nlohmann::json &  j,
const vpMe me 
)
friend

Convert a vpMe object to a JSON representation.

Parameters
j: Resulting json object.
me: The object to convert.

Definition at line 598 of file vpMe.h.