Visual Servoing Platform  version 3.5.1 under development (2023-09-22)

#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
 
int getStrip () const
 
double getThreshold () const
 
vpLikelihoodThresholdType getLikelihoodThresholdType () const
 
void initMask ()
 
void print ()
 
void setAngleStep (const unsigned int &a)
 
void setMaskNumber (const unsigned int &a)
 
void setMaskSign (const int &a)
 
void setMaskSize (const unsigned int &a)
 
void setMinSampleStep (const double &min)
 
void setMu1 (const double &mu_1)
 
void setMu2 (const double &mu_2)
 
void setNbTotalSample (const int &nb)
 
void setPointsToTrack (const int &n)
 
void setRange (const unsigned int &r)
 
void setSampleStep (const double &s)
 
double getSampleStep () const
 
void setStrip (const int &a)
 
void setThreshold (const double &t)
 
void setLikelihoodThresholdType (const vpLikelihoodThresholdType likelihood_threshold_type)
 

Public Attributes

double threshold
 
double mu1
 
double mu2
 
double min_samplestep
 
unsigned int anglestep
 
int mask_sign
 
unsigned int range
 
double sample_step
 
int ntotal_sample
 
int points_to_track
 
unsigned int mask_size
 
unsigned int n_mask
 
int strip
 
vpMatrixmask
 

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>
int main()
{
#if defined(VISP_HAVE_NLOHMANN_JSON)
std::string filename = "me.json";
{
vpMe me;
me.setThreshold(20); // Value in range [0 ; 255]
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:122
void setMu1(const double &mu_1)
Definition: vpMe.h:353
void setMaskSign(const int &a)
Definition: vpMe.h:330
void setRange(const unsigned int &r)
Definition: vpMe.h:383
void setStrip(const int &a)
Definition: vpMe.h:404
void print()
Definition: vpMe.cpp:348
void setLikelihoodThresholdType(const vpLikelihoodThresholdType likelihood_threshold_type)
Definition: vpMe.h:445
void setNbTotalSample(const int &nb)
Definition: vpMe.h:367
void setPointsToTrack(const int &n)
Definition: vpMe.h:376
void setMu2(const double &mu_2)
Definition: vpMe.h:360
@ NORMALIZED_THRESHOLD
Easy-to-use normalized likelihood threshold corresponding to the minimal luminance contrast to consid...
Definition: vpMe.h:132
void setMaskNumber(const unsigned int &a)
Definition: vpMe.cpp:445
void setThreshold(const double &t)
Definition: vpMe.h:435

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
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,"thresholdType":1}
Examples
mbtEdgeKltTracking.cpp, mbtEdgeTracking.cpp, mbtGenericTracking.cpp, mbtGenericTracking2.cpp, mbtGenericTrackingDepth.cpp, servoAfma62DhalfCamVelocity.cpp, servoAfma6Cylinder2DCamVelocity.cpp, servoAfma6Cylinder2DCamVelocitySecondaryTask.cpp, servoAfma6Line2DCamVelocity.cpp, servoAfma6SquareLines2DCamVelocity.cpp, servoAfma6TwoLines2DCamVelocity.cpp, testGenericTracker.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-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 121 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 127 of file vpMe.h.

Constructor & Destructor Documentation

◆ vpMe() [1/2]

vpMe::vpMe ( )

Array of matrices defining the different masks (one for every angle step).

Default constructor.

Definition at line 364 of file vpMe.cpp.

References anglestep, initMask(), and n_mask.

◆ vpMe() [2/2]

vpMe::vpMe ( const vpMe me)

Copy constructor.

Definition at line 376 of file vpMe.cpp.

◆ ~vpMe()

vpMe::~vpMe ( )
virtual

Destructor.

Definition at line 437 of file vpMe.cpp.

References mask.

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 198 of file vpMe.h.

◆ getAngleStep()

unsigned int vpMe::getAngleStep ( ) const
inline

Return the angle step.

Returns
Value of anglestep.

Definition at line 208 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 297 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 214 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 222 of file vpMe.h.

◆ getMaskSign()

int vpMe::getMaskSign ( ) const
inline

Return the mask sign.

Returns
Value of mask_sign.

Definition at line 228 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 236 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_samplestep.

Definition at line 243 of file vpMe.h.

◆ getMu1()

double vpMe::getMu1 ( ) const
inline

Get the minimum image contrast allowed to detect a contour.

Returns
Value of mu1.

Definition at line 249 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 255 of file vpMe.h.

Referenced by vpMeSite::track().

◆ getNbTotalSample()

int vpMe::getNbTotalSample ( ) const
inline

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

Returns
Value of ntotal_sample.

Definition at line 261 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 267 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 279 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 288 of file vpMe.h.

Referenced by vpMeSite::track().

◆ initMask()

void vpMe::initMask ( )

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

Definition at line 329 of file vpMe.cpp.

References mask, mask_size, and n_mask.

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

◆ operator=() [1/2]

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

Move operator.

Definition at line 411 of file vpMe.cpp.

References anglestep, initMask(), mask, mask_sign, mask_size, min_samplestep, mu1, mu2, n_mask, ntotal_sample, points_to_track, range, sample_step, strip, and threshold.

◆ operator=() [2/2]

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

Copy operator.

Definition at line 384 of file vpMe.cpp.

References anglestep, initMask(), mask, mask_sign, mask_size, min_samplestep, mu1, mu2, n_mask, ntotal_sample, points_to_track, range, sample_step, strip, and threshold.

◆ print()

void vpMe::print ( )

Print using std::cout moving edges settings.

Examples
tutorial-mb-generic-tracker.cpp.

Definition at line 348 of file vpMe.cpp.

References mask_size, min_samplestep, mu1, mu2, n_mask, NORMALIZED_THRESHOLD, range, sample_step, strip, and threshold.

◆ setAngleStep()

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

Set the angle step.

Parameters
a: new angle step.

Definition at line 315 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, servoAfma62DhalfCamVelocity.cpp, servoAfma6Cylinder2DCamVelocity.cpp, servoAfma6Cylinder2DCamVelocitySecondaryTask.cpp, servoAfma6Line2DCamVelocity.cpp, servoAfma6SquareLines2DCamVelocity.cpp, servoAfma6TwoLines2DCamVelocity.cpp, testGenericTracker.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-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 445 of file vpMe.h.

◆ setMaskNumber()

◆ setMaskSign()

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

Set the mask sign.

Parameters
a: new mask sign.

Definition at line 330 of file vpMe.h.

◆ setMaskSize()

◆ setMinSampleStep()

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

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

Parameters
min: new minimum sample step.

Definition at line 346 of file vpMe.h.

◆ setMu1()

◆ setMu2()

◆ setNbTotalSample()

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

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

Parameters
nb: 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 367 of file vpMe.h.

◆ setPointsToTrack()

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

Set the number of points to track.

Parameters
n: 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 376 of file vpMe.h.

◆ setRange()

◆ setSampleStep()

◆ setStrip()

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

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

Parameters
a: new strip.

Definition at line 404 of file vpMe.h.

◆ setThreshold()

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

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

Parameters
t: 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]

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.

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.
@ OLD_THRESHOLD
Old likelihood ratio threshold (to be avoided).
Definition: vpMe.h:130
See also
getThreshold(), getLikelihoodThresholdType()
Examples
mbtEdgeKltTracking.cpp, mbtEdgeTracking.cpp, mbtGenericTracking.cpp, mbtGenericTracking2.cpp, mbtGenericTrackingDepth.cpp, servoAfma62DhalfCamVelocity.cpp, servoAfma6Cylinder2DCamVelocity.cpp, servoAfma6Cylinder2DCamVelocitySecondaryTask.cpp, servoAfma6Line2DCamVelocity.cpp, servoAfma6SquareLines2DCamVelocity.cpp, servoAfma6TwoLines2DCamVelocity.cpp, testGenericTracker.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-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 435 of file vpMe.h.

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": 1
"threshold": 20.0
}
Parameters
jJSON representation to convert
meconverted object

