ARNL Documentation
1.7.0
Copyright (c) 2004, 2005 ActivMedia Robotics, LLC.
Copyright (c) 2006, 2007, 2008, 2009 MobileRobots Inc.
All rights reserved.
ARNL is MobileRobots Inc.'s software development kit for localizing and intelligently navigating mobile robots.
The ARNL suite performs two major tasks: Localization uses sensor information together with robot odometry data, and a prepared environment map to find the most probable position of the robot within the map, and resets ArRobot's pose to reflect that position within the map's coordinate system. Path Planning and Navigation uses the robot's position and the map to determine a safe route from the current robot position to any given goal position. The path planning task also will drive robot along the planned path, adjusting the path to avoid unmapped obstacles on the way.
There are several ARNL libraries or packages which implement different localization techniques, plus a base library, 'BaseArnl', which includes the path planning task, as well as common features used by the localization libraries. Which localization libraries you have will depend on what software options were purchased. The 'Arnl' localization library contains ArLocalizationTask which uses data obtained from a scanning laser range finder (ArSick) to localize. Arnl is part of the "Laser Navigation" accessory package. The 'SonArnl' localization library contains ArSonarLocalizationTask which uses the sonar (ultrasonic range sensors) for more approximate localization. SonArnl is included with any MobileRobots robot platform and can be used with any MobileRobots robot equipped with sonar. The 'Mogs' localization library contains ArGPSLocalizationTask which uses data from a GPS receiver to correct for odometry error and to locate the robot in a georegistered map. GPS localization is part of the "MOGS Outdoor Navigation" accessory package. It is also possible to use more than one localization tequnique simultaneosly, merging them into a unified result, though this feature is still experimental. All of the localization task classes from the various libraries are derived from ArBaseLocalizationTask in the BaseArnl library.
This reference manual describes using laser localization with the Arnl library. The ArLocalizationTask class works asynchronously to localize a robot in a known (mapped) indoor environment using data from a laser rangefinder and the robot. Besides a prepared map created and edited with Mapper3 (tm) or similar utility, ArLocalizationTask requires the use of a MobileRobots or ActivMedia robot platform or simulator equipped with a laser range-finding sensor. The map (ArMap, in the Aria library) used in localization and planning contains several types of data and objects. Maps may include designated forbidden areas, goals and a "home" poses.
ArLocalizationTask implements the Monte Carlo Localization Algorithm to accurately place the robot within a given map of its operating environment, as derived from laser-ranging and robot odometry information. The localization task is meant to be initialized and run as a separate thread.
To write a program using ARNL, include the Arnl/Aria.h, Arnl/Arnl.h, Arnl/ArLocalizationTask.h, and, if needed, Arnl/ArNetworking.h header files with your source code and link it with libBaseArnl, libAriaForArnl, libAriaNetworkingForArnl, and libArnl libraries in Arnl/lib.
You need to include five basic objects to enable localization: ArRobot, ArMap, one or more ArLaser objects, ArPathPlanningTask, and ArLocalizationTask. Other objects will also be required, such as ArRobotConnector, ArLaserConnector, etc.
For a complete example program using ARNL see arnlServer::cpp
First create an ArLocalizationTask object with an instantiated ArRobot, an ArLaser object and a map of the robot's environment, explicitly as a file or from ArMap. For example,
Next initialize the robot's location inside the map and do an initial localization. This initial localization may take several seconds.
myLocTask.localizeRobotAtHomeBlocking();
You can later reset the robot to a unique "home" pose, as prescribed in the map, any time before or after initialization using the localizeRobotAtHomeBlocking() or localizeRobotAtHomeNonBlocking() functions. Or use the forceUpdatePose() method to place the robot in the map:
myLocTask.forceUpdatePose(pose);
Thereafter, ArLocalizationTask thread automatically acts to relocate the robot in the map. To conserve processing resources, automatic localization updates happen only when the robot has moved beyond set translational and/or rotational limits. By default, these limits are set to +-200 mm translation and +-5 degrees rotation but may be changed by modifying ARNL's configuration parameters.
Before running your ARNL-enabled application, you can first physically position the robot (or simulated robot) at a starting position, such as its home point or at the place corresponding to 0,0,0 in the map so that ARNL can sucessfully perform the initial localization at that known point when localizeRobotAtHomeBlocking()
is called. Or, connect with MobileEyes and use its "Localize Robot to Point" command to position the robot in the map and trigger a position reset and re-initialize localization at that new starting point.
Aria and Arnl may be configured by modifying params/arnl.p, or through MobileEyes once it's running (if the program includes ArServerHandlerConfig object), or in the program through the global ArConfig object in Aria. For example, you can change the name of the map file used, change speeds and distance thresholds, etc. Each parameter has a description. The parameters are also described below. For most applications, only the "Normal" level parameters usually need to be changed, and sometimes a few "Advanced".
For explanation of the parameters, see ARNL Parameters in Detail below.
Each time ArLocalizationTask acts to update the robot's position in the map, it resets the pose of the ArRobot in ARIA (unless set not to do so). Hence, you may directly read the pose from the ArRobot class. There also are a number of functions in the ArLocalizationTask class which can return the current robot location and the states of the localization. These flags and scores show the state of the localization. These functions incluge getLocalizationScore(), getSensorBelief(), getState(), getIdleFlag().
Since the localization task deals with a map and builds its own occupancy grid, the class also provides access to the map and grid using member functions. Get these data by including the related include files and member functions.
ArLocalizationTask can alert your program if it fails to update localization while running. In order to do this, add a callback function to the class using ArLocalizationTask::addFailedLocalizationCB(). Remove the callback using the ArLocalizationTask::remFailedLocalizationCB() when finished. The integer argument is a count of how many localization attempts have failed so far.
#include "Aria/Aria.h"
#include "Arnl.h"
#include "ArLocalizationTask.h"
class MyClass {
ArLocalizationTask *myLocTask;
ArFunctor1C<MyClass, int> myLocFailedCB;
void failed(int n);
public:
MyClass(ArLocalizationTask *locTask);
~MyClass();
};
MyClass::MyClass(ArLocalizationTask *locTask) :
myLocTask(locTask),
myLocFailedCB(this, &MyClass::failed)
{
locTask->addFailedLocalizationCB(&myLocFailedCB);
}
MyClass::~MyClass()
{
locTask->remFailedLocalizationCB(&myLocFailedCB);
}
void MyClass::failed(int n)
{
ArLog::log(ArLog::Normal, "Localization failure.");
}
To localize and navigate, ARNL needs a map of the robot's operating environment showing obstacles to plan around (it will also plan around any obstacles recently sensed using sensor such as the laser or sonar). Maps may also contain logical features such as goal points, forbidden areas, and more.
The mapping process is different for each localization method, though the map files are compatible and can be reused if they contain enough information useful to other methods (for example, laser localization in particular needs an accurate map of laser-sensed obstacles to match with laser readings).
To learn more about creating a map for laser localization with Arnl, see Mapping.txt.
In addition to the basic laser localization, ARNL has advanced features which enable the robot to localize and navigate in a more specialized manner. Some of these are as follows. These features are complex to use. If you think you need any of them and have any questions, please ask on the aria-users forum.
-
Reflectors: The SICK laser range finder can not only sense the range of an object but also compute its reflectivity. If the robot environment is marked with special reflective tape (manufactured by SICK), the SICK can detect it. ARNL can use the known position of the landmarks on the map and the reflectors it sees in its current laser view to compute the pose of the robot. To achieve this, ARNL uses an extended Kalman filter to fuse the movement from the wheel encoders and the reflections from the laser. The resulting pose computed from the reflectors can be fused with the pose from the MCL localization. If enabled, ARNL can also compute the pose using a closed form solution of the landmark equations. This triangulation computation can compute a solution whenever more than one reflectors come into view. This advanced feature was added to ARNL to enable the robot to localize even in locations such as a factory where the environment varies so widely that the robot loses localization using the regular MCL localization. To use reflectors, the map used must contain the reflector data, and the user must enable the reflector bits for the SICK laser by including the following command line arguments: -laserReflectorBits 3ref -laserUnits 1cm'
(For example, guiServer -map reflectors.map -laserReflectorBits 3ref -laserUnits 1cm
).
To get the reflector localization to work, you will need to use a map created with the Mapper3 software from MobileRobots. Please refer to the Mapper documentation to create a map and set it to display the reflectors on MobileEyes.
-
Use of other robots for localization: When multiple robots are operated in the same map using a central server, there can be situations where the robot sees more of other robot boundaries than the map of the environment. In such cases the known poses and radii of the other robots (obtained from the central server) can be used for aiding instead of losing localization. ARNL now has the capability of adding known but unmapped objects in the map and using them for localization.
-
Ray Tracing for Initial localization: The truth of the initial localization of the robot before it starts to move is essential to keep the robot localized when it does move. Since the samples during initialization are spread about the user set pose, some poses will score high even though the sensor rays in such a pose have to trace through occupied cells to land on another occupied cell. To avoid this, we use a computationally intensive ray tracing to avoid high scores for such sensor impossiblities. This ray tracing is not done for localization triggered after a move because of the computation load. Note that this new feature will cause the initial localization to take longer than was the case earlier. During this initialization the robot localization state will be set to "lost" and the user may not be able to move the robot until this localization finishes successfully.
-
Inter-robot communication and mutual avoidance (ARNL laser localization package only): The multi-robot networking services allow robots to communicate their positions and path data either in a peer-to-peer fashion, or through a central server, to better avoid each other in a multiple-robot application. To use this feature, you must create an ArServerHandlerMultiRobotPeer or an ArServerHandlerMultiRobot object and configure relevant parameters. See the ArServerHandlerMultiRobotPeer and ArServerHandlerMultiRobot documentation for details.
-
Localization Manager. ARNL now has the capablility of localizing the robot in a map using multiple methods such as MCL, Reflector based localization, GPS based outdoor localization (and and perhaps others in the future). When several localizations provide their estimates of the robot pose with varying degrees of accuracy, ARNL uses the localization manager to compute a weighted average of their estimates to find an optimal pose. The weights in the averaging is based on the variance matrices of their respective estimates. The localization manager does the actual move of the robots pose to this optimal pose using the moveTo command. (Earlier, the lone ArLocalizationTask handled this moveTo).
To use the localization manager, you must construct the separate localization tasks and add them to the localization manager one by one. The act of adding a localization task to the manager suppresses its ability to directly alter the robot pose using moveTo and instead lets the manager do it for them.
The actual motion of the robot when following a path depends on a number of factors which are as follows.
-
Low level robot control parameters contained in ARIA such as the maximum allowable linear acceleration, its maximum allowable rotation accelerations etc as set in ARIA's robot parameter files
p3dx.p
when connected to a robot of type "p3dx".
-
The localization and path planning parameters used by ARNL such as the maximum linear and rotational velocities set in the configuration.
-
The degree of crowdedness of the actual environment the robot is moving in.
You can tune many parameters in ARNL to customize the behavior of the robot according to the robot's environment. These parameters are obtained by loading a parameter file using ArConfig. By default, ARNL will load parameters from arnl.p
and SONARNL will load parameters from sonarnl.p
. Parameters may also be changed on-line through MobileEyes.
For example, if the environment has few unmapped obstacles and is relatively fixed, the user can get away with a lower CollisionDistance parameter which will reduce the collision computation. If the robot has to navigate through narrow passages like doors, the PlanRes can be decreased to allow for more resolution. Changing some of these parameters can result in unintended consequences due to the limited resources such as the speed of the on board computer and memory. For example reducing the PlanRes by a factor will cause path planning computations to increase by the square of the factor. Planning and obstacle avoidance can also fail to operate as expected due to parameter values. (Remember, always test your software carefully in a controlled environment.)
The following subsection will list MCL laser localization related parameters and their use in arnl.p. The default values are noted in paratheses.
The default parameters in arnl.p are meant to drive Pioneer class of robots in office type environments. If you are using a larger and heavier robot such as a powerbot, remember to tune the default parameters to your needs.
Key MCL Localization parameters:
-
Map: The path to the map filename of the environment we'll use to navigate.
-
NumSamples: (2000) No of pose samples for MCL. The larger this number, the more computation will localization take. Too low a number will cause the robot to lose localization.
-
NumSamplesAtInit: (4000) No of pose samples for MCL when initializing the robot in the map. Since this is presumably done when the robot is at rest, it can be larger than NumSamples and use more computation for more accuracy. (A value of 0 will make it equal to NumSamples).
-
AdjustNumSamplesFlag: (false) The number of samples is by default kept high to keep the robot from losing localization even after initialization. This number can be lowered during motion in places of the map where the localization score is high to reduce the computation load. Set this flag to true if you want to vary the number of samples with the localization score. (As the score drops, the no of samples will rise)").
-
GridRes: (100 mm) The resolution of the occupancy grid representing the map in mm. Smaller resolution results in more accuracy but more computation.
-
PassThreshold (0.2) After MCL sensor correction, the sample with the maximum probability will have a score based on the match between sensor and the map points. This is the minimum score out of 1.0 to be considered localized.
-
PeturbX: (10 mm) After sensor correction and resampling the chosen pose is perturbed to generate a new sample. This parameter decides the range to perturb the X axis in mm.
-
PeturbY: (10 mm) Same as above for the Y.. This parameter decides the range to perturb at in the Y axis in mm.
-
PeturbTh: (1 deg) Same as above for the Theta. This parameter decides the range to perturb at in the angle in degs.
-
FailedX: (300 mm) Range of the box in the X axis in mm to distribute samples after localization fails.
-
FailedY: (300 mm) Range of the box in the Y axis in mm to distribute samples after localization fails.
-
FailedTh: (45 deg) Range of the angle in degs to distribute samples after localization fails.
-
RecoverOnFail: (false) If localization fails, this flag will decide if a static localization is attempted around last known robot pose. Such a reinitialization can cause the robot to be hopelessly lost if the actual robot is very different from its last known pose.
-
PeakStdX: (10 mm) If the standard deviation of all the X coords of the samples lie within this number then the localization is considered to have a unique solution. If not, the localization is considered to have multiple solutions.
-
PeakStdY: (10 mm) Same as above but pertains to the Y axis in mm.
-
PeakStdTh: (1 deg) Same as above but pertains to the Angle in degrees.
-
PeakFactor: (0.000001) When a number of distinct samples poses have non zero probabilities such as when there are ambiguities along the center of a long corridor. This is the threshold below the maximum probability to be considered a valid hypothesis.
-
StdX: (200 mm) The standard deviation of the Gaussian ellipse when localization is initialized in a map.
-
StdY: (200 mm) Same as above but pertains to the Y axis in mm.
-
StdTh: (30 deg) Same as above but pertains to the Angle in degrees.
-
KMmPerMm: (0.2) When the robot moves linearly, the error in distance is proportional to the distance moved. This error is is given as a fraction in mm per mm
-
KDegPerDeg (0.2) When the robot rotates, the error in the angle is proportional to the angle turned. This is expressed as a fraction in degs per deg.
-
KDegPerMm (0.01) When the robot moves linearly it can also affect its orientation. This drift can be expressed as a fraction in degs per mm.
-
TriggerDistance: (200 mm) Since MCL localization is computationally expensive, it is triggered only when the robot has moved this far in mm.
-
TriggerAngle: (5 deg) Same as above but now it triggers when the robot has turned this far in degs.
-
TriggerTime (0msec) Since MCL localization is computationally expensive, it is triggered only when the robot has been idle for this long in milliseconds. (A value of 0 will disable the feature)
-
TriggerTimeX (100 mm) When localization is triggered by time this parameter decides the range of the samples in X coords in mm.
-
TriggerTimeY (100 mm) When localization is triggered by time this parameter decides the range of the samples in Y coords in mm.
-
TriggerTimeTh (180 deg) When localization is triggered by time this parameter decides the range of the samples in Theta coords in degs.
-
SensorBelief: (0.9) Probability that a range reading from the laser is valid. This is used in the correction of the probabilities of the samples using the sensor.
-
ObsThreshold: (0.1) The threshold value of the occupancy grid to consider as occupied.
-
AngleIncrement: (0 deg) The localization will use only one out of every this many degrees in the laser. The lower limit is decided by the LaserIncrement setting.
-
DiscardThreshold: (0.33) A robot sample pose lying inside an occupancy grid cell with a value above this will be usually discarded. This is useful in cases where robot may intersect map points such as during patrolbot docking.
-
ScoreToVarFactor (4.0) When MCL based localization is combined with other localizations using the variance and mean. The variance of the pose XY in the MCL is increased by the exp(1/pow(score, ScoreToVarFactor) to avoid swamping the other localizations with its typically low values.
-
FuseAllSensors (true) ARNL uses a Kalman filter which allows you to combine the data from the MCL localization, the movement from the encoder between cycles and reflectors if mapped and seen by the laser. This advanced feature can be disabled to revert to the basic MCL localization, using this flag.
-
EnableReflectorLocalization (false) This flag will allow the kalman filter to incorporate any reflector measurements along with the odometry to compute the pose of the robot.
-
ReflectorVar (100000.0 mm*mm) This number will be used as the variance of the (x, y) coords of the center of the reflectors in the R matrix of the Kalman filter.
-
ReflectorMatchDist (2000.0 mm) When matching a seen reflector with a known reflector in the map. This will be the maximum distance to be considered a match.
-
ReflectorMatchAngle (5.0 degs) When matching a seen reflector with a known reflector in the map. This will be the maximum angle from the robot to the known and seen reflector points.
-
ReflectorMaxRange (8000.0 mm) This is the maximum distance that the SICK lrf is capable of seeing a reflector. (This is smaller than the max range of the regular SICK readings).
-
ReflectorMaxAngle (30.0 deg) This is the maximum angle of incidence that the SICK lrf is capable of seeing a reflector at. (This is much smaller than the angle that the regular SICK readings are capable of returning).
-
ReflectorSize (300.0 mm) When clustering the reflector points in the laser return, all reflector points inside this range will be classed as belonging to one reflector.
-
ReflectorAngleVarLimit (0.0 deg) The (2, 2) element in the kalman filter P for the reflector localization seems to be too small. This may swamp out the angle information from the other localizations. Till a solution is found this is artificial lower limit imposed on the (2, 2) element.
-
BadReflectorFactor (1000.0) When reflectors are far away, they are sensed as lone points. Such points sometimes flicker between edges if they are just around a corner. This can mess up localization. So the variance on x and y for this measurement will be increased by this factor in such cases.
-
EnableTriangulationFlag (false) When possible the kalman cycle will resort to triangulation when multiple reflectors are seen. This flag can be used to disable this from happening.
-
ReflectorTriDistLimit (500.0 mm) When possible the kalman cycle will resort to triangulation when multiple reflectors are seen and triangulation is enabled. The resulting pose will be allowed if the standard deviation in the XY coords is less this limit.
-
ReflectorTriAngLimit (5.0 degs) When possible the kalman cycle will resort to triangulation when multiple reflectors are seen and triangulation is enabled. The resulting pose will be allowed if the standard deviation in the angle coord is less this limit.
-
QTra (10000.0 mm*mm) The variance of X and Y coords in the kalman filter's plant model.
-
QRot (100.0 deg*deg) The variance of Theta coords in the kalman filter's plant model.
-
QTraVel (1.0 (mm/s)^2) The variance of X and Y velocity in the kalman filter's plant model.
-
QRotVel (1.0 (deg/s)^2) The variance of rot velocity in the kalman filter's plant model.
-
QTraAcc (1.0 (mm/s/s)^2) The variance of X and Y acceleration in the kalman filter's plant model. (not used)
-
QTraRot (1.0 (deg/s/s)^2) The variance of rotational acceleration in the kalman filter's plant model. (not used)
-
XYLimit (1000.0 mm) Three times this limit will be the maximum innovation allowed in the XY coords during sensor update. If the innovation exceeds this it will be considered an outlier and the sensor reading will be ignored (not used).
-
ThLimit (10.0 deg) Three times this limit will be the maximum innovation allowed in the theta coords during sensor update. If the innovation exceeds this it will be considered an outlier and the sensor reading will be ignored (not used).
-
UseAllK (true) The gain matrix K of the Kalman is sensitive to the values of Q and R especially about the elements related to the angle. In some cases, it might be easier to blank out all innovations related to the angle from all measurements. This is the flag to use in that case.
-
LogFlag (false) Flag to write kalman debug data into file.
Generated on Thu Apr 23 10:19:34 2009 for ARNL by
1.5.1