42 #include <visp/vpMbKltTracker.h>
44 #ifdef VISP_HAVE_OPENCV
104 bool reInitialisation =
false;
108 #ifdef VISP_HAVE_OGRE
134 IplImage* mask = cvCreateImage(cvSize((
int)I.
getWidth(), (int)I.
getHeight()), IPL_DEPTH_8U, 1);
137 for (
unsigned int i = 0; i <
faces.
size(); i += 1){
138 if(
faces[i]->isVisible())
144 for (
unsigned int i = 0; i <
faces.
size(); i += 1){
145 if(
faces[i]->isVisible()){
150 cvReleaseImage(&mask);
163 cvReleaseImage(&
cur);
197 #ifdef VISP_HAVE_OGRE
209 std::vector<vpImagePoint>
212 std::vector<vpImagePoint> kltPoints;
230 std::map<int, vpImagePoint>
233 std::map<int, vpImagePoint> kltPoints;
268 for (
unsigned int i = 0; i <
faces.
size(); i += 1){
269 faces[i]->setCameraParameters(cam);
286 #ifndef VISP_HAVE_OGRE
288 std::cout <<
"WARNING: ViSP doesn't have Ogre3D, basic visibility test will be used. setOgreVisibilityTest() set to false." << std::endl;
306 bool reInitialisation =
false;
310 #ifdef VISP_HAVE_OGRE
317 if(reInitialisation){
318 std::cout <<
"WARNING: Visibility changed, must reinitialize to update pose" << std::endl;
332 CvPoint2D32f* initial_guess = NULL;
333 initial_guess = (CvPoint2D32f*)cvAlloc((
unsigned int)
tracker.
getMaxFeatures()*
sizeof(initial_guess[0]));
335 for (
unsigned int i = 0; i <
faces.
size(); i += 1){
336 if(
faces[i]->isVisible() &&
faces[i]->hasEnoughPoints()){
344 double invDc = 1.0 / plan.
getD();
348 vpGEMM(cdtc, Nc, -invDc, cdRc, 1.0, cdHc, VP_GEMM_B_T);
355 std::map<int, vpImagePoint>::const_iterator iter =
faces[i]->getCurrentPoints().begin();
356 for( ; iter !=
faces[i]->getCurrentPoints().end(); iter++){
358 cdp[0] = iter->second.get_j(); cdp[1] = iter->second.get_i(); cdp[2] = 1.0;
360 double p_mu_t_2 = cdp[0] * cdGc[2][0] + cdp[1] * cdGc[2][1] + cdGc[2][2];
362 if( fabs(p_mu_t_2) < std::numeric_limits<double>::epsilon()){
368 cdp[0] = (cdp[0] * cdGc[0][0] + cdp[1] * cdGc[0][1] + cdGc[0][2]) / p_mu_t_2;
369 cdp[1] = (cdp[0] * cdGc[1][0] + cdp[1] * cdGc[1][1] + cdGc[1][2]) / p_mu_t_2;
372 initial_guess[(
faces[i]->getCurrentPointsInd())[iter->first]].x = (
float)cdp[0];
373 initial_guess[(
faces[i]->getCurrentPointsInd())[iter->first]].y = (
float)cdp[1];
380 if(initial_guess) cvFree(&initial_guess);
381 initial_guess = NULL;
397 vpTRACE(
"Far clipping value cannot be inferior than near clipping value. Far clipping won't be considered.");
399 vpTRACE(
"Far clipping value cannot be inferior than 0. Far clipping won't be considered.");
403 for (
unsigned int i = 0; i <
faces.
size(); i ++){
418 vpTRACE(
"Near clipping value cannot be superior than far clipping value. Near clipping won't be considered.");
420 vpTRACE(
"Near clipping value cannot be inferior than 0. Near clipping won't be considered.");
424 for (
unsigned int i = 0; i <
faces.
size(); i ++){
441 for (
unsigned int i = 0; i <
faces.
size(); i ++)
454 if( corners.size() > 2){
457 polygon->
setNbPoint((
unsigned int)corners.size());
459 for(
unsigned int j = 0; j < corners.size(); j++) {
497 for (
unsigned int i = 0; i <
faces.
size(); i += 1){
498 if(
faces[i]->isVisible()){
501 if(
faces[i]->hasEnoughPoints()){
502 nbInfos +=
faces[i]->getNbPointsCur();
517 bool reInitialisation =
false;
519 unsigned int initialNumber = 0;
520 unsigned int currentNumber = 0;
521 unsigned int shift = 0;
522 for (
unsigned int i = 0; i <
faces.
size(); i += 1){
523 if(
faces[i]->isVisible()){
524 initialNumber +=
faces[i]->getInitialNumberPoint();
525 if(
faces[i]->hasEnoughPoints()){
528 shift += 2*
faces[i]->getNbPointsCur();
530 currentNumber +=
faces[i]->getNbPointsCur();
540 double value =
percentGood * (double)initialNumber;
541 if((
double)currentNumber < value){
543 reInitialisation =
true;
549 #ifdef VISP_HAVE_OGRE
585 double normRes_1 = -1;
586 unsigned int iter = 0;
589 J.
resize(2*nbInfos, 6, 0);
591 while( ((
int)((normRes - normRes_1)*1e8) != 0 ) && (iter<
maxIter) ){
593 unsigned int shift = 0;
594 for (
unsigned int i = 0; i <
faces.
size(); i += 1){
595 if(
faces[i]->isVisible() &&
faces[i]->hasEnoughPoints()){
600 faces[i]->computeInteractionMatrixAndResidu(subR, subJ);
602 std::cerr <<
"exception while tracking face " << i << std::endl;
606 shift += 2*
faces[i]->getNbPointsCur();
627 for (
unsigned int i = 0; i < static_cast<unsigned int>(R.
getRows()); i += 1){
628 w_true = w[i] * w[i];
634 for(
unsigned int i=0; i<static_cast<unsigned int>(R.
getRows()); i++){
635 for(
unsigned int j=0; j<6; j++){
669 unsigned int nbInfos;
670 unsigned int nbFaceUsed;
673 if(nbInfos < 4 || nbFaceUsed == 0){
751 #ifdef VISP_HAVE_XML2
766 std::cout <<
" *********** Parsing XML for MBT KLT Tracker ************ " << std::endl;
768 xmlp.
parse(configFile);
799 vpTRACE(
"You need the libXML2 to read the config file %s", configFile);
815 const vpColor& col ,
const unsigned int thickness,
const bool displayFullModel)
822 for (
unsigned int i = 0; i <
faces.
size(); i += 1){
823 if(displayFullModel ||
faces[i]->isVisible())
825 faces[i]->changeFrame(cMo);
826 faces[i]->computeRoiClipped(c);
827 std::vector<std::pair<vpImagePoint,unsigned int> > roi;
828 faces[i]->getRoiClipped(c, roi);
830 for (
unsigned int j = 0; j < roi.size(); j += 1){
839 ip2 = roi[(j+1)%roi.size()].first;
846 faces[i]->displayPrimitive(I);
851 #ifdef VISP_HAVE_OGRE
869 const vpColor& col ,
const unsigned int thickness,
const bool displayFullModel)
876 for (
unsigned int i = 0; i <
faces.
size(); i += 1){
877 if(displayFullModel ||
faces[i]->isVisible())
879 faces[i]->changeFrame(cMo);
880 faces[i]->computeRoiClipped(c);
881 std::vector<std::pair<vpImagePoint,unsigned int> > roi;
882 faces[i]->getRoiClipped(c, roi);
884 for (
unsigned int j = 0; j < roi.size(); j += 1){
893 ip2 = roi[(j+1)%roi.size()].first;
900 faces[i]->displayPrimitive(I);
905 #ifdef VISP_HAVE_OGRE
922 unsigned int nbTotalPoints = 0;
923 for (
unsigned int i = 0; i <
faces.
size(); i += 1){
924 if(
faces[i]->isVisible()){
925 nbTotalPoints +=
faces[i]->getNbPointsCur();
929 if(nbTotalPoints < 10){
930 std::cerr <<
"test tracking failed (too few points to realize a good tracking)." << std::endl;
932 "test tracking failed (too few points to realize a good tracking).");
936 #endif //VISP_HAVE_OPENCV
bool hasFarClippingDistance() const
void setKltOpencv(const vpKltOpencv &t)
bool compute_interaction
If true, compute the interaction matrix at each iteration of the minimization. Otherwise, compute it only on the first iteration.
virtual void track(const vpImage< unsigned char > &I)
Implementation of a polygon of the model containing points of interest. It is used by the model-based...
vpMatrix get_K_inverse() const
void setWindowName(const Ogre::String &n)
int getPyramidLevels() const
Get the number of pyramid levels.
unsigned int getMaskBorder() const
void setQuality(const double &q)
Definition of the vpMatrix class.
vpMatrix covarianceMatrix
Covariance matrix.
double distFarClip
Distance for near clipping.
virtual ~vpMbKltTracker()
void setQuality(double input)
double getHarrisParam() const
void resize(const unsigned int nrows, const unsigned int ncols, const bool nullify=true)
void track(const IplImage *I)
double distNearClip
Distance for near clipping.
unsigned int clippingFlag
Flags specifying which clipping to used.
void MEstimator(const vpRobustEstimatorType method, const vpColVector &residues, vpColVector &weights)
Compute the weights according a residue vector and a PsiFunction.
int getMaxFeatures() const
Get Max number of features.
void parse(const char *filename)
unsigned int getWidth() const
static void convert(const vpImage< unsigned char > &src, vpImage< vpRGBa > &dest)
double getFarClippingDistance() const
unsigned int maxIter
The maximum iteration of the virtual visual servoing stage.
The class provides a data structure for the homogeneous matrices as well as a set of operations on th...
IplImage * cur
Temporary OpenCV image for fast conversion.
double getHarrisFreeParameter() const
Get Harris free parameter.
void setIdentity()
Basic initialisation (identity)
Class to define colors available for display functionnalities.
double percentGood
Percentage of good points, according to the initial number, that must have the tracker.
void setBackgroundSizeOgre(const unsigned int &h, const unsigned int &w)
vpHomogeneousMatrix cMo
The current pose.
bool postTracking(const vpImage< unsigned char > &I, vpColVector &w)
unsigned int getBlockSize() const
void setUseHarris(const int input)
bool modelInitialised
Flag used to ensure that the CAD model is loaded before the initialisation.
void getCameraParameters(vpCameraParameters &_cam) const
void initOgre(vpCameraParameters _cam=vpCameraParameters())
error that can be emited by ViSP classes.
void computeJTR(const vpMatrix &J, const vpColVector &R, vpMatrix &JTR)
double getAngleAppear() const
double getAngleDisappear() const
unsigned int getMaxFeatures() const
void setInitialGuess(CvPoint2D32f **guess_pts)
void setPyramidLevels(const int input)
void setBlockSize(const int input)
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.
bool firstInitialisation
Flag to specify whether the init method is called the first or not (specific calls to realize in this...
static vpMatrix computeCovarianceMatrix(const vpMatrix &A, const vpColVector &x, const vpColVector &b)
virtual void reinit(const vpImage< unsigned char > &I)
virtual void testTracking()
virtual void loadConfigFile(const std::string &configFile)
vpCameraParameters cam
The camera parameters.
The vpRotationMatrix considers the particular case of a rotation matrix.
vpHomogeneousMatrix ctTc0
The estimated displacement of the pose between the current instant and the initial position...
unsigned int setVisibleOgre(const vpImage< unsigned char > &_I, const vpCameraParameters &_cam, const vpHomogeneousMatrix &_cMo, const double &angleAppears, const double &angleDisappears, bool &changed)
This class aims to compute the homography wrt.two images.
void addPoint(const unsigned int n, const vpPoint &P)
vpAROgre * getOgreContext()
unsigned int setVisible(const vpImage< unsigned char > &_I, const vpCameraParameters &_cam, const vpHomogeneousMatrix &_cMo, const double &angle, bool &changed)
std::vector< vpImagePoint > getKltImagePoints() const
void setPyramidLevels(const unsigned int &pL)
Parse an Xml file to extract configuration parameters of a Mbt Klt object.Data parser for the KLT mod...
unsigned int getWindowSize() const
Error that can be emited by the vpTracker class and its derivates.
void getFeature(int index, int &id, float &x, float &y) const
void setWindowSize(const int input)
double getQuality() const
Get the quality of the tracker.
void changeFrame(const vpHomogeneousMatrix &cMo)
void setWindowSize(const unsigned int &w)
void setTrackerId(int tid)
Definition of the vpSubColVector vpSubColVector class provides a mask on a vpColVector all properties...
unsigned int maskBorder
Erosion of the mask.
Generic class defining intrinsic camera parameters.
int getBlockSize() const
Get the block size.
std::map< int, vpImagePoint > getKltImagePointsWithId() const
bool useOgre
Use Ogre3d for visibility tests.
vpMbHiddenFaces< vpMbtKltPolygon > faces
Set of faces describing the object.
void extract(vpRotationMatrix &R) const
void setAngleDisappear(const double &adisappear)
void setHarrisParam(const double &hp)
bool firstTrack
First track() called.
void setMinDistance(const double &mD)
void addPolygon(PolygonType *p)
vpKltOpencv tracker
Points tracker.
vpColVector getNormal() const
static double rad(double deg)
double threshold_outlier
Threshold below which the weight associated to a point to consider this one as an outlier...
void diag(const vpColVector &A)
void preTracking(const vpImage< unsigned char > &I, unsigned int &nbInfos, unsigned int &nbFaceUsed)
void setAngleAppear(const double &aappear)
unsigned int size() const
double lambda
The gain of the virtual visual servoing stage.
void setMaxFeatures(const unsigned int &mF)
void initTracking(const IplImage *I, const IplImage *mask=NULL)
double getQuality() const
static double deg(double rad)
bool displayFeatures
If true, the features are displayed.
void setCameraParameters(const vpCameraParameters &cam)
Class that provides a data structure for the column vectors as well as a set of operations on these v...
virtual void setOgreVisibilityTest(const bool &v)
Wrapper for the KLT (Kanade-Lucas-Tomasi) feature tracker implemented in OpenCV.
vpHomogeneousMatrix inverse() const
virtual void setNearClippingDistance(const double &dist)
static vpHomogeneousMatrix direct(const vpColVector &v)
int getNbFeatures() const
Get the current number of features.
Contains an M-Estimator and various influence function.
virtual void initFaceFromCorners(const std::vector< vpPoint > &corners, const unsigned int indexFace=-1)
double angleAppears
Angle used to detect a face appearance.
void displayOgre(const vpHomogeneousMatrix &_cMo)
unsigned int getHeight() const
virtual void setClipping(const unsigned int &flags)
vpMatrix pseudoInverse(double svThreshold=1e-6) const
Compute the pseudo inverse of the matrix using the SVD.
virtual void init(const vpImage< unsigned char > &I)
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
virtual void displayLine(const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, unsigned int thickness=1)=0
void setBlockSize(const unsigned int &bs)
This class defines the container for a plane geometrical structure.
double getMinDistance() const
Get Min Distance.
void setMaxFeatures(const int input)
double angleDisappears
Angle used to detect a face disappearance.
void setThreshold(const double noise_threshold)
unsigned int getRows() const
Return the number of rows of the matrix.
bool hasNearClippingDistance() const
double getMinDistance() const
virtual void setNbPoint(const unsigned int nb)
vpColVector & normalize()
normalise the vector
bool getFovClipping() const
void setMinDistance(double input)
void setIteration(const unsigned int iter)
Set iteration.
void computeVVS(const unsigned int &nbInfos, vpColVector &w)
Class that consider the case of a translation vector.
double getNearClippingDistance() const
void setMaskBorder(const unsigned int &mb)
vpHomogeneousMatrix c0Mo
Initial pose.
int getWindowSize() const
Get Max number of features.
virtual void setFarClippingDistance(const double &dist)
unsigned int getPyramidLevels() const
virtual void display(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, const vpColor &col, const unsigned int thickness=1, const bool displayFullModel=false)
void setHarrisFreeParameter(double input)
virtual void setPose(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cdMo)
void resize(const unsigned int i, const bool flagNullify=true)
std::vector< PolygonType * > & getPolygon()
virtual void setIndex(const int i)
void computeFov(const unsigned int &w, const unsigned int &h)