1 Introduction

Mobile robots are becoming increasingly popular across different industrial areas. Recently, a mobile robot has been stated as a machine manipulated by artificial intelligence that uses sensors and other technology to identify its surroundings and move around its environment. Mobile robots have physical robotic elements, such as wheels, tracks, legs, etc. Among the different locomotion devices of mobile robots, wheeled mobile robots (WMRs) have drawn more attention because of structural simplicity than other devices [1]. The demand for outdoor WMRs is rapidly growing to assist humans. For example, autonomous wheeled mobile robots or vehicles are being planned for many applications such as transportation, exploration, rescue, security, military, etc.

Even so, a robot equipped with various sensors is likely to operate differently due to inexplicable factors in outdoor environments. For example, the wheel encoder might lose counting steps upon wheel slippage; the radar may work unsatisfactorily under dense fog or heavy rainy days. An ultrasonic sensor may not detect bounced signals due to bad weather. A camera only works properly in a well-lit environment. A global positioning system (GPS) can quickly lose signals among high-rise buildings or dense forests. Such harsh outdoor environments have demanded an advanced intelligent system to control mobile robots. Conventional WMRs have been developed in indoor environments such as warehouses, factories, etc. However, to control WMRs in outdoor environments, we need somewhat different motion models than indoor environments because of various uncertainty. Thus, the realization of the motion of WMRs is solely vital, and we need to understand how a robot moves in various outdoor environments. Even so, tracking the motion of WMRs in an outdoor environment is not a trivial problem. A typical robot tracking would be computed from a distance traveled given a velocity or acceleration. However, no mobile robot runs on a perfect road. There are different kinds of obstacles that raise and lower the speed, even with slippage. Unlike well-established indoor environments, we have not fully understood how WMRs respond to various outdoor environments.

The conventional analysis mainly concerns several categories of physics laws or differential equations on the movement of robots. The categories of the analysis are composed of kinematics (rolling, yawing, pitching), dynamics (steering, skidding, braking), terrains (uphill, tilted roads), and wheel-ground interactions (ice, rocky, sand). Therefore, most researchers have focused on building detailed physics models concerning each category. This requires a vast amount of research to come up with each of the models. Even for simple robots, the dynamic models are usually very complex, and they would not consider friction between wheels and various ground, wheel slippage, etc. The wheel-ground interaction depends on many parameters, which require prior knowledge of the ground parameters (friction coefficient, wheel slippage, sand friction, etc.). Furthermore, lateral slippage usually may not be observed; thus, a more detailed study is required [2]. Therefore, modeling a WMR moving outdoors is far more complex than in indoor environments because of the interaction between the wheels and the ground.

In this study, we built a four-wheeled mobile robot with encoders installed on each wheel. Tracking a four-wheeled robot is quite involved because each wheel rotates independently and is subjected to different road, traction, and load conditions. Ideally, we need four models for each wheel, which is impractical. Instead of separately establishing physics laws for road conditions, we employed the data-driven approach. In so doing, we may analyze dynamic systems without full knowledge of physics models. All models are inherently not accurate because they come with uncertainty. Thus, models can only partially explain the robot’s underlying phenomena and its environment. Therefore, the probabilistic approach can play an essential role in recognizing uncertainty. Probabilistic algorithms present results in the form of probability distributions. The Bayesian paradigm has been known to fit well with such problems. The filtering technique has played a vital role successfully in many disciplines for temporal data. We employed two variants of Bayes’ filter, the Kalman filter and the unscented Kalman filter, to estimate the robot velocity given wheel speed measurement in an outdoor environment.

In summary,

  1. 1.

    We derived forward and inverse differential kinematic solutions for four-wheeled mobile robots with the fixed-standard wheel system.

  2. 2.

    We carried out more than a thousand test runs in outdoor environments, having the robot run on normal, icy, and sandy roads under a constraint, partially blocked by brick and stuck with grid-type holes. As a result, we obtained wheel speed measurements on different road conditions.

  3. 3.

    We applied the Kalman filter and the unscented Kalman filter, which stemmed from Bayes’ filtering technique, to infer how each wheel’s speed affects the robot’s velocity in different road conditions.

  4. 4.

    We could closely track tri-variate states depicting the robot’s motion: two linear velocities and rotation. We demonstrated how to relate the differential kinematic solutions to a probabilistic model with uncertainty in outdoor environments.

  5. 5.

    We adopted five outdoor environments for estimating the robot’s motion for demonstration purposes; however, we think the present method can be applied to any unknown outdoor environment without significant modifications.

This paper is organized as follows: A brief review of the current research is mentioned in Related work; the wheel equation for a four-wheeled mobile robot with the fixed-standard wheel system is derived in Kinematics, a more general version of the wheel equation is also developed. Bayesian formalism applicable to this study is explained in detail in Bayes’ filter along with the Kalman filter and the unscented Kalman filter. An experimental setup for the robot is described in the Four-wheeled mobile robot. Upon more than a thousand test runs, the estimated robot velocity is listed in Results and Discussion. The brief summary is expressed with further study in Conclusion.

2 Related Work

In general, studies on wheeled mobile robots (WMRs) have been well established [3, 4]. With mainly kinematics [5] and dynamics [6] combined, the models can be utilized for control [7] and design of WMRs equipped with a general or standard type of wheels. Obviously, unlike kinematics models, the dynamics model would be pretty complex to define the motion of WMRs in general because of not a few physics laws and empirical rules to be parameterized [8]. Those parameters should be valued through experimental data, which demands vast experimentation. Furthermore, dynamics models are likely to be more sensitive to external factors; for example, even a slight offset of the center of mass of a robot by an unexpected external force might fail to meet the robot’s design criterion.

The most popular WMRs may be robots with two-differential drive systems [9]. The differential drive is a two-wheeled system with independent motors for each wheel. Thus, two-wheeled mobile robots can make many different movements, even spinning themselves on site simply by differing wheel speeds. Conventional indoor mobile robots typically operate on plain ground where wheel slip is negligible. On the contrary, mobile robots more often experience low traction in outdoor environments: unknown environments [10], skidding and slipping [11], wheel slippage [12], and yawing [13, 14]. It is quite challenging to catch the effects of outdoor environments on the robot’s motion [15, 16] that mapping of the outdoor environment becomes quite important [17]. For example, it may not be possible to exposit the exact movement when robots operate on ice or a slippery surface. There is no sure way for physics laws or equations to explain such an ambiguous situation. In addition, the control of WMRs in unpredictable environments calls for advanced techniques such as Fuzzy control [18, 19]. Therefore, Outdoor robots bring about additional challenges not considered in indoor environments. Therefore, WMRs require dynamic and kinematic models, not to mention terrain. For example, acknowledging the unexpected environment in the autonomous drive is more critical because a robot should run without any human operators’ intervention [20]. Even we might need some degree of terrain classification using machine learning techniques [21].

In this study, we set up a four-wheeled mobile robot with a differential drive system. A study on four-wheeled mobile robots with different wheel systems for trajectory tracking [22], calibration of systematic errors [23], and design and control [24] was published. We derived forward and inverse differential kinematic solutions for four-wheeled mobile robots with the fixed-standard wheel system. We need more information on mobile robots’ movement in outdoor environments. In order to solve robot motion problems relating to outdoor environments, where the conventional approaches have much difficulty, we chose a probabilistic paradigm and experiment data. As for the experiment, we carried out about a thousand test runs in outdoor environments, having the robot run on normal, icy, and sandy roads. In addition, we performed tests on the robot under a constraint partially blocked by brick and being stuck with grid-type holes. As a result, we obtained wheel speed measurements on different road conditions. In general, the motion of a robot can be best described in a set of equations or differential equations. Nevertheless, when we are concerned with a temporal process such as robot motion, employing the state-space process may be more convenient, where the process can be calculated recursively over time. Analytically, perfectly modeling a system is impossible except for the most trivial problems.

