00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 
00038 
00039 
00040 
00041 #ifndef __ARTOOLKIT_TRACKERIMPL_HEADERFILE__
00042 #define __ARTOOLKIT_TRACKERIMPL_HEADERFILE__
00043 
00044 
00045 #include <ARToolKitPlus/ar.h>
00046 #include <ARToolKitPlus/arMulti.h>
00047 #include <ARToolKitPlus/matrix.h>
00048 #include <ARToolKitPlus/Tracker.h>
00049 #include <ARToolKitPlus/MemoryManager.h>
00050 #include <ARToolKitPlus/Camera.h>
00051 #include <ARToolKitPlus/CameraFactory.h>
00052 #include <ARToolKitPlus/extra/BCH.h>
00053 
00054 
00055 #if defined(_MSC_VER)
00056 #  if _MSC_VER<1300
00057 #    define _OLD_MSCOMPILER_
00058 #    pragma message (">>> Compiling for old MS Compiler")
00059 #  endif
00060 #endif
00061 
00062 
00063 #define AR_TEMPL_FUNC template <int __PATTERN_SIZE_X, int __PATTERN_SIZE_Y, int __PATTERN_SAMPLE_NUM, int __MAX_LOAD_PATTERNS, int __MAX_IMAGE_PATTERNS>
00064 #define AR_TEMPL_TRACKER TrackerImpl<__PATTERN_SIZE_X, __PATTERN_SIZE_Y, __PATTERN_SAMPLE_NUM, __MAX_LOAD_PATTERNS, __MAX_IMAGE_PATTERNS>
00065 
00066 
00067 namespace ARToolKitPlus {
00068 
00069 
00070 
00071 
00072 static bool usesSinglePrecision();                              
00073 
00074 
00075 #ifndef _ARTKP_NO_MEMORYMANAGER_
00076 extern MemoryManager* memManager;
00077 #endif //_ARTKP_NO_MEMORYMANAGER_
00078 
00079 void artkp_Free(void* nRawMemory);
00080 
00081 template<class T> T* artkp_Alloc(size_t size)
00082 {
00083 #ifndef _ARTKP_NO_MEMORYMANAGER_
00084         if(memManager)
00085                 return (T*)memManager->getMemory(size*sizeof(T));
00086         else
00087 #endif //_ARTKP_NO_MEMORYMANAGER_
00088                 return (T*)::malloc(size*sizeof(T));
00089 }
00090 
00091 
00093 template <int __PATTERN_SIZE_X, int __PATTERN_SIZE_Y, int __PATTERN_SAMPLE_NUM, int __MAX_LOAD_PATTERNS, int __MAX_IMAGE_PATTERNS>
00094 class TrackerImpl : public Tracker
00095 {
00096 public:
00097         enum {
00098                 PATTERN_WIDTH = __PATTERN_SIZE_X,
00099                 PATTERN_HEIGHT = __PATTERN_SIZE_Y,
00100                 PATTERN_SAMPLE_NUM = __PATTERN_SAMPLE_NUM,
00101 
00102                 MAX_LOAD_PATTERNS = __MAX_LOAD_PATTERNS,
00103                 MAX_IMAGE_PATTERNS = __MAX_IMAGE_PATTERNS,
00104                 WORK_SIZE = 1024*MAX_IMAGE_PATTERNS,
00105 
00106 #ifdef SMALL_LUM8_TABLE
00107                 LUM_TABLE_SIZE = (0xffff >> 6) + 1,
00108 #else
00109                 LUM_TABLE_SIZE = 0xffff + 1,
00110 #endif
00111         };
00112 
00113 
00114         TrackerImpl();
00115         virtual ~TrackerImpl();
00116 
00118         virtual void cleanup();
00119 
00120 
00122 
00125         virtual bool setPixelFormat(PIXEL_FORMAT nFormat);
00126 
00128 
00135         virtual bool loadCameraFile(const char* nCamParamFile, ARFloat nNearClip, ARFloat nFarClip);
00136 
00137         virtual void setLoadUndistLUT(bool nSet)  {  loadCachedUndist = nSet;  }
00138 
00140         virtual void setLogger(ARToolKitPlus::Logger* nLogger)  {  logger = nLogger;  }
00141 
00143         virtual int arDetectMarker(ARUint8 *dataPtr, int thresh, ARMarkerInfo **marker_info, int *marker_num);
00144 
00146         virtual int arDetectMarkerLite(ARUint8 *dataPtr, int thresh, ARMarkerInfo **marker_info, int *marker_num);
00147 
00149         virtual ARFloat arMultiGetTransMat(ARMarkerInfo *marker_info, int marker_num, ARMultiMarkerInfoT *config);
00150 
00152         virtual ARFloat arGetTransMat(ARMarkerInfo *marker_info, ARFloat center[2], ARFloat width, ARFloat conv[3][4]);
00153 
00154         virtual ARFloat arGetTransMatCont(ARMarkerInfo *marker_info, ARFloat prev_conv[3][4], ARFloat center[2], ARFloat width, ARFloat conv[3][4]);
00155 
00156         
00157         virtual ARFloat rppMultiGetTransMat(ARMarkerInfo *marker_info, int marker_num, ARMultiMarkerInfoT *config);
00158         virtual ARFloat rppGetTransMat(ARMarkerInfo *marker_info, ARFloat center[2], ARFloat width, ARFloat conv[3][4]);
00159 
00161         virtual int arLoadPatt(char *filename);
00162 
00164         virtual int arFreePatt(int patno);
00165 
00166         virtual int arMultiFreeConfig( ARMultiMarkerInfoT *config );
00167 
00168         virtual ARMultiMarkerInfoT *arMultiReadConfigFile(const char *filename);
00169 
00170         virtual void activateBinaryMarker(int nThreshold)  {  binaryMarkerThreshold = nThreshold;  }
00171 
00173 
00177         virtual void setMarkerMode(MARKER_MODE nMarkerMode);
00178 
00179 
00181 
00192         virtual void activateVignettingCompensation(bool nEnable, int nCorners=0, int nLeftRight=0, int nTopBottom=0);
00193 
00194 
00196 
00201         static bool calcCameraMatrix(const char* nCamParamFile, int nWidth, int nHeight,
00202                                                                  ARFloat nNear, ARFloat nFar, ARFloat *nMatrix);
00203 
00204         
00206         virtual void changeCameraSize(int nWidth, int nHeight);
00207 
00208 
00210 
00214         virtual void setUndistortionMode(UNDIST_MODE nMode);
00215 
00217 
00221         virtual bool setPoseEstimator(POSE_ESTIMATOR nMethod);
00222 
00224 
00230         virtual void setBorderWidth(ARFloat nFraction)  {  relBorderWidth = nFraction;  }
00231 
00232 
00234         virtual void setThreshold(int nValue)  {  thresh = nValue;  }
00235 
00236 
00238         virtual int getThreshold() const  {  return thresh;  }
00239 
00240 
00242         virtual void activateAutoThreshold(bool nEnable)  {  autoThreshold.enable = nEnable;  }
00243 
00244 
00246         virtual bool isAutoThresholdActivated() const  {  return autoThreshold.enable;  }
00247 
00249 
00258         virtual void setNumAutoThresholdRetries(int nNumRetries)  {  autoThreshold.numRandomRetries = nNumRetries>=1 ? nNumRetries : 1;  }
00259 
00260 
00262 
00267         virtual void setImageProcessingMode(IMAGE_PROC_MODE nMode)  {  arImageProcMode = (nMode==IMAGE_HALF_RES ? AR_IMAGE_PROC_IN_HALF : AR_IMAGE_PROC_IN_FULL);  }
00268 
00269 
00271         virtual const ARFloat* getModelViewMatrix() const  {  return gl_para;  }
00272 
00273 
00275         virtual const ARFloat* getProjectionMatrix() const  {  return gl_cpara;  }
00276 
00277 
00279         virtual const char* getDescription();
00280 
00281 
00283         virtual PIXEL_FORMAT getPixelFormat() const  {  return static_cast<PIXEL_FORMAT>(pixelFormat);  }
00284 
00285 
00287         virtual int getBitsPerPixel() const  {  return pixelSize*8;  }
00288 
00289 
00291         virtual int getNumLoadablePatterns() const  {  return MAX_LOAD_PATTERNS;  }
00292 
00293 
00295         virtual Camera* getCamera()  {  return arCamera;  }
00296 
00297 
00299         virtual void setCamera(Camera* nCamera);
00300 
00301 
00303         virtual void setCamera(Camera* nCamera, ARFloat nNearClip, ARFloat nFarClip);
00304 
00305 
00306         virtual ARFloat calcOpenGLMatrixFromMarker(ARMarkerInfo* nMarkerInfo, ARFloat nPatternCenter[2], ARFloat nPatternSize, ARFloat *nOpenGLMatrix);
00307 
00308 
00309         virtual ARFloat executeSingleMarkerPoseEstimator(ARMarkerInfo *marker_info, ARFloat center[2], ARFloat width, ARFloat conv[3][4]);
00310 
00311 
00312         virtual ARFloat executeMultiMarkerPoseEstimator(ARMarkerInfo *marker_info, int marker_num, ARMultiMarkerInfoT *config);
00313 
00314 
00315 
00316 protected:
00317         bool checkPixelFormat();
00318 
00319         void checkImageBuffer();
00320 
00321         
00322 
00323         
00324         
00325 
00326         
00327         void convertTransformationMatrixToOpenGLStyle(ARFloat para[3][4], ARFloat gl_para[16]);
00328 
00329         
00330         static bool convertProjectionMatrixToOpenGLStyle(ARParam *param, ARFloat gnear, ARFloat gfar, ARFloat m[16]);
00331         static bool convertProjectionMatrixToOpenGLStyle2(ARFloat cparam[3][4], int width, int height, ARFloat gnear, ARFloat gfar, ARFloat m[16]);
00332 
00333 
00334         ARMarkerInfo2* arDetectMarker2(ARInt16 *limage, int label_num, int *label_ref,
00335                                                                    int *warea, ARFloat *wpos, int *wclip,
00336                                                                    int area_max, int area_min, ARFloat factor, int *marker_num);
00337 
00338         int arGetContour(ARInt16 *limage, int *label_ref, int label, int clip[4], ARMarkerInfo2 *marker_infoTWO);
00339 
00340         int check_square(int area, ARMarkerInfo2 *marker_infoTWO, ARFloat factor);
00341 
00342         int arGetCode(ARUint8 *image, int *x_coord, int *y_coord, int *vertex,
00343                                   int *code, int *dir, ARFloat *cf, int thresh);
00344 
00345         int arGetPatt(ARUint8 *image, int *x_coord, int *y_coord, int *vertex,
00346                                   ARUint8 ext_pat[PATTERN_HEIGHT][PATTERN_WIDTH][3]);
00347 
00348         int pattern_match( ARUint8 *data, int *code, int *dir, ARFloat *cf);
00349 
00350         int downsamplePattern(ARUint8* data, unsigned char* imgPtr);
00351 
00352         int bitfield_check_simple(ARUint8 *data, int *code, int *dir, ARFloat *cf, int thresh);
00353 
00354         int bitfield_check_BCH(ARUint8 *data, int *code, int *dir, ARFloat *cf, int thresh);
00355 
00356         void gen_evec(void);
00357 
00358         ARMarkerInfo* arGetMarkerInfo(ARUint8 *image, ARMarkerInfo2 *marker_info2, int *marker_num, int thresh);
00359 
00360         ARFloat arGetTransMat2(ARFloat rot[3][3], ARFloat ppos2d[][2], ARFloat ppos3d[][2], int num, ARFloat conv[3][4]);
00361 
00362 
00363         ARFloat arGetTransMat4(ARFloat rot[3][3], ARFloat ppos2d[][2], ARFloat ppos3d[][3], int num, ARFloat conv[3][4]);
00364 
00365         ARFloat arGetTransMat5(ARFloat rot[3][3], ARFloat ppos2d[][2],
00366                                                    ARFloat ppos3d[][3], int num, ARFloat conv[3][4],
00367                                                    Camera *pCam);
00368                                                    
00369 
00370         ARFloat arGetTransMatSub(ARFloat rot[3][3], ARFloat ppos2d[][2],
00371                                                          ARFloat pos3d[][3], int num, ARFloat conv[3][4],
00372                                                          Camera *pCam);
00373                                                          
00374 
00375         ARFloat arModifyMatrix(ARFloat rot[3][3], ARFloat trans[3], ARFloat cpara[3][4],
00376                                                                   ARFloat vertex[][3], ARFloat pos2d[][2], int num);
00377 
00378         ARFloat arModifyMatrix2(ARFloat rot[3][3], ARFloat trans[3], ARFloat cpara[3][4],
00379                                                                    ARFloat vertex[][3], ARFloat pos2d[][2], int num);
00380 
00381         int arGetAngle(ARFloat rot[3][3], ARFloat *wa, ARFloat *wb, ARFloat *wc);
00382 
00383         int arGetRot(ARFloat a, ARFloat b, ARFloat c, ARFloat rot[3][3]);
00384 
00385         int arGetNewMatrix(ARFloat a, ARFloat b, ARFloat c,
00386                                                           ARFloat trans[3], ARFloat trans2[3][4],
00387                                                           ARFloat cpara[3][4], ARFloat ret[3][4]);
00388 
00389         int arGetInitRot(ARMarkerInfo *marker_info, ARFloat cpara[3][4], ARFloat rot[3][3]);
00390 
00391 
00392         ARFloat arGetTransMatCont2(ARMarkerInfo *marker_info, ARFloat center[2], ARFloat width, ARFloat conv[3][4]);
00393 
00394         ARFloat arGetTransMatContSub(ARMarkerInfo *marker_info, ARFloat prev_conv[3][4], ARFloat center[2], ARFloat width, ARFloat conv[3][4]);
00395 
00396 
00397 
00398         ARInt16* arLabeling(ARUint8 *image, int thresh,int *label_num, int **area,
00399                                                 ARFloat **pos, int **clip, int **label_ref );
00400 
00401 
00402         ARInt16* arLabeling_ABGR(ARUint8 *image, int thresh,int *label_num, int **area, ARFloat **pos, int **clip, int **label_ref);
00403         ARInt16* arLabeling_BGR(ARUint8 *image, int thresh,int *label_num, int **area, ARFloat **pos, int **clip, int **label_ref);
00404         ARInt16* arLabeling_RGB(ARUint8 *image, int thresh,int *label_num, int **area, ARFloat **pos, int **clip, int **label_ref);
00405         ARInt16* arLabeling_RGB565(ARUint8 *image, int thresh,int *label_num, int **area, ARFloat **pos, int **clip, int **label_ref);
00406         ARInt16* arLabeling_LUM(ARUint8 *image, int thresh,int *label_num, int **area, ARFloat **pos, int **clip, int **label_ref);
00407 
00408         
00409         
00410 
00411         
00412         
00413 
00414 
00415         int arActivatePatt(int patno);
00416 
00417         int arDeactivatePatt(int patno);
00418 
00419         int arMultiActivate(ARMultiMarkerInfoT *config);
00420 
00421         int arMultiDeactivate( ARMultiMarkerInfoT *config );
00422 
00423         int verify_markers(ARMarkerInfo *marker_info, int marker_num, ARMultiMarkerInfoT *config);
00424 
00425         int arInitCparam( Camera *pCam );
00426 
00427         int arGetLine(int x_coord[], int y_coord[], int coord_num, int vertex[], ARFloat line[4][3], ARFloat v[4][2]);
00428 
00429         int arGetLine2(int x_coord[], int y_coord[], int coord_num, int vertex[], ARFloat line[4][3], ARFloat v[4][2], Camera *pCam);
00430 
00431         static int arUtilMatMul(ARFloat s1[3][4], ARFloat s2[3][4], ARFloat d[3][4]);
00432 
00433         static int arUtilMatInv(ARFloat s[3][4], ARFloat d[3][4]);
00434 
00435         static int arMatrixPCA(ARMat *input, ARMat *evec, ARVec *ev, ARVec *mean);
00436 
00437         static int arMatrixPCA2(ARMat *input, ARMat *evec, ARVec *ev);
00438 
00439         static int arParamSaveDouble(char *filename, int num, ARParamDouble *param, ...);
00440 
00441         static int arParamLoadDouble(char *filename, int num, ARParamDouble *param, ...);
00442 
00443         static int arParamDecomp(ARParam *source, ARParam *icpara, ARFloat trans[3][4]);
00444 
00445         static int arParamDecompMat(ARFloat source[3][4], ARFloat cpara[3][4], ARFloat trans[3][4]);
00446 
00447         int arParamObserv2Ideal_none(Camera* pCam, ARFloat ox, ARFloat oy, ARFloat *ix, ARFloat *iy);
00448 
00449         int arParamObserv2Ideal_LUT(Camera* pCam, ARFloat ox, ARFloat oy, ARFloat *ix, ARFloat *iy);
00450 
00451         int arParamObserv2Ideal_std(Camera* pCam, ARFloat ox, ARFloat oy, ARFloat *ix, ARFloat *iy);
00452         int arParamIdeal2Observ_std(Camera* pCam, ARFloat ix, ARFloat iy, ARFloat *ox, ARFloat *oy);
00453 
00454         typedef int (TrackerImpl::* ARPARAM_UNDIST_FUNC)(Camera* pCam, ARFloat ox, ARFloat oy, ARFloat *ix, ARFloat *iy);
00455 
00456         typedef ARFloat (TrackerImpl::* POSE_ESTIMATOR_FUNC)(ARMarkerInfo *marker_info, ARFloat center[2], ARFloat width, ARFloat conv[3][4]);
00457         typedef ARFloat (TrackerImpl::* MULTI_POSE_ESTIMATOR_FUNC)(ARMarkerInfo *marker_info, int marker_num, ARMultiMarkerInfoT *config);
00458 
00459         void buildUndistO2ITable(Camera* pCam);
00460 
00461         void checkRGB565LUT();
00462 
00463         
00464         static size_t getDynamicMemoryRequirements();
00465 
00466         Profiler& getProfiler()  {  return profiler;  }
00467 
00468 
00469 public:
00470         static void* operator new(size_t size);
00471 
00472         static void operator delete(void *rawMemory);
00473 
00474 
00475         
00476         
00477         void setFittingMode(int nWhich)  {  arFittingMode = nWhich;  }
00478 
00479         ARFloat arGetTransMat3(ARFloat rot[3][3], ARFloat ppos2d[][2],
00480                                                    ARFloat ppos3d[][2], int num, ARFloat conv[3][4],
00481                                                    Camera *pCam);
00482 
00483         static int arParamObserv2Ideal(Camera *pCam, ARFloat ox, ARFloat oy, ARFloat *ix, ARFloat *iy);
00484         static int arParamIdeal2Observ(Camera *pCam, ARFloat ix, ARFloat iy, ARFloat *ox, ARFloat *oy);
00485 
00486 
00487 protected:
00488         
00489         
00490 
00491         struct AutoThreshold {
00492                 enum {
00493                         MINLUM0 = 255,
00494                         MAXLUM0 = 0
00495                 };
00496 
00497                 void reset()
00498                 {
00499                         minLum = MINLUM0;  maxLum = MAXLUM0;
00500                 }
00501 
00502                 void addValue(int nRed, int nGreen, int nBlue, int nPixelFormat)
00503                 {
00504                         int lum;
00505 
00506                         
00507                         if(nPixelFormat==PIXEL_FORMAT_RGB565 || nPixelFormat==PIXEL_FORMAT_LUM)
00508                                 lum = nRed;
00509                         else
00510                                 lum = (nRed + (nGreen<<1) + nBlue)>>2;
00511 
00512                         if(lum<minLum)
00513                                 minLum = lum;
00514                         if(lum>maxLum)
00515                                 maxLum = lum;
00516                 }
00517 
00518                 int calc()
00519                 {
00520                         return (minLum+maxLum)/2;
00521                 }
00522 
00523                 bool enable;
00524                 int minLum,maxLum;
00525                 int numRandomRetries;
00526         } autoThreshold;
00527 
00528 
00529         PIXEL_FORMAT                    pixelFormat;
00530         int                                             pixelSize;
00531 
00532         int                                             binaryMarkerThreshold;
00533 
00534         
00535         
00536         ARMarkerInfo2                   *marker_info2;
00537         ARMarkerInfo                    *wmarker_info;
00538         int                                             wmarker_num;
00539 
00540         arPrevInfo                              prev_info[MAX_IMAGE_PATTERNS];
00541         int                                             prev_num;
00542 
00543         arPrevInfo                              sprev_info[2][MAX_IMAGE_PATTERNS];
00544         int                                             sprev_num[2];
00545 
00546         
00547         
00548         ARMarkerInfo2                   *marker_infoTWO;                
00549                                                                                                         
00550 
00551     int                                         arGetContour_wx[AR_CHAIN_MAX];
00552     int                                         arGetContour_wy[AR_CHAIN_MAX];
00553 
00554 
00555         
00556         int    pattern_num;
00557         int    patf[MAX_LOAD_PATTERNS];
00558         int    pat[MAX_LOAD_PATTERNS][4][PATTERN_HEIGHT*PATTERN_WIDTH*3];
00559         ARFloat patpow[MAX_LOAD_PATTERNS][4];
00560         int    patBW[MAX_LOAD_PATTERNS][4][PATTERN_HEIGHT*PATTERN_WIDTH*3];
00561         ARFloat patpowBW[MAX_LOAD_PATTERNS][4];
00562 
00563         ARFloat evec[EVEC_MAX][PATTERN_HEIGHT*PATTERN_WIDTH*3];
00564         ARFloat epat[MAX_LOAD_PATTERNS][4][EVEC_MAX];
00565         int    evec_dim;
00566         int    evecf;
00567         ARFloat evecBW[EVEC_MAX][PATTERN_HEIGHT*PATTERN_WIDTH*3];
00568         ARFloat epatBW[MAX_LOAD_PATTERNS][4][EVEC_MAX];
00569         int    evec_dimBW;
00570         int    evecBWf;
00571 
00572         
00573         
00574         ARMarkerInfo    marker_infoL[MAX_IMAGE_PATTERNS];
00575 
00576         
00577         
00578         ARFloat  pos2d[P_MAX][2];
00579         ARFloat  pos3d[P_MAX][3];
00580 
00581         
00582         
00583         ARInt16      *l_imageL; 
00584         ARInt16      *l_imageR;
00585         int                      l_imageL_size;
00586 
00587         int          *workL;  
00588         int          *work2L; 
00589 
00590         int          *workR;
00591         int          *work2R;
00592         int          *wareaR;
00593         int          *wclipR;
00594         ARFloat      *wposR;
00595 
00596         int          wlabel_numL;
00597         int          wlabel_numR;
00598         int          *wareaL;  
00599         int          *wclipL;  
00600         ARFloat       *wposL;  
00601 
00602         int        arFittingMode;
00603         int        arImageProcMode;
00604         Camera     *arCamera;
00605         bool            loadCachedUndist;
00606         int        arImXsize, arImYsize;
00607         int        arTemplateMatchingMode;
00608         int        arMatchingPCAMode;
00609 
00610         ARUint8*   arImageL;
00611 
00612         MARKER_MODE             markerMode;
00613 
00614         unsigned char *RGB565_to_LUM8_LUT;              
00615 
00616 
00617         
00618         
00619         UNDIST_MODE             undistMode;
00620         unsigned int    *undistO2ITable;
00621         
00622 
00623 
00624         ARFloat                 relBorderWidth;
00625 
00626         ARPARAM_UNDIST_FUNC arParamObserv2Ideal_func;
00627         
00628 
00629         
00630         POSE_ESTIMATOR  poseEstimator;
00631         
00632         
00633 
00634         ARToolKitPlus::Logger   *logger;
00635 
00636         int                                             screenWidth, screenHeight;
00637         int                                             thresh;
00638 
00639         ARParam                                 cparam;
00640 
00641         ARFloat                                 gl_para[16];
00642         ARFloat                                 gl_cpara[16];
00643 
00644         char                                    *descriptionString;
00645 
00646         struct {
00647                 bool enabled;
00648                 int corners, leftright, bottomtop;
00649         } vignetting;
00650 
00651         BCH                                             *bchProcessor;
00652         Profiler                                profiler;
00653 };
00654 
00655 
00656 }       
00657 
00658 
00659 
00660 
00661 
00662 #include "../../src/extra/FixedPoint.h"
00663 #include "../../src/core/arBitFieldPattern.cxx"
00664 #include "../../src/core/arDetectMarker.cxx"
00665 #include "../../src/core/arDetectMarker2.cxx"
00666 #include "../../src/core/arGetCode.cxx"
00667 #include "../../src/core/arGetMarkerInfo.cxx"
00668 #include "../../src/core/arGetTransMat.cxx"
00669 #include "../../src/core/arGetTransMat2.cxx"
00670 #include "../../src/core/arGetTransMat3.cxx"
00671 #include "../../src/core/rppGetTransMat.cxx" 
00672 #include "../../src/core/arGetTransMatCont.cxx"
00673 #include "../../src/core/arLabeling.cxx"
00674 #include "../../src/core/arMultiActivate.cxx"
00675 #include "../../src/core/arMultiGetTransMat.cxx"
00676 #include "../../src/core/rppMultiGetTransMat.cxx"       
00677 #include "../../src/core/arMultiReadConfigFile.cxx"
00678 #include "../../src/core/arUtil.cxx"
00679 #include "../../src/core/matrix.cxx"
00680 #include "../../src/core/mPCA.cxx"
00681 
00682 #include "../../src/core/paramDecomp.cxx"
00683 #include "../../src/core/paramDistortion.cxx"
00684 #include "../../src/core/byteSwap.cxx"
00685 #include "../../src/core/paramFile.cxx"
00686 #include "../../src/core/vector.cxx"
00687 
00688 #include "../../src/CameraImpl.cxx"
00689 #include "../../src/CameraAdvImpl.cxx"
00690 #include "../../src/CameraFactory.cxx"
00691 #include "../../src/extra/BCH.cxx"
00692 
00693 #include "../../src/TrackerImpl.cxx"
00694 
00695 
00696 
00697 
00698 #endif //__ARTOOLKIT_TRACKERIMPL_HEADERFILE__