MbICP.h
Go to the documentation of this file.
00001 /*************************************************************************************/
00002 /*                                                                                   */
00003 /*  File:          MbICP.h                                                           */
00004 /*  Authors:       Luis Montesano and Javier Minguez                                 */
00005 /*  Modified:      1/3/2006                                                          */
00006 /*                                                                                   */
00007 /*  This library implements the:                                                     */
00008 /*                                                                                   */
00009 /*                                                                                   */
00010 /*      J. Minguez, L. Montesano, and F. Lamiraux, "Metric-based iterative              */
00011 /*      closest point scan matching for sensor displacement estimation," IEEE           */
00012 /*      Transactions on Robotics, vol. 22, no. 5, pp. 1047 \u2013 1054, 2006.           */
00013 /*************************************************************************************/
00014 
00015 
00016 /*****************************************************************************/
00017 //
00018 //      EVERYTHING IN THE INTERNATIONAL SYSTEM (METERS AND RADIANS)
00019 //
00020 /*****************************************************************************/
00021 
00022 #ifndef MbICP
00023 #define MbICP
00024 #include "TData.h"
00025 
00026 #ifdef __cplusplus
00027 extern "C" {
00028 #endif
00029 
00030 
00031 
00032 // ----------------------------------------------------------------------------
00033 // GLOBAL FUNCTIONS
00034 // ----------------------------------------------------------------------------
00035 
00036 
00037 // ************************
00038 // Function that initializes the SM parameters
00039 // ************************
00040 
00041 /* void InitScanMatching(float Bw, float Br,
00042                                                  float L, int laserStep,float MaxDistInter, float filtrado,
00043                                              int MaxIter, float error_th, float exo, float eyo, float etitao, int IterSmoothConv); */
00044 // in:::
00045 
00046         /* --------------------- */
00047         /* --- Thresold parameters */
00048         /* --------------------- */
00049         /* Bw: maximum angle diference between points of different scans */
00050         /* Points with greater Bw cannot be correspondent (eliminate spurius asoc.) */
00051         /* This is a speed up parameter */
00052         //float Bw;
00053 
00054         /* Br: maximum distance difference between points of different scans */
00055         /* Points with greater Br cannot be correspondent (eliminate spurius asoc.) */
00056         //float Br;
00057 
00058         /* --------------------- */
00059         /* --- Inner parameters */
00060         /* --------------------- */
00061         /* L: value of the metric */
00062         /* When L tends to infinity you are using the standart ICP */
00063     /* When L tends to 0 you use the metric (more importance to rotation) */
00064         //float L;
00065 
00066         /* laserStep: selects points of each scan with an step laserStep  */
00067         /* When laserStep=1 uses all the points of the scans */
00068         /* When laserStep=2 uses one each two ... */
00069         /* This is an speed up parameter */
00070         //int laserStep;
00071 
00072         /* ProjectionFilter: */
00073         /* Eliminate the points that cannot be seen given the two scans (see Lu&Millios 97) */
00074         /* It works well for angles < 45 \circ*/
00075         /* 1 : activates the filter */
00076         /* 0 : desactivates the filter */
00077         // int ProjectionFilter;
00078 
00079         /* MaxDistInter: maximum distance to interpolate between points in the ref scan */
00080         /* Consecutive points with less Euclidean distance than MaxDistInter are considered to be a segment */
00081         //float MaxDistInter;
00082 
00083         /* filter: in [0,1] sets the % of asociations NOT considered spurious */
00084         /* E.g. if filter=0.9 you use 90% of the associations */
00085         /* The associations are ordered by distance and the (1-filter) with greater distance are not used */
00086         /* This type of filtering is called "trimmed-ICP" */
00087         //float filter;
00088 
00089         /* AsocError: in [0,1] */
00090         /* One way to check if the algorithm diverges if to supervise if the number of associatios goes below a thresold */
00091         /* When the number of associations is below AsocError, the main function will return error in associations step */
00092         // float AsocError;
00093 
00094         /* --------------------- */
00095         /* --- Exit parameters */
00096         /* --------------------- */
00097         /* MaxIter: sets the maximum number of iterations for the algorithm to exit */
00098         /* The more iterations, the more chance you give the algorithm to be more accurate   */
00099         //int MaxIter;
00100 
00101         /* errorRatio: in [0,1] sets the maximum error ratio between iterations to exit */
00102         /* In iteration K, let be errorK the residual of the minimization */
00103         /* Error_th=(errorK-1/errorK). When error_th tends to 1 more precise is the solution of the scan matching */
00104         //float error_th;
00105 
00106         /* errx_out,erry_out, errt_out: minimum error of the asociations to exit */
00107         /* In each iteration, the error is the residual of the minimization in each component */
00108         /* The condition is (errorKx<errx_out && errorKx<erry_out && errorKx<errt_out) */
00109         /* When errorK tends to 0 the more precise is the solution of the scan matching */
00110         //float errx_out,erry_out, errt_out;
00111 
00112         /* IterSmoothConv: number of consecutive iterations that satisfity the error criteria (the two above criteria) */
00113         /* (error_th) OR (errorx_out && errory_out && errt_out) */
00114         /* With this parameter >1 avoids random solutions and estabilices the algorithm */
00115         //int IterSmoothConv;
00116 
00117 
00118 
00119 void Init_MbICP_ScanMatching(
00120                              float max_laser_range,
00121                              float Bw,
00122                              float Br,
00123                              float L,
00124                              int   laserStep,
00125                              float MaxDistInter,
00126                              float filter,
00127                              int   ProjectionFilter,
00128                              float AsocError,
00129                              int   MaxIter,
00130                              float errorRatio,
00131                              float errx_out,
00132                              float erry_out,
00133                              float errt_out,
00134                              int IterSmoothConv);
00135 
00136 // -------------------------------------------------------------
00137 
00138 // ************************
00139 // Function that does the scan matching
00140 // ************************
00141 
00142 /* int MbICPmatcher(Tpfp *laserK, Tpfp *laserK1,
00143                                  Tsc *sensorMotion, Tsc *solution); */
00144 
00145 // in:::
00146 //      laserK: is the reference scan in polar coordinates (max. num points is MAXLASERPOINTS)
00147 //              laserK1: is the new scan in polar coordinates (max. num points is MAXLASERPOINTS)
00148 //              sensorMotion: initial SENSOR motion estimation from location K to location K1
00149 //              solution: SENSOR motion solution from location K to location K1
00150 // out:::
00151 //              1 : Everything OK in less that the Maximum number of iterations
00152 //              2 : Everything OK but reached the Maximum number of iterations
00153 //              -1: Failure in the association step
00154 //              -2: Failure in the minimization step
00155 
00156 int MbICPmatcher(Tpfp *laserK, Tpfp *laserK1,
00157                                  Tsc *sensorMotion, Tsc *solution);
00158 
00159 #ifdef __cplusplus
00160 }
00161 #endif
00162 
00163 #endif


csm_ros
Author(s): Gaƫl Ecorchard , Ivan Dryanovski, William Morris, Andrea Censi
autogenerated on Sat Jun 8 2019 19:52:42