The probabilistic approach of the Bayesian framework with state-space models best fits the filtering technique, which can formulate an entire prediction-update-estimation process recursively [25, 26]. The Bayes filter framework comprises an initial distribution (prior), a motion model distribution, and a measurement model distribution (likelihood). The reduced posterior is equivalent to the updated state variables in the corresponding state-space model. In particular, probabilistic approaches are typically more robust in the face of sensor flaws, noise, environment dynamics, etc. There are a few variants of Bayes’ filtering techniques we can apply to infer how each wheel’s speed affects the robot velocity on different road conditions: the Kalman filter [27], the unscented Kalman filter [28], and the extended Kalman filter [29], and so on. In this study, we employed the Kalman filter and the unscented Kalman filter for comparison. We demonstrated how to relate the differential kinematic solutions to a probabilistic model with uncertainty for better design considering outdoor environments. Hence, with the help of Bayes’ filtering technique, we could estimate the motion of a four-wheeled mobile robot at each time step given measured wheel speeds.

3 Kinematics

This section will pursue a solution to wheel equations for a four-wheeled mobile robot in planar environments, subject to two kinematic constraints and three state variables (two linear velocities and rotation) that characterize the robot’s pose in motion.

3.1 Wheel Equations

Fig. 1
figure 1

Four coordinate frames for the fixed standard four-wheeled robot pose. I for the inertial frame, R for the robot body frame, S for the steering frame, and W for the wheel frame. \({}^{I}\textbf{P}_{R}\) is the position vector from I to R, and \({}^{R}\textbf{P}_{S}\) is for from R to S, respectively. The robot body frame makes an angle of \(\theta\) concerning the inertial frame

Fig. 2
figure 2

A fixed standard wheel and the coordinate systems. R for the robot body frame, S for the steering frame, and W for the wheel frame. \(\alpha\) is the steering angle, and \(\beta\) denotes the wheel angle

A schematic of a mobile robot with fixed standard wheels of four is shown in Fig. 1, in which we employ four frames, the inertial, robot body, steering, and wheel frames, to define the position and the velocity of the robot [30]. The position of a wheel in the inertial frame can be expressed as:

$$\begin{aligned} {}^{I}\textbf{P} = {}^{I}\textbf{P}_{R} + {}^{R}\textbf{P}_{S} + {}^{S}\textbf{P}_{W} \end{aligned}$$
(1)

where the coordinate frames I for Inertial, R for Robot’s body, S for steering, and W for wheels. Thus, \({}^{I}\textbf{P}_{R}\) denotes the position of the robot, \({}^{R}\textbf{P}_{S}\) is the steering offset and \({}^{S}\textbf{P}_{W}\) for the wheel offset. By taking the time derivative of Eq. (1), the velocity vectors are

$$\begin{aligned} {}^{I}\textbf{V}_{W} = {}^{I}\textbf{V}_{R} + {}^{I}\varvec{\Omega }_{R} \times {}^{R}\textbf{P}_{S} + {}^{I}\varvec{\Omega }_{R} \times {}^{S}\textbf{P}_{W} + {}^{R}\varvec{\Omega }_{S} \times {}^{S}\textbf{P}_{W} \end{aligned}$$
(2)

where \({}^{I}\textbf{V}_{R}\) is the robot velocity and \({}^{I}\varvec{\Omega }_{R}\) is the robot angular velocity. It is noted that the position vector \({}^{R}\textbf{P}_{S}\) is fixed for the standard wheel system at frame \(\{\varvec{R}\}\) that \({}^{R}\textbf{V}_{S} = {}^{R}\dot{\textbf{P}}_{S} = 0\) upon considering standard wheels. Frame \(\{\varvec{S}\}\) and \(\{\varvec{W}\}\) are concentric that \({}^{S}\textbf{V}_{W} = {}^{S}\dot{\textbf{P}}_{W} = 0\). Moreover, there is no wheel offset that \({}^{S}\textbf{P}_{W} = 0\). Thus, the velocity equation of Eq. (2) can be written

$$\begin{aligned} {}^{I}\textbf{V}_{W} = {}^{I}\textbf{V}_{R} + {}^{I}\varvec{\Omega }_{R} \times {}^{R}\textbf{P}_{S} \end{aligned}$$
(3)

In order to apply the kinematic constraints residing in the wheel plane, the velocity equation of Eq. (3) needs to be projected on the wheel plane to yield

$$\begin{aligned} {}^{W}\left( {}^{I}\textbf{V}_{W}\right) = {}^{W}\left( {}^{I}\textbf{V}_{R}\right) + {}^{W}\left( {}^{I}\varvec{\Omega }_{R} \times {}^{R}\textbf{P}_{S}\right) \end{aligned}$$
(4)

The projected components of LHS and RHS of Eq. (4) in wheel frame \(\{W\}\) are:

LHS of Eq. (4):

$$\begin{aligned}{} & {} {}^{W}\left( {}^{I}\textbf{V}_{W}\right)&= {}^{W}_{I}{R}{}^{I}\textbf{V}_{W} \end{aligned}$$
(5)

RHS of Eq. (4):

$$\begin{aligned} {}^{W}\left( {}^{I}\textbf{V}_{R}\right) + {}^{W}\left( {}^{I}\varvec{\Omega }_{R} \times {}^{R}\textbf{P}_{S}\right)&= {}^{W}_{I}{R}{}^{I}\textbf{V}_{R}+ {}^{W}\left( {}^{I}\varvec{\Omega }_{R} \times {}^{R}\textbf{P}_{S}\right) \nonumber \\&= {}^{W}_{S}{R} {}^{S}_{R}{R} {}^{R}_{I}{R}{}^{I}\textbf{V}_{R} + {}^{W}\varvec{\Omega }_{R} \times {}^{W}_{R}R {}^{R}\textbf{P}_{S}\nonumber \\&= {}^{W}_{S}{R} {}^{S}_{R}{R} {}^{R}_{I}{R}{}^{I}\textbf{V}_{R} + {}^{W}\varvec{\Omega }_{R} \times {}^{W}_{R}R {}^{R}\textbf{P}_{W} \end{aligned}$$
(6)

where \({}^{W}_{I}{R}\), \({}^{W}_{S}{R}\), \({}^{S}_{R}{R}\), and \({}^{R}_{I}{R}\) denote to a rotation in the frame referring to the subscript with respect to the frame indicating the superscript, respectively. Two frames of \(\{S\}\) and \(\{W\}\) are concentric that \({}^{R}\textbf{P}_{S} = {}^{R}\textbf{P}_{W}\) as shown in Fig. 2. Substituting Eqs. (5) and (6) into Eq. (4) to get

$$\begin{aligned} \underbrace{{}^{W}_{I}{R}{}^{I}\textbf{V}_{W}}_\text {Wheel Velocity} = \underbrace{{}^{W}_{S}{R} {}^{S}_{R}{R} {}^{R}_{I}{R}{}^{I}\textbf{V}_{R}}_\text {Robot Velocity} + \underbrace{{}^{W}\varvec{\Omega }_{R} \times {}^{W}_{R}R {}^{R}\textbf{P}_{W}}_\text {Robot Rotation} \end{aligned}$$
(7)

We projected the robot velocity \({}^{I}\textbf{V}_{R}\) of Eq. (7) into the wheel frame \(\{W\}\) as shown in Fig. 2 to yield

$$\begin{aligned} {}^{W}_{S}{R} {}^{S}_{R}{R} {}^{R}_{I}{R}{}^{I}\textbf{V}_{R} = {}^{W}_{S}{R} {}^{S}_{R}{R} {}^{R}_{I}{R}{}^{I}\begin{bmatrix} \dot{x} \\ \dot{y} \\ 0 \end{bmatrix} =R(\alpha +\beta )R(\theta )\begin{bmatrix} \dot{x} \\ \dot{y} \\ 0 \end{bmatrix} \end{aligned}$$
(8)

where \(\dot{x}\) and \(\dot{y}\) are the linear velocity of a robot in their respective directions, and the rotations are

