Visual Servoing Platform
version 3.2.0 under development (2019-01-22)
|
#include <visp3/me/vpMe.h>
Public Member Functions | |
vpMe () | |
vpMe (const vpMe &me) | |
virtual | ~vpMe () |
vpMe & | operator= (const vpMe &me) |
vpMe & | operator= (const vpMe &&me) |
void | checkSamplestep (double &a) |
unsigned int | getAngleStep () const |
vpMatrix * | getMask () 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 |
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) |
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 |
This class defines 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 376 of file vpMe.cpp.
References anglestep, initMask(), and n_mask.
|
inline |
Return the angle step.
Definition at line 114 of file vpMe.h.
Referenced by vpMeSite::convolution().
|
inline |
Get the matrix of the mask.
Definition at line 120 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 128 of file vpMe.h.
Referenced by vpMbtXmlParser::read_ecm(), vpMbtXmlGenericParser::read_ecm(), vpMbtXmlGenericParser::read_ecm_mask(), vpMbtXmlParser::read_mask(), vpMbtEdgeKltXmlParser::readMainClass(), vpMbtXmlParser::readMainClass(), and vpMbtXmlGenericParser::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 142 of file vpMe.h.
Referenced by vpMeSite::convolution(), vpMbtXmlParser::read_ecm(), vpMbtXmlGenericParser::read_ecm(), vpMbtXmlGenericParser::read_ecm_mask(), vpMbtXmlParser::read_mask(), vpMbtEdgeKltXmlParser::readMainClass(), vpMbtXmlParser::readMainClass(), and vpMbtXmlGenericParser::readMainClass().
|
inline |
|
inline |
Get the minimum image contrast allowed to detect a contour.
Definition at line 155 of file vpMe.h.
Referenced by vpMeEllipse::printParameters(), vpMbtXmlParser::read_contrast(), vpMbtXmlParser::read_ecm(), vpMbtXmlGenericParser::read_ecm(), vpMbtXmlGenericParser::read_ecm_contrast(), vpMbtEdgeKltXmlParser::readMainClass(), vpMbtXmlParser::readMainClass(), vpMbtXmlGenericParser::readMainClass(), and vpMeSite::track().
|
inline |
Get the maximum image contrast allowed to detect a contour.
Definition at line 161 of file vpMe.h.
Referenced by vpMeEllipse::printParameters(), vpMbtXmlParser::read_contrast(), vpMbtXmlParser::read_ecm(), vpMbtXmlGenericParser::read_ecm(), vpMbtXmlGenericParser::read_ecm_contrast(), vpMbtEdgeKltXmlParser::readMainClass(), vpMbtXmlParser::readMainClass(), vpMbtXmlGenericParser::readMainClass(), and vpMeSite::track().
|
inline |
|
inline |
Return the number of points to track.
Definition at line 173 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 179 of file vpMe.h.
Referenced by vpMbtDistanceCircle::initMovingEdge(), vpMeTracker::initTracking(), vpMeNurbs::localReSample(), vpMeEllipse::printParameters(), vpMbtXmlParser::read_ecm(), vpMbtXmlGenericParser::read_ecm(), vpMbtXmlGenericParser::read_ecm_range(), vpMbtXmlParser::read_range(), vpMbtEdgeKltXmlParser::readMainClass(), vpMbtXmlParser::readMainClass(), vpMbtXmlGenericParser::readMainClass(), vpMeLine::seekExtremities(), vpMeNurbs::seekExtremities(), vpMeNurbs::seekExtremitiesCanny(), and vpMeSite::track().
|
inline |
Get the minimum distance in pixel between two discretized points.
Definition at line 285 of file vpMe.h.
Referenced by vpMeEllipse::initTracking(), vpMeNurbs::localReSample(), vpMbtXmlParser::read_ecm(), vpMbtXmlGenericParser::read_ecm(), vpMbtXmlGenericParser::read_ecm_sample(), vpMbtXmlGenericParser::read_projection_error(), vpMbtXmlParser::read_sample(), vpMbtXmlParser::read_sample_deprecated(), vpMbtXmlGenericParser::read_sample_deprecated(), vpMbtEdgeKltXmlParser::readMainClass(), vpMbtXmlParser::readMainClass(), vpMbtXmlGenericParser::readMainClass(), vpMeLine::reSample(), vpMeNurbs::reSample(), vpMeLine::sample(), vpMeNurbs::sample(), vpMeLine::seekExtremities(), vpMeNurbs::seekExtremities(), vpMeNurbs::seekExtremitiesCanny(), vpMeNurbs::supressNearPoints(), and vpMeEllipse::~vpMeEllipse().
|
inline |
Get the number of pixels that are ignored around the image borders.
Definition at line 185 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 193 of file vpMe.h.
Referenced by vpMbtXmlParser::read_contrast(), vpMbtXmlParser::read_ecm(), vpMbtXmlGenericParser::read_ecm(), vpMbtXmlGenericParser::read_ecm_contrast(), vpMbtEdgeKltXmlParser::readMainClass(), vpMbtXmlParser::readMainClass(), vpMbtXmlGenericParser::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 340 of file vpMe.cpp.
Referenced by operator=(), setMaskNumber(), setMaskSize(), and vpMe().
Copy operator.
Definition at line 395 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.
|
inline |
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 454 of file vpMe.cpp.
References anglestep, initMask(), and n_mask.
Referenced by vpMbtXmlGenericParser::read_ecm_mask(), and 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 461 of file vpMe.cpp.
References initMask(), and mask_size.
Referenced by vpMbtXmlGenericParser::read_ecm_mask(), and vpMbtXmlParser::read_mask().
|
inline |
|
inline |
Set the minimum image contrast allowed to detect a contour.
mu_1 | : new mu1. |
Definition at line 241 of file vpMe.h.
Referenced by vpMeEllipse::printParameters(), vpMbtXmlParser::read_contrast(), and vpMbtXmlGenericParser::read_ecm_contrast().
|
inline |
Set the maximum image contrast allowed to detect a contour.
mu_2 | : new mu2. |
Definition at line 248 of file vpMe.h.
Referenced by vpMeEllipse::printParameters(), vpMbtXmlParser::read_contrast(), and vpMbtXmlGenericParser::read_ecm_contrast().
|
inline |
Set how many discretizied points are used to track the feature.
nb | : new total number of 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 271 of file vpMe.h.
Referenced by vpMeTracker::initTracking(), vpMeNurbs::localReSample(), vpMeEllipse::printParameters(), vpMbtXmlGenericParser::read_ecm_range(), 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 278 of file vpMe.h.
Referenced by vpMbtXmlGenericParser::read_ecm_sample(), vpMbtXmlGenericParser::read_projection_error(), vpMbtXmlParser::read_sample(), vpMbtXmlParser::read_sample_deprecated(), and vpMbtXmlGenericParser::read_sample_deprecated().
|
inline |
|
inline |
Set the likelihood threshold used to determined if the moving edge is valid or not.
t | : new threshold. |
Definition at line 300 of file vpMe.h.
Referenced by vpMbtXmlParser::read_contrast(), and vpMbtXmlGenericParser::read_ecm_contrast().
unsigned int vpMe::anglestep |
Definition at line 71 of file vpMe.h.
Referenced by operator=(), setMaskNumber(), and vpMe().
vpMatrix* vpMe::mask |
Definition at line 91 of file vpMe.h.
Referenced by operator=(), and ~vpMe().
int vpMe::mask_sign |
Definition at line 72 of file vpMe.h.
Referenced by operator=().
unsigned int vpMe::mask_size |
convolution masks' size in pixels (masks are square),
Definition at line 80 of file vpMe.h.
Referenced by operator=(), and setMaskSize().
double vpMe::min_samplestep |
Contrast continuity parameter (right boundary)
Definition at line 70 of file vpMe.h.
Referenced by operator=().
double vpMe::mu1 |
double vpMe::mu2 |
Contrast continuity parameter (left boundary)
Definition at line 69 of file vpMe.h.
Referenced by operator=().
unsigned int vpMe::n_mask |
the number of convolution masks available for tracking ; defines resolution.
Definition at line 84 of file vpMe.h.
Referenced by operator=(), setMaskNumber(), and vpMe().
int vpMe::ntotal_sample |
Distance between sampled points (in pixels)
Definition at line 75 of file vpMe.h.
Referenced by operator=().
int vpMe::points_to_track |
Definition at line 76 of file vpMe.h.
Referenced by operator=().
unsigned int vpMe::range |
Definition at line 73 of file vpMe.h.
Referenced by operator=().
double vpMe::sample_step |
Seek range - on both sides of the reference pixel.
Definition at line 74 of file vpMe.h.
Referenced by operator=().
int vpMe::strip |
Definition at line 89 of file vpMe.h.
Referenced by operator=().
double vpMe::threshold |
Definition at line 67 of file vpMe.h.
Referenced by operator=().