<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01//EN" "http://www.w3.org/TR/html4/strict.dtd"> <html> <!-- $Id: header.html 8799 2010-06-28 04:12:42Z jpgr87 $ --> <HEAD> <meta HTTP-EQUIV="Content-Type" CONTENT="text/html;CHARSET=utf-8"> <meta name="keywords" content="stage, robot, simulation, player, player/stage"> <link href="doxygen.css" rel="stylesheet" type="text/css"> <style type="text/css"> .floatright { float: right; margin: 0 0 1em 1em; } body { font-family: sans-serif; #font-family: Geneva, Verdana, Helvetica, Arial, sans-serif; background-color: #FFF; color:#000; } a:link { color: #A00; } a:visited { color: #800; } a { text-decoration: none; } a:hover { text-decoration: underline; } .timestamp { text-align:right; background-color: #DDD; font-size:75%;} h1 { font-size:160%; } h2 { font-size:110%; #color: #FFF; #background-color: #666; #padding:3px; } h3 { text-align:left; } img { border: 0; } ul.menu { position:relative; left:-2.5em; margin-bottom:0px; margin-top:0px; } ul.menu1 { position:relative; left:-2.1em; margin-bottom:0px; margin-top:0px; } li.menu { list-style-type: none; position:relative; #left:-0.5em; } #sidebar { position: absolute; left:0px; padding:2em; top:0em; width:12em;} #content { position: absolute; left:12em; top:0em; padding-left:3em; padding-right:3em; padding-bottom:2em; margin-top:1em; margin-right:2em; } div.box { background-color:#EEE; border: 1px solid #000; padding: 0.5ex 0.4em 0.5ex 0.6em; margin:1em; } div.title { font-weight:bold; background-color:#eee; margin-bottom:2px;} div.topbar { position: absolute; top:0px; left:9em; margin:1em; } </style> <TITLE>Player Manual</TITLE> </HEAD> <body> <div id="sidebar"> <h2 style="text-align:center;"> <a href="index.html"> <img width=140 src="http://playerstage.sourceforge.net/images/player_button_v3.png" alt="Player logo"><br></a> </h2> <div class="box"> <div class=title>Player</div> <ul class=menu> <li class=menu><a href="index.html">Frontpage</a> <li class=menu><a href="modules.html">Contents</a> </ul> </div> <div class="box"> <div class=title>User</div> <ul class=menu> <li class=menu><a href="install.html">Installation</a> <li class=menu><a href="start.html">Quick start</a> <li class=menu><a href="supported_hardware.html">Supported devices</a> <li class=menu><a href="group__tutorials.html">Tutorials</a> <li class=menu><a href="group__utils.html">Utilities</a> <li class=menu><a href="group__clientlibs.html">Client libraries</a> <li class=menu><a href="http://playerstage.sourceforge.net/wiki/Basic_FAQ">FAQ</a> <li class=menu><a href="help.html">Help</a> </ul> </div> <div class=box> <div class="title">Developer</div> <ul class=menu> <li class=menu><a href="architecture.html">Architecture</a> <li class=menu><a href="group__libplayercore.html">libplayercore</a> <ul class=menu1> <li class=menu><a href="group__interfaces.html">interfaces</a></li> </ul> <li class=menu><a href="group__libplayerdrivers.html">libplayerdrivers</a> <ul class=menu1> <li class=menu><a href="group__drivers.html">drivers</a></li> </ul> <li class=menu><a href="group__libplayercommon.html">libplayercommon</a> <li class=menu><a href="group__libplayerutils.html">libplayerutils</a> <li class=menu><a href="group__libplayersd.html">libplayersd</a> <li class=menu><a href="group__libplayertcp.html">libplayertcp</a> <li class=menu><a href="group__libplayerxdr.html">libplayerxdr</a> <li class=menu><a href="todo.html">TODO</a> </ul> </div> <div class=box> <!-- <a href="http://sourceforge.net"><img border=0 src="http://sourceforge.net/sflogo.php?group_id=42445&type=1"></a> --> <div class="title">Online</div> <a href="http://playerstage.sourceforge.net">Homepage</a><br> <a href="http://sourceforge.net/project/showfiles.php?group_id=42445">Download</a><br> <a href="http://sourceforge.net/projects/playerstage">Project</a><br> <a href="http://sourceforge.net/tracker/?group_id=42445">Bugs</a><br> <a href="http://sourceforge.net/mail/?group_id=42445">Help</a> </div> </div> <div id="content" > <!-- Generated by Doxygen 1.7.1 --> <div class="header"> <div class="headertitle"> <h1>mbicp<br/> <small> [<a class="el" href="group__drivers.html">Drivers</a>]</small> </h1> </div> </div> <div class="contents"> <p>ScanMatching. <a href="#_details">More...</a></p> <table class="memberdecls"> </table> <p>ScanMatching. </p> <p>This driver implements the metric-based ICP scan-matching algorithm.</p> <p>J. Minguez, L. Montesano, and F. Lamiraux, "Metric-based iterative closest point scan matching for sensor displacement estimation," IEEE Transactions on Robotics, vol. 22, no. 5, pp. 1047 1054, 2006.</p> <dl class="user"><dt><b>Compile-time dependencies</b></dt><dd></dd></dl> <ul> <li>none</li> </ul> <dl class="user"><dt><b>Provides</b></dt><dd></dd></dl> <ul> <li><a class="el" href="group__interface__position2d.html">position2d</a></li> </ul> <dl class="user"><dt><b>Requires</b></dt><dd></dd></dl> <ul> <li><a class="el" href="group__interface__position2d.html">position2d</a> : source of pose and velocity information</li> <li><a class="el" href="group__interface__laser.html">laser</a> : Pose-stamped laser scans (subtype PLAYER_LASER_DATA_SCANPOSE)</li> </ul> <dl class="user"><dt><b>Configuration requests</b></dt><dd></dd></dl> <ul> <li>none</li> </ul> <dl class="user"><dt><b>Configuration file options</b></dt><dd></dd></dl> <ul> <li>max_laser_range (float)<ul> <li>Default: 7.9 m</li> <li>Maximum laser range.</li> </ul> </li> </ul> <ul> <li>laserPose_x (float)<ul> <li>Default: 0.16 m</li> <li>Offset of the laser on the edge x (in the robot's system of reference).</li> </ul> </li> </ul> <ul> <li>laserPose_y (float)<ul> <li>Default: 0.0 m</li> <li>Offset of the laser on the edge y (in the robot's system of reference).</li> </ul> </li> </ul> <ul> <li>laserPose_th (float)<ul> <li>Default: 0.0 rad</li> <li>Offset of the laser on th (in the robot's system of reference).</li> </ul> </li> </ul> <ul> <li>radial_window (float)<ul> <li>Default: 0.3 m</li> <li>Maximum distance difference between points of different scans. Points with greater Br cannot be correspondent (eliminate spurius asoc.).</li> </ul> </li> </ul> <ul> <li>angular_window (float)<ul> <li>Default: 0.523333333 rad</li> <li>Maximum angle diference between points of different scans. Points with greater Bw cannot be correspondent (eliminate spurius asoc.).</li> </ul> </li> </ul> <ul> <li>L (float)<ul> <li>Default: 3.00</li> <li>Value of the metric. When L tends to infinity you are using the standart ICP. When L tends to 0 you use the metric (more importance to rotation), when L tends to infinity you are using Euclidian metric.</li> </ul> </li> </ul> <ul> <li>laserStep (integer)<ul> <li>Default: 1</li> <li>Selects points of each scan with an step laserStep. When laserStep=1 uses all the points of the scans When laserStep=2 uses one each two ... This is an speed up parameter.</li> </ul> </li> </ul> <ul> <li>MaxDistInter (float)<ul> <li>Default: 0.5 m</li> <li>Maximum distance to interpolate between points in the ref scan. Consecutive points with less Euclidean distance than MaxDistInter are considered to be a segment.</li> </ul> </li> </ul> <ul> <li>filter (float)<ul> <li>Default: 0.95</li> <li>In [0,1] sets the % of asociations NOT considered spurious. E.g. if filter=0.9 you use 90% of the associations. The associations are ordered by distance and the (1-filter) with greater distance are not used. This type of filtering is called "trimmed-ICP".</li> </ul> </li> </ul> <ul> <li>ProjectionFilter (int)<ul> <li>Default: 1</li> <li>Eliminate the points that cannot be seen given the two scans (see Lu&Millios 97). It works well for angles < 45 deg. 1 : activates the filter. 0 : desactivates the filter.</li> </ul> </li> </ul> <ul> <li>AsocError (float)<ul> <li>Default: 0.1</li> <li>In [0,1]. Sets the % of minimun associations to run the algorithm. One way to check if the algorithm diverges is to supervise if the number of associatios goes below a thresold. When the number of associations is below AsocError, the main function will return error in associations step.</li> </ul> </li> </ul> <ul> <li>MaxIter (int)<ul> <li>Default: 50</li> <li>Sets the maximum number of iterations for the algorithm to exit. The more iterations, the more chance you give the algorithm to be more accurate.</li> </ul> </li> </ul> <ul> <li>errorRatio (float)<ul> <li>Default: 0.0001 m</li> <li>In [0,1] sets the maximum error ratio between iterations to exit. In iteration K, let be errorK the residual of the minimization. Error_th=(errorK-1/errorK). When error_th tends to 1 more precise is the solution of the scan matching.</li> </ul> </li> </ul> <ul> <li>IterSmoothConv (int)<ul> <li>Default: 2</li> <li>Number of consecutive iterations that satisfity the error criteria (the two above criteria) (error_th) OR (errorx_out && errory_out && errt_out). With this parameter >1 avoids random solutions and estabilices the algorithm.</li> </ul> </li> </ul> <ul> <li>errx_out (float)<ul> <li>Default: 0.0001 m</li> <li>Minimum error in x of the asociations to exit. In each iteration, the error is the residual of the minimization in each component. The condition is (errorKx<errx_out && errorKx<erry_out && errorKx<errt_out). When errorK tends to 0 the more precise is the solution of the scan matching</li> </ul> </li> </ul> <ul> <li>erry_out (float)<ul> <li>Default: 0.0001 m</li> <li>Minimum error in x of the asociations to exit. In each iteration, the error is the residual of the minimization in each component. The condition is (errorKx<errx_out && errorKx<erry_out && errorKx<errt_out). When errorK tends to 0 the more precise is the solution of the scan matching</li> </ul> </li> </ul> <ul> <li>errt_out (float)<ul> <li>Default: 0.0001 m</li> <li>Minimum error in x of the asociations to exit. In each iteration, the error is the residual of the minimization in each component. The condition is (errorKx<errx_out && errorKx<erry_out && errorKx<errt_out). When errorK tends to 0 the more precise is the solution of the scan matching</li> </ul> </li> </ul> <dl class="user"><dt><b>Example</b></dt><dd></dd></dl> <div class="fragment"><pre class="fragment"> driver ( name "mbicp" provides ["position2d:1"] requires ["position2d:0" "laser:1"] max_laser_range 7.9 laserPose_x 0.16 laserPose_y 0 laserPose_th 0 radial_window 0.3 angular_window 0.523333333 L 3.00 laserStep 1 MaxDistInter 0.5 filter 0.95 ProjectionFilter 1 AsocError 0.1 MaxIter 50 errorRatio 0.0001 errx_out 0.0001 erry_out 0.0001 errt_out 0.0001 IterSmoothConv 2 ) </pre></div><dl class="author"><dt><b>Author:</b></dt><dd>Javier Minguez (underlying algorithm) </dd></dl> </div> <!-- render the modification time of the source file --> <div class="timestamp"> <hr> <table style="width:100%;"> <tr> <td style="text-align:left;"> Last updated 12 September 2005 21:38:45 <!-- <td style="text-align:right;"> <a href="http://validator.w3.org/check/referer"><img style="vertical-align:middle;border:0;width:88px;height:31px" src="http://www.w3.org/Icons/valid-html401" alt="Valid HTML 4.01!"></a> <a href="http://jigsaw.w3.org/css-validator/"> <img style="vertical-align:middle;border:0;width:88px;height:31px" src="http://jigsaw.w3.org/css-validator/images/vcss" alt="Valid CSS!"> </a> --> </tr> </table> </div> </tr> </table> </BODY> </HTML>