You are on page 1of 18

J Intell Robot Syst (2015) 77:481–498

DOI 10.1007/s10846-013-9879-6

Different Kinematic Path Following Controllers


for a Wheeled Mobile Robot of (2,0) Type
Joanna Płaskonka

Received: 14 January 2013 / Accepted: 30 June 2013 / Published online: 19 September 2013
© The Author(s) 2013. This article is published with open access at Springerlink.com

Abstract In the paper a comparative study of just to mention platforms for transport opera-
selected kinematic path following controllers for tions, planetary exploration, automatic cleaning,
a wheeled mobile robot of (2,0) type has been museum tours etc. Thus robust control algorithms
presented. The control strategies are based on one for such robotic objects are needed. There are
of two approaches to the path parameterization— numerous papers related to control algorithms
either the Serret-Frenet frame with an orthog- for wheeled mobile robots published in the litera-
onal projection or the Serret-Frenet frame with ture. Three basic types of tasks realized by mobile
a non-orthogonal projection of a robot on the de- platforms can be distinguished:
sired path. The complete control system for the
– point stabilization,
wheeled mobile robot consists of two parts, a
– trajectory tracking (the robot has to follow a
kinematic controller and a dynamic controller, be-
desired curve which is time-parametrized),
cause of a presence of nonholonomic constraints.
– path following (the task of the robot is to
The behaviour of the presented algorithms is
follow a curve parametrized by a curvilinear
demonstrated through computer simulations.
distance from a fixed point).
Keywords Path following · Wheeled mobile While realizing a trajectory tracking task the robot
robot · Serret-Frenet frame · Nonholonomic needs to be in a particular position at a pre-
constraints · Model-based control specified time and thus the robot could be pushed
to its performance limits. In contrary, a path fol-
lowing task requires the robot to converge to a
1 Introduction geometric curve with any feasible speed profile.
This is why a path following problem bypasses
The number of possible applications of wheeled the limitations of the trajectory tracking task. The
mobile robots is huge and is even increasing, objective of the paper is to review different path
following algorithms for a unicycle-type wheeled
mobile robot and verify their robustness proper-
ties with respect to noise and velocity constraints.
J. Płaskonka (B) The considered type of a problem corresponds to
Institute of Computer Engineering,
e.g. automatic wall following or driving on a road
Control and Robotics, Wrocław University
of Technology, Wrocław, Poland while trying to maintain the distance between ve-
e-mail: joanna.plaskonka@pwr.wroc.pl hicle chassis and the side of the road constant.
482 J Intell Robot Syst (2015) 77:481–498

Table 1 Classification of wheeled mobile robots


Many solutions of the path following problem
for the unicycle are dedicated to that particular σm 3 2 2 1 1
σs 0 0 1 1 2
type of a mobile platform. In the approach pre-
sented in [1] the position of the virtual vehicle
to be tracked is simply defined by the orthog-
onal projection of the robot on the path. Such
an approach is valid locally, only near the path.
2 The Mathematical Model of the Robot
The another approach described in [2] overcomes
initial condition constraints imposed on the robot
There are five classes of wheeled mobile robots
by controlling explicitly the rate of progression of
introduced in [12]. The proposed classification is
a virtual target. The consequence of this approach
based on two indices—a degree of mobility σm and
is that the amount of path following errors that
a degree of steerability σs , see Table 1. The robots
have to converge to zero is increased by one com-
of (3,0) type have full mobility in the plane, which
paring to the previously mentioned approach. The
means that they are able to move in any direction
method proposed in [3] solves the problem of the
without any reorientation, while the other have
bounded path curvature. It neither requires the
a restricted mobility. In the article considerations
computation of a projection of the robot position
will be restricted to type (2,0) robots. Such robots
on the path, nor does it need to consider a moving
have no steering wheels, but either one or several
virtual target to be tracked. Morin-Samson algo-
fixed wheels with a common axle, [13].
rithm [4] uses the kinematic equations of the robot
The wheeled mobile robot of (2,0) type, also
derived with respect to the Serret-Frenet frame
called a unicycle, was depicted in Fig. 1. (x, y)
transformed into a canonical form called the cha-
represents coordinates of the characteristic point
ined form. Some of the algorithms available in
M relative to the inertial frame X0 Y0 and θ is
the literature also deal with obstacles avoidance,
a robot’s orientation. The point M is located
e.g. [5–7], or allow to realize a formation path
in the middle of the wheel axle of the vehicle. R
following task, see e.g. [8, 9].
is the radius of the robot’s wheel and d is a half
More general approaches to designing kine-
the width of the mobile platform.
matic control strategies may be applied for various
nonholonomic mobile robots, e.g. one presented
in [10]. However a generality of the proposed
algorithm was achieved at the expense of the oc-
curence of an undesirable chattering phenom-
enon. Usually better results are obtained when
using algorithms dedicated to particular types of
wheeled mobile robots.
In the paper different kinematic path following
algorithms—which use the kinematic model of the
robot expressed with respect to the Serret-Frenet
frame—are compared: Samson algorithm [11],
Morin-Samson algorithm [4], Soetanto-Lapierre-
Pascoal algorithm [2] and two proposed alterna-
tive discontinuous algorithms. The first discon-
tinuous algorithm results from the attempt of
linearisation and decoupling of the equations de-
scribing the dynamics of path following errors,
while the latter one is a modification of Samson
algorithm. Fig. 1 The unicycle’s parameters
J Intell Robot Syst (2015) 77:481–498 483

