Abstract
A novel control approach is proposed for trajectory tracking of a wheeled mobile robot with unknown wheels’ slipping. The longitudinal and lateral slipping are considered and processed as three time-varying parameters. The adaptive unscented Kalman filter is then designed to estimate the slipping parameters online, an adaptive adjustment of the noise covariances in the estimation process is implemented using a technique of covariance matching in the adaptive unscented Kalman filter context. Considering the practical physical constrains, a stable tracking control law for this robot system is proposed by the backstepping method. Asymptotic stability is guaranteed by Lyapunov stability theory. Control gains are determined online by applying pole placement method. Simulation and real experiment results show the effectiveness and robustness of the proposed control method.
Keywords
Introduction
Over the last several years, the control problem of the wheeled mobile robot (WMR) has been regarded as a fascinating problem because of the property of its nonholonomic constraints. Many developed controllers have been designed for tracking and stabilization of nonholonomic mobile robots using several nonlinear control techniques such as sliding mode control, 1–6 adaptive control, 7–11 backstepping control 12 –14 and intelligent control based on neural networks, 15 –19 fuzzy control, 20–23 and other intelligent control method. 24,25
The previous papers 1–24 assume nonholonomic constraints for the controlled WMR. The nonholonomic constraints are generated by the assumption that the mobile robots are subject to a “pure rolling without slipping.” However, since the robotic wheels’ slipping can happen in various practical environments such as the on wet or icy roads, rough terrain, or the rapid cornering, the nonholonomic constraint can be disturbed in a few literatures. 26 –29 To deal with this case, control methods for mobile robots considering slipping were proposed in a few literatures. 26–35 Wang and Low 32 proposed models of the WMR with wheels’ slipping and examined their controllability according to the outdoor maneuverability of the WMR. Moreover, they presented control approaches for trajectory tracking of mobile robots considering skidding and slipping. 31,32 However, the information of skidding and slipping is measured by the global positioning system and small initial conditions between the actual robot and the reference robot are required to design the controllers in. 31,32 Additionally, these papers 33,34 only considered the longitudinal slipping of the kinematic model for mobile robots without lateral slipping. The study by Zhou et al. 35 only considered the lateral slipping of the kinematic model for the WMR without longitudinal slipping. The papers by Cui et al. (2014), Tian and Sarkar (2014), and Yoo (2011) 26 –28 are excellent and distinguished works to deal with slipping perturbation; however, practical physical control constrains are not considered in the process of controller design.
Accordingly, the main theory contributions of our work are the design of an adaptive controller for tracking trajectory the WMR with unknown wheels’ slipping at the kinematics level. More specifically, in the theoretical aspect of this article, considering practical physical constrains, we design a control law that guarantees tracking with bounded error for the WMR with unknown slipping. First, the kinematic model of the WMR considering the slipping is induced from nonholonomic constraints. Three slipping parameters are estimated online by the adaptive unscented Kalman filter (AUKF). An adaptive adjustment of the noise covariances in the estimation process is implemented using a technique of covariance matching in the AUKF context. Meanwhile, a stable tracking control law for this nonholonomic system is proposed and the asymptotic stability is guaranteed by Lyapunov theory. From the Lyapunov stability theorem, we prove that tracking errors of the controlled closed-loop system are uniformly bounded and the tracking errors can be made arbitrarily small by adjusting design parameters regardless of large initial tracking errors and unknown slipping. Second, to simplify the complexity of the tuning parameters for the proposed controller, the controller gains are computed using pole placement method. To the best of our knowledge, this is the first design of a tracking controller for the WMR with two independently driving wheels. Finally, we provide simulation results to verify the effectiveness of the proposed controller.
This article is organized as follows. In “Kinematic model of the WMR with wheels’ slipping” section, we present the kinematics model of WMRs with longitudinal and lateral slipping induced from nonholonomic constraints. In “
Kinematic model of the WMR with wheels’ slipping
A scheme of the WMR is shown as Figure 1. The two front wheels are driven independently by two direct current servo motors, respectively. The two rear wheels are supporting rollers, and they only play the roles of supporting car body, but no guidance.

