00001 /************************************************************************************************** 00002 Software License Agreement (BSD License) 00003 00004 Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt 00005 All rights reserved. 00006 00007 Redistribution and use in source and binary forms, with or without modification, are permitted 00008 provided that the following conditions are met: 00009 00010 *Redistributions of source code must retain the above copyright notice, this list of 00011 conditions and the following disclaimer. 00012 *Redistributions in binary form must reproduce the above copyright notice, this list of 00013 conditions and the following disclaimer in the documentation and/or other materials provided 00014 with the distribution. 00015 *Neither the name of the University of Aveiro nor the names of its contributors may be used to 00016 endorse or promote products derived from this software without specific prior written permission. 00017 00018 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR 00019 IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND 00020 FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR 00021 CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 00022 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, 00023 DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER 00024 IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT 00025 OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00026 ***************************************************************************************************/ 00027 /*************************************************************************************/ 00028 /* */ 00029 /* File: MbICP.h */ 00030 /* Authors: Luis Montesano and Javier Minguez */ 00031 /* Modified: 1/3/2006 */ 00032 /* */ 00033 /* This library implements the: */ 00034 /* */ 00035 /* */ 00036 /* J. Minguez, L. Montesano, and F. Lamiraux, "Metric-based iterative */ 00037 /* closest point scan matching for sensor displacement estimation," IEEE */ 00038 /* Transactions on Robotics, vol. 22, no. 5, pp. 1047 \u2013 1054, 2006. */ 00039 /*************************************************************************************/ 00040 /* 00041 * This program is free software; you can redistribute it and/or modify 00042 * it under the terms of the GNU General Public License as published by 00043 * the Free Software Foundation; either version 2 of the License, or 00044 * (at your option) any later version. 00045 * 00046 * This program is distributed in the hope that it will be useful, 00047 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00048 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00049 * GNU General Public License for more details. 00050 * 00051 * You should have received a copy of the GNU General Public License 00052 * along with this program; if not, write to the Free Software 00053 * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA 00054 * 00055 */ 00056 00057 /*****************************************************************************/ 00058 // 00059 // EVERYTHING IN THE INTERNATIONAL SYSTEM (METERS AND RADIANS) 00060 // 00061 /*****************************************************************************/ 00062 00068 #ifndef MbICP 00069 #define MbICP 00070 #include "TData.h" 00071 #include <stdlib.h> 00072 00073 #ifdef __cplusplus 00074 extern "C" { 00075 #endif 00076 00077 // ---------------------------------------------------------------------------- 00078 // DEFINES 00079 // ---------------------------------------------------------------------------- 00080 00081 /* 00082 #define MAXLASERPOINTS 361 00083 */ 00084 00085 // ---------------------------------------------------------------------------- 00086 // GENERIC TYPES 00087 // ---------------------------------------------------------------------------- 00088 00089 /*typedef struct { 00090 float x; 00091 float y; 00092 }Tpf; 00093 00094 typedef struct { 00095 float r; 00096 float t; 00097 }Tpfp; 00098 00099 typedef struct { 00100 int x; 00101 int y; 00102 }Tpi; 00103 00104 typedef struct { 00105 float x; 00106 float y; 00107 float tita; 00108 }Tsc; 00109 */ 00110 00111 // ---------------------------------------------------------------------------- 00112 // SPECIFIC TYPES 00113 // ---------------------------------------------------------------------------- 00114 00115 00116 // ---------------------------------------------------------------------------- 00117 // GLOBAL FUNCTIONS 00118 // ---------------------------------------------------------------------------- 00119 00120 00121 // ************************ 00122 // Function that initializes the SM parameters 00123 // ************************ 00124 00125 /* void InitScanMatching(float Bw, float Br, 00126 float L, int laserStep,float MaxDistInter, float filtrado, 00127 int MaxIter, float error_th, float exo, float eyo, float etitao, int IterSmoothConv); */ 00128 // in::: 00129 00130 /* --------------------- */ 00131 /* --- Thresold parameters */ 00132 /* --------------------- */ 00133 /* Bw: maximum angle diference between points of different scans */ 00134 /* Points with greater Bw cannot be correspondent (eliminate spurius asoc.) */ 00135 /* This is a speed up parameter */ 00136 //float Bw; 00137 00138 /* Br: maximum distance difference between points of different scans */ 00139 /* Points with greater Br cannot be correspondent (eliminate spurius asoc.) */ 00140 //float Br; 00141 00142 /* --------------------- */ 00143 /* --- Inner parameters */ 00144 /* --------------------- */ 00145 /* L: value of the metric */ 00146 /* When L tends to infinity you are using the standart ICP */ 00147 /* When L tends to 0 you use the metric (more importance to rotation) */ 00148 //float L; 00149 00150 /* laserStep: selects points of each scan with an step laserStep */ 00151 /* When laserStep=1 uses all the points of the scans */ 00152 /* When laserStep=2 uses one each two ... */ 00153 /* This is an speed up parameter */ 00154 //int laserStep; 00155 00156 /* ProjectionFilter: */ 00157 /* Eliminate the points that cannot be seen given the two scans (see Lu&Millios 97) */ 00158 /* It works well for angles < 45 \circ*/ 00159 /* 1 : activates the filter */ 00160 /* 0 : desactivates the filter */ 00161 // int ProjectionFilter; 00162 00163 /* MaxDistInter: maximum distance to interpolate between points in the ref scan */ 00164 /* Consecutive points with less Euclidean distance than MaxDistInter are considered to be a segment */ 00165 //float MaxDistInter; 00166 00167 /* filter: in [0,1] sets the % of asociations NOT considered spurious */ 00168 /* E.g. if filter=0.9 you use 90% of the associations */ 00169 /* The associations are ordered by distance and the (1-filter) with greater distance are not used */ 00170 /* This type of filtering is called "trimmed-ICP" */ 00171 //float filter; 00172 00173 /* AsocError: in [0,1] */ 00174 /* One way to check if the algorithm diverges if to supervise if the number of associatios goes below a thresold */ 00175 /* When the number of associations is below AsocError, the main function will return error in associations step */ 00176 // float AsocError; 00177 00178 /* --------------------- */ 00179 /* --- Exit parameters */ 00180 /* --------------------- */ 00181 /* MaxIter: sets the maximum number of iterations for the algorithm to exit */ 00182 /* The more iterations, the more chance you give the algorithm to be more accurate */ 00183 //int MaxIter; 00184 00185 /* errorRatio: in [0,1] sets the maximum error ratio between iterations to exit */ 00186 /* In iteration K, let be errorK the residual of the minimization */ 00187 /* Error_th=(errorK-1/errorK). When error_th tends to 1 more precise is the solution of the scan matching */ 00188 //float error_th; 00189 00190 /* errx_out,erry_out, errt_out: minimum error of the asociations to exit */ 00191 /* In each iteration, the error is the residual of the minimization in each component */ 00192 /* The condition is (errorKx<errx_out && errorKx<erry_out && errorKx<errt_out) */ 00193 /* When errorK tends to 0 the more precise is the solution of the scan matching */ 00194 //float errx_out,erry_out, errt_out; 00195 00196 /* IterSmoothConv: number of consecutive iterations that satisfity the error criteria (the two above criteria) */ 00197 /* (error_th) OR (errorx_out && errory_out && errt_out) */ 00198 /* With this parameter >1 avoids random solutions and estabilices the algorithm */ 00199 //int IterSmoothConv; 00200 00201 00202 00203 void Init_MbICP_ScanMatching( 00204 float max_laser_range, 00205 float Bw, 00206 float Br, 00207 float L, 00208 int laserStep, 00209 float MaxDistInter, 00210 float filter, 00211 int ProjectionFilter, 00212 float AsocError, 00213 int MaxIter, 00214 float errorRatio, 00215 float errx_out, 00216 float erry_out, 00217 float errt_out, 00218 int IterSmoothConv); 00219 00220 // ------------------------------------------------------------- 00221 00222 // ************************ 00223 // Function that does the scan matching 00224 // ************************ 00225 00226 /* int MbICPmatcher(Tpfp *laserK, Tpfp *laserK1, 00227 Tsc *sensorMotion, Tsc *solution); */ 00228 00229 // in::: 00230 // laserK: is the reference scan in polar coordinates (max. num points is MAXLASERPOINTS) 00231 // laserK1: is the new scan in polar coordinates (max. num points is MAXLASERPOINTS) 00232 // sensorMotion: initial SENSOR motion estimation from location K to location K1 00233 // solution: SENSOR motion solution from location K to location K1 00234 // out::: 00235 // 1 : Everything OK in less that the Maximum number of iterations 00236 // 2 : Everything OK but reached the Maximum number of iterations 00237 // -1: Failure in the association step 00238 // -2: Failure in the minimization step 00239 00240 // int MbICPmatcher(Tpfp *laserK, Tpfp *laserK1, Tsc *sensorMotion, Tsc *solution,int*numIter); 00241 int MbICPmatcher(Tpfp *laserK, Tpfp *laserK1, Tsc *sensorMotion, Tsc *solution); 00242 00243 #ifdef __cplusplus 00244 } 00245 #endif 00246 00247 00248 #endif