Content uploaded by Jaime Valls Miro
Author content
All content in this area was uploaded by Jaime Valls Miro on Aug 30, 2014
Content may be subject to copyright.
178 Int. J. Automation and Control, Vol. 2, Nos. 2/3, 2008
An adaptive manoeuvring strategy for mobile robots
in cluttered dynamic environments
Jaime Valls Miró*, Tarek Taha,
Dalong Wang and Gamini Dissanayake
ARC Centre of Excellence for Autonomous Systems (CAS),
Faculty of Engineering, University of Technology Sydney (UTS),
NSW2007, Australia
E-mail: j.vallsmiro@cas.edu.au
E-mail: t.taha@cas.edu.au
E-mail: d.wang@cas.edu.au
E-mail: g.dissanayake@cas.edu.au
*Corresponding author
Abstract: A novel method which combines an optimised global path planner
with a real-time sensor-based collision avoidance mechanism to accommodate
for dynamic changes in the environment (e.g., people) is presented. The basic
concept is to generate a continually changing parameterised family of virtual
force fields for the robot based on characteristics such as location, travelling
speed and dimension of the objects in the vicinity, static and dynamic. The
interactions among the repulsive forces associated with the various obstacles
provide a natural way for local collision avoidance in a partially known
cluttered environment. This is harnessed by locally modifying the planned
behaviour of the moving platform in real-time, whilst preserving the optimised
nature of the global path. Furthermore, path traversability is continually
monitored by the global planner to trigger a complete path re-planning from the
current location in case of major changes, most notably when the path is
completely blocked by obstacles.
Keywords: autonomous robot navigation; global path planning; dynamic
environments; reactive local obstacle avoidance controller.
Reference to this paper should be made as follows: Valls Miró, J., Taha, T.,
Wang, D. and Dissanayake, G. (2008) ‘An adaptive manoeuvring strategy for
mobile robots in cluttered dynamic environments’, Int. J. Automation and
Control, Vol. 2, Nos. 2/3, pp.178–194.
Biographical notes: The authors are with the Australian Research Council
(ARC) Centre of Excellence for Autonomous Systems (CAS), where they are
actively involved in research in the multi-disciplinary fields of planning,
control, perception and human-robot interaction with mobile robots. Their work
is primarily focused in the indoor environments where humans share their
space with both single and multiple autonomous and semi-autonomous
platforms.
Copyright © 2008 Inderscience Enterprises Ltd.
An adaptive manoeuvring strategy for mobile robots 179
1 Motivation
The problem of planning and tracking a path in a partially known cluttered environment
in the presence of other moving objects is considered here. Classically, the simpler
problem of planning in static environments has been approached from two perspectives,
opposite to some extent, yet both reliant on the use of advanced perception abilities to
gather as much information as possible about the environment:
• use the sensorial data to build or modify a detailed internal representation of this
environment which the robot would then use to re-plan a feasible path from source to
the destination
• employ the measurements in a reactive obstacle avoidance controller.
The former is the most generalised technique to address the problem in highly structured
environments as it follows the intuitive sense-model-plan-act technique which more
closely resembles the human reasoning and a vast number of solutions can be found in
the literature (see Latombe, 1999 for some examples). However, its performance in real
scenarios is poor given the unreliable nature of the perceived data and the high
computational cost of modelling complex environments. Moreover, any changes in the
robot surroundings require a reiteration of the algorithm or the pre-computed path will
almost certainly hit obstacles, hence making it particularly unsuitable for dynamic
environments.
These perceived limitations have led to mobile robot navigation modules where
locally simple reactive behaviours are in charge of computing the motion of the robot.
Rather than storing a detailed model of the world to compute a geometric path free of
collisions with the perceived obstacles, the technique effectively uses the world as its
own model, introducing sensory information within the control loop. The main drawback
then becomes its locality in execution (Minguez et al., 2005), as not all information is
available to the robot’s sensors. For this reason, while some form of reactive obstacle
avoidance behaviour becomes necessary (particularly in dynamic environment), the use
of a high-level world model and a global planning strategy is also mandatory. This hybrid
model has emerged as the preferred motion planning architecture for mobile platforms in
use today.
In our previous work, Taha et al. (2006b), we addressed the problem of designing an
efficient near optimal global planner for mobile platforms. The proposed solution was
proved to be time efficient and feasible even in the case of large robots in narrow
passages, and compared favourably to currently available static path planning algorithms
such as RRTs and PRMs. However, the uncertainties the system was capable of dealing
with were limited to those a simple linear controller could overcome in bringing the robot
back to the pre-planned path. The absence of an interactive response to changes in the
environment meant the solution was limited to known static environments. In the work
presented here, these shortcomings are overcome by introducing a novel reactive planner
in the loop in line with the hybrid approach scenario described.
1.1 Contribution
The main contribution of this paper lies with the framework proposed to ensure safe and
optimal navigation of a robot in uncertain dynamically changing scenarios. Given a
180 J. Valls Miró et al.
partially known model of the environment, a higher-level planner (Taha et al., 2006b) is
employed for describing an optimised path from source to destination and also for
constantly monitoring the traversability of the way-points to trigger a global re-planning
when the feasible path gets obstructed. An innovative strategy is then presented to handle
underlying local navigation issues in between way-points. The methodology, framed
within the context of a force field approach recently proposed in Wang et al. (2006) for
multi-robot path planning and collaboration is suitably modified here to handle the
behaviour of the robot at a local scale in the presence not only of static changes and
uncertain localisation within the environment, but also of moving objects in the vicinity.
In the approach, a virtual force field is constructed around the robot based on the current
characteristics from the moving platform itself such as travelling speed, dimension and
location, combined with the status of the surrounding dynamic and static obstacles as
given by the sensorial information. It is the interaction of all the attractive and repulsive
forces at play what drives the robot towards its local goal in an efficient and natural
manner. This is demonstrated with the simulation of an autonomous wheelchair operating
in a challenging office-like scenario with dynamic obstacles moving nearby.
The remainder of this manuscript is organised as follows: latest proposals to the path
planning and obstacle avoidance problem and where our approach represents an
improvement is analysed in Section 2. The methodology used for the creation of the
search space and the actual path finding is summarised in Section 3, with Section 4
focusing on the proposed force field reactive planner. Detailed simulation results are
given in Section 5. Finally, Section 6 summarises the contributions of this paper and
future work.
2 Path planning and obstacle avoidance background
2.1 Path planning
Motion planning is characterised by the ability to compute a collision-free path from an
initial pose to a goal position in between static obstacles, or by maintaining a set of
constraints in the state of the world such as following a target or exploring unknown
environments. Motion planning has been extensively studied and the reader is referred to
Latombe (1999) for a thorough review. Most of the current approaches are based on the
concept of configuration space (C-space) introduced by Lozano-Pérez and Wesley (1979)
and Lozano-Pérez (1983) in which robots are regarded as a single point in a high
dimensional space equivalent to the degrees of freedom of the robot. As the obstacles are
generally expanded in an over-simplistic manner by the length of the larger robot
dimension, this approach very often pre-vents larger robots in cluttered environment from
ever reaching a solution, even when it exist (Lozano-Pérez, 1983).
The exact construction of the C-space is a computationally expensive solution
(Hwang and Ahuja, 1992) and sampling-based techniques, in which a random set of
points are used to represent the C-space, have been developed which provide a faster
practical solution by sacrificing completeness (Kavraki et al., 1996; LaValle and Kuffner,
2000). Traditionally, sampling-based algorithms are based on uniform sampling which
considers the whole environment as uniformly complex and thus the overall sampling
density will be equivalent to that needed by the most complex region, reaching its worst
case scenario when narrow passage areas exist in the environment (Hsu et al., 1998).
An adaptive manoeuvring strategy for mobile robots 181
Non-uniform methods such as the Gaussian sampling strategy (Boor et al., 1999) and the
bridge test (Hsu et al., 2003) have been proposed to ensure that most of the configuration
space is actually close to obstacles or inside a narrow passage, thus reducing unnecessary
samples and decreasing the computational time.
Sampling algorithms are generally divided into two based on the complexity of the
pre-processing step heuristics which set up the search space: multi-query and
single-query approaches. The former starts with a step that usually takes a large amount
of time but makes solving path planning problems in the same environment faster. PRMs
(Kavraki et al., 1996) is an example of a multi-query approach that initially used uniform
sampling in constructing the path, although nowadays, PRMs are moving into
non-uniform sampling methods (Barraquand et al., 1997). Single-query methods were
developed to avoid the large pre-computational time that the multi-query methods take,
and they have been proved to be efficient (Sanchez and Latombe, 2001). RRTs (LaValle
and Kuffner, 2000); Cheng and LaValle, 2002) mainly based on single-query methods,
have gained popularity from their good performances. This has lead to a number of
extensions specifically targeted to the solution of complicated geometrical problems
(Choudhury and Lynch, 2002), such as the deterministic resolution-complete alternatives
that have been proposed to replace the random sampling methods in Kim and Ostrowski
(2003).
In many cases, an optimal and not just a feasible path is required. The random nature
of the above planners means the paths generated are very often sub-optimal and
non-smooth, not particularly suitable for realistic robot traversal. A two-phase approach
was proposed in Philips et al. (2004) to optimise paths in the special case where the
first-phase generated paths are made up of straight line segments connected by
way-points. Another two-phase planning algorithm based on RRT was developed in
Vougiouksa (2005) where low cost paths are computed by a numerical gradient descent
algorithm that minimises the Hamiltonian of the entire path. In this work, a hybrid
time-efficient path planning algorithm developed by the authors which has proved to
compare favourably to PRMs and RRTs (Taha et al., 2006a) has been employed. The
strategy, based on a non-uniform multi-query planner, uses a-priory static map of the
environment to calculate an offline, minimalistic free search space where computational
resources are directed towards the narrow passages. The algorithm takes further
advantage of techniques like the bridge test and an optimised obstacle expansion method
to further reduce the number of samples and the points to be check for obstacle collision.
The optimality and smoothness weaknesses of probabilistic path planners are addressed
by the addition of a smooth cost function to the search space. A modified A* search (Hart
et al., 1968) is then implemented to find suitable paths on this space. The result is a
time-efficient path planner with smooth and cost optimal paths.
2.2 Obstacle avoidance
Local obstacle avoidance methods focus on changing the robot’s trajectory based on its
sensors data during robot motion. The ‘bug’ algorithm (Lumelsky and Skewis, 1990),
which proposes to circumnavigate the obstacles by following the contour of each obstacle
in the robot’s way is perhaps the simplest obstacle avoidance algorithm, where no
control, kinematic or dynamic constraints are considered. Techniques, such as potential
field methods (Khatib, 1986) are particularly attractive too as their simple conception can
be used for online purposes to drive the robot among static obstacles towards the target.
182 J. Valls Miró et al.
Here, the robot is treated as a point under the influence of an artificial potential field. The
basic idea behind all potential field approaches is that the robot is attracted toward the
goal, while being repulsed by the sensed obstacles. Although the approach does not take
into account robot kinematics, other strategies have been proposed to transform the
three-dimensional obstacle avoidance problem with shape and kinematics constraints into
the simpler planning scenario of a point moving in a two-dimensional space without
kinematic restrictions (Minguez et al., 2005).
However, traditionally the problem is solved in the control space by computing a set
of collision-free admissible motions, followed by a selection based on some form of
optimisation and convergence towards the target. This is the case of the curvature
velocity method (CVM) (Simmons, 1996), which takes the actual kinematics constrains
and some dynamic constrain into account. The drawback of this method resides in the
circular simplifications attributed to the shape of the obstacles, and the existence of local
minima. Other techniques which also take into account admissible controls and robot
shape constraints include the dynamic window obstacle avoidance method (DWA) (Fox
et al., 1997) and the global dynamic window approach (GDWA) (Brock and Khatib,
1999) variation.
The family of vector field histogram (VFH) (Borenstein and Koren, 1990) technique
also takes into consideration some form of kinematic/dynamic constraints and is a
preferred choice in mobile robot applications for its speed and results. The algorithm
looks for gaps between the obstacles in front of the robot and builds a local map based on
the concept of certainty grid (Moravec and Elfes, 1985) from recent sensor range
readings. A variation of the original, the VFH+ (Ulrich and Borenstein, 1998), first
comes up with a simplified model of the moving robot’s possible trajectories based on its
kinematics limitations. Then obstacles which block the robot’s allowable trajectories are
properly taken into account in a masked polar histogram. VFH*, which introduced the A*
search (Hart et al., 1968) in the process to determine direction, has been proved to obtain
better solutions than VFH+ in certain cases (Ulrich and Borenstein, 2000).
A method which is particularly relevant to the work presented here is the elastic band
method proposed in Quinlan and Khatib (1993). This technique tries to combine the
global path planning with real-time sensor-based collision avoidance. A pre-planned
global path is deformed in real time to keep a robot away from obstacles during its
movement, while the internal contraction forces will bring the robot back to its original
path when the obstacle is out of the sensor range. The method takes also into account the
actual shape of the robot and restricts the search space by the concept of a ‘bubble’. A
bubble is defined as the maximum local subset of the free space around a given
configuration of the robot which can be safely travelled in any direction without
collisions. Given such bubbles, a band or string of bubbles can be used along the
trajectory from the robot’s initial position to its goal position to show the robots expected
free space along the pre-planned path.
The obstacle avoidance techniques just mentioned and other variations which follow
similar concepts have been proved to be effective in the presence of static obstacles in the
environment. However, one aspect they all have in common is that they are not directly
applicable to deal with dynamic obstacles, since characteristics from the moving objects
such as travelling speed, size, etc. are not built into the algorithms. That is not to say
some of them will not be able to deal with a certain degree of dynamism in the
environment, but it is not designed in their methodology to do it in an efficient manner.
An adaptive manoeuvring strategy for mobile robots 183
The obstacle avoidance technique proposed here is designed around these
premises and performs well in partially known and continuously changing environments.
Its basic principle is to generate a repelling force field for the robot based on its own
kinematic and dynamic status – shape, size, travelling speed, etc. – and those of the
moving objects, as well as the surrounding static obstacles to generate a combined force
that drives the robot towards the target.
2
DV SF
3 The optimised global planner
In this section, an overview of the proposed path planner algorithm is given. Further
details can be obtained from Taha et al. (2006b).
3.1 Generating the search space
The pre-processing step aims at minimising the online computation by pre-generating a
search space to contain all the information that will be used during the online path
planning. The steps used during the search space creation can be defined as follows:
Algorithm 1 Search-space generation
Input: map, robot dimensions
1 expand obstacles
2 generate regular grid with low resolution
3 apply bridge test to add dense narrow passages
4 penalise nodes by adding a smoothing cost
5 connect nodes to form search space discretisation
6 eliminate those that cause collision
Output: free search space.
Figure 1 The area of the robot is covered by circles of radius , the centres of these circles will
be the points to be checked for collision. R
3.1.1 Collision detection
In this step, obstacles are enlarged with a radius to simplify the online collision
detection by reducing the number of points on the robots to be checked for collision. This
R
184 J. Valls Miró et al.
is done by finding the largest possible expansion radius that allows the robot to pass
through the narrowest path and then divide the area of the robot into circles of that radius,
as depicted in Figure 1. The centre points of those circles will then be used to check for
obstacle collision. The expansion radius is determined based on the a-priory
knowledge of the environment: suppose that the narrowest passage is of width and the
largest robot dimension is then the largest expansion that allows the robot to pass
through can be determined by:
R
R
l
r
if 2
2 otherwise
llr
R
r
ε
−<
=⎧
⎪
⎨
⎪
⎩ (1)
where
ε
is a minimal safety distance to make sure the platform does not get
uncomfortably close to the obstacles.
3.1.2 Regular grid discretisation
The C-space is then populated with nodes using a low resolution regular grid. This will
help in maintaining the connectivity of the graph by defining a minimum discretisation
for the open spaces. The discretisation density is adjusted to suit the environment,
selecting as sparse a grid as possible. Up to this stage, the nodes hold only position
information.
3.1.3 Bridge test
The bridge test (Hsu et al., 2003) was introduced to boost the sampling density inside
narrow passages using only a simple test of the local geometry. A short line segment of
length can sample randomly through a point in the free space such that the end
points of the line segment lie in obstacles. This line segment is what we call a bridge
because it acts like a bridge across the narrow passage with its endpoints in an occupied
location and the point in a free space. If we are able to build a bridge through point
, then the bridge test is successful at this point and point is added to the search
space. These steps can be summarised as follows:
dm
m
m m
Algorithm 2 Bridge test
1 repeat
2 Pick a point
p from the regular-grid map
3 If
p is in an occupied location then
4 Pick a point
p that is distance away from
′p
d
5 If
p is in an occupied location then
′
6 Let
m be the midpoint of pp
′
line segment
7 If
m is in a free location then
8 Insert
m into the search space as a new node
An adaptive manoeuvring strategy for mobile robots 185
3.1.4 Clearance (smoothness) penalty
To insure that the paths generated are directed to the middle of the empty space not
adjacent to the obstacles, we introduced a cost added to the nodes in the search space
indicating how far they are from an obstacle. The cost
p
C is a normalised cost that is
inversely proportional to this distance , so that the closer the point is from an obstacle
the higher its cost, according to: d
d
p
d
K
d
C
K
−
= (2)
where d
K
indicates the clearance distance beyond which the node will be assigned a
zero cost. This cost will be used during the online path planning process to plan smoother
paths in one step.
3.1.5 Node connections
In order to find a path among the resulting nodes, these need to be connected together in a
tree structure. This is done by establishing a link between each node and its neighbouring
nodes a certain distance away. The more neighbours a node is linked to, the more discrete
poses (position and orientation) will be available during the search for a viable path.
3.1.6 Connections reduction
In a final step, we eliminate those connections that cause a collision of the platform with
the obstacles. The connections between nodes determines the possible orientations of the
robot should it follow that path. The centre of the circles that describe the area of the
robot along that path can be rotated and translated accordingly. Hence, we can then
determine if any of them falls into an occupied area or not.
Figure 2 The repulsive virtual force field generated by an obstacle on the robot
186 J. Valls Miró et al.
3.2 Online path planning
In the algorithm proposed here, we use the well known A* algorithm (Hart et al., 1968)
where our cost function
()
J
d combines the sum of the partial path distances , the
sum of all the distances travelled as a result of changing orientation
dΔ
x
θ
Δ
where
x
is the
length of the axis of the rear wheels, the sum of the clearance penalties previously
computed offline – which is directly proportional to the distance
p
C
d
Δ
, the number of
reversals (backward motion) in the path and the heuristic function h representing
the distance to goal at each step. The cost function, defined as follows:
rev
n
() prev
dx
J
ddC
θ
Δ+ Δ + Δ=nh++
∑
∑∑ ∑ (3)
encourages the robot to avoid whenever possible turns and reversing actions, while at the
same time directing it towards the middle of free space. The result is a smooth and secure
path – in the context of the obstacles around the platform – efficiently generated in a
single step.
4 The virtual force field for local planning
This section describes the modified method for local re-planning in the presence
of static and dynamic obstacles, . For more details on the
multi-robot motion planning, the reader may refer to Wang et al. (2006).
2
VSF
DV 2
SF 2
VSF
4.1 Definition of the force field
A force field is defined as a virtual repulsive force in the vicinity of a robot whose
magnitude and orientation varies constantly with the robot’s status as it travels along the
workspace towards the goal. Intuitively, it is a force that increases as the sensed distance
to any obstacles in the environment decreases, hence keeping the robot from hitting
obstacles.
Figure 3 Reference parameters that define the robot’s virtual force field
An adaptive manoeuvring strategy for mobile robots 187
To introduce the concept of the virtual force field, it is important to understand how the
interacting forces from obstacles and robot are calculated. Assuming a rectangular shape
differential-drive platform like the automated wheelchair robot considered here, restricted
to move on a flat surface, the contours of the force fields at various distances are
geometrically represented by conic sections of different eccentricities, as depicted in
Figure 2. The robot coordinate system, at its centre of rotation, coincides with the conic
section focus, and the robot’s
D
r
X
axis lies along the conic section’s major axis. It is
shown how Dmax describes the maximum distance where the field is felt, whilst Dmin is the
distance at which this robot has maximum repulsive force. Or, in other words, Dmax
represents how far the robot can influence its vicinity and Dmin preserves a safe area
around the robot onto which no other objects should ever be present. These relationships
can be mathematically described in the robot reference system depicted in Figure 3. Let
be the radius, from the robot’s origin, of the maximum circle embedding the robot,
r
R
r
θ
the robot orientation in the global coordinates,
θ
the orientation of the obstacle
relative to the robot, and r
υ
the linear component of the robot speed (υmax being its
maximum value). Then:
1,
r
r
max
E
K
υ
υ
υ
υ
=1K
> (4)
()
()
,1
1cos
r
max r r r
r
DE
KR K
E
θ
=>
− (5)
min
min max
d
DKD= (6)
K
υ
is the eccentricity factor required to limit the speed ratio so that when
r
E
r
υ
= υmax the resulting conic is an ellipse. This is required to guarantee the effect of the
field is felt in a limited, closed area around the robot. A parabolic or hyperbolic open
ended field would not allow for the proper detection of the obstacles around the robot as
it moves about. The factor allows us to take the size of the robot in the calculations of
the field, so that bigger platforms generate larger fields, whilst the positive multiplier
r
R
r
K
represents an extra degree of control of the influence that the environment has in the
resulting field by permitting larger virtual fields when the area is a-priory known to be
fairly clear of obstacles. Dmin is a percentage of Dmax, i.e., 0< <1. The choice of
denotes to some extent the environment’s influence on the force, as it heavily
influences how close the robot can get to obstacles. For a large robot such as a wheelchair
operating through narrow doors this needs to be fairly small, or the robot could get stuck.
min
d
K
min
d
K
4.1.1 Repulsive force
With the above definitions in mind, the repulsive force generated by a robot at a distance
from its boundary is defined by:
D
188 J. Valls Miró et al.
()
0
otherwise
max
max min
max
DD
rep
f
min max
DD
max
DD
FD K D DD
F
−
−
>
=≤
⎧
⎪
⎨
⎪
⎩
JG
<
(7)
where
f
K
is a positive constant which determines the magnitude of the repulsive force.
As distance changes from Dmin to Dmax the magnitude of the repulsive force changes
gradually from
D
f
K
to 0. If obstacles are detected in the area of Dmin, the magnitude of
the repulsive force is set to be Fmax with Fmax
f
K
, which will bring maximum
deceleration.
Equation (7) can be easily transformed to emphasise the concept of the contour of the
force field as seen in Figure 2 by defining:
max
D
D
ρ
= (8)
so that (7) becomes:
()
00
1
1
01
otherwise
rep f
max
p
p
FK
F
ρ
ρρ
−
−
>
=≤
⎧
⎪
⎪
⎨
⎪
⎪
⎩
JG 1
ρ
<
(9)
Now when
ρ
changes from 0
ρ
to 1, the magnitude of repulsive force changes from
f
K
to 0. With this mapping equation (6) becomes:
0
min max
DD
ρ
= (10)
Given the manifold of repulsive force fields that accompany the robot in its motion, when
an obstacle is sensed in the vicinity, the interaction point where the maximum repulsive
force is felt is selected as the repelling contour force for the obstacle,
()
_rep obstacle
F
ρ
J
JG .
4.1.2 Attractive force
At any given time, a goal is selected as the furthest visible point provided by the sensor
along the optimised pre-planned global path. A virtual attractive force attr
F
J
JG is associated
with this local target to attract the robot from its current location towards the goal. The
attractive force is presumed exerted from the centre of rotation of the robot and is
calculated as a positive value set to be larger than the sum of all repulsive forces from the
obstacles, so that the robot is guaranteed to always being pulled in the broad direction of
the target.
An adaptive manoeuvring strategy for mobile robots 189
()
i
4.2 The combined forces
The resulting forces exhorted on the robot can then be calculated by:
_total attr rep total
FFF=+
JJGJJGJJG (11)
where the reaction repulsive force is the sum of the fields from each of the n
obstacles – static and dynamic – bserved in the local are, as given by:
_
1
_
n
rep total i
i
rep obstacleFF
ρ
=
=∑
JJGG (12)
4.3 The controller
2
DV SF
The motion of a wheelchair-like differential robot in a two-dimensional surface is
constrained by the well known non-holonomic relationship:
sin cos 0xy
θ
θ
−+ =
(13)
whose effect is to reduce the dimension of the location and orientation configuration
space
(
)
,,qxy
θ
= to a kinematics model whose instantaneous velocity lateral to the
heading has to be zero. This is normally expressed in terms of the translational movement
r
υ
and the rotation movement about its centre of mass r
ω
, which are also the controls of
the wheelchair robot. Hence, given the interacting forces expressed by equation (11), the
following motion controls are proposed:
_
max
1
max
rrep obstaclei
f
F
K
υ
υ
⎛
⎜⎟
⎝⎠
=
+
JJG ⎞
(14)
(
)
,
total
rfF r
ω
θ
=
J
JG (15)
where
(
)
,
total r
fF
ω
JJG is a normalising function of the angular error difference between the
desired direction along the resultant force total
F∠
J
JG and the robot’s current orientation,
while equation (14) guarantees that the robot’s speed will be sensibly influenced by the
obstacles’ repulsive forces. These two controls permit the robot platform to decelerate
and steer clear of nearby obstacles, given the appropriate choice of parameters for the
controller. The reader is referred to Wang et al. (2007) for more details on the
strategy employed to search for the most suitable candidates.
2
SF DV
5 Experimental results
The results of simulating the proposed algorithm in an automated wheelchair platform are
presented next. The mechanical platform measures 1.2 × 0.7 , by all accounts a large
robot when made to manoeuvre in a challenging office-like environment with narrow
passages, doors, long corridors and cluttered static and dynamic obstacles. The
m m
190 J. Valls Miró et al.
wheelchair has two differentially driven wheels at the rear and two passive casters at the
front and can travel at speeds of up to 15km/h.
The wheelchair relies on a SICK laser range finder for localisation. Starting in the
proximity of a known location, it continuously updates this estimation using an Adaptive
Monte-Carlo Localisation (AMCL) algorithm (Thrun et al., 2000). During navigation,
ranging scans are used to build local maps that are compared to the internally stored map1
using the Iterative Closest Point (ICP) method (Besl and McKay, 1992). If the two maps
are slightly different, then a local re-planning is triggered whereby the local path is
regenerated and connected to the closest global path segment outside the local area. If the
local differences between the re-mapped area and the stored map are major (exceeds a
certain threshold), categorising a path blockage, then a complete path re-planning starting
from the current location takes place.
In our simulated scenario, the wheelchair planner starts by finding the shortest
collision-free path between a given start and goal configurations, as illustrated in Figure
4(a). Note the resulting smoothness in the path, and how the planner tends to direct the
robot as far as possible from obstacles and along the middle of the empty spaces, making
the path not only feasible and kinematically ‘gentle’ on the platform, but also maximising
clearances with the obstacles known at this stage along the minimal distance path.
Figure 4(b) depicts the scenario when a static obstacle (red square box) is placed in
vicinity of the robot as it is navigating along the given path. It can be seen how the active
is capable of avoiding the obstacle, generating the tracking trajectory shown in
blue. The presence of a moving obstacle in the narrow corridor seen in Figure 4(c) also
makes the controller take evasive action. The close proximity of the robot and the
dynamic obstacle has as a result slow motions, the robot picking up speed once the
obstacle has been cleared. This is also the case when the platform crosses narrow spaces
such as doors, as forces sensed from the environment are exerted on the platform in
opposed directions, effectively resulting in reduced linear speeds. For the simulations
presented here, the moving obstacle has been made to follow a predetermined path,
tracked by a constant speed linear controller, with the objective to simulate the presence
of a person moving about in the vicinity.
2
DV SF
In the final scenario considered, the path the robot is made to follow is completely
blocked by the presence of the static obstacle. The planner is capable of discerning this
situation which triggers a complete re-planning. ICP is used to register the changes in the
virtual map and the search space is modified accordingly, removing the blocked nodes
and finding a new path from the robot current location to the goal2. An example is
displayed in Figure 4(d).
An adaptive manoeuvring strategy for mobile robots 191
Figure 4 A case study of the robot navigation strategy in the presence of static and dynamic
obstacles, (a) initial configuration, clear of obstacles; (b) reacting to a new static
obstacle (red) in the scene; (c) reacting to the presence of a dynamic obstacles (orange)
in the scene and (d) the path is fully blocked and a major replanning is carried out (see
online version for colours)
(a) (b)
(c) (d)
An intrinsic drawback of the proposed methodology is due to the reactive speed changes
as dictated by the controller. It can be observed how, when traversing narrow
passages such as doors, the repulsive force field felt by the robot produces slightly
oscillating angular motions. This is because as the robot is made to closely approach
the discomfort zone, the strongest of repulsive forces are at play. The zealous
safety-oriented proposed controls dictate very slow linear speeds for this scenario, which
combined with the fast nature of the opposing repulsive forces, manifest themselves in
the angular controls oscillating behaviour. While this known issue is dampened on the
2
DV SF
min
D
192 J. Valls Miró et al.
real platform, a low-pass filter is nevertheless necessary to smooth out this undesirable
behaviour.
The approach is currently being implemented on the real wheelchair platform where
more engineering work is underway to provide it with better sensing capabilities to be
able to fully demonstrate the concept.
6 Conclusions and future works
A local obstacle avoidance controller integrated within an optimised path planner has
been proposed to counteract the effect of uncertainties arising from planning in an ever
changing world. Based on perceptive data, and the kinematic status of robot and
surroundings, a varying family of virtual force fields are generated around the moving
platform in response to objects in the environment. The effect of this repulsive force (null
in the absence of obstacles) is to maximise the safe motion of the robot towards the local
way-points provided by the planner, ‘shielding’ the platform in an optimal manner and
preventing collisions with the objects in the local area, static and dynamic.
Arrays of challenging simulated scenarios have been presented to demonstrate the
good results of the proposed reactive behaviour in cluttered environments. This was made
even more acute given the dimensions and mobility of the robot – an automated
wheelchair – with respect to its surroundings.
Work is currently underway to implement the proposal in the real wheelchair
platform. A mechanism to segmenting out the moving obstacle from its surroundings is
necessary to fully demonstrate the approach and moving object detection and tracking
strategy (Wang et al., 2003) is being developed.
Acknowledgements
This work is supported by the Australian Research Council (ARC) through its Centre of
Excellence programme, and by the New South Wales State Government. The ARC
Centre of Excellence for Autonomous Systems (CAS) is a partnership between the
University of Technology Sydney, the University of Sydney and the University of New
South Wales.
References
Barraquand, J., Kavraki, L.E., Latombe, J.C., Li, T.Y., Motwani, R. and Raghavan, P.A. (1997)
‘Random sampling scheme for path planning, International Journal of Robotics Research,
Vol. 16, No. 6, pp.759–774.
Besl, P.J. and McKay, N.D. (1992) ‘A method for registration of 3-D shapes’, IEEE Transactions
on Pattern Analysis and Machine Intelligence, Vol. 14, No. 2, pp.239–256.
Boor, V., Overmars, M.H. and Van Der Stappen, A.F. (1999) ‘The Gaussian sampling strategy for
probabilistic roadmap planners’, IEEE International Conference on Robotics and Automation,
Detroit, USA, pp.1018–1023.
Borenstein, J. and Koren, Y. (1990) ‘Real-time obstacle avoidance for fast mobile robots in
cluttered environments’, IEEE International Conference on Robotics and Automation,
Cincinnati, USA, pp.572–577.
An adaptive manoeuvring strategy for mobile robots 193
Brock, O. and Khatib, O. (1999) ‘High-speed navigation using the global dynamic window
approach’, IEEE International Conference on Robotics and Automation, Detroit, USA,
pp.341–346.
Cheng, P. and LaValle, S.M. (2002) ‘Resolution complete rapidly exploring random trees’, IEEE
International Conference on Robotics and Automation, Washington DC, USA, pp.267–272.
Choudhury, P. and Lynch, K. (2002) ‘Trajectory planning for second-order under actuated
mechanical systems in presence of obstacles’, Workshop on Algorithmic Foundation of
Robotics, Nice, France, pp.559–575.
Fox, D., Burgard, W. and Thrun, S. (1997) ‘The dynamic window approach to collision avoidance’,
IEEE Robotics and Automation Magazine, Vol. 4, No. 1, pp.23–33.
Hart, P.E., Nilsson, N.J. and Raphael, B. (1968) ‘A formal basis for the heuristic determination of
minimum cost paths’, IEEE Transactions on Systems Science and Cybernetics, Vol. 4, No. 2,
pp.100–107.
Hsu, D., Kavaki, L.E., Latombe, J.C., Motwani, R. and Sorkin, S. (1998) ‘On finding narrow
passages with probabilistic roadmap planners’, Workshop on Algorithmic Foundations of
Robotics, Houston, USA, pp.141–154.
Hsu, D., Jiang, T., Reif, J. and Sun, Z. (2003) ‘The bridge test for sampling narrow passages with
probabilistic roadmap planners’, IEEE International Conference on Robotics and Automation,
Taipei, Taiwan, pp.4420–4426.
Hwang, Y.K. and Ahuja, N. (1992) ‘Gross motion planning – a survey’, ACM Computing Surveys,
Vol. 24, No. 3, pp.219–291.
Kavraki, L.E., Svestka, P., Latombe, J.C. and Overmars, M.H. (1996) ‘Probabilistic roadmaps for
path planning in high-dimensional configuration spaces’, IEEE Trans. on Robotics and
Automation, Vol. 12, No. 4, pp.566–580.
Khatib, O. (1986) ‘Real-time obstacle avoidance for manipulators and mobile robots’, International
Journal of Robotics Research, Vol. 5, No. 1, pp.90–98.
Kim, J. and Ostrowski, J.P. (2003) ‘Motion planning of aerial robot using rapidly-exploring random
trees with dynamic constraints’, IEEE International Conference on Robotics and Automation,
Taipei, Taiwan, pp.2200–2205.
Latombe, J.C. (1999) ‘Motion planning: a journey of robots, molecules, digital actors and other
artifacts’, International Journal of Robotics Research, Vol. 18, No. 11, pp.1119–1128.
LaValle, S.M. and Kuffner J.J. (2000) ‘Rapidly-exploring random trees: progress and prospects’,
Workshop on the Algorithmic Foundations of Robotics, Hanover, USA, pp.293–308.
Lozano-Pérez, T. and Wesley, M. (1979) ‘An algorithm for planning collision-free paths among
polyhedral obstacles’, Communications of the ACM, Vol. 22, No. 10, pp.560–570.
Lozano-Pérez, T. (1983) ‘Spatial planning: a configuration space approach’, IEEE Transactions on
Computers, Vol. 32, No. 2, pp.108–120.
Lumelsky, V.J. and Skewis, T. (1990) ‘Incorporating range sensing in the robot navigation
function’, IEEE Transactions on Systems, Man and Cybernetics, Vol. 20, No. 5,
pp.1058–1069.
Minguez, J., Montano, L. and Santos-Victor, J. (2005) ‘Abstracting vehicle shape and kinematic
constraints from obstacle avoidance methods’, Autonomous Robots, Vol. 20, No. 1, pp.43–59.
Moravec, H. and Elfes, A. (1985) ‘High resolution maps from wide angle sonar’, IEEE
International Conference on Robotics and Automation, Philadelphia, USA, pp.116–121.
Philips, J.M., Bedrossian, N. and Kavraki, L.E. (2004) ‘Guided expansive spaces trees: a search
strategy for motion and cost-constrained state spaces’, IEEE International Conference on
Robotics and Automation, New Orleans, USA, pp.3968–3973.
Quinlan, S. and Khatib, O. (1993) ‘Elastic bands: connecting path planning and control’, IEEE
International Conference on Robotics and Automation, Atlanta, USA, pp.802–807.
194 J. Valls Miró et al.
Sanchez, G. and Latombe, J.C. (2001) ‘A single-query bi-directional probabilistic roadmap planner
with lazy collision checking’, International Symposium Robotics Research, Lorne, Australia,
pp.403–417.
Simmons, R. (1996) ‘The curvature-velocity method for local obstacle avoidance’, IEEE
International Conference on Robotics and Automation, Minneapolis, USA, pp.3375–3382.
Taha, T., Valls Miró, J. and Dissanayake, G. (2006a) ‘Sampling based time efficient path planning
algorithm for mobile platforms’, International Conference on Man-Machine Systems,
Langkawi Islands, Malaysia.
Taha, T., Valls Miró, J. and Liu, D. (2006b) ‘An efficient path planner for large mobile platforms in
cluttered environments’, IEEE International Conference on Robotics, Automation and
Mechatronics, Bangkok, Thailand, pp.225–230.
Thrun, S., Fox, D., Burgard, W. and Dellaert, F. (2000) ‘Robust Monte-Carlo localization for
mobile robots’, Artificial Intelligence, Vol. 128, Nos. 1–2, pp.99–141.
Ulrich, I. and Borenstein, J. (1998) ‘VFH+: reliable obstacle avoidance for fast mobile robots’,
IEEE International Conference on Robotics and Automation, Leuven, Belgium,
pp.1572–1577.
Ulrich, I. and Borenstein, J. (2000) ‘VFH*: local obstacle avoidance with look–ahead verification’,
IEEE International Conference on Robotics and Automation, San Francisco, USA,
pp.2505–2511.
Vougiouksa, S.G. (2005) ‘Optimization of robot paths computed by randomised planners’, IEEE
International Conference on Robotics and Automation, Barcelona, Spain, pp.2160–2165.
Wang, C., Thorpe, C. and Suppe, A. (2003) ‘LADAR-based detection and tracking of moving
objects from a ground vehicle at high speeds’, IEEE Intelligent Vehicles Symposium,
Columbus, USA, pp.416–421.
Wang, D., Liu, D. and Dissanayake, G. (2006) ‘A variable speed force field method for multi-robot
collaboration’, IEEE/RSJ International Conference on Intelligent Robots and Systems, Beijing,
China, pp.2697–2702.
Wang, D., Kwok, N.M., Liu, D.K., Lau, H. and Dissanayake, G. (2007) ‘PSO-tuned F2 method for
multi-robot navigation’, IEEE/RSJ International Conference on Intelligent Robots and System,
San Diego, USA, pp.3765–3770.
Notes
1 This map was first fabricated via ICP scan-matching of real laser data collected by driving the
actual wheelchair platform around an office-like area, and is therefore quite truthful if
somewhat noisy.
2 The whole re-planning process is fast, around 300 ms in a modern PC, but the robot is
nevertheless stopped for some time while re-planning takes place for safety reasons, with the
view of implementing the strategy on the real platform.