$$\begin{aligned} R(\theta )&= \begin{bmatrix} \sin \theta &{}\quad \cos \theta &{}\quad 0 \\ -\cos \theta &{}\quad \sin \theta &{}\quad 0 \\ 0 &{}\quad 0 &{}\quad 1 \\ \end{bmatrix} \\ R(\alpha +\beta )&= \begin{bmatrix} \sin (\alpha +\beta ) &{}\quad \cos (\alpha +\beta ) &{}\quad 0 \\ -\cos (\alpha +\beta ) &{}\quad \sin (\alpha +\beta ) &{}\quad 0 \\ 0 &{}\quad 0 &{}\quad 1 \\ \end{bmatrix} \end{aligned}$$

Each wheel-ground contact is a single point, and normal forces acting on the wheel-ground contact points are constant depending on the mass of a robot and gravity. Throughout the kinematic wheel equation derivation steps, we assume that wheels do not slip while rolling. The longitudinal constraint is due to the rolling of wheels on the ground, and the lateral constraint is due to sliding. It is noted that the wheel velocity \({}^{W}_{I}{R}{}^{I}\textbf{V}_{W}\) in LHS of Eq. (7) is given as the wheel constraints to each wheel:

$$\begin{aligned} {}^{W}_{I}{R}{}^{I}\textbf{V}_{W} = \begin{bmatrix} r \dot{\phi } \\ 0 \\ 0 \end{bmatrix} ~ \begin{array}{c} \text {rolling constraint} \\ \text {no-sliding constraint} \\ \text {planar motion assumption} \end{array} \end{aligned}$$
(9)

where r is the radius of a wheel, and \(\dot{\phi }\) denotes the wheel speed. The rotation in Eq. (7) can be calculated by

$$\begin{aligned} {}^{W}\varvec{\Omega }_{R} \times {}^{W}_{R}R {}^{R}\textbf{P}_{W} = \begin{bmatrix} 0 &{}\quad - \dot{\theta } &{}\quad 0 \\ \dot{\theta } &{}\quad 0 &{}\quad 0 \\ 0 &{}\quad 0 &{}\quad 0 \end{bmatrix} \begin{bmatrix} l \cos \beta \\ -l \sin \beta \\ 0 \end{bmatrix} = \begin{bmatrix} l \sin \beta \\ l \cos \beta \\ 0 \end{bmatrix} \dot{\theta } \end{aligned}$$
(10)

where, as shown in Fig. 2, l is the position vector \({}^{R}\textbf{P}_S\), \(\beta\) is the wheel angle, and \(\dot{\theta }\) denotes the rotation of a robot body (yawing). Equations (8), (9), and (10) are substituted into Eq. (7) to yield two constraints applying to a wheel:

  • Rolling constraint:

    $$\begin{aligned} {[}\cos (\alpha + \beta ), \sin (\alpha + \beta ), l \sin \beta ] R(\theta ) {}^{I} \dot{\xi } - r \dot{\phi } = 0 \end{aligned}$$
    (11)
  • No-sliding constraint (lateral movement):

    $$\begin{aligned} {[}-\sin (\alpha + \beta ), \cos (\alpha + \beta ), l \cos \beta ] R(\theta ) {}^{I} \dot{\xi } =0 \end{aligned}$$
    (12)

where the pose \({}^{I} \xi = [x,y,\theta ]^T\) and velocity \({}^{I} \dot{\xi } =[\dot{x},\dot{y},\dot{\theta }]^T\). We have derived the wheel equation as Eqs. (11) and (12) subject to the two kinematic constraints.

3.2 Differential Kinematics

We have already derived the wheel equation in Sect. 3.1, where a set of wheel speed (constraints) determines robot velocity. Each wheel operates independently in the four-wheeled mobile robot; thus, we must apply the wheel equation to each wheel separately, called the differential kinematic equation. The wheel equation of Eqs. (11) and (12) for a robot with n wheels of the radius \(r_i\), for \(i=1,\dots ,n\) is written as follows.

$$\begin{aligned} J_1 (\beta _i) R(\theta ) {}^{I}\dot{\xi } - r \dot{\phi _i}&= 0 \\ C_1 (\beta _i) R(\theta ) {}^{I}\dot{\xi }&= 0 \nonumber \end{aligned}$$
(13)

where

$$\begin{aligned} J_1 (\beta _i)&= [\cos (\alpha _i + \beta _i), \sin (\alpha _i + \beta _i), l \sin \beta _i] \nonumber \\ C_1 (\beta _i)&= [-\sin (\alpha _i + \beta _i), \cos (\alpha _i + \beta _i), l \cos \beta _i] \end{aligned}$$

where \(\alpha _i\) is the steering offset angle and \(\beta _i\) is the wheel offset angle of i-th wheel. Stacking Eq. (13) to yield a compact matrix equation:

$$\begin{aligned} \begin{bmatrix} J_1 (\beta ) \\ C_1 (\beta ) \end{bmatrix} {}^{R}\dot{\xi } = \begin{bmatrix} J_2 \\ 0 \end{bmatrix} \dot{\Phi } \end{aligned}$$
(14)

where \({}^{R}\dot{\xi } = R(\theta ){}^{I}\dot{\xi }\), \(\dot{\Phi } = [\dot{\phi }_1, \dots , \dot{\phi }_n]^T\), and

$$\begin{aligned} J_1 (\beta ) = \begin{bmatrix} J_1(\beta _1) \\ \vdots \\ J_1(\beta _n) \end{bmatrix} \quad J_2 = \text {diag}(r_1, \dots , r_n) \quad C_1 (\beta ) = \begin{bmatrix} C_1(\beta _1) \\ \vdots \\ C_1(\beta _n) \end{bmatrix} \end{aligned}$$

For a robot with four wheels, we have \(J_1 (\beta ) \in {\mathbb {R}}^{4 \times 3}\) and \(C_1 (\beta ) \in {\mathbb {R}}^{4 \times 3}\) because each wheel has one rolling constraint and one no-sliding constraint defined in Eqs. (11) and (12). Equation (14) can be written in a compact form:

$$\begin{aligned} \textbf{A} {}^{R}\dot{\varvec{\xi }} = \textbf{B} \dot{\varvec{\Phi }} \end{aligned}$$
(15)

where \(\textbf{A} \in {\mathbb {R}}^{8 \times 3}\) and \(\textbf{B} \in {\mathbb {R}}^{8 \times 4}\), and

$$\begin{aligned} \textbf{A} = \begin{bmatrix} J_1 (\beta ) \\ C_1 (\beta ) \end{bmatrix} \quad \textbf{B} = \begin{bmatrix} J_2 \\ 0 \end{bmatrix} \end{aligned}$$

or

$$\begin{aligned} \textbf{A} = \left[ \begin{array}{rrr} 1 &{}\quad 0 &{}\quad -l \sin \alpha \\ 1 &{}\quad 0 &{}\quad l \sin \alpha \\ 1 &{}\quad 0 &{}\quad l \sin \alpha \\ 1 &{}\quad 0 &{}\quad -l \sin \alpha \\ 0 &{}\quad 1 &{}\quad l \cos \alpha \\ 0 &{}\quad 1 &{}\quad l \cos \alpha \\ 0 &{}\quad 1 &{}\quad - l \cos \alpha \\ 0 &{}\quad 1 &{}\quad - l \cos \alpha \\ \end{array} \right] \qquad \textbf{B} = \begin{bmatrix}r &{}\quad 0 &{}\quad 0 &{}\quad 0\\ 0 &{}\quad r &{}\quad 0 &{}\quad 0\\ 0 &{}\quad 0 &{}\quad r &{}\quad 0\\ 0 &{}\quad 0 &{}\quad 0 &{}\quad r\\ 0 &{}\quad 0 &{}\quad 0 &{}\quad 0\\ 0 &{}\quad 0 &{}\quad 0 &{}\quad 0\\ 0 &{}\quad 0 &{}\quad 0 &{}\quad 0\\ 0 &{}\quad 0 &{}\quad 0 &{}\quad 0\end{bmatrix} \end{aligned}$$