2.1 The Kinematic Model Using the symbols v and ω the kinematic model
of the considered wheeled mobile robot can be
The motion of the unicycle can be described by described by the equations
generalized coordinates qm ∈ Rn and generalized ⎧
velocities q̇m ∈ Rn . The assumption that the robot ⎨ ẋ = v cos θ,
ẏ = v sin θ, (7)
is moving on a plane without slippage of its wheels ⎩
is made. It is equivalent to an assumption that the θ̇ = ω.
momentary velocity at the contact point between
each wheel and the motion plane is equal to zero. 2.2 The Dynamic Model
This implies the existence of l (l < n) independent
nonholonomic constraints expressed in Pfaffian To obtain the model of the unicycle’s dynamics,
form the d’Alembert Principle has to be evoked

M(qm ) q̈m = B(qm ) τ + AT (qm ) λ, (8)


A(qm )q̇m = 0, (1)
where:
where A(qm ) is a full-rank matrix of (l × n) size.
Since due to Eq. 1, the platform velocity is in M(qm ) inertia matrix of the mobile platform,
a null space of A(qm ), it is always possible to find a A(qm ) matrix of nonholonomic constraints for
vector of special auxiliary velocities η ∈ Rm , m = the platform,
n − l, such that λ vector of Lagrange multipliers,
B(qm ) input matrix,
q̇m = G(qm )η, (2) τ vector of controls.
where G is an n × m full rank matrix satisfying the Matrix A(qm ) is Pfaffian matrix for the plat-
relationship AG = 0. The Eq. 2 is called the kine- form, see Eq. 1, while B(qm ) describes which state
matics of the nonholonomic mobile platform. For variable is directly controlled by the actuator. The
the unicycle the Eq. 2 has the following form model (8) can be also expressed using auxiliary
⎛ ⎞ ⎡ ⎤ velocities η. For this purpose q̈m is computed
ẋ cos θ cos θ
⎜ ẏ ⎟ ⎢ sin θ sin θ ⎥   q̈m = G(qm )η̇ + Ġ(qm )η (9)
⎜ ⎟ ⎢ 1 ⎥
1 ⎥ η1
⎜ θ̇ ⎟ = ⎢
⎜ ⎟ ⎢ d −2d ⎥ η2 , (3)
and the vector of Lagrange multipliers is elimi-
⎝ φ̇1 ⎠ ⎣ 0 ⎦
R nated, using a condition GT AT = 0, by left-sided
φ̇2 2
0
R multiplying the mobile platform equations by GT
where auxiliary velocities η1 and η2 are scaled matrix. After substituting q̈m the Eq. 8 transforms
rotation velocities of the unicycle’s wheels φ̇1 into
and φ̇2 :
M∗ (qm )η̇ = B∗ (qm )τ (10)
R R
η1 = φ̇2 , η2 = φ̇1 . (4) with
2 2
One can use notations M∗ = GT MG (11)

and
v = η1 + η2 , (5)
B∗ = GT B. (12)
where v is the linear velocity of the robot and
The considered dynamic model of the wheeled
1
ω = (η1 − η2 ), (6) mobile robot of (2,0) type is very simple as ele-
d ments of the inertia matrix are constant, neverthe-
where ω denotes angular velocity of the robot. less introducing dynamic model allows to observe
484 J Intell Robot Syst (2015) 77:481–498

an influence of the inertia of the robot on the


realization of a desired task.

3 Description of the Robot Relative


to a Desired Path

To describe the position of the robot relative


to a desired path, different approaches may be
applied. The one of the most commonly used
approaches is based on the Serret-Frenet frame—
which consists of vectors tangent, normal and bi-
normal to a curve—moving along a desired path.
The robot moving on a plane is considered so Fig. 2 The Serret-Frenet frame definition in a case
the Serret-Frenet frame consists only of vectors of an orthogonal projection of a robot on the path
tangent and normal to the path.
The path P is characterized by a curvature κ(s),
which is the inversion of the radius of the circle  q1 
is equal to t0 = , while its position relative to
1
tangent to the path at a point characterized by  
the parameter s which is a curvilinear distance the Serret-Frenet frame is equal to t1 = r11 . The
from the fixed point, i.e. from the beginning of relationship between t0 and t1 can be described by
the path. The desired orientation of the mobile the matrix equation
platform satisfies the equation     
q1 Rθr p1 r1
θ̇r = ±κ(s)ṡ. (13) = , (14)
1 0 1 1
The sign on the right side of the Eq. 13 depends
where
on the direction of moving along a desired curve
⎡ ⎤
(negative when the Serret-Frenet frame moves in cos θr − sin θr 0
the clockwise direction, positive otherwise). Rθr = R = Rot(z, θr ) = ⎣ sin θr cos θr 0 ⎦ . (15)
0 0 1
3.1 The Serret-Frenet Frame
with an Orthogonal Projection Therefore the following equation holds
of a Robot on the Path
q1 = Rr1 + p1 . (16)
In this approach it is assumed that the robot has to
follow a virtual target which is its orthogonal pro- After differentiating and transforming the Eq. 16,
jection on the desired curve, see Fig. 2. The point one has
M’ is the orthogonal projection of the point M
Rṙ1 = q̇1 − Ṙr1 − ṗ1 . (17)
on the path P and l is the distance error between
the actual vehicle and the virtual one. The point
The Eq. 17 could be multiplied by RT on the left
M’ exists and is uniquely defined if the following
side
conditions are satisfied:
– the curvature κ(s) is bounded from above (the ṙ1 = RT q̇1 − RT Ṙr1 − RT ṗ1 . (18)
desired path cannot be too much curved),
– the robot cannot move too far from the path The transformation from the inertial frame X0 Y0
(the Serret-Frenet parametrization is local), to the Serret-Frenet frame is equal to
 
