40 #include <visp3/core/vpImageConvert.h> 41 #include <visp3/core/vpTrackingException.h> 42 #include <visp3/core/vpVelocityTwistMatrix.h> 43 #include <visp3/mbt/vpMbKltTracker.h> 44 #include <visp3/mbt/vpMbtXmlGenericParser.h> 46 #if defined(VISP_HAVE_MODULE_KLT) && (defined(VISP_HAVE_OPENCV) && (VISP_HAVE_OPENCV_VERSION >= 0x020100)) 48 #if defined(__APPLE__) && defined(__MACH__) // Apple OSX and iOS (Darwin) 49 #include <TargetConditionals.h> 81 double h00 = H[0][0], h01 = H[0][1], h02 = H[0][2];
82 double h10 = H[1][0], h11 = H[1][1], h12 = H[1][2];
83 double h20 = H[2][0], h21 = H[2][1], h22 = H[2][2];
85 double A = h00 * px + u0 * h20;
86 double B = h01 * px + u0 * h21;
87 double C = h02 * px + u0 * h22;
88 double D = h10 * py + v0 * h20;
89 double E = h11 * py + v0 * h21;
90 double F = h12 * py + v0 * h22;
92 G[0][0] = A * one_over_px;
93 G[1][0] = D * one_over_px;
94 G[2][0] = h20 * one_over_px;
96 G[0][1] = B * one_over_py;
97 G[1][1] = E * one_over_py;
98 G[2][1] = h21 * one_over_py;
100 double u0_one_over_px = u0 * one_over_px;
101 double v0_one_over_py = v0 * one_over_py;
103 G[0][2] = -A * u0_one_over_px - B * v0_one_over_py + C;
104 G[1][2] = -D * u0_one_over_px - E * v0_one_over_py + F;
105 G[2][2] = - h20 * u0_one_over_px - h21 * v0_one_over_py + h22;
113 #if (VISP_HAVE_OPENCV_VERSION >= 0x020408)
118 c0Mo(), firstInitialisation(true), maskBorder(5), threshold_outlier(0.5), percentGood(0.6), ctTc0(), tracker(),
119 kltPolygons(), kltCylinders(), circles_disp(), m_nbInfos(0), m_nbFaceUsed(0), m_L_klt(), m_error_klt(), m_w_klt(),
120 m_weightedError_klt(), m_robust_klt(), m_featuresToBeDisplayedKlt()
132 #ifdef VISP_HAVE_OGRE 146 #if (VISP_HAVE_OPENCV_VERSION < 0x020408) 148 cvReleaseImage(&
cur);
154 for (std::list<vpMbtDistanceKltPoints *>::const_iterator it =
kltPolygons.begin(); it !=
kltPolygons.end(); ++it) {
156 if (kltpoly != NULL) {
166 if (kltPolyCylinder != NULL) {
167 delete kltPolyCylinder;
169 kltPolyCylinder = NULL;
191 bool reInitialisation =
false;
195 #ifdef VISP_HAVE_OGRE 230 #if (VISP_HAVE_OPENCV_VERSION >= 0x020408) 231 cv::Mat mask((
int)I.
getRows(), (int)I.
getCols(), CV_8UC1, cv::Scalar(0));
233 IplImage *mask = cvCreateImage(cvSize((
int)I.
getWidth(), (int)I.
getHeight()), IPL_DEPTH_8U, 1);
242 unsigned char val = 255 ;
243 for (std::list<vpMbtDistanceKltPoints *>::const_iterator it =
kltPolygons.begin(); it !=
kltPolygons.end(); ++it) {
256 kltPolyCylinder = *it;
261 if (
faces[indCylBBox]->isVisible() &&
faces[indCylBBox]->getNbPoint() > 2u) {
262 faces[indCylBBox]->computePolygonClipped(
m_cam);
277 for (std::list<vpMbtDistanceKltPoints *>::const_iterator it =
kltPolygons.begin(); it !=
kltPolygons.end(); ++it) {
286 kltPolyCylinder = *it;
292 #if (VISP_HAVE_OPENCV_VERSION < 0x020408) 293 cvReleaseImage(&mask);
305 #if (VISP_HAVE_OPENCV_VERSION < 0x020408) 307 cvReleaseImage(&
cur);
313 for (std::list<vpMbtDistanceKltPoints *>::const_iterator it =
kltPolygons.begin(); it !=
kltPolygons.end(); ++it) {
315 if (kltpoly != NULL) {
325 if (kltPolyCylinder != NULL) {
326 delete kltPolyCylinder;
328 kltPolyCylinder = NULL;
376 #ifdef VISP_HAVE_OGRE 391 std::vector<vpImagePoint> kltPoints;
412 std::map<int, vpImagePoint> kltPoints;
454 for (std::list<vpMbtDistanceKltPoints *>::const_iterator it =
kltPolygons.begin(); it !=
kltPolygons.end(); ++it) {
476 std::cout <<
"WARNING: Cannot set pose when model contains cylinder(s). " 477 "This feature is not implemented yet." 479 std::cout <<
"Tracker will be reinitialized with the given pose." << std::endl;
489 #if (VISP_HAVE_OPENCV_VERSION >= 0x020408) 490 std::vector<cv::Point2f> init_pts;
491 std::vector<long> init_ids;
492 std::vector<cv::Point2f> guess_pts;
494 unsigned int nbp = 0;
495 for (std::list<vpMbtDistanceKltPoints *>::const_iterator it =
kltPolygons.begin(); it !=
kltPolygons.end(); ++it) {
501 CvPoint2D32f *init_pts = NULL;
504 unsigned int iter_pts = 0;
506 CvPoint2D32f *guess_pts = NULL;
521 for (std::list<vpMbtDistanceKltPoints *>::const_iterator it =
kltPolygons.begin(); it !=
kltPolygons.end(); ++it) {
534 double invDc = 1.0 / plan.
getD();
538 vpGEMM(cdtc, Nc, -invDc, cdRc, 1.0, cdHc, VP_GEMM_B_T);
545 std::map<int, vpImagePoint>::const_iterator iter = kltpoly->
getCurrentPoints().begin();
548 #if (VISP_HAVE_OPENCV_VERSION >= 0x020408) 550 if (std::find(init_ids.begin(), init_ids.end(), (long)(kltpoly->
getCurrentPointsInd())[(
int)iter->first]) !=
553 if (std::find(init_ids.begin(), init_ids.end(),
564 cdp[0] = iter->second.get_j();
565 cdp[1] = iter->second.get_i();
568 #if (VISP_HAVE_OPENCV_VERSION >= 0x020408) 569 cv::Point2f p((
float)cdp[0], (
float)cdp[1]);
570 init_pts.push_back(p);
577 init_pts[iter_pts].x = (float)cdp[0];
578 init_pts[iter_pts].y = (float)cdp[1];
582 double p_mu_t_2 = cdp[0] * cdGc[2][0] + cdp[1] * cdGc[2][1] + cdGc[2][2];
584 if (fabs(p_mu_t_2) < std::numeric_limits<double>::epsilon()) {
590 cdp[0] = (cdp[0] * cdGc[0][0] + cdp[1] * cdGc[0][1] + cdGc[0][2]) / p_mu_t_2;
591 cdp[1] = (cdp[0] * cdGc[1][0] + cdp[1] * cdGc[1][1] + cdGc[1][2]) / p_mu_t_2;
594 #if (VISP_HAVE_OPENCV_VERSION >= 0x020408) 595 cv::Point2f p_guess((
float)cdp[0], (
float)cdp[1]);
596 guess_pts.push_back(p_guess);
598 guess_pts[iter_pts].x = (float)cdp[0];
599 guess_pts[iter_pts++].y = (float)cdp[1];
611 #if (VISP_HAVE_OPENCV_VERSION >= 0x020408) 629 bool reInitialisation =
false;
637 #ifdef VISP_HAVE_OGRE 659 for (std::list<vpMbtDistanceKltPoints *>::const_iterator it =
kltPolygons.begin(); it !=
kltPolygons.end(); ++it) {
746 for (std::list<vpMbtDistanceKltPoints *>::const_iterator it =
kltPolygons.begin(); it !=
kltPolygons.end(); ++it) {
780 bool reInitialisation =
false;
782 unsigned int initialNumber = 0;
783 unsigned int currentNumber = 0;
784 unsigned int shift = 0;
786 for (std::list<vpMbtDistanceKltPoints *>::const_iterator it =
kltPolygons.begin(); it !=
kltPolygons.end(); ++it) {
821 double value =
percentGood * (double)initialNumber;
822 if ((
double)currentNumber < value) {
825 reInitialisation =
true;
830 #ifdef VISP_HAVE_OGRE 839 if (reInitialisation)
862 double normRes_1 = -1;
863 unsigned int iter = 0;
867 while (((
int)((normRes - normRes_1) * 1e8) != 0) && (iter <
m_maxIter)) {
870 bool reStartFromLastIncrement =
false;
872 if (reStartFromLastIncrement) {
876 if (!reStartFromLastIncrement) {
898 for (
unsigned int j = 0; j < 6; j++) {
935 unsigned int shift = 0;
938 for (std::list<vpMbtDistanceKltPoints *>::const_iterator it =
kltPolygons.begin(); it !=
kltPolygons.end(); ++it) {
1085 std::cout <<
" *********** Parsing XML for MBT KLT Tracker ************ " << std::endl;
1087 xmlp.
parse(configFile.c_str());
1089 vpERROR_TRACE(
"Can't open XML file \"%s\"\n ", configFile.c_str());
1146 bool displayFullModel)
1150 for (
size_t i = 0; i < models.size(); i++) {
1157 double n20 = models[i][3];
1158 double n11 = models[i][4];
1159 double n02 = models[i][5];
1172 std::stringstream ss;
1179 #ifdef VISP_HAVE_OGRE 1198 bool displayFullModel)
1202 for (
size_t i = 0; i < models.size(); i++) {
1209 double n20 = models[i][3];
1210 double n11 = models[i][4];
1211 double n02 = models[i][5];
1224 std::stringstream ss;
1231 #ifdef VISP_HAVE_OGRE 1239 std::vector<std::vector<double> > features;
1241 for (std::list<vpMbtDistanceKltPoints *>::const_iterator it =
kltPolygons.begin(); it !=
kltPolygons.end(); ++it) {
1246 features.insert(features.end(), currentFeatures.begin(), currentFeatures.end());
1256 features.insert(features.end(), currentFeatures.begin(), currentFeatures.end());
1280 bool displayFullModel)
1282 std::vector<std::vector<double> > models;
1304 for (std::list<vpMbtDistanceKltPoints *>::const_iterator it =
kltPolygons.begin(); it !=
kltPolygons.end(); ++it) {
1306 std::vector<std::vector<double> > modelLines = kltpoly->
getModelForDisplay(cam, displayFullModel);
1307 models.insert(models.end(), modelLines.begin(), modelLines.end());
1313 std::vector<std::vector<double> > modelLines = kltPolyCylinder->
getModelForDisplay(cMo, cam);
1314 models.insert(models.end(), modelLines.begin(), modelLines.end());
1319 std::vector<double> paramsCircle = displayCircle->
getModelForDisplay(cMo, cam, displayFullModel);
1320 if (!paramsCircle.empty()) {
1321 models.push_back(paramsCircle);
1336 unsigned int nbTotalPoints = 0;
1338 for (std::list<vpMbtDistanceKltPoints *>::const_iterator it =
kltPolygons.begin(); it !=
kltPolygons.end(); ++it) {
1353 if (nbTotalPoints < 10) {
1354 std::cerr <<
"test tracking failed (too few points to realize a good tracking)." << std::endl;
1356 "test tracking failed (too few points to realize a good tracking).");
1371 const std::string & )
1401 int ,
const std::string &name)
1415 const std::string &name)
1417 bool already_here =
false;
1432 if (!already_here) {
1460 #if (VISP_HAVE_OPENCV_VERSION < 0x020408) 1462 cvReleaseImage(&
cur);
1470 for (std::list<vpMbtDistanceKltPoints *>::const_iterator it =
kltPolygons.begin(); it !=
kltPolygons.end(); ++it) {
1472 if (kltpoly != NULL) {
1482 if (kltPolyCylinder != NULL) {
1483 delete kltPolyCylinder;
1485 kltPolyCylinder = NULL;
1513 for (std::list<vpMbtDistanceKltPoints *>::const_iterator it =
kltPolygons.begin(); it !=
kltPolygons.end(); ++it) {
1521 #elif !defined(VISP_BUILD_SHARED_LIBS) 1524 void dummy_vpMbKltTracker(){};
1525 #endif // VISP_HAVE_OPENCV virtual void setKltOpencv(const vpKltOpencv &t)
bool m_computeInteraction
virtual void track(const vpImage< unsigned char > &I)
unsigned int getCols() const
void setWindowName(const Ogre::String &n)
int getPyramidLevels() const
Get the list of features id.
Implementation of a matrix and operations on matrices.
virtual void loadConfigFile(const std::string &configFile, bool verbose=true)
void setTracked(const bool &track)
virtual std::vector< std::vector< double > > getModelForDisplay(unsigned int width, unsigned int height, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, bool displayFullModel=false)
void setMaxFeatures(int maxCount)
virtual ~vpMbKltTracker()
double getFarClippingDistance() const
vpCameraParameters m_cam
The camera parameters.
virtual void display(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, const vpColor &col, unsigned int thickness=1, bool displayFullModel=false)
void resize(unsigned int nrows, unsigned int ncols, bool flagNullify=true, bool recopy_=true)
virtual void computeVVSCheckLevenbergMarquardt(unsigned int iter, vpColVector &error, const vpColVector &m_error_prev, const vpHomogeneousMatrix &cMoPrev, double &mu, bool &reStartFromLastIncrement, vpColVector *const w=NULL, const vpColVector *const m_w_prev=NULL)
std::vector< std::vector< double > > getFeaturesForDisplay()
unsigned int computeNbDetectedCurrent(const vpKltOpencv &_tracker)
void setCameraParameters(const vpCameraParameters &camera)
double get_px_inverse() const
void removeOutliers(const vpColVector &weight, const double &threshold_outlier)
void setUseKltTracking(const std::string &name, const bool &useKltTracking)
double getKltMinDistance() const
void setVerbose(bool verbose)
void setHarrisFreeParameter(double harris_k)
int getMaxFeatures() const
Get the list of lost feature.
virtual void loadModel(const std::string &modelFile, bool verbose=false, const vpHomogeneousMatrix &T=vpHomogeneousMatrix())
unsigned int getWidth() const
void setKltQuality(const double &q)
static void convert(const vpImage< unsigned char > &src, vpImage< vpRGBa > &dest)
void parse(const std::string &filename)
vpMbHiddenFaces< vpMbtPolygon > faces
Set of faces describing the object.
double getNearClippingDistance() const
void removeOutliers(const vpColVector &weight, const double &threshold_outlier)
Implementation of an homogeneous matrix and operations on such kind of matrices.
void buildFrom(const vpPoint &_p1, const vpPoint &_p2, const vpPoint &_p3, double r)
void setKltPyramidLevels(const unsigned int &pL)
std::vector< int > listIndicesCylinderBBox
Pointer to the polygon that define a face.
double getHarrisFreeParameter() const
Get the free parameter of the Harris detector.
double get_py_inverse() const
virtual void initFaceFromCorners(vpMbtPolygon &polygon)
bool hasNearClippingDistance() const
std::vector< std::vector< double > > m_featuresToBeDisplayedKlt
Display features.
unsigned int getKltBlockSize() const
std::vector< double > getModelForDisplay(const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, bool displayFullModel=false)
Class to define RGB colors available for display functionnalities.
static bool equal(double x, double y, double s=0.001)
double getAngleAppear() const
std::list< vpMbtDistanceKltCylinder * > kltCylinders
void setBackgroundSizeOgre(const unsigned int &h, const unsigned int &w)
vpMbHiddenFaces< vpMbtPolygon > * hiddenface
Pointer to the list of faces.
bool postTracking(const vpImage< unsigned char > &I, vpColVector &w)
static void displayText(const vpImage< unsigned char > &I, const vpImagePoint &ip, const std::string &s, const vpColor &color)
bool hasEnoughPoints() const
void setMinDistance(double minDistance)
void getCameraParameters(vpCameraParameters &cam) const
error that can be emited by ViSP classes.
vpMbScanLine & getMbScanLineRenderer()
vpColVector m_weightedError_klt
Weighted error.
vpPoint * p
corners in the object frame
void init(const vpKltOpencv &_tracker, const vpHomogeneousMatrix &cMo)
bool useOgre
Use Ogre3d for visibility tests.
double getLodMinLineLengthThreshold() const
void setKltMaskBorder(const unsigned int &mb)
virtual void initFromPose(const vpImage< unsigned char > &I, const std::string &initFile)
Definition of the vpSubMatrix vpSubMatrix class provides a mask on a vpMatrix all properties of vpMat...
bool computeCovariance
Flag used to specify if the covariance matrix has to be computed or not.
std::vector< std::vector< double > > getModelForDisplay(const vpCameraParameters &cam, bool displayFullModel=false)
virtual void reinit(const vpImage< unsigned char > &I)
unsigned int setVisibleOgre(unsigned int width, unsigned int height, const vpCameraParameters &cam, const vpHomogeneousMatrix &cMo, const double &angleAppears, const double &angleDisappears, bool &changed)
virtual void setLod(bool useLod, const std::string &name="")
virtual void computeVVSInteractionMatrixAndResidu()
Implementation of a polygon of the model containing points of interest. It is used by the model-based...
virtual void testTracking()
Class that defines a 3D point in the object frame and allows forward projection of a 3D point in the ...
unsigned int getInitialNumberPoint() const
void computeClippedPolygons(const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam)
Implementation of a rotation matrix and operations on such kind of matrices.
void setQuality(double qualityLevel)
vpHomogeneousMatrix ctTc0
std::map< int, int > & getCurrentPointsInd()
virtual void initCylinder(const vpPoint &, const vpPoint &, double, int, const std::string &name="")
Parse an Xml file to extract configuration parameters of a mbtConfig object.Data parser for the model...
void initOgre(const vpCameraParameters &cam=vpCameraParameters())
Implementation of an homography and operations on homographies.
vpAROgre * getOgreContext()
void setKltHarrisParam(const double &hp)
void changeFrame(const vpHomogeneousMatrix &cMo)
bool hasFarClippingDistance() const
unsigned int getRows() const
std::vector< vpImagePoint > getKltImagePoints() const
vpRobust m_robust_klt
Robust.
vpColVector & normalize()
Manage a circle used in the model-based tracker.
vpMatrix oJo
The Degrees of Freedom to estimate.
Error that can be emited by the vpTracker class and its derivates.
virtual void initCircle(const vpPoint &, const vpPoint &, const vpPoint &, double, int, const std::string &name="")
Implementation of a polygon of the model used by the model-based tracker.
void setAngleDisappear(const double &adisappear)
virtual void setCameraParameters(const vpCameraParameters &_cam)
void computePolygonClipped(const vpCameraParameters &cam=vpCameraParameters())
void computeInteractionMatrixAndResidu(const vpHomogeneousMatrix &cMc0, vpColVector &_R, vpMatrix &_J)
void setName(const std::string &circle_name)
std::string getName() const
double getQuality() const
void changeFrame(const vpHomogeneousMatrix &cMo)
bool useScanLine
Use Scanline for visibility tests.
vpVelocityTwistMatrix buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
void setKltMinDistance(const double &mD)
void setPyramidLevels(int pyrMaxLevel)
double minLineLengthThresholdGeneral
Minimum line length threshold for LOD mode (general setting)
void setTrackerId(int tid)
unsigned int maskBorder
Erosion of the mask.
Generic class defining intrinsic camera parameters.
double getKltHarrisParam() const
void setOgreShowConfigDialog(bool showConfigDialog)
static void displayEllipse(const vpImage< unsigned char > &I, const vpImagePoint ¢er, const double &coef1, const double &coef2, const double &coef3, bool use_normalized_centered_moments, const vpColor &color, unsigned int thickness=1, bool display_center=false, bool display_arc=false)
int getBlockSize() const
Get the size of the averaging block used to track the features.
unsigned int m_nbFaceUsed
Implementation of a polygon of the model containing points of interest. It is used by the model-based...
virtual void reInitModel(const vpImage< unsigned char > &I, const std::string &cad_name, const vpHomogeneousMatrix &cMo, bool verbose=false, const vpHomogeneousMatrix &T=vpHomogeneousMatrix())
std::map< int, vpImagePoint > getKltImagePointsWithId() const
unsigned int getInitialNumberPoint() const
void extract(vpRotationMatrix &R) const
double m_initialMu
Initial Mu for Levenberg Marquardt optimization loop.
void setWindowSize(int winSize)
double m_lambda
Gain of the virtual visual servoing stage.
virtual void computeVVSWeights(vpRobust &robust, const vpColVector &error, vpColVector &w)
bool hasEnoughPoints() const
vpMbtOptimizationMethod m_optimizationMethod
Optimization method used.
unsigned int getRows() const
void initTracking(const cv::Mat &I, const cv::Mat &mask=cv::Mat())
double getAngleDisappear() const
double angleAppears
Angle used to detect a face appearance.
vpKltOpencv tracker
Points tracker.
void setInitialGuess(const std::vector< cv::Point2f > &guess_pts)
vpColVector getNormal() const
void setKltWindowSize(const unsigned int &w)
bool useScanLine
Use scanline rendering.
unsigned int m_maxIter
Maximum number of iterations of the virtual visual servoing stage.
void init(const vpKltOpencv &_tracker, const vpImage< bool > *mask=NULL)
virtual void setMinPolygonAreaThresh(double minPolygonAreaThresh, const std::string &name="")
virtual bool isVisible(const vpHomogeneousMatrix &cMo, double alpha, const bool &modulo=false, const vpCameraParameters &cam=vpCameraParameters(), unsigned int width=0, unsigned int height=0)
std::map< int, vpImagePoint > & getCurrentPoints()
void setAngleAppear(const double &aappear)
static double rad(double deg)
void buildFrom(const vpPoint &p1, const vpPoint &p2, const double &r)
vpMbHiddenFaces< vpMbtPolygon > * hiddenface
Pointer to the list of faces.
cv::Mat cur
Temporary OpenCV image for fast conversion.
void computeHomography(const vpHomogeneousMatrix &_cTc0, vpHomography &cHc0)
vpColVector m_w_klt
Robust weights.
const vpImage< bool > * m_mask
Mask used to disable tracking on a part of image.
void resize(unsigned int i, bool flagNullify=true)
static void displayCross(const vpImage< unsigned char > &I, const vpImagePoint &ip, unsigned int size, const vpColor &color, unsigned int thickness=1)
virtual void computeVVSPoseEstimation(const bool isoJoIdentity_, unsigned int iter, vpMatrix &L, vpMatrix <L, vpColVector &R, const vpColVector &error, vpColVector &error_prev, vpColVector <R, double &mu, vpColVector &v, const vpColVector *const w=NULL, vpColVector *const m_w_prev=NULL)
std::list< vpMbtDistanceCircle * > circles_disp
Vector of the circles used here only to display the full model.
unsigned int getKltPyramidLevels() const
double minPolygonAreaThresholdGeneral
Minimum polygon area threshold for LOD mode (general setting)
static double deg(double rad)
virtual void setCameraParameters(const vpCameraParameters &_cam)
bool displayFeatures
If true, the features are displayed.
void setCameraParameters(const vpCameraParameters &cam)
bool ogreShowConfigDialog
void preTracking(const vpImage< unsigned char > &I)
bool applyLodSettingInConfig
Implementation of column vector and the associated operations.
unsigned int getKltMaskBorder() const
Wrapper for the KLT (Kanade-Lucas-Tomasi) feature tracker implemented in OpenCV. Thus to enable this ...
vpHomogeneousMatrix inverse() const
static vpHomogeneousMatrix direct(const vpColVector &v)
void getFeature(const int &index, long &id, float &x, float &y) const
int getNbFeatures() const
Get the number of current features.
virtual void computeCovarianceMatrixVVS(const bool isoJoIdentity_, const vpColVector &w_true, const vpHomogeneousMatrix &cMoPrev, const vpMatrix &L_true, const vpMatrix &LVJ_true, const vpColVector &error)
double getKltQuality() const
double angleDisappears
Angle used to detect a face disappearance.
virtual unsigned int getNbPolygon() const
void setUseHarris(int useHarrisDetector)
virtual void initFaceFromLines(vpMbtPolygon &polygon)
vpMbtPolygon * polygon
Pointer to the polygon that define a face.
virtual void computeVVSInit()
std::vector< std::vector< double > > getModelForDisplay(const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam)
unsigned int getHeight() const
unsigned int getNbPoint() const
bool getFovClipping() const
unsigned int getKltMaxFeatures() const
void addCircle(const vpPoint &P1, const vpPoint &P2, const vpPoint &P3, double r, const std::string &name="")
virtual void setClipping(const unsigned int &flags)
virtual void init(const vpImage< unsigned char > &I)
virtual void loadConfigFile(const std::string &configFile, bool verbose=true)
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
virtual void setMinLineLengthThresh(double minLineLengthThresh, const std::string &name="")
unsigned int getCurrentNumberPoints() const
This class defines the container for a plane geometrical structure.
unsigned int clippingFlag
Flags specifying which clipping to used.
double getMinDistance() const
unsigned int computeNbDetectedCurrent(const vpKltOpencv &_tracker, const vpImage< bool > *mask=NULL)
void setMinMedianAbsoluteDeviation(double mad_min)
void displayOgre(const vpHomogeneousMatrix &cMo)
unsigned int getCurrentNumberPoints() const
vpColVector m_error_klt
(s - s*)
void updateMask(cv::Mat &mask, unsigned char _nb=255, unsigned int _shiftBorder=0)
virtual void setFarClippingDistance(const double &dist)
void setKltBlockSize(const unsigned int &bs)
void setKltMaxFeatures(const unsigned int &mF)
vpImage< unsigned char > m_I
Grayscale image buffer, used when passing color images.
double getLodMinPolygonAreaThreshold() const
void setBlockSize(int blockSize)
static void displayLine(const vpImage< unsigned char > &I, const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, unsigned int thickness=1, bool segment=true)
bool useLodGeneral
True if LOD mode is enabled.
void computeScanLineRender(const vpCameraParameters &cam, const unsigned int &w, const unsigned int &h)
virtual std::vector< std::vector< double > > getFeaturesForDisplayKlt()
vpHomogeneousMatrix m_cMo
The current pose.
std::vector< std::vector< double > > getFeaturesForDisplay()
Class that consider the case of a translation vector.
std::list< vpMbtDistanceKltPoints * > kltPolygons
bool isoJoIdentity
Boolean to know if oJo is identity (for fast computation)
void computeInteractionMatrixAndResidu(vpColVector &_R, vpMatrix &_J)
vpHomogeneousMatrix c0Mo
Initial pose.
int getWindowSize() const
Get the window size used to refine the corner locations.
unsigned int getKltWindowSize() const
unsigned int setVisible(unsigned int width, unsigned int height, const vpCameraParameters &cam, const vpHomogeneousMatrix &cMo, const double &angle, bool &changed)
void track(const cv::Mat &I)
virtual void setPose(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cdMo)
bool useScanLine
Use scanline rendering.
void updateMask(cv::Mat &mask, unsigned char _nb=255, unsigned int _shiftBorder=0)
virtual void setNearClippingDistance(const double &dist)
vpMatrix m_L_klt
Interaction matrix.
void computeFov(const unsigned int &w, const unsigned int &h)