Because \(\textbf{A}\) is a rectangular matrix that we cannot obtain an inverse matrix to solve the forward differential equation in Eq. (15) for \({}^R\dot{\varvec{\xi }}\) by a direct manner. Thus, the solution can be given via a pseudo-inverse matrix:

$$\begin{aligned} {}^R\dot{\varvec{\xi }} = (\textbf{A}^T\textbf{A})^{-1}\textbf{A}^T \textbf{B} \dot{\varvec{\Phi }} \end{aligned}$$
(16)

or in an explicit form:

$$\begin{aligned} \begin{bmatrix} \dot{x} \\ \dot{y} \\ \dot{\theta } \end{bmatrix} = \begin{bmatrix} r/4 &{}\quad r/4 &{}\quad r/4 &{}\quad r/4 \\ 0 &{}\quad 0 &{}\quad 0 &{}\quad 0 \\ -r \sin {\alpha }/4l &{}\quad r \sin {\alpha }/4l &{}\quad r \sin {\alpha }/4l &{}\quad -r \sin {\alpha }/4l \end{bmatrix} \begin{bmatrix} \dot{\phi _1} \\ \dot{\phi _2} \\ \dot{\phi _3} \\ \dot{\phi _4} \end{bmatrix} \end{aligned}$$

This concludes the derivation of the forward kinematic solution to the wheel equation upon two kinematic constraints. Hence, with Eq. (16), we may estimate the robot velocity given each wheel speed.

For later use, we need another equation called inverse kinematic solution, where we can relate the wheel speed with the robot velocity. This can be done by solving Eq. (15) for the wheel speed \(\dot{\varvec{\Phi }}\):

$$\begin{aligned} \dot{\varvec{\Phi }}&= (\textbf{B}^T \textbf{B})^{-1} \textbf{B}^T \textbf{A} {}^R\dot{\varvec{\xi }} \nonumber \\&= \textbf{H} {}^R\dot{\varvec{\xi }} \end{aligned}$$
(17)

where

$$\begin{aligned} \textbf{H} =(\textbf{B}^T \textbf{B})^{-1} \textbf{B}^T \textbf{A} \end{aligned}$$

or

$$\begin{aligned} \textbf{H} = \left[ \begin{array}{rrr}\frac{1}{r} &{}\quad 0 &{}\quad - \frac{l \sin {\left( \alpha \right) }}{r}\\ \frac{1}{r} &{}\quad 0 &{}\quad \frac{l \sin {\left( \alpha \right) }}{r}\\ \frac{1}{r} &{}\quad 0 &{}\quad \frac{l \sin {\left( \alpha \right) }}{r}\\ \frac{1}{r} &{}\quad 0 &{}\quad - \frac{l \sin {\left( \alpha \right) }}{r}\end{array}\right] \end{aligned}$$

We have established the forward differential kinematic equation of Eq. (16) and inverse differential kinematic equation of Eq. (17) for the four-wheeled mobile robot.

3.3 Maneuverability

The mobility of a robot is about movement in the environment. The fundamental constraint is the limitation that each wheel should meet the no-sliding constraint, where no lateral movement or slip is allowed. Complying the constraint \(C_1 (\beta ) {}^{R}\dot{\xi } = 0\) in Eq. (14), the velocity \({}^{R}\dot{\xi }\) is the null space of the projection matrix \(C_1 (\beta )\). The null space of is the space N such that vector \(n \in N\), that is \(C_1 (\beta ) n = 0\). The robot kinematics is closely related to the set of independent constraints of wheels, which are also directly connected to the rank of the projection matrix. The rank of \(C_1 (\beta )\) is the number of independent constraints. Thus, three degrees of freedom exist in each wheel. However, since two kinematic constraints apply to each wheel, as we discussed before, the maneuverability may change accordingly. The rank of \(C_1 (\beta )\) of the robot can be calculated as two and is higher than that of a two-wheeled mobile robot, which is one. Interestingly, the four-wheeled mobile robot has less maneuverability because of degenerated configuration. The degree of mobility can be defined as \(\delta _m = 3 - rank(C_1(\beta ))\). Thus, \(\delta _m =1\) for the robot. This can be explained that the robot may control only forward or backward velocity by varying each wheel speed. However, it may not always be possible for the robot to keep the constraints, in particular, in the outdoor environment. The robot may slip and slide perpendicular to the wheel plane. Therefore, such a violation, for example, on an icy road or a terrain with fine grain sand, may result in significant errors on the odometer and cause position tracking into less accurate. That is a reason that we pursued in this study the velocity approach in Eq. (15) rather than the odometric approach.

4 Bayes Filters

4.1 Motivation

To track the robot’s motion, we need a model closely following the robot’s behavior over time. Although we have derived the differential kinematic equations in Sect. 3.1, this equation may contain some unknown uncertainty. Alternatively, we may need to understand in depth how the robot will behave in ever-changing wheel-ground interactions in outdoor environments. A variety of uncertainty may arise due to various factors: such as erratic hardware, software flaws, motors, sensors, or even slippage of wheels. Filtering techniques have been used to alleviate such uncertainties for many applications. The Bayesian framework can explain the technique best, forming the Kalman filtering technique and several other probabilistic algorithms. In the probabilistic fashion, the estimated velocity of a robot can be represented by a probability density function relating to the state space. The idea with the Bayes filter is to employ Bayes’ rule, and the corresponding notion of conditional probability to form probability distributions representing a belief in the robot’s state, given the robot’s previous state and predicted state. The filter outputs the probability of the state variables at each time step. The prediction is the prior belief of the robot’s state after a motion before updating recent sensor measurements. In the measurement update step, we compute the posterior.

In this study, rather than disregarding uncertainty and forming an estimated state, we employed the probability to yield mathematically optimal estimates using the unscented Kalman filter and Kalman filter algorithm. The goal is to account for the robot’s uncertainty as it interacts with outdoor environments with insufficient information.

Fig. 3
figure 3

Graph of a state space model for a robot’s motion and measurement. The Markov process implies that the current state variable \(\dot{\varvec{\xi }}\) contains all the information needed to compute the next state. We may update the state variable only through the measurements \(\dot{\varvec{\Phi }}\) and the most recent estimated state

4.2 Bayes’ Filter and Robot Motion

We have sought a model that can describe the robot’s motion in outdoor environments over time. As seen in the forward differential equation of Eq. (16), the velocity \(\dot{\varvec{\xi }}\) of a robot is dictated by the wheel speed measurements \(\dot{\varvec{\Phi }}\). Hence, an ideal motion model can be written in a joint distribution of the velocity and wheel speed measurement:

$$\begin{aligned} p(\dot{\varvec{\xi }}_1,\cdots \dot{\varvec{\xi }}_k, \dot{\varvec{\Phi }}_1,\cdots ,\dot{\varvec{\Phi }}_k) \end{aligned}$$
(18)

If we could get such a model of Eq. (18), the motion of a robot can be tracked and explained over the entire time steps. However, dictating the dependencies of future measurements on all previous measurements, the model would be impractical because its complexity would grow unbounded as the number of measurements accrues. For example, when a new measurement \(\dot{\varvec{\Phi }}_{k+1}\) comes in, we need to recalculate the states over the entire time steps, which is computationally intractable in practice. Therefore, we may alleviate the requirement and calculate the probability for the most recent step, confining the full joint probability model to a tractable model using some assumptions. The Markov assumption implies that the current state variable \(\dot{\varvec{\xi }}_k\) contains all the information needed to compute the next state. This paradigm can be thought of as the state-space model in Fig. 3. In so doing, we may come up with a motion model with fewer requirements to meet.

Bayes’ filter technique can be used to estimate the state variables \(\dot{\varvec{\xi }}\). It is noted that the forward kinematic solution we have derived in Sect. 3.1 is a motion model without considering noise, whereas Bayes’ filter model could embrace uncertainty both in the system equations and the measurement.

figure b

Bayes’ filter algorithm [31] can be briefly explained in Algorithm 1. We need a model that can mimic the behavior of a four-wheeled mobile robot, in particular, under unknown outdoor environments. However, it is impossible to earn the fully jointed probability for the model shown in Eq. (18) analytically; a conditional probability can be employed instead. In so doing, we may define the belief for the current state as