see for a detailed explanation e.g. [14]. The posi- R p1
K10 = , (19)
tion of the point M relative to an inertial frame 0 1
J Intell Robot Syst (2015) 77:481–498 485

thus the velocity of point M relative to the Serret- orthogonal projection of a robot on the path is
Frenet frame can be calculated as follows given by the following system of equations
    ⎧
RT Ṙ ṘT ṗ1 [ωB ] vB ⎪
⎪ l˙ = v sin θ̃,
VB = (K10 )−1 K̇10 = = . ⎪

0 0 0 0 ⎨ v cos θ̃
ṡ = ,
(20) ⎪ 1 ∓ κ(s)l (29)

⎪ κ(s)v cos θ̃

⎩ θ̃˙ = ω ∓ .
Using the relationships 1 ∓ κ(s)l

r1 = (0 l 0)T , (21) The model described by the Eq. 29 can be trans-


formed into the three-dimensional chained system

q1 = (x y 0)T (22) ż1 = u1 ,


ż2 = u2 , (30)
and
ż3 = z2 u1
vB = Ṙ ṗ1 = (ṡ
T
0 0) ,T
(23)
using the change of coordinates
as the reference vehicle is moving along a desired
path in the direction of X axis of the Serret-Frenet z1 = s,
frame, the Eq. 18 can be rewritten as z2 = (1 ∓ κ(s)l) tan θ̃, (31)
⎛ ⎞ ⎡ ⎤⎛ ⎞
0 cos θr sin θr 0 ẋ z3 = l
⎝ l˙ ⎠ = ⎣ − sin θr cos θr 0 ⎦ ⎝ ẏ ⎠
0 0 0 1 0 and control variables
⎡ ⎤⎛ ⎞ ⎛ ⎞
0 −θ̇r 0 0 ṡ v cos θ̃

− θ̇r 0 0 ⎦ ⎝ l − 0⎠.
⎠ ⎝ u1 = ,
(24) 1 ∓ κ(s)l
0 0 0 0 0 u2 = (∓ċ(s)l ∓ κ(s)u1 z2 ) · tan θ̃ (32)
1 ∓ κ(s)l
Finally one can obtain equations for l˙ and ṡ + (ω+u1 κ(s)) .
  cos2 θ̃
˙l = (− sin θr cos θr ) ẋ , (25)
ẏ The presented transformation into the chained
system is local, |θ̃| < π2 .
 
(cos θr sin θr ) ẋ
ṡ = . (26) 3.2 The Serret-Frenet Frame
1 ∓ κ(s)l ẏ
with a Non-orthogonal Projection
To avoid singularity l = ± κ(s) 1
one has to en- of a Robot on the Path
sure that during the control process an inequality
|l κ(s)| < 1 holds, which means that the parame- The similar reasoning can be carried out for the
trization is local. In addition, the orientation error case when the position of the virtual target is
is determined defined by the non-orthogonal projection of the
actual vehicle on the path (see Fig. 3). In that
θ̃ = θ − θr (27) situation there are three path following errors—
an orientation error and two distance errors, one
and its derivative in the direction of the X axis and second in the
θ̃˙ = θ̇ − θ̇r = θ̇ ∓ κ(s)ṡ. (28) direction of Y axis of the Serret-Frenet frame. The
velocity of r2 is equal to
For the unicycle the kinematic model expressed
with respect to the Serret-Frenet frame with an ṙ2 = RT q̇2 − RT Ṙr2 − RT ṗ2 (33)
486 J Intell Robot Syst (2015) 77:481–498

For the unicycle the kinematic model expressed


with respect to the Serret-Frenet frame with
a non-orthogonal projection of a robot on the path
is given by the following system of equations


⎨ ṡ1 = −ṡ(1 − κ(s)y1 ) + v cos θ̃,
ẏ1 = −κ(s)ṡs1 + v sin θ̃, (40)

⎩ θ̃˙ = ω ∓ κ(s)ṡ.

4 Control Problem Statement

The control problem for the considered robot is as


follows:
Design a control law τ such that the wheeled
Fig. 3 The Serret-Frenet frame definition in a case mobile robot of (2,0) type with a fully known
of a non-orthogonal projection of a robot on the path dynamics follows a desired path and path
following errors converge to zero.
The desired path has to be admissible, i.e. it can
with
be realized without slippage of robot’s wheels. It
r2 = (s1 y1 0)T , (34) is assumed that the desired path is a smooth curve
which has two smooth and bounded derivatives
q2 = (x y 0)T (35) relative to s variable.
The complete model of a nonholonomic system
and consisting of kinematics and dynamics has a struc-
ture of two cascaded equations. To find a control
ṘT ṗ2 = (ṡ 0 0)T . (36) law for such a cascade system, one may use the
backstepping-like procedure [15]:
From Eq. 33 one gets
⎛ ⎞ ⎡ ⎤⎛ ⎞ – kinematic controller ηr —generates a ‘velocity
ṡ1 cos θr sin θr 0 ẋ profile’ which ensures the realizability of a
⎝ ẏ1 ⎠ = ⎣ − sin θr cos θr 0 ⎦ ⎝ ẏ ⎠
path following task in such a way that nonholo-
0 0 0 1 0 nomic constraints are satisfied; the kinematic
⎡ ⎤⎛ ⎞ ⎛ ⎞
0 −θ̇r 0 s1 ṡ controller does not take into account the dy-
− ⎣ θ̇r 0 0 ⎦ ⎝ y1 ⎠ − ⎝ 0 ⎠ (37) namics of the object,
0 0 0 0 0 – dynamic controller τ —its task is to regulate
real velocities η towards the reference con-
and thus trol ηr .
 
  ẋ
