ViSP
2.10.0
|
#include <vpMe.h>
Public Member Functions | |
vpMe () | |
vpMe (const vpMe &me) | |
virtual | ~vpMe () |
const vpMe & | operator= (const vpMe &me) |
void | initMask () |
void | checkSamplestep (double &a) |
void | print () |
vpMatrix * | getMask () const |
void | setMaskNumber (const unsigned int &a) |
unsigned int | getMaskNumber () const |
void | setMaskSign (const int &a) |
int | getMaskSign () const |
void | setMaskSize (const unsigned int &a) |
unsigned int | getMaskSize () const |
void | setMu1 (const double &mu_1) |
double | getMu1 () const |
void | setMu2 (const double &mu_2) |
double | getMu2 () const |
void | setNbTotalSample (const int &nb) |
int | getNbTotalSample () const |
void | setPointsToTrack (const int &n) |
int | getPointsToTrack () const |
void | setRange (const unsigned int &r) |
unsigned int | getRange () const |
void | setAngleStep (const unsigned int &a) |
unsigned int | getAngleStep () const |
void | setMinSampleStep (const double &min) |
double | getMinSampleStep () const |
void | setSampleStep (const double &s) |
double | getSampleStep () const |
void | setStrip (const int &a) |
int | getStrip () const |
void | setThreshold (const double &t) |
double | getThreshold () const |
Deprecated Functions | |
vp_deprecated void | setAberration (const double &a) |
vp_deprecated void | setInitAberration (const double &a) |
vp_deprecated void | setMinSamplestep (const double &min) |
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 |
vpMatrix * | mask |
Deprecated Attributes | |
double | aberration |
double | init_aberration |
Contains predetermined masks for sites and holds moving edges tracking parameters.
vpMe::vpMe | ( | ) |
Array of matrices defining the different masks (one for every angle step).
Definition at line 413 of file vpMe.cpp.
References anglestep, initMask(), and n_mask.
|
inline |
Return the angle step.
Definition at line 250 of file vpMe.h.
Referenced by vpMeSite::convolution().
|
inline |
Get the matrix of the mask.
Definition at line 116 of file vpMe.h.
Referenced by vpMeSite::convolution().
|
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.
Definition at line 134 of file vpMe.h.
Referenced by vpMbtXmlParser::read_ecm(), vpMbtXmlParser::read_mask(), vpMbtEdgeKltXmlParser::readMainClass(), and vpMbtXmlParser::readMainClass().
|
inline |
|
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.
Definition at line 164 of file vpMe.h.
Referenced by vpMeSite::convolution(), vpMbtXmlParser::read_ecm(), vpMbtXmlParser::read_mask(), vpMbtEdgeKltXmlParser::readMainClass(), and vpMbtXmlParser::readMainClass().
|
inline |
|
inline |
Get the minimum image contrast allowed to detect a contour.
Definition at line 178 of file vpMe.h.
Referenced by vpMbtXmlParser::read_contrast(), vpMbtXmlParser::read_ecm(), vpMbtEdgeKltXmlParser::readMainClass(), vpMbtXmlParser::readMainClass(), and vpMeSite::track().
|
inline |
Get the maximum image contrast allowed to detect a contour.
Definition at line 192 of file vpMe.h.
Referenced by vpMbtXmlParser::read_contrast(), vpMbtXmlParser::read_ecm(), vpMbtEdgeKltXmlParser::readMainClass(), vpMbtXmlParser::readMainClass(), and vpMeSite::track().
|
inline |
Get how many discretizied points are used to track the feature.
Definition at line 206 of file vpMe.h.
Referenced by vpMbtXmlParser::read_sample(), vpMbtEdgeKltXmlParser::readMainClass(), and vpMbtXmlParser::readMainClass().
|
inline |
Return the number of points to track.
Definition at line 222 of file vpMe.h.
Referenced by vpMeNurbs::localReSample(), and vpMeNurbs::sample().
|
inline |
Return the seek range on both sides of the reference pixel.
Definition at line 236 of file vpMe.h.
Referenced by vpMbtDistanceCircle::initMovingEdge(), vpMeTracker::initTracking(), vpMeNurbs::localReSample(), vpMbtXmlParser::read_ecm(), vpMbtXmlParser::read_range(), vpMbtEdgeKltXmlParser::readMainClass(), vpMbtXmlParser::readMainClass(), vpMeNurbs::seekExtremities(), vpMeLine::seekExtremities(), vpMeNurbs::seekExtremitiesCanny(), and vpMeSite::track().
|
inline |
Get the minimum distance in pixel between two discretized points.
Definition at line 278 of file vpMe.h.
Referenced by vpMeEllipse::initTracking(), vpMeNurbs::localReSample(), vpMbtXmlParser::read_sample(), vpMbtEdgeKltXmlParser::readMainClass(), vpMbtXmlParser::readMainClass(), vpMeLine::reSample(), vpMeNurbs::reSample(), vpMeLine::sample(), vpMeNurbs::sample(), vpMeLine::seekExtremities(), vpMeNurbs::seekExtremities(), vpMeNurbs::seekExtremitiesCanny(), and vpMeNurbs::supressNearPoints().
|
inline |
Get the number of pixels that are ignored around the image borders.
Definition at line 292 of file vpMe.h.
Referenced by vpMeSite::convolution().
|
inline |
Return the likelihood threshold used to determined if the moving edge is valid or not.
Definition at line 306 of file vpMe.h.
Referenced by vpMbtXmlParser::read_contrast(), vpMbtXmlParser::read_ecm(), vpMbtEdgeKltXmlParser::readMainClass(), vpMbtXmlParser::readMainClass(), and vpMeSite::track().
void vpMe::initMask | ( | ) |
Initialise the array of matrices with the defined size and the number of matrices to create.
Definition at line 368 of file vpMe.cpp.
References mask, mask_size, and n_mask.
Referenced by operator=(), setMaskNumber(), setMaskSize(), and vpMe().
Definition at line 440 of file vpMe.cpp.
References aberration, anglestep, init_aberration, initMask(), mask, mask_sign, mask_size, min_samplestep, mu1, mu2, n_mask, ntotal_sample, points_to_track, range, sample_step, strip, and threshold.
void vpMe::print | ( | ) |
Definition at line 392 of file vpMe.cpp.
References aberration, init_aberration, mask_size, min_samplestep, mu1, mu2, n_mask, range, sample_step, strip, and threshold.
|
inline |
a | : new value. |
|
inline |
|
inline |
a | : new value. |
void vpMe::setMaskNumber | ( | const unsigned int & | a | ) |
Set 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.
a | : the number of mask. |
Definition at line 480 of file vpMe.cpp.
References anglestep, initMask(), and n_mask.
Referenced by vpMbtXmlParser::read_mask().
|
inline |
void vpMe::setMaskSize | ( | const unsigned int & | a | ) |
Set the 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.
a | : new mask size. |
Definition at line 488 of file vpMe.cpp.
References initMask(), and mask_size.
Referenced by vpMbtXmlParser::read_mask().
|
inline |
|
inline |
|
inline |
Set the minimum image contrast allowed to detect a contour.
mu_1 | : new mu1. |
Definition at line 171 of file vpMe.h.
Referenced by vpMbtXmlParser::read_contrast().
|
inline |
Set the maximum image contrast allowed to detect a contour.
mu_2 | : new mu2. |
Definition at line 185 of file vpMe.h.
Referenced by vpMbtXmlParser::read_contrast().
|
inline |
Set how many discretizied points are used to track the feature.
nb | : new total number of sample. |
Definition at line 199 of file vpMe.h.
Referenced by vpMbtXmlParser::read_sample().
|
inline |
Set the number of points to track.
n | : new number of points to track. |
|
inline |
Set the seek range on both sides of the reference pixel.
r | : new range. |
Definition at line 229 of file vpMe.h.
Referenced by vpMeTracker::initTracking(), vpMeNurbs::localReSample(), vpMbtXmlParser::read_range(), vpMeLine::seekExtremities(), vpMeNurbs::seekExtremities(), and vpMeNurbs::seekExtremitiesCanny().
|
inline |
Set the minimum distance in pixel between two discretized points.
s | : new sample_step. |
Definition at line 271 of file vpMe.h.
Referenced by vpMbtXmlParser::read_sample().
|
inline |
|
inline |
Set the likelihood threshold used to determined if the moving edge is valid or not.
t | : new threshold. |
Definition at line 299 of file vpMe.h.
Referenced by vpMbtXmlParser::read_contrast().
double vpMe::aberration |
Definition at line 313 of file vpMe.h.
Referenced by operator=(), and print().
unsigned int vpMe::anglestep |
Definition at line 81 of file vpMe.h.
Referenced by operator=(), setMaskNumber(), and vpMe().
double vpMe::init_aberration |
Definition at line 314 of file vpMe.h.
Referenced by operator=(), and print().
vpMatrix* vpMe::mask |
Definition at line 97 of file vpMe.h.
Referenced by initMask(), operator=(), and ~vpMe().
int vpMe::mask_sign |
Definition at line 82 of file vpMe.h.
Referenced by operator=().
unsigned int vpMe::mask_size |
convolution masks' size in pixels (masks are square),
Definition at line 88 of file vpMe.h.
Referenced by initMask(), operator=(), print(), and setMaskSize().
double vpMe::min_samplestep |
Contrast continuity parameter (right boundary)
Definition at line 80 of file vpMe.h.
Referenced by operator=(), and print().
double vpMe::mu1 |
Likelihood ratio threshold.
Definition at line 78 of file vpMe.h.
Referenced by operator=(), and print().
double vpMe::mu2 |
Contrast continuity parameter (left boundary)
Definition at line 79 of file vpMe.h.
Referenced by operator=(), and print().
unsigned int vpMe::n_mask |
the number of convolution masks available for tracking ; defines resolution.
Definition at line 90 of file vpMe.h.
Referenced by initMask(), operator=(), print(), setMaskNumber(), and vpMe().
int vpMe::ntotal_sample |
Distance between sampled points (in pixels)
Definition at line 85 of file vpMe.h.
Referenced by operator=().
int vpMe::points_to_track |
Definition at line 86 of file vpMe.h.
Referenced by operator=().
unsigned int vpMe::range |
Definition at line 83 of file vpMe.h.
Referenced by operator=(), and print().
double vpMe::sample_step |
Seek range - on both sides of the reference pixel.
Definition at line 84 of file vpMe.h.
Referenced by operator=(), and print().
int vpMe::strip |
Definition at line 95 of file vpMe.h.
Referenced by operator=(), and print().
double vpMe::threshold |
Definition at line 77 of file vpMe.h.
Referenced by operator=(), and print().