$$\begin{aligned} bel(\dot{\varvec{\xi }}_k) = p(\dot{\varvec{\xi }}_k\vert \dot{\varvec{\Phi }}_{1:k}) \end{aligned}$$
(19)

It is shown that the belief of Eq. (19) is based on the measurement over time as presented by a probability density function distributed over the state space. By applying Bayes’ rule to Eq. (19) to yield

$$\begin{aligned} bel(\dot{\varvec{\xi }}_k)&= p(\dot{\varvec{\xi }}_k\vert \dot{\varvec{\Phi }}_{1:k})\nonumber \\&= \frac{p(\dot{\varvec{\Phi }}_{1:k}\vert \dot{\varvec{\xi }}_{k}) p(\dot{\varvec{\xi }}_{1:k})}{\int p(\dot{\varvec{\Phi }}_k\vert \dot{\varvec{\xi }}_k,\dot{\varvec{\Phi }}_{1:k-1})p(\dot{\varvec{\xi }}_k \vert \dot{\varvec{\Phi }}_{1:k-1}) d \dot{\varvec{\xi }}_k} \nonumber \\&= \eta p(\dot{\varvec{\Phi }}_k \vert \dot{\varvec{\xi }}_k,\dot{\varvec{\Phi }}_{1:k-1})p(\dot{\varvec{\xi }}_k \vert \dot{\varvec{\Phi }}_{1:k-1}) \end{aligned}$$
(20)

where \(\eta\) is the normalizing constant, which is a marginalization of the denominator over \(\dot{\varvec{\xi }}_k\):

$$\begin{aligned} \eta = \left[ \int p(\dot{\varvec{\Phi }}_k\vert \dot{\varvec{\xi }}_k,\dot{\varvec{\Phi }}_{1:k-1})p(\dot{\varvec{\xi }}_k\vert \dot{\varvec{\Phi }}_{1:k-1}) d \dot{\varvec{\xi }}_k \right] ^{-1} \end{aligned}$$

We have derived the belief for estimating the unknown state based on the measurement as shown in Eq. (20). However, in this study, we employed the probabilistic models of the motion and measurement separately; thus, Eq. (20) still seems impractical to be used for the calculation. Therefore, with further mathematical manipulation, we expanded Eq. (20) into a more explicit form with models of motion and measurement. With the help of Bayes’ rule and Markov process assumption, it resulted in a more tractable equation shown in Eq. (21).

$$\begin{aligned} bel(\dot{\varvec{\xi }}_k)&= \eta p(\dot{\varvec{\Phi }}_k\vert \dot{\varvec{\xi }}_k,\dot{\varvec{\Phi }}_{1:k-1}) p(\dot{\varvec{\xi }}_k\vert \dot{\varvec{\Phi }}_{1:k-1}){} & {} \text {(B)} \nonumber \\&= \eta p(\dot{\varvec{\Phi }}_k\vert \dot{\varvec{\xi }}_k)p(\dot{\varvec{\xi }}_k \vert \dot{\varvec{\Phi }}_{1:k-1}){} & {} \text {(M)} \nonumber \\&= \eta p(\dot{\varvec{\Phi }}_k\vert \dot{\varvec{\xi }}_k) \int p(\dot{\varvec{\xi }}_k \vert \dot{\varvec{\xi }}_{k-1},\dot{\varvec{\Phi }}_{1:k-1}) p(\dot{\varvec{\xi }}_{k-1} \vert \dot{\varvec{\Phi }}_{1:k-1})d \dot{\varvec{\xi }}_{k-1}{} & {} \text {(T)} \nonumber \\&= \eta p(\dot{\varvec{\Phi }}_k\vert \dot{\varvec{\xi }}_k) \int p(\dot{\varvec{\xi }}_k \vert \dot{\varvec{\xi }}_{k-1}) p(\dot{\varvec{\xi }}_{k-1}\vert \dot{\varvec{\Phi }}_{1:k-1})d \dot{\varvec{\xi }}_{k-1}{} & {} \text {(M)} \nonumber \\&= \eta p(\dot{\varvec{\Phi }}_k\vert \dot{\varvec{\xi }}_k) \int p(\dot{\varvec{\xi }}_k \vert \dot{\varvec{\xi }}_{k-1}) bel(\dot{\varvec{\xi }}_{k-1}) d \dot{\varvec{\xi }}_{k-1} \end{aligned}$$
(21)

where (B) for Bayes’ rule applied, (M) for Markov process assumed, (T) for total probability, where

$$\begin{aligned} bel(\dot{\varvec{\xi }}_{k-1}) = p(\dot{\varvec{\xi }}_{k-1}\vert \dot{\varvec{\Phi }}_{1:k-1}) \end{aligned}$$

As can be seen in Eq. (21), we derived a recursive Bayes filter. The recursive refers to the fact that the belief in the present time \(bel(\dot{\varvec{\xi }}_k)\) is determined by the belief in the previous time step \(bel(\dot{\varvec{\xi }}_{k-1})\) recursively. In addition, the belief \(bel(\dot{\varvec{\xi }}_k)\) is expressed in terms of the motion model \(p(\dot{\varvec{\xi }}_k\vert \dot{\varvec{\xi }}_{k-1})\) and the measurement model \(p(\dot{\varvec{\Phi }}_k\vert \dot{\varvec{\xi }}_k)\). For the computation’s sake, the recursive process can be divided into two steps shown in Algorithm 1: one is for the prediction, and the other for the update. The prediction step is defined as

$$\begin{aligned} \overline{bel}(\dot{\varvec{\xi }}_{k}) = \int p(\dot{\varvec{\xi }}_k\vert \dot{\varvec{\xi }}_{k-1}) {bel}(\dot{\varvec{\xi }}_{k-1}) d \dot{\varvec{\xi }}_{k-1} \end{aligned}$$

and the update step is written as

$$\begin{aligned} {bel}(\dot{\varvec{\xi }}_{k}) = \eta p(\dot{\varvec{\Phi }}_k\vert \dot{\varvec{\xi }}_k) \overline{bel}(\dot{\varvec{\xi }}_{k}) \end{aligned}$$

In conclusion, as shown in Algorithm 1, with the help of the Bayes filter, through recursive fashion on the prediction and update, we can successfully track the motion of the four-wheeled mobile robot based on the wheel-speed measurement. There are a few filters that are Bayes’ filter’s practical realization, avoiding direct analytic high-dimensional integration; the Kalman filter is a classical optimal filter for linear-Gaussian models. The unscented Kalman filter is a sigma-point transformation-based extension of the Kalman filter. In this study, we employed the Kalman filter and the unscented Kalman filter to realize Bayes’ filter in comparison.

4.3 Kalman Filter

The classical recursive solution to the state space estimation is called the optimal filter. The filter computes the posterior distribution of the state or the belief \(bel(\dot{\varvec{\xi }}_k)\) given the measurements as written in Eq. (21). Typical linear Gaussian state-space models in probabilistic notation are expressed as

$$\begin{aligned} p(\dot{\varvec{\Phi }}_k\vert \dot{\varvec{\xi }}_{k})&= \mathcal {N}(\dot{\varvec{\Phi }}_k\vert \textbf{H}\dot{\varvec{\xi }}_{k},\textbf{R}){} & {} \text {Measurement model} \nonumber \\ p(\dot{\varvec{\xi }}_k\vert \dot{\varvec{\xi }}_{k-1})&= \mathcal {N}(\dot{\varvec{\xi }}_k\vert \textbf{F}\dot{\varvec{\xi }}_{k-1} ,\textbf{Q}){} & {} \text {Motion model} \nonumber \\ p(\dot{\varvec{\xi }}_0)&= \mathcal {N}(\textbf{m}_0,\textbf{P}_0){} & {} \text {Prior distribution} \end{aligned}$$
(22)