ṡ1 = cos θr sin θr − ṡ(1 − y1 κ(s)), (38)

5 Path Following for a Unicycle—Kinematic
 
  ẋ Control
ẏ1 = − sin θr cos θr − ṡκ(s)s1 . (39)

There are different approaches to formulation of a
There is no singularity related to distance errors path following task. The robot’s motion can finish
in Eqs. 38–39. Thus a path parametrization based by stopping on a path or it may be continuous,
on the Serret-Frenet frame with a non-orthogonal cyclic. In this paper the latter approach is adopted.
projection of a robot on the path is not local. It is assumed that a direction of a movement along
J Intell Robot Syst (2015) 77:481–498 487

the desired curve is opposite to the clockwise 5.2 Discontinuous Control Algorithm—First
direction, this means that Proposal

θ̃˙ = κ(s)ṡ. (41) The following discontinuous control law for the
system (42) is proposed
Hence the equations describing path following ⎧
⎨ −k1l
errors for a case of an orthogonal projection of θ̃ = 0,
v = sin θ̃
a robot on the path have a form as below ⎩
vc θ̃ = 0, (48)
κ(s)v cos θ̃
l˙ = v sin θ̃, ω = −k2 θ̃ + ,
1 − κ(s)l
κ(s)v cos θ̃ (42)
θ̃˙ = ω −
1 − κ(s)l where vc = const, k1 , k2 > 0. The initial orienta-
tion error θ̃(0) can not be equal to zero. The
and in a case of a non-orthogonal projection are system (42) with a closed-loop of a signal (48) has
equal to the form

−k1l θ̃ = 0,
ṡ1 = −ṡ(1 − κ(s)y1 ) + v cos θ̃, l˙ =
0 θ̃ = 0, (49)
ẏ1 = −κ(s)ṡs1 + v sin θ̃, (43) ˙θ̃ = −k θ̃.
2
θ̃˙ = ω − κ(s)ṡ.
The inequality |l κ(s)| < 1 resulting from the re-
strictions imposed on the desired path is satisfied
5.1 Samson Control Algorithm
when l(0) satisfies this inequality since the time-
derivative of l is non-increasing.
Path following errors for the unicycle can be ex-
The expression −k 1l
sin θ̃
is undefined for (l, θ̃ ) =
pressed as follows
(0, 0). Therefore the proposed algorithm is ap-
plied in a modified version
l˙ = v sin θ̃, (44)

θ̃˙ = u, ⎨ −k1l
(45) |θ̃ | > ,
v = sin θ̃

vc |θ̃ | ≤ , (50)
where u = ω − κ(s) cos θ̃
v is a new control for the
1−κ(s)l κ(s)v cos θ̃
second equation. Samson kinematic control law ω = −k2 θ̃ +
[11] for the systems (44)–(45) is equal to 1 − κ(s)l

with to be a small positive number, e.g. =


sin θ̃ 0.001.
v = const, u = −k2lv − k3 θ̃, k2 , k3 > 0.
θ̃
(46) 5.3 Discontinuous Control Algorithm—Second
Proposal
The systems (44)–(45) with a closed-loop of the
feedback signal (46) is asymptotically stable. That The another proposed kinematic path following
can be shown using the following Lyapunov func- algorithm for the system (42)
tion ⎧
⎨ −k1l
θ̃ = 0,
l2 θ̃ 2 v = sin θ̃
V(l, θ̃ ) = k2 + ⎩
(47) vc θ̃ = 0, (51)
2 2
sin θ̃ κ(s)v cos θ̃
ω = −k2lv − k3 θ̃ +
and Barbalat lemma, see for details e.g. [16]. θ̃ 1 − κ(s)l
488 J Intell Robot Syst (2015) 77:481–498

is a modification of the Samson algorithm [11]. must by Hurwitz polynomial. That condition is
In practice this algorithm is used in the following fulfilled for ki > 0. Then consider the Lyapunov
form function

⎨ −k1l 1
V(z2 , z3 ) = (z22 + k3 z23 ).
|θ̃| > , (58)
v = sin θ̃ 2

vc |θ̃| ≤ , (52) For a positive coefficient k3 the proposed Lya-
sin θ̃ κ(s)v cos θ̃ punov function is non-negative
ω = −k2lv − k3 θ̃ + ,
θ̃ 1 − κ(s)l
V > 0, (z2 , z3 ) = (0, 0),
where is a small positive number. (59)
V = 0, (z2 , z3 ) = (0, 0).

5.4 Morin-Samson Control Algorithm The time-derivative of V calculated along a sys-


tem’s solution
For the kinematic equations expressed with re- V̇ = z2 ż2 + k3 z3 ż3 = −|u1 |k2 z22 (60)
spect to the Serret-Frenet frame with an orthog-
onal projection of the guidance point on a path is non-positive. Thus V is non-increasing and con-
which are transformed into the 3-dimensional verges to some limit value Vlim ≥ 0. This implies
chained system (30), the following control law that the variables z2 and z3 are bounded. If it is
is proposed [4] assumed that the control signal u1 is bounded, the
second derivative of V
u1 = const,
(53) V̈ = 2u1 |u1 |k2 k3 z2 z3 + 2u21 k22 z22
u2 = −u1 k3 z3 − |u1 |k2 z2 . (61)

In general u1 does not have to be constant. It is a sum of bounded functions. Therefore V̇ is


