Skip to main content

Neural Network-Based Adaptive Motion Control for a Mobile Robot with Unknown Longitudinal Slipping

Abstract

When the mobile robot performs certain motion tasks in complex environment, wheel slipping inevitably occurs due to the wet or icy road and other reasons, thus directly influences the motion control accuracy. To address unknown wheel longitudinal slipping problem for mobile robot, a RBF neural network approach based on whole model approximation is presented. The real-time data acquisition of inertial measure unit (IMU), encoders and other sensors is employed to get the mobile robot’s position and orientation in the movement, which is applied to compensate the unknown bounds of the longitudinal slipping using the adaptive technique. Both the simulation and experimental results prove that the control scheme possesses good practical performance and realize the motion control with unknown longitudinal slipping.

1 Introduction

With the development of robotic applications, higher requirements have been presented for the motion control problem of mobile robots. Most researches shown the control schemes for mobile robots are based on the assumption that the wheels roll without slipping and skidding [1,2,3]. In previous work, many intelligent control technologies, such as kinematic∕torque control method using backstepping [4], a modified input–output linearization method [5], a data-based tracking control [6, 7], a sliding-mode based tracking algorithms [8,9,10], neural networks tracking control method [11, 12], extended state observer based nonlinear tracking and obstacle avoidance control method [13], disturbance observer-based robust trajectory tracking method [14], based on this assumption have been proposed for the robotics research. However, when the mobile robot performs certain motion tasks in complex environment, such as in wet or icy ground, high velocity starting and stopping and so on, these assumptions cannot be met due to slipping effect. All of these will cause the accumulative error of pose compared with conventional mobile robots [15] and certainly do deteriorate motion accuracy of mobile robot.

Consequently, approaches form control perspective have been receiving increased attention for the mobile robot in presence of slipping. Many researches have mentioned previously regarding the slipping phenomenon for the mobile robots. In Ref. [16], Dixon et al. [17] on the basis of their previous work addressed the skidding for mobile robots by designing robust tracking and regulation controllers at the kinematic level. Relying on kinematic-global positioning system and other sensors to collect the robot’s information, such as posture, velocities, Chang Boon Low et al. developed a GPS-based controller to realize the path following [18, 19]. In Ref. [20], considering the disturbing influence of skid-slip effects, the Vector Field Orientation (VFO) feedback approach is presented to perform the trajectory tracking tasks. For mobile robots in presence of slip conditions, Gonzalez et al. [21] proposed an adaptive control law together with an LMI-Based approach, which guarantee the stability and asymptotical convergence subject to both constraints and varying dynamics. Aimed at the trajectory tracking subject to unknown wheels’ slipping, Cui et al. [22] addressed the unknown skidding for mobile robots by designing adaptive unscented Kalman filter scheme.

Though kinematic modeling with wheel slipping phenomena gives a theoretical possibility of obtaining good performance of the control action, the kinematics model is only taken position and velocity into account, and without model uncertainties, unmodelled or unstructured disturbances, nonlinear friction and other factors. For that reason, it is necessary to study the motion control problem from the viewpoint of dynamics.

For the wheeled mobile robot under unknown skidding and slipping conditions, one previous study [23] presented an adaptive tracking control scheme with torque saturation.

Regarding skidding and slipping as disturbances, Kang et al. [24] proposed a robust tracking approach using a generalized extended state observer at kinematic and dynamic level. Later in their work, Kang et al. [25] proposes a robust tracking controller based on the fuzzy disturbance observer for a WMR with unknown skidding and slipping. Subject to Wheel Slip, Tian et al. [26] developed a time-invariant discontinuous feedback law is to asymptotically stabilize the robot system. In order to perform trajectory tracking under the longitudinal slip condition, Gao et al. [27] proposed an improved adaptive controller together with a neural network learning procedure. When existing the skidding, slipping and input disturbance, Chen [28] proposed a robust tracking control scheme based on the disturbance observer for wheeled mobile robots. In Ref. [29], a reinforcement learning-based adaptive neural tracking algorithm is proposed for the nonlinear discrete-time dynamic system of the WMR with skidding and slipping. From all the research above, we can find that most of the work focus on the control scheme design, which is only validated by simulation, lacking of experimental validation.

In the practical applications of our mobile robot, as longitudinal slipping is a more common phenomenon, this paper focus on the motion control research for mobile robots with unknown longitudinal slipping. Accordingly, based on the dynamic model, a neural network approach based on whole model approximation for the motion control of mobile robots under unknown longitudinal slipping occurrence is proposed. The unknown bounds of the longitudinal slipping are compensated by the adaptive technique. The proposed control system can achieve the accurate motion control of the mobile robot.

The rest of this paper is organized as follows. Kinematics and dynamics of a mobile robot with longitudinal slipping are derived mathematically in Section 2. Section 3 introduce the model of control system. In Section 4, simulations on motion control problems for a wheeled mobile robot subject to longitudinal slipping are carried out. Three groups of experiments are presented in Section 5, to validate the applicability of the proposed control scheme to real system, showing the robustness property of the proposed scheme. Section 6 concludes this paper.