where the measurement matrix \(\textbf{H}\), the state transition matrix \(\textbf{F}\), the measurement noise matrix \(\textbf{R} = \mathcal {N}(0,\sigma _\phi ^2)\), the system noise matrix \(\textbf{Q} = \mathcal {N}(0,\sigma _\xi ^2)\), and \(\sigma _\phi\) and \(\sigma _\xi\) are their respective covariances. The prior distribution \(p(\dot{\varvec{\xi }}_0)\) models the information already known with the mean \(\textbf{m}_0\) and covariance \(\textbf{P}_0\). Substitution of Eq. (22) into Eq. (21), the optimal filter solution via Kalman filter is obtained in a form of Gaussian distribution. Hence, the solution in Eq. (19) can be obtained with the mean \(\textbf{m}_k\) and covariance \(\textbf{P}_k\) as follows:

$$\begin{aligned} p(\dot{\varvec{\xi }}_{k}\vert \dot{\varvec{\Phi }}_{1:k}) = \mathcal {N}(\textbf{m}_k,\textbf{P}_k) \end{aligned}$$
(23)

We assumed that the robot’s velocity might not vary significantly at each time step due to the low wheel speeds and rather a short sampling time (\(\Delta t = 0.1\) s). Thus, the transition matrix of Eq. (22) can be set as \(\textbf{F} = \textbf{I}\), which is the identity matrix. The measurement matrix \(\textbf{H}\) is given in Eq. (17). All of the state variables are set to zero initially, the initial covariance is 5.0, the system noise \(\textbf{Q}\) is a discrete white noise with a variance of 0.5, and a variance of the measurement noise \(\textbf{R}\) is 0.5. Those values are hyperparameters, which can be adjusted by the optimal computational and accuracy consideration through several test runs.

4.4 Unscented Kalman Filter

Unscented Kalman Filter (UKF) is one of newly developed Bayes filters [32]. The UKF utilizes a series of transformation and sigma points instead of direct use of state variables as in the Kalman filter. The entire process of UKF can be divided into three algorithms: Sigma point algorithm, unscented transform, an unscented Kalman filter algorithm.

figure c

4.4.1 Van der Merwe’s Scaled Sigma Point Algorithm

There are a few algorithms for sigma points generation, among which Merwe’s Scaled Sigma Point Algorithm has been most popular for superior performance to others. The Merwe’s algorithm uses three parameters to control how the sigma points are distributed and weighted: \(\alpha = 0.1\), \(\beta = 2\), and \(\kappa = 0\) are used in this study. A detailed algorithm is shown in Algorithm 2. The algorithm takes the mean and covariance of the state variables and outputs the corresponding sigma points \(\varvec{\chi }\), the weights \(w^m\), and \(w^c\). The sampled sigma points for a normal road are displayed in Fig. 4. In the figure, the points at three different time steps are shown in the temporal order. The figure shows a pattern of how the sigma points are generated as time goes.

Fig. 4
figure 4

Sigma points \(\varvec{\chi }\) at \(k=0\), \(k=10\), and \(k=99\) for the unscented Kalman filter on a normal road. The depth of the point color is proportional to the value of \(\dot{\theta }\)

4.4.2 Unscented Transform

figure d

The unscented transform (UT) is the essence of the unscented Kalman filter algorithm as written in Algorithm 3. Firstly, the sigma points \(\varvec{\chi }\) are passed through a nonlinear function resulting in a transformed set of points \(\mathcal {Y}\). The UT takes the sigma points sampled from some arbitrary probability distribution, passes them through a function f (motion model in this study), and outputs a Gaussian, of which weighted mean \(\varvec{\mu }\) and weighted variance \(\varvec{\Sigma }\), for each transformed point.

figure e

4.4.3 Prediction Step

The UKF is divided into two steps: the prediction and the update step. A transformed set of sigma points is

$$\begin{aligned} \mathcal {Y} = f(\varvec{\chi }) \end{aligned}$$
(24)

The prediction step of the UKF computes the prediction (prior) as listed in Algorithm 4 using the sigma points \(\varvec{\chi }\) generated from Algorithm 2. The predicted mean \(\dot{\varvec{\xi }}^-\) and covariance \(\textbf{P}^-\) using the UT on the transformed sigma points are computed as follows:

$$\begin{aligned} \dot{\varvec{\xi }}^-, \textbf{P}^- = UT(\mathcal {Y},w^m,w^c,\textbf{Q}) \end{aligned}$$

where

$$\begin{aligned} \dot{\varvec{\xi }}^- = \sum _{i=0}^{2n} w^m_i \mathcal {Y}^i, \qquad \textbf{P}^- = \sum _{i=0}^{2n} w^c_i (\mathcal {Y}^i - \dot{\varvec{\xi }}^-) (\mathcal {Y}^i - \dot{\varvec{\xi }}^-)^T \end{aligned}$$

This result is obtained while the measurement is yet seen; therefore, the correction can be made through the update step.

4.4.4 Update Step

The UKF performs the update in measurement space as shown in Algorithm 4. Thus, we need to map the sigma points into the measurement space using a measurement function h. A set of transformed points in the measurement space is:

$$\begin{aligned} \mathcal {Z} = h(\mathcal {Y}) \end{aligned}$$

The mean and covariance of those points of \(\mathcal {Z}\) through the UT are given by

$$\begin{aligned} \varvec{\mu }_{\dot{\Phi }}, \textbf{P}_{\dot{\Phi }} = UT(\mathcal {Z},w^m,w^c,\textbf{R}) \end{aligned}$$
(25)

where

$$\begin{aligned} \varvec{\mu }_{\dot{\Phi }} = \sum _{i=0}^{2n} w^m_i \mathcal {Z}^i, \qquad \textbf{P}_{\dot{\Phi }} = \sum _{i=0}^{2n} w^c_i (\mathcal {Z}^i - \varvec{\mu }_{\dot{\Phi }}) (\mathcal {Z}^i - \varvec{\mu }_{\dot{\Phi }})^T + \textbf{R} \end{aligned}$$

The residual of the measurement \(\textbf{y}\) is

$$\begin{aligned} \textbf{y}=\dot{\varvec{\Phi }} - \varvec{\mu }_{\dot{\Phi }} \end{aligned}$$
(26)

To compute the Kalman gain we first compute the cross covariance of the state and the measurements of Eqs. (25) and (26).

$$\begin{aligned} \textbf{P}_{\dot{\varvec{\xi }}\dot{\Phi }} = \sum _{i=0}^{2n} w^c_i (\mathcal {Y}^i - \dot{\varvec{\xi }}^-) (\mathcal {Z}^i - \varvec{\mu }_{\dot{\Phi }})^T \end{aligned}$$
(27)

And then the Kalman gain is defined with Eqs. (25) and (27) as

$$\begin{aligned} \textbf{K} = \textbf{P}_{\dot{\varvec{\xi }}\dot{\varvec{\Phi }}} \textbf{P}^{-1}_{\dot{\varvec{\Phi }}} \end{aligned}$$

Finally, we obtain the estimated \(\dot{\varvec{\xi }}\) and \(\textbf{P}\) using the residual and the Kalman gain as shown in Algorithm 4 as follows.

$$\begin{aligned} \dot{\varvec{\xi }} = \dot{\varvec{\xi }}^- + \textbf{K} \textbf{y}, \qquad \textbf{P} = \textbf{P}^- - \textbf{K} \textbf{P}_{\dot{\varvec{\Phi }}} \textbf{K}^T \end{aligned}$$
(28)

In so doing, we may conclude that the tri-variate states (two linear velocities and rotation) of the robot has been realized as a numerically tractable form in Eq. (28).

5 Four-Wheeled Mobile Robot

Fig. 5
figure 5

Different views of the four-wheeled mobile robot with a fixed standard wheel system. Four optical encoders are equipped into each wheel to send wheel speed data through the Raspberry Pi computer board