is sufficient if it is a bounded differentiable time uniformly continuous. From Barbalat lemma one
function whose derivative is bounded and which may conclude that V̇ tends to zero which implies
does not tend to zero as t tends to infinity. that z2 tends to zero and thus θ̃ → 0. The time-
What is more, if the following inequality holds derivative of v 2 z2
˙
z23 (0) +
1 2 1
z2 (0) < 2 (54) v 2 z2 = 2v v̇z2 − v 2 u1 k3 z3 − v|u1 |k2 z2 (62)
k3 κmax
is the sum of two terms which tends to zero and
with κmax = maxs |κ(s)|, then the constraint a third which is uniformly continuous since its
|l κ(s)| < 1 is satisfied along any solution to the derivative is bounded. Using the fact that v 2 z2
controlled system. tends to zero and the extension of Barbalat’s
˙
lemma [1], one may conclude that v 2 z2 → 0. Thus
Proof The system containing only state variables v 2 u1 k3 z3 tends to zero, too. As the linear velocity
z2 and z3 is considered. Such a system can be of the robot v does not tend to zero and u1 , k3 are
written in the below matrix form constant, limt→∞ z3 must be equal to zero which
means that Vlim = 0 and l → 0.
żc = zc , (55)
Moreover the following inequality holds
 T
where zc = z2 z3 and a matrix  is equal to
2V ≥ k3 z23 (63)
 
−|u1 |k2 −u1 k3 which leads to
= . (56)
u1 0
2V 2V(0) 1
z23 ≤ ≤ < 2 . (64)
The system (55) will be asymptotically stable if k3 k3 κmax
all eigenvalues of the matrix  have negative real
Finally one has
part, i.e. the characteristic polynomial of the 
matrix |l κmax | < 1. (65)
p(λ) = det(λI2 − ) = λ2 + |u1 |k2 λ + u21 k3 (57)

J Intell Robot Syst (2015) 77:481–498 489

5.5 Soetanto-Lapierre-Pascoal Control is the sum of two terms which tend to zero and
Algorithm third term which is uniformly continuous. As
v 2 (θ̃ − δ) tends to zero, the extension of Barbalat’s
The control algorithm proposed in [2] for the ˙
lemma tells us that v 2 (θ̃ − δ) also tends to zero
system (43) is equal to θ̃−sin δ
which implies that the term γ y1 v 3 sin θ̃−δ → 0.
The linear velocity v does not tend to zero when t
ṡ = v cos θ̃ + k1 s1 ,
θ̃−sin δ
tends to infinity and γ is constant. The expression
ω = κ(s)ṡ + δ̇ − γ y1 v sin θ̃−δ − k2 (θ̃ − δ), (66) sin θ̃−sin δ
θ̃−δ
could be rewritten in the following way
k1 , k2 > 0,
sin θ̃ − sin δ sin θ̃−δ cos θ̃+δ
where the following assumptions have been made = 2 2
(71)
θ̃ − δ θ̃−δ
2
– limt→∞ v(t) = 0, e.g. v = const,
– δ(0, v) = 0, which for (θ̃ − δ) → 0 tends to cos δ. If only δ
θ̃−sin δ
– ∀ y1 ∀v y1 v sin δ(y1 , v) ≤ 0. does not tend to kπ2
, the the whole term sin θ̃−δ
does not tend to zero. Under this assumption y1
It guarantees the convergence of y1 , s1 and θ̃ to tends to zero. This implies that V given by the
zero. Eq. 67 also tends to zero. From the assumption
that δ(0, v) = 0 and the convergence of y1 to zero,
Proof Consider the Lyapunov function δ → 0 which leads to θ̃ → 0.

1 2 1
V= (s1 + y21 ) + (θ̃ − δ(y1 , v))2 (67)
2 2γ
6 Dynamic Control
with γ to be constant. The time-derivate of V
The exact linearisation algorithm would be ap-
V̇ = s1 ṡ1 + y1 ẏ1 + (θ̃ − δ)(θ̃˙ − δ̇)
1 plied for a task of dynamic control of the uni-
γ cycle. To the model (10) the following control is
plugged
= s1 (v cos θ̃ − ṡ) + y1 v(sin θ̃ − sin δ)
1 τ = (B∗ (qm ))−1 M∗ (qm ) ω1 , (72)
+ y1 v sin δ + (θ̃ − δ)(ω − κ(s)ṡ − δ̇)
γ where ω1 is a new input for the linearised system.
= −k1 s21 − k2 (θ̃ − δ)2
(68) Then the system (10) with a closed-loop of the
feedback signal (72) has a fom
in non-positive. This means that limt→∞ V(t) = η̇ = ω1 . (73)
Vlim and s1 , y1 and (θ̃ − δ) are bounded. V̇ is
uniformly continuous because its derivative is ω1 is chosen to be equal to
bounded as sum of bounded functions. By Bar- ω1 = η̇r − Km (η − ηr ) (74)
balat’s lemma V̇ tends to zero. Therefore s1 → 0
and (θ̃ − δ) → 0. Differentiating (θ̃ − δ) with re- with Km = KTm > 0. Then the equation describing
spect to time gives the dynamics of errors

˙ sin θ̃ − sin δ ėη + Km eη = 0, e η = η − ηr (75)


(θ̃ − δ) = γ y1 v − k2 (θ̃ − δ). (69)
θ̃ − δ is asymptotically stable.
Hence
7 Simulations
˙ sin θ̃ − sin δ
v 2 (θ̃ − δ) = 2v v̇(θ̃ − δ) − γ y1 v 3
θ̃ − δ The simulations were carried out to illustrate
+ − v 2 k2 (θ̃ − δ) (70) the behaviour of the wheeled mobile robot of
490 J Intell Robot Syst (2015) 77:481–498

