1. Introduction
Industrial automation is a prerequisite for intelligent manufacturing, and mobile robots represent a core component of industrial automation systems. In recent decades, due to the broad applications for mobile robots, the core issues in motion control of mobile robots, including point stabilization, path planning, trajectory tracking, and real-time avoidance, have attracted considerable attention from both academic scholars and practitioners [
1,
2,
3,
4,
5].
Although large numbers of mobile robots have begun to enter homes, hospitals, and many other industrial areas, mobile robots with new structures (as opposed to the traditional dual-drive wheeled mobile robots), are required to meet continuously increasing demands with respect to high flexibility, efficiency, and safety of complex and diverse applications in reality. Omni-directional mobile robots (OMRs) with mecanum wheels provide an alternative and have drawn much attention from researchers. In [
6,
7], two different omni-directional mobile structures with mecanum wheels were proposed. In [
7,
8], the kinematics of OMRs were analyzed and the motion control of robots was achieved. In [
9], a comprehensive omni-directional soccer player robot with no head direction was proposed and it was capable of more sophisticated behaviors, such as ball passing and goal keeping. Compared with the traditional nonholonomic dual-drive wheeled robot, the omni-directional mobile robot is able to synchronize steering and linear motion in any direction. This advantage not only improves the flexibility of the robot greatly in order to achieve fast target tracking and obstacle avoidance, but also provides more references for robot motion control methods.
Motion control is a core issue in the mobile robot system and guarantees the smooth movement of the robot. Due to the diversity of motion and increasing performance requirements, motion control algorithms are becoming more and more complex. In [
10], a receding horizon (RH) controller was developed for the tracking control of a nonholonomic mobile robot. In [
11], a novel biologically inspired tracking control approach for real-time navigation of a nonholonomic mobile robot was proposed by integrating a backstepping technique and a neurodynamics model. In [
12], an approach was proposed for complete characterization of the shortest paths to a goal position and it was used for path planning of the robot. A novel method referred to as the visibility binary tree algorithm for robot navigation with global information was introduced in [
13]. The set of all complete paths between the robot and target in the global environment with some circle obstacles was obtained by using the tangent visibility graph. Then, an algorithm based on the visibility binary tree created for the shortest paths was run to obtain the optimal path for the robot. In [
14], a real-time obstacle avoidance approach for mobile robots was presented based on the artificial potential field concept. The motion control of omni-directional mobile robot has also been investigated and many results have been reported [
15,
16,
17,
18]. Among them, the model predictive control (MPC) algorithm is the most common control method used for trajectory tracking of the OMR.
The MPC algorithm is an efficient predictive control technique and is composed of model prediction, rolling optimization, and feedback correction. The MPC algorithm has been widely used in industrial control applications and is able to take various constraints into consideration. The core of MPC control problem finding the optimal solution of a cost function constructed according to the error between system output at the sampling time and the predicted output of the established prediction system model. The optimal solution is taken as the optimal control input in the future prediction time domain and the first control vector of the optimal solution is used as the real control input. The advantages of the MPC algorithm are: (1) It is easy to model; (2) It has a rolling optimization strategy with good dynamic control effect; (3) It can correct the output by feedback which improves the robustness of the control system; (4) As a computer optimization control algorithm, it is easy to realize on a computer. In recent years, the MPC algorithm has also been widely used to achieve optimized motion control of mobile robots. In [
19], a novel visual servo-based model predictive control method was proposed to steer a wheeled mobile robot moving in a polar coordinate. In [
20], a model-predictive trajectory-tracking controller, which used linearized tracking-error dynamics to predict future system behavior, was presented. In [
21], a state feedback MPC method was proposed and applied for trajectory tracking of a three-wheeled OMR. The cost function in the proposed MPC method is constructed over finite horizon and is optimized in the linear matrix inequalities (LMI) framework. In [
22], a virtual-vehicle concept and an MPC strategy were combined to handle robot motion constraints and the path-following problem.
In this paper, the kinematic analysis of the OMR is conducted and then an MPC algorithm for point stabilization and trajectory tracking is proposed. In the proposed MPC controller, the rotation speeds of the three wheels and the state outputs of the robot are taken as manipulated variables and controlled variables, respectively. In stabilization control of the robot, a target point and an arbitrary initial direction, which lie within a given constraint range of the coordinate, are set and then the robot tracks the target point and stabilizes itself automatically. In the trajectory tracking of the robot, a pulsed route is planned and different target angles at each node point are set. The robot can move from the start point of the trajectory to the end point along the given route with target angles.
This paper is organized as follows: A brief description and kinematics analysis of the considered OMR are given in
Section 2.
Section 3 presents the MPC strategy including MPC elements and the optimization method. Simulation results of the proposed MPC algorithm are presented in
Section 4. Finally,
Section 5 concludes the work in this paper.
3. MPC Strategy
The MPC algorithm has been widely used in motion control of mobile robots and it has three basic characteristics: model prediction, rolling optimization, and feedback correction. It has unique advantages for solving motion control problems, such as point stabilization and trajectory tracking of mobile robots. Traditional methods often neglect or simplify the robot kinematics and dynamics constraints which have a significant impact on the robot’s control performance. Meanwhile, the MPC algorithm takes the constraints into consideration to improve the system robustness. The existing controllers have high requirements with respect to the accuracy of the system model and tend to obtain effective control parameters based on the model and multiple experimental tests;. However, the MPC algorithm has low requirements with respect to the accuracy of the system model and can acquire the control parameters through simple experiments. Through applying the characteristics of rolling optimization and feedback correction, the influence of time-delay in the closed-loop system can be effectively reduced or even eliminated, and the motion control is optimized to achieve improved control performance. Particularly, the MPC algorithm can handle multivariate and constrained problems effectively.
The MPC problem can be described as solving the optimal solution of the cost function. At each sampling time, the outputs of the future N sampling instants are predicted according to the system model, and the cost function is constructed based on the errors between the predicted outputs and the true state outputs of the system. The optimal control inputs of the next N sampling instants are obtained by minimizing the cost function, however, only the first control vector is used as the system input. At the next sampling time, this process is repeated and rolling optimization is performed.
In this section, an MPC-based kinematic controller is designed to ensure that the mobile robot can be driven to the desired position accurately, smoothly, and stably.
Define
as the state of mobile robot in coordinate
and
. Then, it can be derived that
where
Based on zero-order hold (ZOH), a continuous-time system can be transformed into a discrete-time form with a sampling period T.
The discrete-time system (
14) can be transformed into a discrete state space system as
where
The parameter n is the number of state variables and m is the number of input variables. The matrix A is a constant identity matrix, and matrix B is determined by orientation of the system dynamically.
Based on the state space model (
15), the MPC algorithm is designed to control the system. Here, a cost function is required and optimized through solving a quadratic program (QP) problem to obtain the optimal control sequence in predictive horizon
N. The cost function for the MPC can be defined as
where
and
are appropriate weighting matrices.
and
denote the predicted state and control vector in predictive horizon at time
k.
Through solving the following finite-horizon optimal control problem online, the optimal control sequence can be obtained.
Since the torques generated by motors are limited by the performance of the motors, the
has an upper and lower bound, and the range of state variable
is also constrained. Thus, the following constraints should be imposed on the system:
In order to solve the optimal control problem, Equation (
17) is transformed into a standard quadratic form which a QP solver can solve. The following prediction vector is defined:
Based on Equation (
15), the relationship between vectors
and
can be described as
where
with
defined as
Two block diagonal matrices are defined:
Thus, the optimal control problem (
17) can be rewritten as
subjected to
where
and
are the lower and upper bounds of the control vector in predictive horizon, respectively.
and
are the lower and upper bounds of the predictive state vector, respectively.
After some algebraic manipulations, the optimization problem (
23) is transformed into a standard quadratic form:
with
where matrix
denotes the quadratic part of the objective function and the vector
describes the linear part.
The QP problem (
26) can be solved online to obtain an optimal prediction control sequence. The first control vector of the sequence is applied to the system at time
k. In the next sampling instant, this process is repeated to achieve rolling optimization.
4. Simulation Verification
In this section, the simulation is carried out to verify the accuracy of the derived kinematic model of the OMR and the performance of the MPC algorithm. In this simulation, the range of motion for the OMR is set to (−10 m, 10 m) and it serves as the state constraint; The rotation velocity of each mecanum wheel is set to (−2 m/s, 2 m/s), which is treated as the input constraint. Two tests, point stabilization and trajectory tracking, are performed. In the point stabilization test, the OMR moves to a target point and changes the orientation in the moving process. In the trajectory tracking test, the OMR moves along a known pulse trajectory with different target orientations at different nodes.
4.1. Point Stabilization
In this test, the goal and initial states are predefined. Here, the goal and initial position are set to (3 m, 2 m, /3 rad) and (0 m, 0 m, 0 rad), respectively. In order to simulate the real movement of the OMR, the noise is added to the output state.
In each prediction period, a control matrix
is obtained through solving the QP problem (
26). The
is the velocity input sequence to control the movement of the OMR. Actually, only the first control vector in
is used as the effective velocity input. The velocity input throughout the whole motion process is shown in
Figure 7. In this figure, there are two red dotted horizontal lines, which present the velocity constraints. It can be seen from this figure, with the application of MPC algorithm, that the control velocities of three wheels converge to zero gradually and smoothly. Meanwhile, velocity
is affected by the maximum control input constraint at the beginning.
The state trajectories of the OMR in Cartesian coordinates are shown in
Figure 8. Two position parameters,
and
, are given in the upper subfigure of
Figure 8. The initial position of
is set to (0 m, 0 m) and the target position is set to (3 m, 2 m). The orientation angle
of the OMR in the moving process is presented in the lower subfigure of
Figure 8. The initial orientation angle is 0 rad and the target orientation angle is set to
/3 rad. As shown in
Figure 8, the MPC controller can steer the OMR to the target quickly and steadily.
The coordinates,
, of the OMR in moving process are shown in
Figure 9. It can be seen from this figure that the movement trajectory is very close to the target trajectory. The tracking error between the movement trajectory and the target trajectory is shown in
Figure 10. The maximal tracking error is about 4 cm. From
Figure 8 and
Figure 10, it can be seen that the OMR moves along the predefined target trajectory to the target point, which demonstrates the effectiveness of the developed MPC algorithm.
4.2. Trajectory Tracking
In this test, the trajectory tracking of the OMR along a pulse trajectory is conducted to evaluate the performance of the proposed MPC strategy. The node parameters of the trajectory are shown in
Table 2.
There are six nodes, including the starting point and end point, in the pulse trajectory. The trajectory tracking is achieved by tracking each node according to the position and target direction given in
Table 2. In order to simulate the real state of the OMR, the noise is added to the output state.
The linear velocity and angular velocity curves of the OMR in the trajectory-tracking process are shown in
Figure 11. It can be seen from this figure that at each node, the axis component of linear velocity fluctuates due to steering action, but converges to zero soon.
The comparisons of true and tracked trajectory and direction are shown in
Figure 12 and
Figure 13, respectively. As shown in these figures, the position and angle of the OMR change at the same time and the angle reaches the target faster than the position. The trajectory tracking error is presented in
Figure 14. The maximal tracking error of the OMR is about 0.08 m.
The omni-directivity and flexibility of the kinematic structure of the OMR are verified through these two tests. The OMR can achieve movement of any direction without turning, which solves the problem that nonholonomic wheeled mobile robots are not flexible in real-time avoidance. In addition, the results of the first test show that the MPC algorithm can be applied in stabilization control of the robot and the target position and angle can be reached quickly and steadily.