2 Problem Formulation

Before discussing control strategy, a typical example of a differentially driven mobile robot used for the research of trajectory tracking is considered in this paper. The mobile robot platform under study is depicted in Figure 1, which composes of a vehicle with two driving wheels mounted on the same axis, whereas both a front and a rear free wheel only used for supporting the robot platform and without guide effect. The motion of mobile robot is achieved by two motors providing the necessary torques for the driving wheels, although both two motors are completely independent in the whole system, each motor has almost the same characteristics, such as position, velocity, acceleration, force response, friction model and other nonlinear phenomenon.

Figure 1
figure 1

Overview of the mobile robot system

The dynamic model of the mobile robot can be expressed in the Lagrange form [2]

$$\varvec{M}\left( q \right)\ddot{q} + \varvec{V}\left( {q,\dot{q}} \right)\dot{q} + \varvec{G}\left( q \right) +\varvec{\tau}_{d} = \varvec{B}\left( q \right)\varvec{\tau - A}^{\text{T}} \left( q \right)\lambda ,$$
(1)

where \(q = \left[ {\begin{array}{*{20}c} x & y & \theta \\ \end{array} } \right]^{\text{T}}\) is the location of the mobile robot in the inertial Cartesian frame, (x, y) and θ represent the position and orientation respectively. \(\varvec{M}\left( q \right) = \left[ {\begin{array}{*{20}c} m & 0 & 0 \\ 0 & m & 0 \\ 0 & 0 & {I_{c} } \\ \end{array} } \right]\) is a symmetric, positive definite inertia matrix, \(\varvec{V}\left( {q,\dot{q}} \right) = 0\) is the centripetal and coriolis matrix, \(\varvec{G}\left( q \right)\) is the gravity vector, \(\varvec{\tau}_{d}\) denotes bounded unknown disturbances including unstructured unmodelled dynamics, \(\varvec{B}\left( q \right) = \frac{1}{r}\left[ {\begin{array}{*{20}c} {\cos \theta } & {\cos \theta } \\ \begin{aligned} \sin \theta \\ - \frac{d}{2} \\ \end{aligned} & \begin{aligned} \sin\theta \\ \frac{d}{2} \\ \end{aligned} \\ \end{array} } \right]\) is the input transformation matrix, \(\varvec{\tau}= \left[ {\begin{array}{*{20}c} {\tau_{l} } \\ {\tau_{r} } \\ \end{array} } \right]\) is the control input torque supplied by two motors, \(\varvec{A}^{\text{T}} \left( q \right) = \left[ { - \begin{array}{*{20}c} {\sin \theta } & {\cos \theta } & 0 \\ \end{array} } \right]\) is the matrix associated with the constraints, and \(\lambda = - m\left( {\dot{x}_{c} \cos \theta + \dot{y}_{c} \sin\theta } \right)\dot{\theta }\) is the vector of constraint forces. In the above formula, m is the mass of mobile robot platform, Ic is its moment of inertia, r is the wheel radius, d is the distance between the two driving wheels, \(\tau_{i}\) is the wheel torque for the ith wheel. As the mobile robot being studied is working on a level surface with no slope, here the gravitational vector \(\varvec{G}\left( q \right)\) tends to zero.

The nominal kinematic model in the ideal case can be formulated as follows:

$$\dot{q} = \left[ {\begin{array}{*{20}c} {\dot{x}_{c} } \\ {\dot{y}_{c} } \\ {\dot{\theta }} \\ \end{array} } \right] = \left[ {\begin{array}{*{20}c} {\frac{\cos \theta }{2}} & {\frac{\cos \theta }{2}} \\ \begin{aligned} \frac{\sin\theta }{2} \\ - \frac{1}{d} \\ \end{aligned} & \begin{aligned} \frac{\sin\theta }{2} \\ \frac{1}{d} \\ \end{aligned} \\ \end{array} } \right]\left[ {\begin{array}{*{20}c} {v_{l} } \\ {v_{r} } \\ \end{array} } \right].$$
(2)

For conciseness, we denote

$$\dot{q} = \varvec{S}\left( \theta \right)\varvec{v} .$$
(3)

The subscript number l and r represent the left and right drive wheel respectively, \(\varvec{v} = \left[ {\begin{array}{*{20}c} {v_{l} } & {v_{r} } \\ \end{array} } \right]^{\text{T}}\) is the corresponding driving velocity.

When longitudinal slipping occurs during the movement, the slip ratios is defined as follows [21]:

$$\left\{ {\begin{array}{*{20}c} {s_{l} = \frac{{v_{l} - \bar{v}_{l} }}{{v_{l} }},} \\ {s_{r} = \frac{{v_{r} - \bar{v}_{r} }}{{v_{r} }},} \\ \end{array} } \right.$$
(4)

where \(s_{l}\) and \(s_{r}\) are the slip ratios of the left and right wheels, \(\bar{v}_{l}\) and \(\bar{v}_{r}\) are the corresponding current velocity caused by longitudinal slipping, respectively. There are two points worth noting in relation to the longitudinal slip. Firstly, if the longitudinal slippage do not happen, the current driving velocity is equal to the reference velocity with \(s_{l} = s_{r} = 0\). Secondly, in any case the slip ratios \(s_{r} \ne 1\) and \(s_{l} \ne 1\), assuming that \(s_{r} = s_{l} = 1\) that means wheel totally slipping and leads the mobile robot in uncontrolled state, therefore this situation is generally neglected.

The current velocity of the left and right drive wheel under the longitudinal slipping conditions is as follows:

$$\left[ {\begin{array}{*{20}c} {v_{l} } \\ {v_{r} } \\ \end{array} } \right] = \left[ {\begin{array}{*{20}c} {\frac{1}{{1 - s_{l} }}} & 0 \\ 0 & {\frac{1}{{1 - s_{r} }}} \\ \end{array} } \right]\left[ {\begin{array}{*{20}c} {\bar{v}_{l} } \\ {\bar{v}_{r} } \\ \end{array} } \right].$$
(5)

Substituting Eq. (5) into Eq. (3) yields, the kinematics model in presence of longitudinal slipping is shown as follows

$$\dot{q} = \bar{\varvec{S}}\left( {\theta ,s_{l} ,s_{r} } \right)\bar{\varvec{v}} ,$$
(6)

where

$$\bar{\varvec{S}}\left( {\theta ,s_{l} ,s_{r} } \right) = \left[ {\begin{array}{*{20}c} {\frac{\cos \theta }{{2\left( {1 - s_{l} } \right)}}} & {\frac{\cos \theta }{{2\left( {1 - s_{r} } \right)}}} \\ \begin{aligned} \frac{\sin\theta }{{2\left( {1 - s_{l} } \right)(1 - s_{l} )}} \\ - \frac{1}{{d\left( {1 - s_{l} } \right)}} \\ \end{aligned} & \begin{aligned} \frac{\sin\theta }{{2\left( {1 - s_{r} } \right)}} \\ \frac{1}{{d\left( {1 - s_{r} } \right)}} \\ \end{aligned} \\ \end{array} } \right],$$

\(\bar{\varvec{v}} = \left[ {\begin{array}{*{20}c} {\bar{v}_{l} } & {\bar{v}_{r} } \\ \end{array} } \right]^{\text{T}}\) are the current velocity of the two wheels, which can be real-time measured by encoders.

Substituting Eq. (6) into Eq. (1) yields, we can obtain the dynamic form of the mobile robot subject to longitudinal slipping as

$$\bar{\varvec{M}}\left( {\bar{v}} \right)\dot{\bar{v}} + \bar{\varvec{V}}\left( {\bar{v}} \right)\bar{v} + \bar{\varvec{\tau }}_{d} = \bar{\varvec{B}}\left( {\bar{v}} \right)\bar{\varvec{\tau }} ,$$
(7)

where

$$\bar{\varvec{M}}\left( v \right) = \bar{S}^{\text{T}} M\bar{S},\;\bar{\varvec{V}}\left( v \right) = \bar{S}^{\text{T}} \left( {M\dot{\bar{S}} + V\bar{S}} \right) = 0,\;\bar{\varvec{\tau }}_{d} = \bar{S}^{\text{T}}\varvec{\tau}_{d} ,$$

\(\bar{\varvec{B}}\left( {\bar{v}} \right) = \bar{S}^{\text{T}} B\). We observe that when longitudinal slipping impact are considered in the dynamic model, it becomes more complicated.

3 Mathematical Model of Control System for Mobile Robot

The ultimate goal of motion control considering the longitudinal slipping is to control the torque so that the robot can follow preconcerted trajectory. In the inertial coordinate system, given a reference trajectory \(\varvec{q}_{r} \left( t \right) = \left( {\begin{array}{*{20}c} {x_{r} } & {y_{r} } & {\theta_{r} } \\ \end{array} } \right)^{\text{T}}\) and a current trajectory \(\varvec{q}\left( t \right) = \left( {\begin{array}{*{20}c} x & y & \theta \\ \end{array} } \right)^{\text{T}}\), the tracking error is expressed as

$$\varvec{e}\left( t \right) = \left[ {\begin{array}{*{20}c} {\cos \theta } & {\sin\theta } & 0 \\ { - \sin\theta } & {\cos \theta } & 0 \\ 0 & 0 & 1 \\ \end{array} } \right]\left[ {\begin{array}{*{20}c} {x_{r} - x} \\ {y_{r} - y} \\ {\theta_{r} - \theta } \\ \end{array} } \right].$$
(8)

The derivative of \(\varvec{e}\left( t \right)\) with respect to t

$$\dot{\varvec{e}}\left( t \right) = \left[ {\begin{array}{*{20}c} {v_{r} \cos \theta_{r} - v + x_{e} \dot{\theta }} \\ {v_{r} \sin\theta_{r} + x_{e} \dot{\theta }} \\ {w_{r} - \dot{\theta }} \\ \end{array} } \right].$$
(9)

The auxiliary velocity is defined as [30]

$${\varvec{\upxi}}_{c} = \left[ {\begin{array}{*{20}c} {v_{c} } \\ {w_{c} } \\ \end{array} } \right] = \left[ {\begin{array}{*{20}c} {v_{r} \cos \theta_{e} + k_{1} x_{e} } \\ {w_{r} + k_{2} v_{r} y_{e} + k_{3} v_{r} \sin \theta_{e} } \\ \end{array} } \right],$$
(10)

where k1, k2, k3 are design parameters.

The derivation of \({\varvec{\upxi}}_{c}\) can be written as

$$\begin{aligned} {\dot{\mathbf{\xi }}}_{c} = \left[ {\begin{array}{*{20}c} {\dot{v}_{c} } \\ {\dot{w}_{c} } \\ \end{array} } \right] & = \left[ {\begin{array}{*{20}c} {\dot{v}_{r} \cos \theta_{e} } \\ {\dot{w}_{r} + k_{2} \dot{v}_{r} y_{e} } \\ \end{array} } \right] \\ & \quad + \left[ {\begin{array}{*{20}c} {\begin{array}{*{20}c} {k_{1} } \\ 0 \\ \end{array} } & {\begin{array}{*{20}c} 0 \\ {k_{2} v_{r} } \\ \end{array} } & {\begin{array}{*{20}c} { - v_{r} \sin \theta_{e} } \\ {k_{3} v_{r} \cos \theta_{e} } \\ \end{array} } \\ \end{array} } \right]\dot{\varvec{e}} . \\ \end{aligned}$$
(11)

And assuming that the linear and angular reference velocities are constant, we obtain [4]

$${\dot{\mathbf{\xi }}}_{c} = \left[ {\begin{array}{*{20}c} {\dot{v}_{c} } \\ {\dot{w}_{c} } \\ \end{array} } \right] = \left[ {\begin{array}{*{20}c} {\begin{array}{*{20}c} {k_{1} } \\ 0 \\ \end{array} } & {\begin{array}{*{20}c} 0 \\ {k_{2} v_{r} } \\ \end{array} } & {\begin{array}{*{20}c} { - v_{r} \sin \theta_{e} } \\ {k_{3} v_{r} \cos \theta_{e} } \\ \end{array} } \\ \end{array} } \right]\dot{\varvec{e}} .$$
(12)

To design the control input and follow the desired velocity, we introduce the auxiliary velocity tracking error

$$\varvec{e}\left( t \right) = {\varvec{\upxi}} - {\varvec{\upxi}}_{c} .$$
(13)

In this part, we adopt tracking error \(\bar{e}\) as the design criteria for neural adaptive controller. The filtered tracking error [31] is

$$r = \dot{\bar{e}} + \varLambda \bar{e},$$
(14)

where \(\varLambda = \varLambda^{\text{T}} > 0.\) Differentiating the above formula, the dynamics can be expressed in the filtered tracking error

$$\bar{\varvec{M}}\left( v \right)\dot{r} = - \bar{\varvec{V}}\left( v \right)r + g\left( x \right) + \bar{\varvec{\tau }}_{d} - \bar{\varvec{B}}\left( {\bar{v}} \right)\bar{\tau },$$
(15)

where the nonlinear function is

$$g\left( x \right) = \bar{\varvec{M}}\left( v \right)\left( {\dot{v}_{c} + \varLambda \dot{e}} \right)\varvec{ + \bar{V}}\left( v \right)\left( {v_{c} + \varLambda e} \right)v_{c} + \bar{\varvec{G}}\left( v \right)$$

and, for instance

$$x = \left[ {\begin{array}{*{20}c} {\bar{e}^{\text{T}} } & {\dot{\bar{e}}^{\text{T}} } & {v_{r}^{\text{T}} } & {\begin{array}{*{20}c} {\dot{v}_{r}^{\text{T}} } & {\ddot{v}_{r}^{\text{T}} } \\ \end{array} } \\ \end{array} } \right].$$
(16)

In this part a computed torque method is developed for trajectory tracking. Define a control input torque as

$$\varvec{\bar{\tau } = }\hat{g} + K_{v} r,$$
(17)

where \(\hat{g}\) is the estimate of \(g\left( x \right)\) and \(K_{v} = K_{v}^{\text{T}} > 0\) is the gain matrix. Substituting Eq. (17) into Eq. (15) yields, we can get

$$\begin{aligned} \bar{\varvec{M}}\left( v \right)\dot{r} & = - \bar{\varvec{V}}\left( v \right)r + g\left( x \right) + \bar{\varvec{\tau }}_{d} - \bar{\varvec{B}}\left( {\bar{v}} \right)\left( {\hat{g} + K_{v} r} \right) \\ & = - \left( {\bar{\varvec{V}}\left( v \right) + K_{v} \bar{\varvec{B}}\left( {\bar{v}} \right)} \right)r + \zeta_{o} , \\ \end{aligned}$$
(18)

where the functional estimation error is expressed as \(\tilde{g} = g - \bar{\varvec{B}}\left( {\bar{v}} \right)\hat{g}\), \(\zeta_{o} = \tilde{g} + \bar{\varvec{\tau }}_{d}\).

Due to RBF neural network has a good performance in learning and approximating nonlinear functions, hence in this paper to eliminate these uncertainties, the RBF is applied into the mobile robot system for approximating function \(g\left( x \right)\):

$$\hat{g}\left( x \right) = \hat{W}^{\text{T}} \varphi \left( x \right),$$

where \(\hat{W}\) is the current values of the neural network weights provided by the tuning algorithm, \(W\) is ideal weights.

Define the weight estimation errors as

$$\tilde{W} = W - \hat{W},$$

here the ideal weights is to be known bounded under the assumptions, so that

$$\left\| W \right\|_{F} \le W_{\text{max} } .$$

With \(\bar{\varvec{\tau }}\) defined in Eq. (17), the control input is

$$\varvec{\bar{\tau } }\,{ = }\,\hat{g}\left( x \right) + K_{v} r - \nu = \hat{W}^{\text{T}} \varphi \left( x \right) + K_{v} r - \nu ,$$
(19)

where ν is a function to be determined to provide robustness in the face of the net reconstruction error ε. Then substituting Eq. (14) into Eq. (13) yields,

$$\begin{aligned} \bar{\varvec{M}}\left( v \right)\dot{r} & = - \left( {K_{v} + \bar{\varvec{V}}\left( v \right)} \right)r + \hat{W}^\text{T} \varphi \left( x \right) + \left( {\varepsilon + \bar{\varvec{\tau }}_{d} } \right) + \nu \\& = - \left( {K_{v} + \bar{\varvec{V}}\left( v \right)} \right)r + \zeta_{1} , \\ \end{aligned}$$
(20)

where \(\zeta_{1} = \hat{W}^\text{T} \varphi \left( x \right) + \left( {\varepsilon + \bar{\varvec{\tau }}_{d} } \right) + \nu .\)

The auxiliary signal

$$\nu = - \left( {\varepsilon_{N} + b_{d} } \right)\text{sgn} \left( r \right),$$

and the weight tuning is given as

$$\dot{\hat{W}} = F\varphi r^{\text{T}} ,$$

where the constant matrix \(F = F^{\text{T}} > 0.\)

Define the Lyapunov function candidate

$$L = \frac{1}{2}r^{\text{T}} \bar{\varvec{M}}\left( v \right)r + \frac{1}{2}tr\left( {\tilde{W}^{\text{T}} F^{ - 1} \tilde{W}} \right).$$
(21)

Differentiating yields

$$\dot{L} = r^{\text{T}} \bar{\varvec{M}}\left( v \right)\dot{r} + \frac{1}{2}r^{\text{T}} \varvec{\dot{\bar{M}}}\left( v \right)r \quad + tr\left( {\tilde{W}^{\text{T}} F^{ - 1} \dot{\tilde{W}}} \right).$$
(22)

Substituting Eq. (20) into Eq. (22) yields,

$$\begin{aligned} \dot{L} & = - r^{\text{T}} K_{v} r + \frac{1}{2}r^{\text{T}} \left( {\varvec{\dot{\bar{M}}}\left( v \right) - 2\bar{\varvec{V}}\left( v \right)} \right)r \\ & \quad + tr\tilde{W}^{\text{T}} \left( {F^{ - 1} \dot{\tilde{W}} + \varphi r^{\text{T}} } \right) + r^{\text{T}} \left( {\varepsilon + \bar{\varvec{\tau }}_{d} + \nu } \right). \\ \end{aligned}$$

Due to the skew symmetry property, we can get the second term zero and the third term is zero when choosing \(\dot{\tilde{W}} = - F\varphi r^{\text{T}}\),

$$\dot{L} = - r^{\text{T}} K_{v} r + r^{\text{T}} \left( {\varepsilon + \bar{\varvec{\tau }}_{d} + \nu } \right),$$

where

\(\begin{aligned} r^{\text{T}} \left( {\varepsilon + \bar{\varvec{\tau }}_{d} + \nu } \right) = r^{\text{T}} \left( {\varepsilon + \bar{\varvec{\tau }}_{d} } \right) + r^{\text{T}} \nu \\ = r^{\text{T}} \left( {\varepsilon + \bar{\varvec{\tau }}_{d} } \right) - \left\| r \right\|\left( {\varepsilon_{N} + b_{d} } \right) \le 0. \\ \end{aligned}\)

Finally, we get

\(\dot{L} \le 0.\)

The control system diagram is shown in Figure 2.

Figure 2
figure 2

Control system diagram

4 Simulation Results

In this section, we perform representative simulations for the mobile robot platform subject to unknown longitudinal slipping to demonstrate the validity of the proposed scheme. The proposed method was implemented in MATLAB/Simulink software. In addition, by utilizing the dynamic analysis software, we have the parameters of our mobile robot shown in Table 1.

Table 1 Parameters used in the simulation

In the simulations, in order to eliminate the difference influence of the velocities of the two driving wheels, a liner reference trajectory is considered. Given the reference trajectory velocities \(v=[0.1sint, 0.1sint]^T\) where t∈[0‒50] s is the simulation time. Assume that the left and right wheels’ longitudinal slipping described by \(s_{l} = 0.2\sin \left( {\bar{v}_{l} } \right)\) and \(s_{r} = 0.2\sin \left( {\bar{v}_{r} } \right)\). The control gains are selected as:

$$K_{v} = \left[ {\begin{array}{*{20}c} {50} & 0 \\ 0 & {50} \\ \end{array} } \right],$$
$$\bar{\varvec{F}}\left( {\bar{v}} \right) = 0.02\text{sgn} \left( {\bar{v}} \right),$$
$$\bar{\varvec{\tau }}_{d} = \left[ {\begin{array}{*{20}c} {0.2\sin \left( t \right)} & {0.2\sin \left( t \right)} \\ \end{array} } \right]^{\text{T}} .$$

Under the wheel longitudinal slipping conditions, Figure 3 shows the performance of control scheme for the mobile robot. The velocity tracking results of each driving wheel in our method is shown in Figure 3(a), which traced the reference signal rapidly and stably. Under the longitudinal slipping conditions, the corresponding torque on each driving wheel is shown in Figure 3(b), showing that the proposed method can perform well to adapt to the disturbance phenomena of the longitudinal slipping. The reason for this is that the model-based adaptive law is employed to compensate the disturbances in the mobile robot systems. Furthermore, since RBF network have good approximate capability for the nonlinear function with enough precision, in this paper the neural network is employed to approximate the non-linear component of the whole system, as shown in Figure 3(c). Figure 3(d) gives the corresponding position and orientation tracking errors in inertia coordinate, which indicates that this control algorithm can realize the good precision of position control and orientation control in the motion with longitudinal slipping.

Figure 3
figure 3

Simulation results

5 Experimental Verification

Besides the simulation, a verification platform has been set up to verify the above presented scheme and study fundamental problems in motion control process of mobile robot with longitudinal slipping, as displayed in Figure 4. The experiment platform consists of two sets of direct motor system with absolute rotary encoder, ultrasonic sensor, IMU, obstacle detection sensor, stargazer infrared position sensor, security touch sensor. IMU equipped in the mobile robot platform is used to collect the robot’s current orientation information and the absolute rotary encoder to collect the current velocity. The parameters used in the experiment system are the same with the one in simulation shown in Table 1. Under RT-Linux operation system, C language has been adopted to write all computations, as shown in Figure 5.

Figure 4
figure 4

Experiment platform

Figure 5
figure 5

Implementation architecture

In the experimental verifications, we conducted the experiment using the linear trajectory with linear velocity v = 1 m/s to avoid the impacts of the different velocity of drive wheels of other trajectory, such as circular trajectory. Considering the practical working environment, three different groups of plane ground conditions were conducted on the experimental system: Group A—normal marble floor brick surface, Group B—damp marble floor brick surface, and Group C—icy marble floor brick surface were considered.

In the following experiments, we introduce the error of position tracking error \(e = \sqrt {\left( {e_{x} } \right)^{2} + \left( {e_{y} } \right)^{2} }\) and error of orientation tracking error \(e_{\theta }\) respectively to evaluate the effects.

Under the longitudinal slipping conditions, for the surfaces A, B and C the experiment results are showed in Figure 6. For experiments of three groups, the linear trajectory tracking results between the Group B and the Group C presented a similar tendency under the same experimental conditions apart from the floor surface. A slightly worse result of the group C was illustrated in Figure 6(c), where the more highly slippery surface compared with the group B made that slipping phenomena more obvious, both the position error and orientation error of the group C presented a greater experimental error than that of group B in Figure 6(b) when the mobile robot suddenly changes the direction.

Figure 6
figure 6

Experiment result

It is worth noting that a longer time for experiment group C is required for the mobile robot from the starting point to destination. The reason for this phenomenon is the fact that the longitudinal slipping as an external disturbance reduces the linear velocity, as a result the controllers must adjust the input to compensate this deviation caused by the longitudinal slipping. Furthermore, we may also see from Figure 6 that the longitudinal slipping phenomena mainly occurs at the acceleration stage of the mobile robot. From the experiment results, we obtain that under different surface environment the method has certain practicality to the unknown longitudinal slipping and robustness, realizing adaptive tracking ability.

6 Conclusions

An adaptive motion control problem was formulated for the mobile robot under the longitudinal slipping condition in this paper. To address the unknown longitudinal slipping, by utilizing the real-time multi-sensor data to get the position and orientation of the robot, an adaptive neural network approach based on whole model approximation has been developed, to compensate the trajectory error caused by longitudinal slipping. Both the simulation and experimental results have been proved to be robust and adaptive to the environment with unknown longitudinal slipping in the practical application.

References

  1. Z P Jiangdagger, H Nijmeijer. Tracking control of mobile robots: A case study in backstepping. Automatica, 1997, 33(7): 1393–1399.

    Article  MathSciNet  MATH  Google Scholar 

  2. J M Yang, J H Kim. Sliding mode control of trajectory tracking for nonholonomic wheeled mobile robots. IEEE Transactions on Robotics and Automation, 1999, 15(3): 578–587.

    Article  Google Scholar 

  3. H Yang, X Fan, P Shi, et al. Nonlinear control for tracking and obstacle avoidance of a wheeled mobile robot with nonholonomic constraint. IEEE Transactions on Control Systems Technology, 2016, 24(2): 741–746.

    Google Scholar 

  4. R Fierro, F L Lewis. Control of a nonholonomic mobile robot: Backstepping kinematics into dynamics. Proceedings of the 34th Conference on Decision & Control, New Orleans, 1995: 3805–3810.

  5. D H Kim, J H Oh. Tracking control of a two-wheeled mobile robot using input–output linearization. Control Engineering Practice Control, 1999, 7(3): 369–373.

    Article  Google Scholar 

  6. J Chen, W E Dixon, M Dawson, et al. Homography-based visual servo tracking control of a wheeled mobile robot. IEEE Transactions on Robotics, 2006, 22: 406–415.

    Article  Google Scholar 

  7. H Mirzaeinejad, A M Shafei. Modeling and trajectory tracking control of a two-wheeled mobile robot: Gibbs-Appell and prediction-based approaches. Robotica, 2018, 36(10): 1551–1570.

    Article  Google Scholar 

  8. J M Yang, J H Kim. Sliding mode control for trajectory tracking of nonholonomic wheeled mobile robots. IEEE Transactions on Robotics & Automation, 1999, 15(3): 578–587.

    Article  Google Scholar 

  9. M Asif, M J Khan, N Cai. Adaptive sliding mode dynamic controller with integrator in the loop for nonholonomic wheeled mobile robot trajectory tracking. International Journal of Control, 2014, 87(5): 964–975.

    Article  MathSciNet  MATH  Google Scholar 

  10. S Peng, W Shi. Adaptive fuzzy integral terminal sliding mode control of a nonholonomic wheeled mobile robot. Mathematical Problems in Engineering, 2017: 3671846:1–12.

    MathSciNet  Google Scholar 

  11. M Boukens, A Boukabou, M Chadli. Robust adaptive neural network-based trajectory tracking control approach for nonholonomic electrically driven mobile robots. Robotics & Autonomous Systems, 2017, 92: 30–40.

    Article  Google Scholar 

  12. L Ding, S Li, Y J Liu, et al. Adaptive neural network-based tracking control for full-state constrained wheeled mobile robotic system. IEEE Transactions on Systems Man & Cybernetics Systems, 2017, 47(8): 2410–2419.

    Article  Google Scholar 

  13. H Yang, X Fan, P Shi, C C Hua. Nonlinear control for tracking and obstacle avoidance of a wheeled mobile robot with nonholonomic constraint. IEEE Transactions on Control Systems Technology, 2016, 24(2): 741–746.

    Google Scholar 

  14. D Huang, J Zhai, W Ai, et al. Disturbance observer-based robust control for trajectory tracking of wheeled mobile robots. Neurocomputing, 2016, 198(C): 74–79.

    Article  Google Scholar 

  15. L Ding, H B Gao, Z Q Deng, et al. Experimental study and analysis on driving wheels’ performance for planetary exploration rovers moving in deformable soil. Journal of Terramechanics, 2011, 48: 27–45.

    Article  Google Scholar 

  16. W E Dixon, D M Dawson, E Zergeroglu. Robust control of a mobile robot system with kinematic disturbances. IEEE International Conference on Control Applications, 2000: 437–442.

  17. W Dixon, D M Dawson, E Zergeroglu. Nonlinear control of wheeled mobile robot. Lecture Notes in Control and Information Sciences. New York: Springer-Verlag, 2001.

  18. B L Chang, D Wang. GPS-based tracking control for a car-like wheeled mobile robot with skidding and slipping. IEEE/ASME Transactions on Mechatronics, 2008, 13(4): 480–484.

    Article  Google Scholar 

  19. C B Low, D Wang. GPS-based path following control for a car-like wheeled mobile robot with skidding and slipping. IEEE Transactions on Control Systems Technology, 2008, 16(2): 340–347.

    Article  Google Scholar 

  20. M Michalek, P Dutkiewicz, M Kielczewski, et al. Trajectory tracking for a mobile robot with skid-slip compensation in the vector-field-orientation control system. International Journal of Applied Mathematics & Computer Science, 2009, 19(4): 547–559.

    Article  MathSciNet  MATH  Google Scholar 

  21. R Gonzalez, M Fiacchini, T Alamo, et al. Adaptive control for a mobile robot under slip conditions using an LMI-based approach. European Journal of Control, 2010, 16(2): 144–155.

    Article  MathSciNet  MATH  Google Scholar 

  22. M Cui, D Sun, W Liu, et al. Adaptive tracking and obstacle avoidance control for mobile robots with unknown sliding. International Journal of Advanced Robotic Systems, 2012, 9: 1.

    Article  Google Scholar 

  23. S J Yoo. Adaptive tracking control for a class of wheeled mobile robots with unknown skidding and slipping. IET Control Theory & Applications, 2010, 4(10): 2109–2119.

    Article  MathSciNet  Google Scholar 

  24. H S Kang, Y T Kim, C H Hyun, et al. Generalized extended state observer approach to robust tracking control for wheeled mobile robot with skidding and slipping. International Journal of Advanced Robotic Systems, 2013, 10: 463–474.

    Google Scholar 

  25. H S Kang, C H Hyun, S Kim. Robust tracking control using fuzzy disturbance observer for wheeled mobile robots with skidding and slipping. International Journal of Advanced Robotic System, 2014, 11(1): 1–11.

    Article  Google Scholar 

  26. Y Tian, N Sarkar. Control of a mobile robot subject to wheel slip. Journal of Intelligent & Robotic Systems, 2014, 74: 915–929.

    Article  Google Scholar 

  27. H Gao, X Song, D Liang, et al. Adaptive motion control of wheeled mobile robot with unknown slippage. International Journal of Control, 2014, 87(8): 1513–1522.

    Article  MathSciNet  MATH  Google Scholar 

  28. M Chen. Disturbance attenuation tracking control for wheeled mobile robots with skidding and slipping. IEEE Transactions on Industrial Electronics, 2017, 64(4): 3359–3368.

    Article  Google Scholar 

  29. Li S, Ding L, Gao H, et al. Adaptive neural network tracking control-based reinforcement learning for wheeled mobile robots with skidding and slipping. Neurocomputing, 2018: 1–11.

  30. Y Kanayama, Y Kimura, F Miyazaki, et al. A stable tracking control method for an autonomous mobile robot. International Conference on Robot Automation, 1990: 384–389.

  31. F L Lewis, K Liu, A Yesildirek. Neural net robot controller with guaranteed tracking performance. IEEE Transactions on Neural Networks, 1995, 6(3): 703–715.

    Article  Google Scholar 

Download references

Funding

Supported by Scientific and Innovation Research Funds for the Beijing University of Posts and Telecommunications (Grant No. 2017RC22).

Author information

Authors and Affiliations

Authors

Contributions

GW was in charge of the whole trial and wrote the manuscript; XL advised on how to write the manuscript during the whole preparation. YZ and SH assisted with sampling and laboratory analyses. All authors read and approved the final manuscript.

Authors’ Information

Gang Wang, born in 1981, is currently a Lecturer with Beijing University of Posts and Telecommunications, China. He received his Bachelor’s degree and Master’s degree from Shandong University of Science and Technology, China, in 2006 and 2009 respectively, and his Ph.D. degree from Beihang University, China, in 2016. His research interests include robot calibration and mobile robot navigation.

Xiaoping Liu, born in 1965, is currently a Professor with Beijing University of Posts and Telecommunications, China. He received his Bachelor’s degree, Master’s degree and Ph.D. degree from Tianjin University, China, in 1988, 1991, 1994, respectively. From 1998 to 1999, he was with University of Washington, USA. His research interests include robotics, fault diagnosis and detection.

Yunlong Zhao, born in 1990, is currently a PhD candidate with Automation School, Beijing University of Posts and Telecommunications, China. He received his Master’s degree from China University of Mining and Technology, Beijing, China, in 2016.

Song Han, born in 1991, is currently a PhD candidate with Automation School, Beijing University of Posts and Telecommunications, China. He received his Bachelor’s degree from University of Science and Technology of China, China, in 2014. His research interests include robot calibration and mobile robot navigation.

Corresponding author

Correspondence to Gang Wang.

Ethics declarations

Competing Interests

The authors declare that they have no competing interests.

Rights and permissions

Open Access This article is distributed under the terms of the Creative Commons Attribution 4.0 International License (http://creativecommons.org/licenses/by/4.0/), which permits unrestricted use, distribution, and reproduction in any medium, provided you give appropriate credit to the original author(s) and the source, provide a link to the Creative Commons license, and indicate if changes were made.

Reprints and permissions

About this article

Check for updates. Verify currency and authenticity via CrossMark

Cite this article

Wang, G., Liu, X., Zhao, Y. et al. Neural Network-Based Adaptive Motion Control for a Mobile Robot with Unknown Longitudinal Slipping. Chin. J. Mech. Eng. 32, 61 (2019). https://doi.org/10.1186/s10033-019-0373-3

Download citation

  • Received:

  • Revised:

  • Accepted:

  • Published:

  • DOI: https://doi.org/10.1186/s10033-019-0373-3

Keywords