(2,0) type with the presented controllers and


the dynamic model of the robot was simulated.
The initial position of the platform was equal
to (x0 , y0 , θ0 ) = (1.5, 0, π3 ) for all algorithms
except Soetanto-Lapierre-Pascoal algorithm and
(x0 , y0 , θ0 ) = (5, 1, π3 ) for Soetanto-Lapierre-
Pascoal algorithm. The desired path was the circle
described by the equations
s
x(s) = R cos ,
R
s
y(s) = R sin , Fig. 4 The path following for the unicycle, XY plot (Sam-
R son algorithm, ideal conditions)

where R = 2 m. The simulation time was set for


25 s for all algorithms except Soetanto-Lapierre-
Parameters of the kinematic controllers were
Pascoal algorithm and for 50 s for SLP algorithm.
set to the values presented below:
Simulations were carried out in ideal condi-
tions, i.e. without modelling any kind of a distor- – Samson algorithm: k2 = k3 = 1, v = 1,
tion, and in the case when the robot’s orientation – discontinuous algorithm, first proposal: k1 =
was distorted by a Gaussian white noise with a k2 = 1, vc = 1,
variance σ 2 . For the wheeled mobile robot of (2,0) – discontinuous algorithm, second proposal:
type the parameter that has the biggest influence k1 = k2 = k3 = 1, vc = 1,
on the control is the orientation—this is why θ was – Morin-Samson algorithm: k2 = 10, k3 = 100,
chosen to be noised. It was assumed that σ = 0.1 u1 = 1,
which may be treated as the total measurement – Soetanto-Lapierre-Pascoal algorithm: γ = 1,
inaccuracy of devices at the level of approximately k1 = 10, k2 = 1000, δ = −sign(v)θa tanh y1 ,
±5 degrees. Separate simulations with the white θa = π4
noise added to velocities of wheels to verify the
and the matrix Km in the dynamic controller is
influence of a motor quality on the realization
equal to 50 · I2 . The results of the simulations have
of the path following task by the presented al-
been presented in Figs. 4, 5, 6, 7, 8, 9, 10, 11, 12, 13,
gorithms were carried out as well. In that case a
14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27,
noise variance was chosen to be equal to 0.1. To
28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41,
illustrate the influence of an inertia on the per-
42, 43.
formance of the different control strategies in the
perturbed cases two graphs have been combined
together—the one when only the kinematic model
was simulated and the second when the dynamical
model was simulated.
Some additional simulations which take into ac-
count velocity constraints were carried out as well.
The velocity constraints imposed on the robot are
chosen as
(a) (b)
−1 ≤ v ≤ 1 [m/s],
Fig. 5 The path following for the unicycle (Samson al-
π π gorithm, ideal conditions): a the distance error l, b the
− ≤ω≤ [rad/s].
5 5 orientation error θ̃
J Intell Robot Syst (2015) 77:481–498 491

(a) (b)
Fig. 6 The path following for the unicycle, XY plot Fig. 9 The path following for the unicycle (Samson algo-
(Samson algorithm with a noised orientation, thin dashed rithm with noised wheels velocities, thin dashed line—only
line—only kinematic model simulated, thick solid line— kinematic model simulated, thick solid line—dynamical
dynamical model simulated) model simulated): a the distance error l, b the orientation
error θ̃

(a) (b)
Fig. 7 The path following fo the unicycle (Samson algo-
rithm with a noised orientation, thin dashed line—only
kinematic model simulated, thick solid line—dynamical
model simulated): a the distance error l, b the orientation
error θ̃

Fig. 10 The path following for the unicycle, XY plot


(Samson algorithm, velocity constraints)