In this study, we set up a four-wheeled mobile robot, as shown in Fig. 5, operated by a DC motor at each wheel, which comes with a 120:1 gearbox and an integrated quadrature encoder that provides a resolution of 16 pulse single per round giving a maximum output of 1920 within one round. The dimension of the robot is the length of 24 cm, the width of 17.5 cm, a diameter of a wheel of 6.6 cm. A Raspberry Pi single-board computer delivers commands into the robot and receives measurements from the encoders. The reference wheel speed is set to 6.54 rad/s (200 encoder ticks per second) for all the wheels throughout the test runs. In other words, regardless of road conditions, we demand that each wheel spins at the reference wheel speed. Thus, as long as an ideal condition to the robot’s motion holds without any hindrance, the robot would move forward at 21.6 cm/s in the heading direction. The information of electric specification for the robot is listed in Table 1.

Table 1 Overall specification of the robot system and the encoders

6 Results and Discussion

Table 2 Specification of the five different road conditions in which the robot runs more than a thousand tests

We had more than a thousand test runs along with five different road conditions: normal, sandy, icy, partially blocked, and grid holes. The detail of the tests is listed in Table 2. The reference wheel speed was set to a constant of 6.54 rad/s (about 62.5 rpm) throughout the tests.

Fig. 6
figure 6

The robot runs on difference roads. Icy road (top left), sandy road (bottom left), partially blocked by a brick (center), and grid type holes (right)

Fig. 7
figure 7

Measured wheel speeds of the robot on a normal road

Fig. 8
figure 8

A swarm plot of the measured wheel speed of each wheel of the robot on a normal road. Note FL (forward left), FR (forward right), RR (rear right), and RL (rear left). It is observed that RR seems to spin faster than the others

The overall schematic of different roads is displayed in Fig. 6. For example, we may anticipate that wheels can quickly get stuck with fine grain sand. In Fig. 7, variation of each wheel speed on a normal road for 10 s is shown. We initiated the robot on a normal road, demanding each wheel spin at the reference wheel speed so that the robot may go straight in the heading direction. Interestingly, the rear right wheel spins faster than the others. The median and variance of the velocities is shown in Fig. 8. However, it is not clear that what causes the rear right wheel to run faster. Since we built the robot with identical DC motors and wheels, we expected all wheels to run at the same speed upon the same road condition. It could be an encoder error or road conditions, or unknown flaws in the robot itself. Unmistakably, this unbalanced wheel speed can bring about some uncertainty and difficulty to the analysis. Therefore, we need to know whether that unbalance in wheel speeds should be regarded as statistically significant or not. That is, the presence of this unbalance may not be justified without rigorous statistical examination. Thus, we performed an ANOVA (Analysis of Variance) test on it. With the ANOVA \(F = 28.5\) and the p-value is significant \(p < 0.05\), we may conclude significant speed differences among wheels with a 95% confidence level. Hence, we learned that not all wheels run at an identical speed upon demanding them so. Such an unexpected issue is not uncommon in the actual world, making modeling harder.

Fig. 9
figure 9

A comparison of the estimated state velocities (\(\dot{x}\), \(\dot{y}\), and \(\dot{\theta }\)) of the robot on a normal road through different algorithms (no filters, Kalman filter, and unscented Kalman filter). The expected velocity is 21.6 cm/s (6.25 rad/s with 6.6 cm of the diameter of the wheel)

A comparison of different filtering techniques for the estimated state velocities of the robot on a normal road is shown in Fig. 9. The velocity of heading direction \(\dot{x}\) is displayed in the figure (left). The expected velocity (red-dashed line) is 21.6 cm/s (6.25 rad/s with 6.6 cm of the diameter of the wheel). However, any of the estimated velocity has not reached the designated value. We were not sure whether it was because of the unbalanced wheel speed we observed earlier or varying ground-wheel conditions, or both. Among two filtering algorithms, the unscented Kalman filter shows an excellent fit to the estimated velocity from experiment data (no filter). Furthermore, the no-lateral movement constraint seems to be kept all the time (center pane in the figure). Thus, the robot does not make a lateral move (no sliding). Even so, the robot’s rotation (right) shows some interesting behaviors. Even if no rotation is theoretically allowed due to the fixed wheel, some positive rotation rate is seen, which is the counter-clockwise rotation. We may conclude that such rotation is caused by the unbalanced wheel speed in which the rear right wheel runs faster and the road condition.

Fig. 10
figure 10

On a normal road, the estimated velocity \(\dot{\varvec{\xi }}\) in the form of Gaussian distribution is evolving at each time step. Each distribution is calculated via the Kalman filter

In Fig. 10, it is shown that the probability density function of the estimated velocity in the robot heading direction \(\dot{x}\) evolves at each time step, which is calculated via the Kalman filter. As time goes, the distribution gets narrow and higher probability density value; we may conclude that the model closely estimates the robot’s motion on a normal road.

Fig. 11
figure 11

Measured wheel speeds of the robot on an icy road

In Fig. 11, the measured wheel speeds on an icy road are shown. Each wheel’s speed appears relatively more scattered. Besides, considering the faster speed in the rear-right wheel discussed earlier, the front-left wheel spins a bit fast. That can be because of the slippage of the wheels on an icy road. Once a wheel gets into a slippage, the robot may not get back to a designated pose without external intervention, such as a human operator. We observed that no single test was similar to the others during several test runs on an icy road. Therefore, analytical modeling based on a wheel-ground interaction for an icy road might not be practical at all. It is because each time we place the robot on an icy road, an ice condition may change due to inexplicable factors such as the non-uniform melting of ice due to wheel-ice contacts.

Fig. 12
figure 12

A comparison of the estimated state velocities (\(\dot{x}\), \(\dot{y}\), and \(\dot{\theta }\)) of the robot on an icy road through different algorithms (no filters, Kalman filter, and unscented Kalman filter). The expected velocity is 21.6 cm/s (6.25 rad/s with 6.6 cm of the diameter of the wheel)

The performance comparison of modeling on an icy road is shown in Fig. 12. The velocity \(\dot{x}\) (left) in the heading direction is significantly displaced from the reference and scattered. Even so, the unscented Kalman filter appears to perform exceptionally well against the uncertainty of the measurements. The lateral velocity \(\dot{y}\) (center) seems to remain around zero. As for the rotation rate \(\dot{\theta }\) (right), significant impacts must have been exerted to the robot that the rotation rate peaks of about 0.6 rad/s during 4–7 s. Then, the robot would likely move sideways quite violently due to this heavy rotational rate change. According to the forward differential equation in Eq. (16), the robot is not supposed to be rotated at any moment (see the dashed red line in the figure). However, this rule seems to be much violated due to an icy road. That helpful information might be hard to obtain when only sticking to analytical models without allowing any uncertainty in motion and measurement models.

Fig. 13
figure 13

Comparison of the estimated covariances on an icy road calculated through the Kalman filter (red) and the unscented Kalman filter (green) at \(T=0\), \(T=0.5\), and \(T=9.9\) s. In order to get a better appearance for comparison, each ellipsoid is drawn not to scale. The red (Kalman filter) and green (unscented Kalman filter) dots are sampled from their respective tri-variate Gaussian distributions. (Color figure online)

In Bayes’ framework, the estimated results are produced in probability, particularly for Gaussian distribution. We drew a plot with the mean and covariance of the distribution. In so doing, we may get more information on how the filtering algorithm works on various conditions. In Fig. 13, the ellipsoids of the covariance obtained from the Kalman filter and unscented Kalman filter are shown, respectively. The estimated velocity \(\dot{\varvec{\xi }}\) is composed of three elements of velocities \(\dot{x}\), \(\dot{y}\), and \(\dot{\theta }\). The ellipsoid represents the covariance space; thus, the larger the space, the less belief we can rely on from the result. Also, we need to pay some attention to the shape of an ellipsoid. For example, the ellipsoid being similar to a sphere can be considered that three elements are not correlated much. The dots on the surface of an ellipse are sampled from the tri-variate normal distribution. Three panels at the top of the figure show the temporal trend of covariance via the Kalman filter. As time goes, although the ellipsoid gets smaller and longer, the red dots appear to be away from the surface of the ellipsoids. This explains why the Kalman filter solution deteriorates over time. Likewise, three panels at the bottom of the figure show the trend of the covariance from the unscented Kalman filter. As can be seen, most of the green dots appear to dwell closely on the surface of the ellipsoids. As is seen in the comparison, we may conclude that the unscented Kalman filter works better than the Kalman filter in general.