WMR with two independent driving wheels. WMR: wheeled mobile robot.
To describe the motion features of tracked WMR simply and rigorously in the general plane motion, a fixed reference coordinate frame F1(xw, yw) and a moving coordinate frame F2(xm, ym) are defined which attach to the robot body with origin at the geometric center Om . ω is the angular velocity of the WMR around the geometric center Om .
The linear velocities of left and right driving wheels of mobile robot without slipping are given as follows
where ωL and ωR are the angular velocities of the left and right wheels, respectively and r is radius of the wheels. Longitudinal slipping ratio of the left and right wheels of the WMR are defined as follows 33
where
Assumption 1
The range of longitudinal slip ratio
Remark 1
If aR = aL = 1, from equation (2), we know that
Lateral slipping ratio of the WMR is defined as 35
where α is the lateral slipping angle of a mobile robot (see Figure 1), it is the angle between the velocity of the mobile robot v and the x axis of a local frame attached to the mobile robot.
Assumption 2
The lateral slip angle α lies in (0, π/2).
Remark 2
If α = π/2, it implies that mobile robot is in a state of complete lateral slipping, the mobile robot is uncontrollable, this case is not considered. That is, lateral slip ratio δ is bounded.
From equation (2), the linear velocities of the left and right wheels of the mobile robot with wheels’ slipping are given as
In coordinate frame F1(xw, yw), the kinematic mode of the WMR without wheels’ slipping is described as
In coordinate frame F2(xm, ym), a suitable model with slipping can be written as
where b is the distance between two driving wheels. As shown in Figure 1, the coordinate rotation transformation from F2(xm, ym) to F1(xw, yw) is given by
From equations (6) and (7), in coordinate frame F1(xw, yw), the kinematic mode of the differential WMR with slipping is described as follows
where [x, y, θ] T is posture vector of the mobile robot and θ is heading angle of the WMR.
Assumption 3
Slipping parameters aR , aL , and δ are not measurable.
Define an auxiliary control input [v, ω] T , and then the relationship between auxiliary control input and real control input [ωL, ωR] T is regarded as
where matrix
Then, equation (8) can be rewritten as
We can see from equation (8), to handle tracking control problem of the WMR with unknown slipping parameters aL , aR , and δ, it is the top priority to estimate time-varying slipping parameters online, and then to design tracking controller on the basis of the estimation of the slipping parameters.
A scheme of the robotic slipping parameter estimation
Because three slipping parameters aR , aL , and δ in equation (8) cannot be measured directly, it is necessary to estimate slipping parameters in order to design tracking controller. To estimate the states and slipping parameters, joint estimation technique can be used, that is, states and parameters are estimated simultaneously using a same filter. 36 It is often used to solve the state feedback control with uncertain parameters, or the modeling of the parameters with noise and states that can’t be measured directly. Because of the incorporation of the states and the parameters, more accurate results may be made using this approach. In the localization of the WMR with slipping, the pose and the slipping parameters should be estimated at the same time. A new state vector P = [x, y, θ, aR, aL, δ] T is defined as a combination of the old states and parametric vector. In this augmented state, the dynamic of the slipping parameters are often unknown. In discrete time domain, it can be rewritten as following
where Pk ∈ Rp is the discrete parametric vector and wp,k ∈ Rp is the additive process noise which drives the model. The UKF is introduced to estimate jointly the state and slipping parameters. Unlike extended Kalman filter (EKF), 37 the UKF is able to approximate the nonlinear process and observation models. 38 Instead, it uses the true nonlinear models and approximates the distribution of the state random variable. The UKF, which does not need to compute the Jacobian, the so-called unscented transform and sigma points are used to propagate all of them through models. As a result, the UKF often leads to more accurate estimations than the EKF.
Given the following general nonlinear system
where f(xk, uk) and h (xk) are the nonlinear process and measurement models of the robot, respectively. The immeasurable state vector is represented by xk = [x, y, θ, aR, aL, δ]
T
, uk
is known as the control input vector, and
Standard UKF
Initization at k = 0
where
The augmented state including original states, parameters, and process noises are defined as
(2) For K=1,2,…,∞
(a) Calculate sigma points
(b) The prediction step
where Qk
is the process noise covariance matrix, and the weights
where n is the dimension of the augmented states; α controls the size of the sigma point distribution and should be ideally a small number to avoid sampling nonlocal effects when the nonlinearities are strong; and β is a nonnegative weighting term, which can be used to acknowledge the information of the higher order moments of the distribution. For a Gaussian prior the optimal choice is β = 2, and to guarantee positive semi-definiteness of the covariance matrix tuning, parameter κ ≥ 0 is chosen. The rest parameters are defined as
(c) The update step
where Rk is the measurement noise covariance matrix.
Adaptive UKF
In order to further improve the estimation precision, an adaptive adjustment of the noise covariances in the estimation process is implemented using a technique of covariance matching in the UKF context. More specifically, the adaptive estimation of the process noise covariance Qk and measurement noise Rk on the basis of the pose sequence of the mobile robot will be considered. Therefore, Qk and Rk are estimated and updated iteratively from the following 39
where
where
Moreover, in order to reduce the chattering of AUKF, a low-pass filter (LPF) is applied to process the estimation signal. A first-order LPF is described in Figure 2.

