ar.h
Go to the documentation of this file.
00001 /*  --------------------------------------------------------------------------
00002 *   Copyright (c) 20042-2007 HIT Lab NZ.
00003 *   The distribution policy is described in the file COPYING.txt furnished 
00004 *    with this library.
00005 *   -------------------------------------------------------------------------*/
00024 /*  --------------------------------------------------------------------------
00025 *   History : 
00026 *   Rev         Date            Who             Changes
00027 *
00028 *----------------------------------------------------------------------------*/
00029 
00030 #ifndef AR_H
00031 #define AR_H
00032 #ifdef __cplusplus
00033 extern "C" {
00034 #endif
00035 
00036 // ============================================================================
00037 //      Public includes.
00038 // ============================================================================
00039 
00040 #include <stdio.h>
00041 #ifndef __APPLE__
00042 #include <malloc.h>
00043 #else
00044 #include <stdlib.h>
00045 #endif
00046 
00047 #include <AR/config.h>
00048 #include <AR/param.h>
00049 
00050 // ============================================================================
00051 //      Public types and defines.
00052 // ============================================================================
00053 
00062 #define arMalloc(V,T,S)  \
00063 { if( ((V) = (T *)malloc( sizeof(T) * (S) )) == 0 ) \
00064 {printf("malloc error!!\n"); exit(1);} }
00065 
00066 /* overhead ARToolkit type*/
00067 typedef char              ARInt8;
00068 typedef short             ARInt16;
00069 typedef int               ARInt32;
00070 typedef unsigned char     ARUint8;
00071 typedef unsigned short    ARUint16;
00072 typedef unsigned int      ARUint32;
00073 
00132 typedef int AR_PIXEL_FORMAT;
00133 
00147 typedef struct {
00148     int     area;
00149     int     id;
00150     int     dir;
00151     double  cf;
00152     double  pos[2];
00153     double  line[4][3];
00154     double  vertex[4][2];
00155 } ARMarkerInfo;
00156 
00170 typedef struct {
00171     int     area;
00172     double  pos[2];
00173     int     coord_num;
00174     int     x_coord[AR_CHAIN_MAX];
00175     int     y_coord[AR_CHAIN_MAX];
00176     int     vertex[5];
00177 } ARMarkerInfo2;
00178 
00179 // ============================================================================
00180 //      Public globals.
00181 // ============================================================================
00182 
00192 extern int      arDebug;
00193 
00200 extern ARUint8  *arImage;
00201 
00212 extern int      arFittingMode;
00213 
00224 extern int      arImageProcMode;
00225 
00231 extern ARParam  arParam;
00232 
00243 extern int      arImXsize, arImYsize;
00244 
00254 extern int      arTemplateMatchingMode;
00255 
00265 extern int      arMatchingPCAMode;
00266 
00267 // ============================================================================
00268 //      Public functions.
00269 // ============================================================================
00270 
00271 /*
00272    Initialization
00273 */
00274 
00316 ARUint32 arGetVersion(char **versionStringRef);
00317 
00329 int arInitCparam( ARParam *param );
00330 
00339 int arLoadPatt( const char *filename );
00340 
00341 /*
00342    Detection
00343 */
00344 
00362 int arDetectMarker( ARUint8 *dataPtr, int thresh,
00363                     ARMarkerInfo **marker_info, int *marker_num );
00364 
00382 int arDetectMarkerLite( ARUint8 *dataPtr, int thresh,
00383                         ARMarkerInfo **marker_info, int *marker_num );
00384 
00402 double arGetTransMat( ARMarkerInfo *marker_info,
00403                       double center[2], double width, double conv[3][4] );
00404 
00425 double arGetTransMatCont( ARMarkerInfo *marker_info, double prev_conv[3][4],
00426                           double center[2], double width, double conv[3][4] );
00427 
00428 double arGetTransMat2( double rot[3][3], double pos2d[][2],
00429                        double pos3d[][2], int num, double conv[3][4] );
00430 double arGetTransMat3( double rot[3][3], double ppos2d[][2],
00431                      double ppos3d[][2], int num, double conv[3][4],
00432                      double *dist_factor, double cpara[3][4] );
00433 double arGetTransMat4( double rot[3][3], double ppos2d[][2],
00434                        double ppos3d[][3], int num, double conv[3][4] );
00435 double arGetTransMat5( double rot[3][3], double ppos2d[][2],
00436                        double ppos3d[][3], int num, double conv[3][4],
00437                        double *dist_factor, double cpara[3][4] );
00438 
00447 int arFreePatt( int patt_no );
00448 
00457 int arActivatePatt( int pat_no );
00458 
00467 int arDeactivatePatt( int pat_no );
00468 
00479 int arSavePatt( ARUint8 *image,
00480                 ARMarkerInfo *marker_info, char *filename );
00481 
00482 
00483 /*
00484     Utility
00485 */
00486 
00497 int    arUtilMatInv( double s[3][4], double d[3][4] );
00498 
00510 int    arUtilMatMul( double s1[3][4], double s2[3][4], double d[3][4] );
00511 
00522 int    arUtilMat2QuatPos( double m[3][4], double q[4], double p[3] );
00523 
00533 int    arUtilQuatPos2Mat( double q[4], double p[3], double m[3][4] );
00534 
00541 double arUtilTimer(void);
00542 
00549 void   arUtilTimerReset(void);
00550 
00557 void   arUtilSleep( int msec );
00558 
00559 /*
00560   Internal processing
00561 */
00562 
00577 ARInt16 *arLabeling( ARUint8 *image, int thresh,
00578                      int *label_num, int **area, double **pos, int **clip,
00579                      int **label_ref );
00580 
00587  void arLabelingCleanup(void);
00588 
00589 
00599 void arGetImgFeature( int *num, int **area, int **clip, double **pos );
00600 
00617 ARMarkerInfo2 *arDetectMarker2( ARInt16 *limage,
00618                                 int label_num, int *label_ref,
00619                                 int *warea, double *wpos, int *wclip,
00620                                 int area_max, int area_min, double factor, int *marker_num );
00621 
00631 ARMarkerInfo *arGetMarkerInfo( ARUint8 *image,
00632                                ARMarkerInfo2 *marker_info2, int *marker_num );
00633 
00647 int arGetCode( ARUint8 *image, int *x_coord, int *y_coord, int *vertex,
00648                int *code, int *dir, double *cf );
00649 
00662 int arGetPatt( ARUint8 *image, int *x_coord, int *y_coord, int *vertex,
00663                ARUint8 ext_pat[AR_PATT_SIZE_Y][AR_PATT_SIZE_X][3] );
00664 
00677 int arGetLine(int x_coord[], int y_coord[], int coord_num,
00678               int vertex[], double line[4][3], double v[4][2]);
00679 
00691 int arGetContour( ARInt16 *limage, int *label_ref,
00692                   int label, int clip[4], ARMarkerInfo2 *marker_info2 );
00693 
00706 double arModifyMatrix( double rot[3][3], double trans[3], double cpara[3][4],
00707                              double vertex[][3], double pos2d[][2], int num );
00708 
00719 int arGetAngle( double rot[3][3], double *wa, double *wb, double *wc );
00720 
00731 int arGetRot( double a, double b, double c, double rot[3][3] );
00732 
00746 int arGetNewMatrix( double a, double b, double c,
00747                     double trans[3], double trans2[3][4],
00748                     double cpara[3][4], double ret[3][4] );
00749 
00759 int arGetInitRot( ARMarkerInfo *marker_info, double cpara[3][4], double rot[3][3] );
00760 
00766 typedef struct {
00767     ARMarkerInfo  marker;
00768     int     count;
00769 } arPrevInfo;
00770 
00771 
00772 /*------------------------------------*/
00773 
00774 extern ARUint8  *arImageL;
00775 extern ARUint8  *arImageR;
00776 extern ARSParam arsParam;
00777 extern double   arsMatR2L[3][4];
00778 
00779 int           arsInitCparam      ( ARSParam *sparam );
00780 void          arsGetImgFeature   ( int *num, int **area, int **clip, double **pos, int LorR );
00781 ARInt16      *arsLabeling        ( ARUint8 *image, int thresh,
00782                                    int *label_num, int **area, double **pos, int **clip,
00783                                    int **label_ref, int LorR );
00784 int           arsGetLine         ( int x_coord[], int y_coord[], int coord_num,
00785                                    int vertex[], double line[4][3], double v[4][2], int LorR);
00786 ARMarkerInfo *arsGetMarkerInfo   ( ARUint8 *image,
00787                                    ARMarkerInfo2 *marker_info2, int *marker_num, int LorR );
00788 int           arsDetectMarker    ( ARUint8 *dataPtr, int thresh,
00789                                    ARMarkerInfo **marker_info, int *marker_num, int LorR );
00790 int           arsDetectMarkerLite( ARUint8 *dataPtr, int thresh,
00791                                    ARMarkerInfo **marker_info, int *marker_num, int LorR );
00792 double        arsGetTransMat     ( ARMarkerInfo *marker_infoL, ARMarkerInfo *marker_infoR,
00793                                    double center[2], double width,
00794                                    double transL[3][4], double transR[3][4] );
00795 double        arsGetTransMatCont ( ARMarkerInfo *marker_infoL, ARMarkerInfo *marker_infoR,
00796                                    double prev_conv[3][4],
00797                                    double center[2], double width,
00798                                    double transL[3][4], double transR[3][4] );
00799 double        arsGetTransMat2    ( double rot[3][3],
00800                                    double ppos2dL[][2], double ppos3dL[][3], int numL,
00801                                    double ppos2dR[][2], double ppos3dR[][3], int numR,
00802                                    double transL[3][4], double transR[3][4] );
00803 double        arsGetPosErr( double pos2dL[2], double pos2dR[2] );
00804 int           arsCheckPosition   ( double pos2dL[2], double pos2dR[2], double thresh );
00805 int           arsCheckMarkerPosition( ARMarkerInfo *marker_infoL, ARMarkerInfo *marker_infoR,
00806                                       double thresh );
00807 
00808 double arsModifyMatrix( double rot[3][3], double trans[3], ARSParam *arsParam,
00809                         double pos3dL[][3], double pos2dL[][2], int numL,
00810                         double pos3dR[][3], double pos2dR[][2], int numR );
00811 
00812 #ifdef __cplusplus
00813 }
00814 #endif
00815 #endif
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


ar_recog
Author(s): Graylin Trevor Jay and Christopher Crick
autogenerated on Fri Jan 25 2013 12:14:59