Fig. 14
figure 14

Measured wheel speeds of the robot on a sandy road

Figure 14 shows the wheel speeds on a sandy road. The road is covered by a 2-cm thick fine grain of sand as shown in Fig. 6. We might expect that the robot gets in easily stuck intermittently into slippage states. Thus, it may be hard for the robot to maintain the designated wheel speed all the time. Furthermore, front-left and rear-left wheels spin at the reverse rotation rate of about negative 2 rad/s during the first half of the test run. Then, the wheel comes to a stop and then gets back in the reverse direction. In this test, we can be sure that fine grain of sand is a great hindrance to the wheels’ spin, in particular, during the first half of the test run.

Fig. 15
figure 15

A comparison of the estimated state velocities (\(\dot{x}\), \(\dot{y}\), and \(\dot{\theta }\)) of the robot on a sandy road through different algorithms (no filters, Kalman filter, and unscented Kalman filter). The expected velocity is 21.6 cm/s (6.25 rad/s with 6.6 cm of the diameter of the wheel)

A comparison of the estimated state velocities of the robot on a sandy road is shown in Fig. 15. The velocity in the heading direction \(\dot{x}\) goes up and down. It has reached about 16 cm/s at most, which is below the expected velocity. As for the lateral velocity \(\dot{y}\), it lands around zero; thus, the no-sliding constraint has been met. The rotation rate shows a significant peak between 2 and 3 s. The unbalanced wheel speed may cause this peak in the rotation. Furthermore, the rotation rate has changed significantly in a relatively short time. It may be because of the big motion that the robot makes in order to get out of stuck in the sand. As for the overall performance, the unscented Kalman filter gets the highest score.

Fig. 16
figure 16

Measured wheel speeds of the robot on partially blocked

In Fig. 16, each wheel speed when the robot is partially blocked by brick is shown. Initially, the wheel speeds go down immediately. Around 5 s, the wheel speeds of the front-left and rear-right wheels bounce back to near the designated wheel speed. It can be explained that the robot being blocked can cause a lowering of its wheel speeds. Since the robot head and the brick are partially contacted over a small area, the robot tends to rotate clockwise about the brick. Even though the brick keeps the robot from going forward, the rotation will occur to be out of the blockage; thus, the wheel speeds rise again.

Fig. 17
figure 17

The estimated velocities of the robot on partially blocked

The estimated velocities of the robot partially blocked are displayed in Fig. 17. The velocity of heading direction \(\dot{x}\) seems to be directly affected by a subtle change of each wheel speed due to the blockage. It appears that the brick keeps the robot from moving forward, and \(\dot{x}\) is suppressed under a speed of 15 cm/s. The lateral velocity remains around zero without violating the constraint. The rotation rate shows quite an interesting result that in the first half, the counter-clockwise rotation occurs, followed by the clockwise rotation. That direction change informs us of helpful information about how the robot makes movement subject to a brick on a partial contact. As seen in the figure, the unscented Kalman filter performs well throughout the test run.

Fig. 18
figure 18

Measured wheel speeds of the robot on grid holes

Figure 18 shows the wheel speeds on grid-type holes. The robot initially starts on a normal road and then gets into the grid holes. We might anticipate that the robot does not freely move as intended because of the complicated ground-wheel conditions of grid-type holes. This may be true, as seen in the figure. However, it is pretty difficult for us to get any explicable information from the result in this case. Besides, as seen in Fig. 6, two wheels get stuck in the grid holes, whereas the other wheels are on a dirt road. There might not exist an easy solution to incorporate such road conditions into physics laws or empirical equations to be used as a wheel-ground interaction model.

Fig. 19
figure 19

A comparison of the estimated state velocities (\(\dot{x}\), \(\dot{y}\), and \(\dot{\theta }\)) of the robot on grid type holes through different algorithms (no filters, Kalman filter, and unscented Kalman filter). The expected velocity is 21.6 cm/s (6.25 rad/s with 6.6 cm of the diameter of the wheel)

In Fig. 19, the velocity of heading direction \(\dot{x}\) appears to be affected by the grid holes. In this case, the two robot wheels get stuck into the grid holes while the others are on the normal road. The lateral velocity remains around zero. The rotation rate \(\dot{\theta }\) shows that the positive and negative rotation rates. However, it is not easy to explain the cause of the rotations because of the complexity of the motion in this case.

Fig. 20
figure 20

Comparison of log MLE (maximum likelihood estimation) convergence of Kalman filter and unscented Kalman filter for four different cases: Icy road, sandy road, grid holes, and partially blocked

We have made several comparisons between Bayes’ algorithms (the Kalman filter and the unscented Kalman filter). Besides comparing the results, it might be interesting to pay attention to the numerical aspect of those algorithms. Since Bayes’ rule is composed of the multiplication of likelihoods and priors to yield posteriors, we need to check the behavior of likelihoods given each measurement. The maximum likelihood estimation (MLE) often calculates the optimal parameters for the likelihood given measurements. The likelihood can be written:

$$\begin{aligned} \mathcal {L}(\varvec{\Theta })&= \log {p(\dot{\varvec{\Phi }}\vert \varvec{\Theta })} \nonumber \\&= \log \prod _{i=1}^{n} {p(\dot{\varvec{\phi }}_i\vert \varvec{\Theta })} \nonumber \\&= \sum _{i=1}^{n} \log p(\dot{\varvec{\phi }_i}\vert \varvec{\Theta }) \end{aligned}$$
(29)

where \(\varvec{\Theta }\) is the parameter given the measurement \(\dot{\varvec{\Phi }} = \{\dot{\varvec{\phi }}_1,\dots , \dot{\varvec{\phi }}_n\}\). Applying maximum likelihood estimation to Eq. (29) to yield

$$\begin{aligned} \widehat{\varvec{\Theta }} = \text {argmax}_\Theta {\mathcal {L}(\varvec{\Theta })} \end{aligned}$$

where \(\widehat{\varvec{\Theta }}\) is the optimal parameter. In Fig. 20, the trend of MLE values of two algorithms on different road conditions is shown. For all cases, the unscented Kalman filter has clearly shown superior performance to those of the Kalman filter. The Kalman filter seems to fluctuate severely per varying measurements, whereas the unscented Kalman filter keeps a relatively steady state for all the cases. This may explain that the unscented Kalman filter is not likely to be affected by measurement uncertainties, guaranteeing more reliable results.

In summary, we carried out more than a thousand test runs over different road conditions. Using Bayes’ filtering techniques, we could obtain the estimated velocities of the robot given only measured wheel speeds. In most cases, the kinematic constraints are met well, particularly in the lateral velocity being zero.

7 Conclusion

As the popularity and demand for outdoor wheeled mobile robots are rapidly growing, the lack of fundamental study on kinematics, dynamics, wheel-ground interaction, and terrains can hinder the further development of wheeled mobile robots. Particularly autonomous wheeled mobile robots should run without human intervention in unknown outdoor environments. This study derived forward and inverse differential kinematic solutions for four-wheeled mobile robots with the fixed-standard wheel system. Furthermore, with a thousand tests performed in outdoor environments, we could build the motion model of the robot. With the help of Bayes’ filtering framework, we learned that the unscented Kalman filter outperformed other algorithms, such as the Kalman filter, for the task. The notion of ensemble modeling of kinematics and data-driven models demonstrated in this study can be extended to any wheeled mobile robot as long as the fundamental kinematic solution and measurement data are given. This ensemble approach would incorporate analytical and data-driven methods into a recursive state-space equation to model the robot’s motion against outdoor environments. Undoubtedly, further study is needed; for example, we could have employed machine learning to find significant patterns inside seemingly unstructured data of wheel speeds in outdoor environments. We hope to see more research to utilize machine learning in this field soon.