Filtering processing of the estimation signal.
The relationship between input u and output y of LPF is given as
where
Remark 3
Note that we employ the first-order LPF (23) to reduce the chattering problem and guarantees smoothness of the estimation signal. After the estimation of the slipping parameters is processed by the LPF, their first-order derivative values
Design of the tracking controller
Design of the tracking control law
Assume there is a superposition between center of mass and movement geometric center of the WMR. The kinematic model of the WMR with the slipping can be described by equation (8), so actual posture of the WMR is decided by equation (8). The desired posture is defined as pr = [xr, yr, θr] T , the desired posture satisfies the following equations
where vr and ωr are reference linear velocity and angular velocity of the mobile robot, respectively.
Assumption 4
The reference linear velocity vr and ωr as well as their derivatives are all bounded.
Our control objective is to design a trajectory tracking controller, when the wheels’ slipping will occur between the WMR and the ground, which making the actual and desired posture of the WMR satisfy as following
In the coordinate frame F1(x, y), the tracking error dynamics of the WMR are described as follows
where e 1, e 2, and e 3 are state-tracking errors, they are expressed in the frame of real robot, as shown in Figure 3.

Robotic pose error coordinates scheme.
Tracking errors vector of the WMR is defined as e = [e1, e2, e3] T , the error dynamics of the WMR is obtained as follows 11
In the presence of the wheels’ slipping, applying backstepping method, the auxiliary control input is designed as follows 7
where k
2 is a positive design constant, and k1(vr, ωr) and k3(vr, ωr) are bounded continuous functions with bounded first derivatives, strictly positive on
Now, if the slipping parameters aR
, aL
, and δ that appear in equation (8) are unknown, we cannot choose directly the auxiliary control input as given by equation (28). Hence, we will employ an A
where k1 = k1 (vr, ωr) and k3 = k3 (vr, ωr) are defined in equation (28). Actual control input ωL and ωR can also be obtained as follows
Remark 4
The estimation values of the slipping parameters are possible to be ones when we use AUKF. Once
Control constraints
Because of the bounded velocity capability of the motors, each wheel can achieve a maximum angular velocity ωmax. With the saturation, it is necessary to perform a suitable velocity scaling so as to preserve the curvature radius corresponding to the nominal velocities ωL
and ωR
. The actual commands
From equation (27), the actual commands
Remark 5
In equation (32), the nominal velocity control commands ωL and ωR are computed from equation (30).
Stability analysis of control system
Theorem 1
The trajectory tracking errors e = [e1, e2, e3] T in the tracking error dynamics equation (27) of the WMR with unknown slipping parameters will asymptotically converge to zero vector, if the control law equation (29) and AUKF are applied.
Proof
We choose the following Lyapunov function candidate as
The first-order derivative of the Lyapunov function V(t) can be obtained as
The error dynamics equation (27) is substituted into equation (34),
Substituting equation (29) into equation (35),
The domain D is defined by
As t∈[0,∞), V(t) is a nonincreasing function, we can obtain as
This implies that V(t) is bounded as t∈[0, ∞). From equaion (33), we know e
1 and e
2 are all bounded as t∈[0, ∞). Since desired velocity vr
and ωr
are assumed to be bounded, from equation (28), we know the auxiliary control inputs v and ω are bounded. From equation (27), we can know
From remark 3, assumption 4, and equation (39), we can know
From equations (27) and (29), we have
Thus
Because
In conclusion, the equilibrium point e = [e1, e2, e3] T = [0, 0, 0] T is uniform and asymptotically stable. This implies the WMR can converge asymptotically to the reference posture pr = [xr, yr, θr] T from the arbitrary initial posture. Thus, the control objective is implemented accordingly.
Adaptive adjustment of control parameters
Since the location of the poles determines the damping ratio ξ of transient response near the reference trajectory, so the transient response of closed-loop robot system can be analyzed from the location of the poles in a closed-loop system. The theory of the location of poles shows that the poles are always in the area not exceeding ±45∘ in the left-half s-plane. That is to say,
The tracking error vector of the WMR is defined as e = [e1, e2, e3] T , after substituting equation (28) into equation (27), the tracking error differential equations of closed-loop robotic system can be obtained as
After linearizing the equation (42) around the equilibrium point [e1, e2, e3] T = [0, 0, 0] T , we have
Remark 6
Note that the mismatch between the linearized model and the nonlinear system grows for values of e 3 far from zero. It will be shown that, in practice, after the transient, e 3 remains very close to zero. Then, the problem could be present at the first instants, due to the initial condition. For that reason, we assume that, in practice, the real robot and the reference virtual robot start close. In this case, the linearization is successful.
Generally, the trial-and-error method is used to determine controller gains. If so, not only the accuracy of the controlled robotic system can not be guaranteed but also its adaptation is bad. Based on the linearization model, an online computing method of control gains is proposed by the pole placement strategy.
The controller gains can be determined by comparing the actual and desired characteristic polynomial equations. Here, pole placement methodology is employed to decide control gains of robotic tracking controller. The desired poles are chosen as
where ξ is desired damping coefficient of closed-loop robotic system, ωn is the characteristic frequency, both of them are positive constants, and s is Laplace operator.
Equation (43), the characteristic polynomial of the system matrix Aq can be obtained as
The robotic closed-loop poles are now equal to the roots of the characteristic polynomial equation (45). Comparing equation (44) with equation (45), the following equations can be obtained as
Equation (46), we can obtained as
where ωn should be larger than the maximum-allowed robotic angular velocity, ωn > ωrmax, ωrmax is the maximum-allowed robot angular velocity. ωrmax can be obtained as follows
where ωmax is robot’s wheel, which can achieve the maximum angular velocity, r is radius of the wheels, and b is the distance between two driving wheels. In equation (47), vr → 0 and k2 → ∞. One way to avoid this is by allowing the closed-loop poles only depend on the values of vr
and ωr
. Consequently, a gain scheduling should be chosen for
Remark 7
In equation (49), the slipping parameter δ is estimated by AUKF online (see “Scheme of the robotic slipping parameter estimation” section).
Remark 8
From assumption 1 and equation (49), we know that ki ∈ (0, ∞),(i=1, 2, 3) are realizable in physics.
Since the dynamic performance of closed-loop system is determined by the damping ratio ξ, thus we can predetermine the damping ratio ξ in accordance with the desired performance requirements. Therefore, controller gains k 1, k 2, and k 3 can be determined only by adjusting parameter d, and then the control parameter adjusting process is simplified greatly. Since the reference velocity vr and ωr are time varying, then the control gains k 1 and k 3 are also time varying. Accordingly, they can be adjusted online in accordance with equation (49). Hence, the real-time property and flexibility of the controlled robot system are improved greatly.
From the above analysis (see “A scheme of the robotic slipping parameter estimation,” “Design of the tracking controller,” and “Adaptive adjustment of control parameters

A scheme of the trajectory tracking control principle for the WMR. WMR: wheeled mobile robot.
Simulations and experiment
Simulations
In this section, to verify the effectiveness of the proposed tracking control scheme, some simulations are performed on the kinematic model of the tracked WMR with slipping. In the simulations, the angular velocities of the two driving wheels are considered as control input variables. To observe and compare the simulation results more easily, two kinds of reference trajectories are chosen as follows: one is a straight-line trajectory, and the other is a circle one. The parameters of the WMR are chosen as follows:
b = 1 m, r = 0.125 m, ξ = 0.707 (both to ensure that convergence speed of the tracking errors and ensure that as far as possible little overshoot, the best damping ratio ξ = 0.707 is chosen), robot's wheels can achieve a maximum angular velocity ωmax = 8.5rad/s, k 2 = d = 60; the parameters of the AUKF should be determined carefully. For the AUKF, the three constant filter parameters are chosen as follows: α = 1, β = 2 and γ = 0, L = 100. The parameters of the LPF are chosen as follows: γ1 = 0.6, γ2 = 0.2, γ3 = 0.8. Let us suppose the three states about the robot's poses, which can be measured directly.
Note that the kinematics and the dynamics of the robot are described by the continuous-time equations and (26). On the other hand, the AUKF is a discrete-time algorithm. Thus, to perform the computer simulation, the continuous-time equations (8) and (26) are discretized using Euler’s forward difference scheme with a sampling period of Ts = 0.02 s.
The straight-line reference trajectory tracking
In this case, a straight-line reference trajectory is considered. The initial posture of the reference trajectory is set at
The actual initial posture of the WMR is given as
The actual initial posture errors of the WMR is
Reference velocities are given as vr = 2 m/s, ωr = 0 rad/s, and the reference orientation angle θr = π rad/4. In order to demonstrate the tracking performance, abrupt changes are simulated to occur in the three slipping parameters at time t = 15 s, they are given as follows:
From Figure 5, we can see that proposed control method can track the desired straight-line trajectory rather quickly. Furthermore, when the wheel’s slipping are introduced into the robot’s system, we can observe that the proposed adaptive tracking controller has excellent ability to overcome the wheel’s slipping perturbation. Meanwhile, we can see that the AUKF can estimate the time-varying slipping parameters rather precisely. The estimations of the slipping parameters have a rather light oscillation due to LPF is applied.

Straight-line trajectory tracking. (a) Straight-line trajectory tracking result; (b) x orientation error e 1; (c) y orientation error e 2; (d) heading angle error e 3; (e) slipping parameter aL estimation; (f) slipping parameter aR estimation; (g) slipping parameter δ estimation; (h) control input ωL ; (i) control input ωR ; (j) control gains (k1 = k3).
The circle reference trajectory tracking
The equation of the circle reference trajectory is given as
where t is simulation time. The initial posture of the reference trajectory is set at
The actual initial posture of the WMR is
The actual initial posture errors of the WMR is
To facilitate comparison of the simulation results, the control parameters, the parameters of the AUKF, and the changes of the slipping parameters are all the same as in the previous simulation. In this case, the reference line velocity vr(t) = 2 rad/s, and the tangential angle velocity of each point on the reference trajectory is given as follow: ωr(t) = 1 rad/s.
From Figure 6, we can see that the proposed control approach has the good tracking control performance for the curved path in spite of the effects of the unknown wheels’ slipping. That is to say, the proposed control method can effectively conquer the slipping effect for the given curved trajectory tracking of the WMR. Meanwhile, the AUKF can estimate three time-varying slipping parameters accurately, even when sudden changes happen.

Circle trajectory tracking. (a) Circle trajectory tracking result; (b) x orientation error e 1 ; (c) y orientation error e 2; (d) heading angle error e 3; (e) slipping parameter aL estimation; (f) slipping parameter aR estimation; (g) slipping parameter δ estimation; (h) control input ωL ; (i) control input ωR ; (j) control gains (k1 = k3).
Furthermore, from Figures 5 and 6, we can futher find that the proposed control method can effectively overcome the slipping for the given trajectory tracking of the WMR, this is mainly because that the designed tracking controller have an adaptive ability, whose some control parameters k 1 and k 3 can be adaptively modifying in real time. Moreover, even if the wheels’ slipping parameters change suddenly, the AUKF can still exactly estimate slipping parameters in real time to satisfy the demands of the robot in the actual working environment. Consequently, the adaptive tracking control algorithm has good robustness and adaptive ability to confront slipping parameter perturbations of the WMR.
Further, by comparing Figure 5 with Figure 6, we can also find that the tracking errors of circle trajectory is bigger than straight-line trajectory, this is mainly because that circle path have a time-varying reference angular velocity θr
while reference angular velocity of the straight-line reference path is constant. Compared Figure 5(j) with Figure 6(j), we can see that k
1 and k
3 are all constants in straight-line trajectory environment, from equation (47), we know
Real experiment
In order to demonstrate the effectiveness and applicability of the proposed method, a real-time control system is implemented for the mobile robot. In the experiment, a mobile robot with one vision navigation system fixed on the top moves along the marking line. Figure 7 shows the picture of the robot which is used in the experiment. It has the same structure as Figure 8, with two driving wheels and two passive wheels. The diameter of the robot is 50 cm and the radius of driving wheel is 12.5 cm. The driving wheels are driven by motors with the maximum permissible speed of 3900 n/min. The motor and the driving wheel are connected by a reduction gearbox. For the convenience of comparing, the control parameters are all same as the simulations.

Mobile robot in real experiment.

Schematic diagram of the experiment control system.
The control board of the mobile robot consists of the main controller and motor controller. The main controller of the robot is dsPIC30F6014, which is running at 32 MHz. It is used to communicate with host computer and motor controller. It receives the voltage instruction from the host computer and calculates the voltage distribution on the right and left motors, respectively, and then sends the data through SPI communication to the auxiliary motor controller, dsPIC4012. The motor controller generates pulse-width modulation (PWM) signal with different duty cycles according to the voltage instruction.
Figure 8 shows the whole schematic diagram of the trajectory tracking system for the mobile robot. Because of the complexity of the calculation process, the proposed adaptive tracking controller based on AUKF is carried out in the main computer running at the frequency of 1.86 MHz. The software for implementing the algorithm is developed in Visual C++6.0. After the reference trajectory has been set up, the proposed adaptive tracking controller generates the real voltage instruction. The dsPIC controller can generate the PWM signal to control the velocity of the mobile robot so that the mobile robot moves according to the instruction. The vision navigation system evaluates the posture of the robot and feedback the information to the host computer until the posture error is minimized.
In order to validate the applicability of the proposed control scheme, the mobile robot was required to track reference trajectories. The real position of the mobile robot is feedback to the mobile robot every 0.2 s by camera navigation system.
In order to prove the effectiveness of the proposed adaptive tracking controller based on AUKF, real experiment is implemented for the desired trajectory of a straight line. Reference velocities are given as vr = 2 m/s and ωr = 0 rad/s, The robot started tracking with initial errors e1 = 0 m, e2 = 0 m, and e3 = 0 rad. At 25 s, the arbitrary external wheels’ slipping disturbance is fed in robotic system by laying sand on the ground. The experimental results are shown in Figure 9. From Figure 9, we can see that the tracking errors of the proposed adaptive control algorithm are asymptotically convergent. It implies that the mobile robot eventually approaches the reference trajectory with asymptotic stability within 3 s to 0.32% error bound by the proposed adaptive controller. This fact demonstrates the effectiveness of the proposed adaptive control algorithm.

Experimental results for the straight-line tracking errors with initial error (0 m, 0 m, 0 rad).
Conclusions
The wheels’ slipping effects appear generally in practice and are really significant problems for the control of the WMR. In this article, the wheels’ slipping is taken into account and modeled as three time-varying parameters. The kinematic model containing the slipping parameters is proposed and AUKF is designed to estimate unknown slipping. The estimated results are introduced into a uniformly asymptotically stable tracking controller to implement the path tracking objective. Furthermore, based on pole placement strategy, the controller parameters are adjusted online in real time in accordance with the practial reference trajectory. The simulation and real experiment results are given to validate the performance of the proposed tracking control approach. More works should be done to research the physical mechanism of slipping and the dynamic tracking controller design will be investigated in future.
Footnotes
Acknowledgement
Authors Mingyue Cui, Hongzhao Liu, Wei Liu and Rongjie Huang are also affiliated with Oil Equipment Intelligent Control Engineering Laboratory of Henan province, Nanyang, Henan, 473061, China.
Declaration of conflicting interests
The author(s) declared no potential conflicts of interest with respect to the research, authorship, and/or publication of this article.
Funding
The author(s) disclosed receipt of the following financial support for the research, authorship, and/or publication of this article: This work was supported by the National Natural Science Foundation (no.U1404614), the Henan Province Education Department Foundation (no.14B120003 and no.17A413002), and the Henan Province Scientific and Technological Foundation (no. 142300410455).