Definition at line 523 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
jresulting json object
methe object to convert

Definition at line 505 of file vpMe.h.

Member Data Documentation

◆ anglestep

unsigned int vpMe::anglestep

Definition at line 147 of file vpMe.h.

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

◆ mask

vpMatrix* vpMe::mask

Definition at line 166 of file vpMe.h.

Referenced by initMask(), operator=(), and ~vpMe().

◆ mask_sign

int vpMe::mask_sign

Definition at line 148 of file vpMe.h.

Referenced by operator=().

◆ mask_size

unsigned int vpMe::mask_size

Convolution masks' size in pixels (masks are square),

Warning
should not be public, use setMaskSize() and getMaskSize() instead (kept public for compatibility reasons).

Definition at line 156 of file vpMe.h.

Referenced by initMask(), operator=(), print(), and setMaskSize().

◆ min_samplestep

double vpMe::min_samplestep

Contrast continuity parameter (right boundary)

Definition at line 146 of file vpMe.h.

Referenced by operator=(), and print().

◆ mu1

double vpMe::mu1

Old likelihood ratio threshold (to be avoided) or easy-to-use normalized threshold: minimal contrast.

Definition at line 144 of file vpMe.h.

Referenced by operator=(), and print().

◆ mu2

double vpMe::mu2

Contrast continuity parameter (left boundary)

Definition at line 145 of file vpMe.h.

Referenced by operator=(), and print().

◆ n_mask

unsigned int vpMe::n_mask

The number of convolution masks available for tracking ; defines resolution.

Warning
Should not be public, use setMaskNumber() and getMaskNumber() instead (kept public for compatibility reasons).

Definition at line 160 of file vpMe.h.

Referenced by initMask(), operator=(), print(), setMaskNumber(), and vpMe().

◆ ntotal_sample

int vpMe::ntotal_sample

Distance between sampled points in pixels.

Definition at line 151 of file vpMe.h.

Referenced by operator=().

◆ points_to_track

int vpMe::points_to_track

Definition at line 152 of file vpMe.h.

Referenced by operator=().

◆ range

unsigned int vpMe::range

Definition at line 149 of file vpMe.h.

Referenced by operator=(), and print().

◆ sample_step

double vpMe::sample_step

Seek range - on both sides of the reference pixel.

Definition at line 150 of file vpMe.h.

Referenced by operator=(), and print().

◆ strip

int vpMe::strip

Definition at line 165 of file vpMe.h.

Referenced by operator=(), and print().

◆ threshold

double vpMe::threshold

Definition at line 143 of file vpMe.h.

Referenced by operator=(), and print().