Fig. 8 The path following for the unicycle, XY plot (Sam- (a) (b)
son algorithm with noised wheels velocities, thin dashed
line—only kinematic model simulated, thick solid line— Fig. 11 The path following for the unicycle (Samson algo-
dynamical model simulated) rithm, velocity a the distance error l, b the orientation error θ̃
492 J Intell Robot Syst (2015) 77:481–498

(a) (b)
Fig. 15 The path following for the unicycle (discontinuous
control algorithm I with a noised orientation, thin dashed
line—only kinematic model simulated, thick solid line—
dynamical model simulated): a the distance error l, b the
Fig. 12 The path following for the unicycle, XY plot (dis- orientation error θ̃
continuous control algorithm I, ideal conditions)

(a) (b)
Fig. 13 The path following for the unicycle (discontinuous
control algorithm I, ideal conditions): a the distance error
l, b the orientation error θ̃ Fig. 16 The path following for the unicycle, XY plot (dis-
continuous control algorithm I with noised wheels veloc-
ities, thin dashed line—only kinematic model simulated,
thick solid line—dynamical model simulated)

(a) (b)
Fig. 17 The path following for the unicycle (discontinu-
Fig. 14 The path following for the unicycle, XY plot (dis- ous control algorithm I with noised wheels velocities, thin
continuous control algorithm I with a noised orientation, dashed line—only kinematic model simulated, thick solid
thin dashed line—only kinematic model simulated, thick line—dynamical model simulated): a the distance error l, b
solid line—dynamical model simulated) the orientation error θ̃
J Intell Robot Syst (2015) 77:481–498 493

(a) (b)
Fig. 21 The path following for the unicycle (discontinuous
control algorithm II, ideal conditions): a the distance error
l, b the orientation error θ̃
Fig. 18 The path following for the unicycle, XY plot (dis-
continuous control algorithm I, velocity constraints)

(a) (b)
Fig. 19 The path following for the unicycle (discontinuous
control algorithm I, velocity constraints): a the distance Fig. 22 The path following for the unicycle, XY plot (dis-
error l, b the orientation error θ̃ continuous control algorithm II with a noised orientation,
thin dashed line—only kinematic model simulated, thick
solid line—dynamical model simulated)

(a) (b)
Fig. 23 The path following for the unicycle (discontinuous
control algorithm II with a noised orientation, thin dashed
line—only kinematic model simulated, thick solid line—
Fig. 20 The path following for the unicycle, XY plot (dis- dynamical model simulated): a the distance error l, b the
continuous control algorithm II, ideal conditions) orientation error θ̃
494 J Intell Robot Syst (2015) 77:481–498

(a) (b)
Fig. 27 The path following for the unicycle (discontinuous
control algorithm II, velocity constraints): a the distance
error l, 2 the orientation error θ̃
Fig. 24 The path following for the unicycle, XY plot (dis-
continuous control algorithm II with noised wheels veloc-
ities, thin dashed line—only kinematic model simulated,
thick solid line—dynamical model simulated)

(a) (b)
Fig. 25 The path following for the unicycle (discontinuous
control algorithm II with noised wheels velocities, thin
dashed line—only kinematic model simulated, thick solid
line—dynamical model simulated): a the distance error l, Fig. 28 The path following for the unicycle, XY plot
b the orientation error θ̃ (Morin-Samson algorithm, ideal conditions)

(a) (b)
Fig. 29 The path following for the unicycle (Morin-
Fig. 26 The path following for the unicycle, XY plot (dis- Samson algorithm, ideal conditions): a the distance error l,
continuous control algorithm II, velocity constraints) b the orientation error θ̃
J Intell Robot Syst (2015) 77:481–498 495

(a) (b)
Fig. 30 The path following for the unicycle, XY plot
(Morin-Samson algorithm with a noised orientation, thin Fig. 33 The path following for the unicycle (Morin-
dashed line—only kinematic model simulated, thick solid Samson algorithm with noised wheels velocities, thin
line—dynamical model simulated) dashed line—only kinematic model simulated, thick solid
line—dynamical model simulated): a the distance error l, b
the orientation error θ̃

(a) (b)
Fig. 31 The path following for the unicycle (Morin-
Samson algorithm with a noised orientation, thin dashed
line—only kinematic model simulated, thick solid line—
dynamical model simulated): a the distance error l, b the
orientation error θ̃

Fig. 34 The path following for the unicycle, XY plot


(Morin-Samson algorithm, velocity constraints)

Fig. 32 The path following for the unicycle, XY plot


(Morin-Samson algorithm with noised wheels velocities, Fig. 35 The path following for the unicycle (Morin-
thin dashed line—only kinematic model simulated, thick Samson algorithm, velocity constraints): a the distance
solid line—dynamical model simulated) error l, b the orientation error θ̃
496 J Intell Robot Syst (2015) 77:481–498

Fig. 36 The path following for the unicycle, XY plot


(Soetanto-Lapierre-Pascoal algorithm, ideal conditions)

Fig. 39 The path following for the unicycle (Soetanto-


Lapierre-Pascoal algorithm with a noised orientation, thin
dashed line—only kinematic model simulated, thick solid
line—dynamical model simulated): a the distance error s1 ,
b the distance error y1 , c the orientation error θ̃

Samson algorithm seems to be the most noise-


robust among presented algorithms. For the
noised orientation the path circled by the robot
in XY plane is almost the same as the desired
path—it is shifted a bit. Little worse results were
obtained for the noised velocity of wheels case
because the robot followed a circle-shaped path
with a bigger radius than the radius of the desired
path.
Fig. 37 The path following for the unicycle (Soetanto- The discontinuous control algorithms work
Lapierre-Pascoal algorithm, ideal conditions): a the dis- properly in ideal conditions and are characterized
tance error s1 , b the distance error y1 , c the orientation
error θ̃ by a fast convergence of path following errors to
zero without an occurrence of oscillations in the

Fig. 38 The path following for the unicycle, XY plot Fig. 40 The path following for the unicycle, XY plot
(Soetanto-Lapierre-Pascoal algorithm with a noised orien- (Soetanto-Lapierre-Pascoal algorithm with noised wheels
tation, thin dashed line—only kinematic model simulated, velocities, thin dashed line—only kinematic model simu-
thick solid line—dynamical model simulated) lated, thick solid line—dynamical model simulated)
J Intell Robot Syst (2015) 77:481–498 497

Fig. 43 The path following for the unicycle (Soetanto-


Fig. 41 The path following for the unicycle (Soetanto- Lapierre-Pascoal algorithm, velocity constraints): a the dis-
Lapierre-Pascoal algorithm with noised wheels velocities, tance error s1 , b the distance error y1 , c the orientation
thin dashed line—only kinematic model simulated, thick error θ̃
solid line—dynamical model simulated): a the distance
error s1 , b the distance error y1 , c the orientation error θ̃

tion case. The robot does not move too far from
the path, however it wanders around the path
courses of the variables l and θ̃ during the tran- which is an undesirable behaviour.
sient phase. However they are not noise-robust, The main difference between Morin-Samson
even for a relatively small value of noise variance. and Samson algorithms is that before Morin-
It means that they cannot be used in practical ap- Samson algorithm could be used, two nonlinear
plications where one has to take into account the transformations of the robot’s kinematics have to
probabilistic nature of the physical world. Thus it be computed, while for Samson algorithm one
is recommended to design rather continuous con- transformation is enough. Morin-Samson algo-
trol algorithms for the path following task instead rithm does not work properly for the noised ori-
of discontinuous ones. entation. However when one detaches the object’s
Soetanto-Lapierre-Pascoal algorithm does not dynamics and controls the robot only at the kine-
perform sufficiently well for the noised orienta- matic level, Morin-Samson algorithm works just
a little worse than Samson algorithm. That issue
has to be deeply investigated in the future.
What is more, the path following task is real-
ized correctly by the considered wheeled mobile
robot when the presented algorithms are modified
by adding velocity constraints. Introducing such
constraints slows down the convergence of path
tracking errors to zero, but does not disrupt the
realization of the task.

8 Conclusions

Fig. 42 The path following for the unicycle, XY plot In the paper different kinematic path following
(Soetanto-Lapierre-Pascoal algorithm, velocity constraints algorithms for the wheeled mobile robot of (2,0)
498 J Intell Robot Syst (2015) 77 :481–498

type have been presented. For the two of the pre- Technical Report No. 2097, INRIA, Sophia-Antipolis,
sented algorithms the proofs of their convergence France (1993)
2. Soetanto, D., Lapierre, L., Pascoal, A.: Adaptive, non-
have been performed. singular path-following control of dynamic wheeled ro-
The choice of the path parametrization is of bots. Proc. IEEE Conf. Decis. Control 2, 1765–1770
a great importance in the path following task. The (2003)
significant constraint of the parametrization which 3. Morro, A., Sgorbissa, A., Zaccaria, R.: Path following
for unicycle robots with an arbitrary path curvature.
uses the Serret-Frenet frame with an orthogonal
IEEE Trans. Robot. 27(5), 1016–1023 (2011)
projection of the robot on the desired path is its 4. Morin, P., Samson, C.: Motion control of wheeled mo-
local character. Therefore if the initial position bile robots. In: Siciliano, B., Khatib, O.: (eds.) Hand-
of the robot is too far from the path, the robot book of Robotics. Springer (2008)
5. Soueres, P., Hamel, T., Cadenat, V.: A path following
has to at first get closer to the desired path before
controller for wheeled robots which allows to avoid ob-
it can start the realization of the path following stacles during transition phase. Proc. IEEE Int. Conf.
task. In contrary the approach using the Serret- Robot. Autom. 2, 1269–1274 (1998)
Frenet frame with an non-orthogonal projection 6. Lapierre, L., Zapata, R., Lepinay, P.: Simulatneous
path following and obstacle avoidance control of a
does not have such a drawback but it has a bigger unicycle-type robot. In: IEEE International Confer-
amount of path following errors to be brought to ence on Robotics and Automation 2007, pp. 2617–2622
zero and the designing of the control law may be (2007)
more difficult. 7. Campani, M., Capezio, F., Rebora, A., Sgorbissa, A.,
Zaccaria, R.: A minimalist approach to path following
The study showed that the impact of the noise
among unknown obstacles. In: IEEE/RSJ International
on the realization of the path following task might Conference on Intelligent Robots and Systems, (IROS)
be huge. This is why when using model-based 2010, pp. 3604–3610 (2010)
control one has to measure the robot’s posture as 8. Consolini, L., Morbidi, F., Prattichizzo, D., Tosques,
M.: Leader-follower formation control of nonholo-
precisely as possible and ensure as high motor’s
nomic mobile robots with input constraints. Automat-
quality as possible. The article is not comprehen- ica, 44(5), 1343–1349 (2008)
sive and only a selected group of algorithms which 9. Ghommam, J., Mehrjerdi, H., Saad, M., Mnif, F.:
are based on the Serret-Frenet frame attached to Formation path following control of unicycle-type
mobile robots. Robot. Auton. Syst. 58(5), 727–736
a path was tested. In the future the other types
(2010)
of path following algorithms could be investigated 10. Mazur, A.: Hybrid adaptive control laws solving a path
taking into account their noise robustness. The following problem for nonholonomic mobile manipu-
extension of this work could be a study of the lators. Int. J. Control 77(15), 1297–1306 (2004)
11. Samson, C.: Path following and time-varying feedback
robustness properties of path following algorithms
stabilization of a wheeled mobile robots. In: Proceed-
which deal with obstacles avoidance. ings of the IEEE International Conference on Ad-
vanced Robotics and Computer Vision, pp. 1.1–1.5
(1992)
Acknowledgement This work was supported by the fel- 12. Campion, G., Bastin, G., d’Andréa Novel, B.: Struc-
lowship co-financed by European Union within European tural properties and classification of kinematic and dy-
Social Fund. namic models of wheeled mobile robots. IEEE Trans.
Robot. Autom. 12(5), 47–61 (1996)
13. Campion, G., Chung, W.: Wheeled robots. In: Siciliano,
Open Access This article is distributed under the terms of B., Khatib, O. (eds.) Handbook of Robotics. Springer
the Creative Commons Attribution License which permits (2008)
any use, distribution, and reproduction in any medium, 14. Samson, C.: Control of chained systems—application
provided the original author(s) and the source are credited. to path following and time-varying point-stabilization
of mobile robots. IEEE Trans. Autom. Control 40(1),
64–77 (1995)
15. Krstić, M., Kanellakopoulos, I., Kokotović, P.: Nonlin-
References ear and Adaptive Control Design. Wiley, Boca Raton
(1994)
1. Micaelli, A., Samson, C.: Trajectory tracking for 16. Canudas de Wit, C., Siciliano, B., Bastin, G.: Theory
unicycle-type and two-steering-wheels mobile robots. of Robot Control. Springer, London (1996)

You might also like