1 Introduction

Autonomous intelligent systems (AISs) are a series of systems that act or react to the environment independently of human control, e.g., autonomous ground vehicles (AGVs) or unmanned aerial vehicles (UAVs). An AIS generally consists of the following main functions: acquire sensory inputs, identify the current situation, choose an objective, construct a plan according to experience, act as planned, receive the resulting rewards, and learn from experience [1]. AISs need to be able to make safe and rational decisions in unknown environments. Their decision making or actions should be understandable to guarantee the necessary trust by human users or collaborators.

AIS has become a field of intense research within the robotics and control community, wherein unmanned ground/aerial/underwater vehicles applies from the civil to the military sector, such as logistics, mine detection, intruder detection and attacking. New technologies and application domains increase the need for research and development resulting in new challenges to be overcome in order to apply AIS in a reliable and user-independent way.

AGVs, as one of the most representative AISs, have attracted considerable attention from academia, industry and governments around the world for their great significance in reducing road injuries, increasing traffic efficiency, and saving energy. Thanks to the tremendous progress of computer science, control science, communication technology and engineering, as well as the promotion of new policies and laws, AGVs are experiencing explosive development and leading a deep revolution in automobile and transportation industries [2].

Model predictive control (MPC) is one of the most widely used advanced control methods. MPC has gradually matured both in application and theory and a vast amount of literature has been published, see, e.g., [3, 4] for a thorough discussion of the basics of MPC.

In AGVs, autonomous refers to the ability to percept, predict, and act in an unknown environment. Since MPC is an established control methodology that systematically uses forecasts, application of MPC to AGVs is sensible, effective and computational realizable. For this reason, MPC has been extensively applied to AGVs, however, there is no comprehensive survey of these applications so far. This paper comprehensively reviews the application of MPC to AGVs and summarizes the current challenges and opportunities for these applications.

This paper is organized as follows: the next section briefly presents the basic theoretical knowledge of MPC with a focus on distributed MPC. Then, applications of MPC to single AGVs are reviewed, followed by applications to multiple AGVs. In addition, some existing challenges and future trends are highlighted. Finally, the contribution of this paper is summarized.

2 Basis of MPC

Because of the extensive attention MPC received during the past years, and subsequently the expansive body of contributions that have been published, only a brief overview over the basic idea of MPC with a focus on distributed MPC is given. For more details about MPC, the interested reader is referred to one of the many available reviews or books specifically about MPC, e.g. [35].

In the following, an AGV is represented by a discrete-time, nonlinear dynamical system

$$ x(t + 1) = f(x(t), u(t)),\qquad x(0) = x_{0} $$
(1)

with time step \(t \in \mathbb {N}^{0}\), state \(x(t) \in \mathbb {X} \subseteq \mathbb {R}^{n}\) and control input \(u(t) \in \mathbb {U} \subseteq \mathbb {R}^{m}\) at time t, \(f: \mathbb {X} \times \mathbb {U} \to \mathbb {X}\), and initial condition \(x_{0} \in \mathbb {X}\). The state and input are subject to point-wise-in-time constraints \((x(t), u(t)) \in \mathcal {Z} \subset \mathbb {X} \times \mathbb {U}\). As part of the MPC law, at each time step t, the state x(t) is measured and the following finite-horizon optimal control problem is solved

$$\begin{array}{*{20}l} \underset{\boldsymbol{u}(\cdot \vert t)}{\text{minimize}} &\sum_{k=0}^{N-1} \ell(x(k\vert t), u(k\vert t)) + V^{\mathrm{f}}(x(N\vert t)) \end{array} $$
(2a)
$$\begin{array}{*{20}l} \text{s. t.} \quad & x(0\vert t) = x(t), \end{array} $$
(2b)
$$\begin{array}{*{20}l} & x(k + 1 \vert t) = f(x(k \vert t), u(k \vert t)), \quad \forall k = 0,\dots, N-1, \end{array} $$
(2c)
$$\begin{array}{*{20}l} & (x(k \vert t), u(k \vert t)) \in \mathcal{Z}, \quad \forall k = 0,\dots, N-1, \end{array} $$
(2d)
$$\begin{array}{*{20}l} & x(N \vert t) \in \mathbb{X}^{\mathrm{f}}, \end{array} $$
(2e)

where \(\boldsymbol {u}(\cdot \vert t) = (u(0 \vert t), \dots, u(N-1 \vert t))\) and \(\boldsymbol {x}(\cdot \vert t) = (x(0 \vert t), \dots, x(N \vert t))\) are the predicted input and state sequences at time t with the prediction horizon \( N \in \mathbb {N}\). The constraints (2b) and (2c) ensure that the predicted state and input sequences satisfy the system’s model and (2d) safeguards constraint satisfaction. The terminal cost \(V^{\mathrm {f}}:\mathbb {X}^{\mathrm {f}}\to \mathbb {R}\) and terminal constraint (2e) are typically designed to guarantee closed-loop properties and are commented on momentarily.

For simplicity, it is assumed that the optimization problem (2) is well defined, i.e., a minimizing control input exists which is denoted by u(·|t). In general, recursive feasibility of (2), i.e., if a solution exists at t0, then there exists a solution for all tt0, is an important property in MPC, that has to be established.

A standard MPC scheme for a discrete-time system is then given by the following algorithm.

Algorithm 1.Measure the state x(t)of system (1) at each time step t. Then, solve the optimization problem (2) and apply the control input uMPC(t)=u(0|t). Repeat for the next time step t+1.

If the MPC scheme is applied, then the closed-loop system is given by

$$ x(t + 1) = f(x(t), u^{*}(0 \vert t)), \quad x(0) = x_{0}. $$

In many cases, the design of MPC schemes is concerned with stabilizing a set-point of (1) as the control objective. For this reason, the stage cost is usually chosen to be positive definite with respect to this set-point. Even in this case, additional assumptions are, in general, needed to establish closed-loop stability. One possible approach is to design suitable terminal ingredients, i.e., a terminal cost Vf and terminal set \(\mathbb {X}_{\mathrm {f}}\) [3, 57]. Another approach is so-called unconstrained MPC, i.e., MPC without terminal constraints, usually requiring an additional controllability assumption [810].

Because in reality systems are subject to disturbances and (model) uncertainties, inherent robustness of nominal MPC has been studied [11, 12], as well as the design of robust MPC schemes [1318].

Furthermore, besides set-point stabilization, more general control objectives like tracking or path following have been considered [1924]. In addition, minimization of a more general economical cost that is not necessarily positive definite with respect to a set-point or reference trajectory is studied in economic MPC [25, 26].

Recently, data-driven MPC, where collected input-output data are directly used in the optimization instead of a model, have received increasing attention [27, 28].

Large-scale systems which comprise a large number of interconnected subsystems, as, e.g., power grids [29], transportation networks [30], and large scale irrigation systems [31], lead to complex, high-dimensional models. A centralized controller, e.g., as shown in Fig. 1, may not be desirable for these systems, due to a large required communication overhead, it being susceptible to single-point failure, or because the centralized MPC problem (2) is computationally intractable. In these cases, the development of suitable distributed MPC schemes is of interest.

Fig. 1
figure 1

Centralized MPC structure

2.1 Distributed MPC

In a distributed setting, a large-scale (global) system is decomposed into smaller subsystems that are connected in some way to a subset of other subsystems, called neighbors, of the global system. Possible connections may be due to dynamic coupling, i.e., the dynamics of neighboring subsystems are coupled, cost coupling, e.g., when a cooperative objective should be achieved, and constraint coupling, for example, a certain minimum distance between subsystems or because a shared resource is used.

More formally, consider \(M \in \mathbb {N}\) subsystems, e.g., AGVs, where the i-th subsystem is a nonlinear, discrete time system

$$ x_{i}(t + 1) = f_{i}(x_{i}(t), u_{i}(t), x_{\mathcal{N}_{i}}(t)),\qquad x_{i}(0) = x_{i,0} $$
(3)

with the local state and input \(x_{i}(t) \in \mathbb {X}_{i} \subseteq \mathbb {R}^{n_{i}}\) and \(u_{i}(t) \in \mathbb {U}_{i} \subseteq \mathbb {R}^{m_{i}}\), the states of system i’s neighbors \(x_{\mathcal {N}_{i}}(t) \in \mathbb {X}_{\mathcal {N}_{i}} \subseteq \mathbb {R}^{n_{\mathcal {N}_{i}}}\), \(f_{i}: \mathbb {X}_{i} \times \mathbb {U}_{i} \times \mathbb {X}_{\mathcal {N}_{i}} \to \mathbb {X}\), and the local initial condition xi,0. For simplicity, a possible dependence of fi on the input of the neighbors is omitted.

The global system (1) may then be written as

$$\begin{aligned}x(t + 1) \,=\, \left[\begin{array}{c} x_{1}(t + 1) \\ \vdots \\ x_{M}(t + 1) \end{array}\right] \,=\, \left[\begin{array}{c} f_{1}(x_{1}(t), u_{1}(t), x_{\mathcal{N}_{1}}(t)) \\ \vdots \\ f_{i}(x_{M}(t), u_{M}(t), x_{\mathcal{N}_{M}}(t)) \end{array}\right] \,=\, f(x(t), u(t)) \end{aligned} $$

where the state and input of the subsystems are simply stacked in a vector. It is assumed, that the global stage cost can be separated into local parts, i.e., \(\ell (x, u) = \sum _{i=1}^{M} \ell \left (x_{i}, u_{i}, x_{\mathcal {N}_{i}}\right)\), and each subsystem is equipped with a local controller that has access to only the information of its neighbors. In DMPC, this information often has the form of predicted state and input trajectories. Depending on the choice of terminal cost and terminal constraints, it may then be possible to divide the centralized optimization problem (2) and distribute it among the subsystems, each now solving a smaller sub-problem. An example for the resulting structure in DMPC is given in Fig. 2.

Fig. 2
figure 2

Distributed MPC structure

Main challenges in DMPC include the coordination of (coupling) constraints, i.e., maintaining recursive feasibility and guaranteeing closed-loop stability of the global system or the fulfillment of a more general cooperative task.

In the following, two different approaches to DMPC are considered: iterative MPC schemes and non-iterative MPC schemes.

In most iterative MPC schemes, the centralized MPC optimization problem (2) is solved using a variant of a distributed optimization algorithm, for example, using the alternating direction method of multipliers (ADMM) [3234], or a Jacobi-type iteration [35, 36]. That is, each subsystem solves its optimization problem while iteratively exchanging the current solution candidate with its neighbors. Although iterative algorithms generally may require much communication, they can also recover the solution to the centralized problem in the limit, as, e.g., in [35]. As pointed out before, designing a suitable terminal cost and terminal constraint is one possible way to achieve a stabilizing MPC. In [37] a distributed synthesis approach is presented, which makes the terminal cost and constraint amenable to distributed optimization, i.e., iterative DMPC.

In sequential MPC, an example of a non-iterative scheme, the subsystems solve their optimization problem sequentially instead of iteratively. After all subsystems communicated a predicted candidate sequences to neighbors, one system after the other solves its local optimization problem while other subsystems keep their trajectories fixed. MPC schemes for stabilization and other cooperative control task are, for example, proposed in [3841]. Other non-iterative MPC schemes include approaches based on robustness considerations, [4244], and using additional constraints that force subsystems to be consistent with what they communicated before [45].

Another classification of DMPC schemes, which is also taken in [46], is based on the view-point on the structure of the large-scale global system. On one hand, a large number of subsystems, possibly dynamically decoupled as in the multi-agent case, can make up the global system, providing a bottom-up perspective. Multiple AGVs that form a large-scale system often fall into this category. On the other hand, a large-scale sytem, e.g., a power network or chemical plant, might be divided into smaller subsystems by the control engineer in order to apply distributed control schemes. This constitutes a top-down view. For an extensive collection of DMPC schemes presented in a unified notation and sorted into both categories, the interested reader is referred to [46].

Due to many different types of large-scale systems and requirements in their control, many different DMPC schemes exist. Reviewing them goes beyond the scope of this work and the reader is referred to reviews of DMPC, e.g., [4749].

In the case of multiple AGVs interacting with each other, the goal is often to achieve a cooperative task. As the consensus problem is a simple but important example of such a cooperative task, a brief review on some results in using DMPC for consensus, which could be applied in the control of AGVs, is given.

2.1.1 DMPC for consensus

In the context of dynamical (sub-)systems, the consensus problem is to reach an agreement in a common variable, e.g., the subsystems’ outputs [50]. Consensus problems are found in many applications including, e.g., formation control, distributed sensor fusion, and multi-vehicle platooning.

In [51], a contractive constraint is imposed on the systems’ states in the proposed DMPC scheme and consensus is guaranteed for systems with double integrator dynamics and input constraints, where the communication network is time-varying. In [52], a weighted-average consensus protocol for a single integrator multi-agent system is designed based on a DMPC approach. After each subsystem solved its optimization problem, the average of the computed optimal inputs of neighboring systems is applied. Convergence to a weighted-average consensus point is proven for a fixed and time-varying communication topology. In [53], an iterative DMPC approach that includes an auxiliary consensus state as a decision variable in the optimization is proposed for single and double integrator systems.

In [54], a consensus protocol for linear homogeneous systems is developed based on the explicit solution of a DMPC optimization problem, where no constraints are considered. In [55], a similar approach is used to show consensus of a double-integrator multi-agent systems subject to input constraints that are active a finite number of times.

In [56], a DMPC problem for linear systems subject to state and input constraints is formulated and solved using the alternating direction method of multipliers (ADMM). Zhan et al. propose a non-iterative DMPC algorithm where each agent obtains a candidate state sequence of the neighbors for the optimization and an additional consistency constraint is added to the individual optimization problems in order to achieve consensus of homogeneous linear systems [57]. In addition, the DMPC is extended to be self-triggered, i.e., the DMPC problem is only solved at self-selected time instants. In [58], the non-iterative DMPC algorithm is extended using a constraint-tightening approach to provide practical consensus if an additive bounded disturbance affects the agent.

In [59], a robust min-max DMPC scheme is proposed to achieve practical consensus in tracking the same reference for homogeneous linear systems subject to additive disturbances and time-varying communication delays. Copp et al. propose a combined min-max moving-horizon estimate and MPC problem to drive a system of linear additively disturbed agents to practical consensus using output feedback [60]. The resulting centralized optimization problem is solved iteratively using a distributed implementation.

In [61], a distributed optimization scheme is developed to negotiate an optimal consensus point of a multi-agent system with heterogeneous linear dynamics, which can be used as a set-point in an MPC formulation. In [62], the negotiation and the set-point tracking MPC scheme are combined and convergence to a common consensus point is proven both if in each time step the negotiations about the consensus point have converged and if they have been terminated before convergence. Shi et al. present a different distributed optimization method to compute a consensus point which is then used in a DMPC scheme for output consensus of a linear, heterogeneous multi-agent system [63]. In [64], a suitable consensus protocol is used to generate a trajectory towards consensus for a linear, homogeneous multi-agent system. This trajectory is then tracked using a tracking MPC scheme which can satisfy input and state constraints. In [65], a sequential DMPC scheme for output consensus of a linear, heterogeneous multi-agent system subject to state and input constraints is presented. In each individual optimization problem, an auxiliary output is chosen and simultaneously tracked. Online, only the auxiliary outputs need to be shared between agents.

In [40], a sequential DMPC framework for general cooperative control tasks, which include consensus as a special case, is proposed. It is shown that the cooperative control task is achieved for multi-agent systems with nonlinear dynamics that are subject to (possibly coupled) state and input constraints if the terminal ingredients are suitably designed, which is done for the special case of consensus. In [41], a sequential DMPC scheme for coordination of self-interested interacting linear systems with coupling constraints is proposed. The goal, which the scheme accomplishes, is to asymptotically achieve a cooperative objective, e.g., consensus or sensor coverage, where the agents may act in self-interest with respect to an individual objective while negotiating the cooperative solution.

3 MPC for individual AGVs

Due to the nature of MPC, it is readily applicable in motion control, i.e., tracking of a planned trajectory with a vehicle. In a fast changing driving environment, the planned trajectory is sometimes dynamically infeasible and thus unable to be tracked. To handle this, some works consider the vehicle’s dynamics as a constraints in trajectory planning to compute a dynamically feasible trajectory. However, considering the constraints both in trajectory planning and motion control makes the algorithm computationally complex. Thus, recent works attempt to combine trajectory planning and motion control in an integrated framework, which directly receives the driving behavior command from decision-making and produces the corresponding control variables.

3.1 Motion control of single AGVs using MPC

As aforementioned, motion control is a main component of autonomous driving. The aim is that the algorithm drives the vehicle to follow a preplanned trajectory by considering the dynamics of the AGV. When MPC is used, researchers usually design algorithms by considering aspects such as, e.g., hard constraints, chance constraints, multi-objectives, robustness, and computational complexity.

In [66], the authors propose a collision-free trajectory planning method based on an artificial potential field, followed by a multiple constrained MPC to track the trajectory. In [67] an MPC-based path tracking method for autonomous ground vehicles is presented, which considers two model predictive controllers in a cascade structure. The upper layer controller is based on a vehicle kinematic model, and the lower layer controller utilizes a vehicle dynamic model, in which longitudinal and lateral motion control are separately considered to achieve a lower computational complexity.

In [68], an MPC-based motion controller for marine vessels is developed and compared to a two-layer control structure, that is typically used in this case. Furthermore, the MPC-based approach appears to provide promising advantages. In [69], an optimization algorithm for predictive motion control is developed that addresses both hybrid car dynamics and a hybrid minimization criterion by using the Hamiltonian-switching hybrid nonlinear predictive control algorithm and several adaptive prediction horizon approaches.

In [70], an adaptive model predictive controller for motion control is developed, in which a weights adaptation strategy is designed to improve the controller’s capabilities in different driving scenarios, and a multi-model adaptive rule is proposed to deal with the uncertainties of the tire cornering stiffness. In [71], an MPC-based motion control method is proposed, in which the appropriate MPC cost function weights can be automatically determined through a logistic function. In [72], MPC-based controllers for driving autonomous vehicles in dangerous situations, as for example lane changes in order to avoid an obstacle, are proposed and evaluated. In [73], an MPC-based simultaneous trajectory planning and tracking approach for obstacle avoidance of an intelligent vehicle is proposed, where the reference trajectory is determined by both the lateral position and velocity of the intelligent vehicle and the velocity and yaw angle of the obstacle vehicle.

In [74], an MPC-based motion controller considering the cut-in behavior of other vehicles is proposed, predicting it using long short-term memory, in addition, the lateral velocity is estimated through a moving horizon estimator. In [75], the cut-in behavior is predicted through a rule-based method and an MPC is used for trajectory tracking under different cut-in scenarios.

In [76], a set-theoretic MPC is proposed to deal with disturbances and constraints in an uncertain dynamic driving environment. In [77, 78], a motion controller to track designated waypoints based on robust nonlinear MPC (NMPC) with constrained workspace is proposed, which guarantees the robustness of the system against model uncertainties. In [79], the authors propose a motion control method using an integrated MPC and PID controller to deal with the changing velocity effects, in which a radial basis function-extreme learning machine (RBF-ELM) neural network is designed for high-accuracy prediction and an RBF neural network is used to tune the PID controller. In [80], a learning MPC-based motion controller for a racing car is proposed, which incorporates a safe set construction module, an objective function approximation module and an affine time-varying prediction module. In [81], an MPC-based motion control method considering the varying velocity and parameter uncertainties is presented to improve the control accuracy and robustness. A polytope with finite vertices is designed to describe the varying velocity. The controller is solved through linear matrix inequalities and worst-case infinite horizon minimization. A novel robust MPC with a finite time horizon is proposed in [82] to develop a motion controller, which is able to handle the time-varying and uncertain vehicle dynamics as well as the external disturbance. A linear parameter varying model with polytopic vertices is established taking the uncertain cornering stiffness and the varying velocity into account, and the proposed scheme is then utilized to solve a min-max optimization problem in real time. The study [83] considers a random network delay in the transmission of the steering angle and proposes a motion controller based on adaptive MPC for an uncertain model which predicts the next control variable and reduces the steering angle discontinuity.

The authors in [84, 85] develop a linear MPC based motion tracking controller using differential flatness theory, which has less model linearization errors and better performance than traditional linear MPC. The authors in [86] develop two MPC-based motion controllers with a nonlinear vehicle model and a successive-online-linearized vehicle model, respectively. Furthermore, the computational complexity and control performance are analyzed. A Takagi-Sugeno MPC method to design a motion controller is proposed in [87], which is able to convert a nonlinear problem into a linear form and greatly reduce the computation burden.

3.2 Motion planning by MPC for a single AGV

Since recently MPC algorithms are also used for trajectory planning, this section mainly focuses on MPC-based motion planning and decision making aspects of single AGVs.

Potential field is an effective method to model the dynamics of the vehicle and describe its interaction with surrounding obstacles. In [88], a human-like decision making framework for autonomous vehicles is proposed, where the potential field method and MPC are used to plan the collision-avoidance path and provide predicted motion states for the human-like decision making module. An integrated framework to deal with the decision making and motion planning is presented in [89] for lane-change maneuvers, while considering social behaviors of surrounding traffic participants. In [90, 91], an integrated decision-making and motion planning module is proposed in an MPC framework which incorporates the lane selection and a potential field in the objective function to improve comfortability.

A separated longitudinal and lateral motion planning framework based on MPC and a vehicle point-mass model is proposed in [92] to reduce the complexity of optimization and thus improve the computational efficiency. The feasibility of MPC is investigated in [93] for autonomous vehicle motion planning, where a linearization-convexification and a brute-force search approach are presented to determine control invariant sets in order to ensure the recursive feasibility. In [94], an MPC formulation for motion planning is built, which incorporates actuator dynamics in the underlying optimization and improves the computational efficiency compared with the joint formulation that simultaneously optimizes linear velocities and angular accelerations.

In [95], a coordinated longitudinal collision avoidance and lateral stability control method is proposed, in which an MPC motion planner is developed to provide the desired deceleration and additional yaw moment. In [96], a trajectory planner based on NMPC is developed, which considers the vehicle dynamics and the constraints from obstacles, surrounding vehicles, velocity limits and road boundaries. A longitudinal motion planning method is proposed in [97] for car following in a chance-constrained MPC framework, in which the predicted probability distribution of the front vehicle position is determined through a Markov chain and maximum likelihood motion predictor in order to provide longitudinal constraints for the MPC.

A longitudinal motion planning method based on MPC is presented in [98], which incorporates a responsibility-sensitive safety model to evaluate the safety performance. An MPC-based motion planning method for uncontrolled intersections is proposed in [99], which determines the desired acceleration while ensuring safety based on a risk management module. A motion planning method based on robust MPC is presented in [100]. The safe area is first determined through potential field and reachable sets, and then a tube-based robust MPC is designed to generate integrated lateral and longitudinal motions.

3.3 MPC for combined motion planning and control of an individual AGV

MPC applications in AGVs are extended to include more tasks recently. For example, based on what has been mentioned in the previous two subsections, MPC can easily combine the planning and control in a unified framework. In addition, AGVs with MPC can achieve better quality by considering behaviors of surrounding traffic participants, incorporating more future information and integrating efficient prediction methods.

An integrated motion planning and tracking (IMPT) method based on adaptive tube-based NMPC is developed in [101], where a fixed nominal model and a separate adaptive model are utilized. In addition, a Newton or generalized minimum residual method (GMRES) solver is adopted to guarantee a real-time implementation. A longitudinal IMPT method in an MPC framework is proposed in [102], in which a robust invariant terminal set is computed in real time to ensure the safety and can handle the road grade and the motion prediction uncertainties of the front vehicle. An MPC-based framework incorporating a multi-target tracking method and a motion planning method is proposed in [103], which can handle unreliable detections and uncertain changes of surrounding vehicles. An IMPT method for maximizing lateral clearance against a construction zone is proposed in [104], in which a bias penalty function of the construction area is added in the total cost function.

A lateral IMPT scheme for emergency collision avoidance based on MPC is presented in [105], in which the lateral motion prediction is constrained in a safe area determined by road boundaries and obstacles positions. Furthermore, differential braking is employed to achieve fast maneuvers and to maintain vehicle stability. The concept of torque vectoring is to control the traction and braking torque of each wheel to generate a direct yaw moment. An MPC-based IMPT scheme is developed in [106] for high-speed emergency collision avoidance under low road friction and heavy crosswinds driving conditions, in which the forward and the rear safe areas are shaped linearly to constrain the predicted states, and the torque vectoring controller is applied to ensure lateral-yaw stability. An integrated motion planning and control method based on MPC is proposed in [107] to deal with emergency situations where collision is inevitable by generating a path to mitigate the crash as much as possible. A longitudinal IMPT controller considering the road slope is developed in [108], where the nonlinear powertrain dynamics and the collision-avoiding constraint from the front vehicle are considered in order to improve the tracking accuracy and reduce the fuel consumption. The constraints that are unrelated to safety are slacked to improve the feasibility of MPC, and the pseudospectral discretization technique is adopted to achieve high computing accuracy with much less collocation. An IMPT controller based on MPC is developed in [109], in which a bundle adjustment algorithm is used to detect obstacles and compute a sparse representation of the environment. Furthermore, this sparse representation is added as additional safety constraints to the optimization problem in the MPC.

An MPC-based longitudinal IMPT method is presented in [110] for energy-saving control of internal combustion engine vehicles, which optimizes the speed and the gears to minimize the fuel consumption. The optimal control problem is formulated and simplified to a mixed integer programming problem with a convex quadratic objective function and linear constraints. A computationally efficient nonlinear control for autonomous overtaking is proposed in [111], which conducts sampling in relative distance to the leading vehicle, replaces velocity state with its inverse, and utilizes a nonlinear change of control variables. These three steps achieve a computationally efficient nonlinear control problem that can be solved using sequential quadratic programming.

An IMPT controller based on game theoretic MPC is proposed in [112] which uses game theory to interact with surrounding vehicles to evaluate lane-change options. In addition, a four-stage hybrid MPC is used for longitudinal position and lane decision. An IMPT method for mandatory lane change using game theoretic MPC with aggressiveness estimation of human drivers is proposed in [113]. The scheme is able to maintain a good balance of driving safety and intelligent decision-making.

An IMPT framework using MPC is proposed in [114] to achieve a personalized and safe control. A random forest classifier is first designed to assess the driving risk while learning the personal desired velocities, and then the safety-focused MPC and the personalized MPC are conducted to ensure safety in risky situations, and to perform personal driving in risky-free situations, respectively. A shared control problem based on MPC is investigated in [115, 116], in which a lane-following, a left turn and a right turn MPC controllers are respectively designed as candidates to match the driver’s intended behavior, and the control authority allocation can be dynamically adapted with respect to the driver’s authority intention.

Ethical decision-making during inevitable crashes, especially when humans are involved, has become a big and sensitive roadblock autonomous vehicles. The authors in [117] proposed a lexicographic optimization based MPC framework for ethical decision-making in autonomous driving using rational ethics, where obstacle and constraints are prioritized.

4 MPC for multi-AGVs

In recent years, autonomous ground vehicle platooning has received considerable attention [118120]. This is mainly related to its potential benefits for road transport, including improved traffic organization, improved road welfare, and reduced fuel consumption [121, 122]. The vehicle platoon uses a longitudinal steering strategy to force each vehicle to move in a lane. It is achieved by changing the driver of the vehicle schedule dispatcher, which forces the vehicles to follow each other and move at the same velocity while keeping a chosen formation shape or geometry, which is started by a desired inter-vehicle spacing tactics [118, 123125].

At present, the coordinated control of a vehicle platoon has become the key technology of automobile manufacturers’ competition. These projects aim to study how to realize the safety and fuel-saving of the whole fleet through the coordinated control of a vehicle platoon.

  • The research of vehicle platoon cooperative control first started in the United States in 1986. Partners for advanced transportation technology (PATH) aims to alleviate traffic congestion, improve road capacity and safety, and promote energy conservation and emission reduction [126].

  • Through heavy truck simulation and real vehicle tests, the PATH project shows that the vehicle platoon can improve the transportation capacity when the vehicle spacing is controlled at 3 to 4 m. The leader vehicle can save 10% fuel, and the following vehicles can save 10% to 15% fuel [127].

  • The research of vehicle platoon cooperative control in Japan started the energy intelligent transportation systems (ITS) project in 2008.

  • Through this project, three full-automatic trucks were tested. The test results show that the energy consumption can be reduced by 15% when the vehicle runs at 80 km/h and maintains a distance of 10 m [128].

  • The European Union started the safe road trains for the environment (SARTRE) project in 2009, focusing on the platoon driving technology of hybrid vehicles (e.g., cars, commercial vehicles) [129, 130]. This project aims to realize the safety, environmental protection, and energy-saving of vehicle platoon driving through the collaborative control of vehicle platooning.

  • Besides the SARTRE project, Europe has launched SCANIA-platooning and grand cooperative driving challenge (GCDC) projects [131, 132].

Next, the framework, control objective and topology of vehicle platoons are introduced, respectively. Platoon Framework

The purpose of a vehicle platoon is to manipulate the individual vehicle to move at a consistent speed while maintaining adequate space between vehicles. The platoon has a leader vehicle (LV, indicated by P0) and the following vehicles (FVs, indicated by P1, ⋯, PN). As shown in Fig. 3, the platoon system can be viewed as a combination of four main components:

  • Node dynamics, which describes the behavior of the involved vehicles [134137];

    Fig. 3
    figure 3

    Distributed controllers in the platoon framework [133]

  • Information flow topology, which defines how information is exchanged between nodes [138];

  • Distributed controller, which uses information about neighbors to achieve feedback control [139141];

  • Formation geometry, which defines the distance between vehicles required to form a platoon [142, 143].

Note that, in Fig. 3, the i-th vehicle in the platoon is marked as i, and i=P0 is the leading one, i=P1,⋯,PN are the followers. The term ui is the control signal of i-th vehicle, C is the controller. Denote pi and vi as the position and speed of the Pi vehicle. Control Objective for Platoons

Multi-vehicle platoon collaborative driving is one of the important research directions in intelligent connected vehicle systems. Its main task is to combine several individual vehicles to form a hybrid flexible formation, according to different road conditions, based on wireless and ad hoc networks, through interactive cooperation.

For a vehicle platoon system, the control goal is that the vehicles in a platoon keep the same speed as the leader vehicle, and a safe distance to the former vehicle. The mathematical description of the control objective is

$$ \left\{ \begin{array}{l} \mathop {\lim }\limits_{t \to \infty} \left\| {{v_{i}}(t) - {v_{0}}(t)} \right\| = 0\\ \mathop {\lim }\limits_{t \to \infty} \left\| {{p_{i - 1}}(t) - {p_{i}}(t) - {d_{i - 1,i}}(t)} \right\| = 0 \end{array} \right. $$
(4)

where di−1,i(t) is the desired distance between adjacent vehicles. Topologies

In a system consisting of several vehicles, one key problem is how to exchange information with other vehicles. The communication topology in a platoon can be modeled by a directed graph G={V,E}, where V={0,1,2,⋯,N} is the set of nodes, and EV×V is the set of connected edges [144, 145].

The properties of the graph G can be described by three matrices, namely the adjacency matrix A, the Laplacian matrix L, and the Pinning matrix P.

Topologies define the communication process, which defines how the vehicles in the platoon exchange data with each other. Figure 4 shows some leader-follower topologies, where (a) is a predecessor-following topology [147], (b) is a predecessor-leader following topology [142], (c) is a bidirectional topology [148], (d) is a bidirectional-leader topology [146], (e) is a topology of two-predecessor following topology, and (f) shows a two-predecessor-leader following topology [138].

Fig. 4
figure 4

Leader follower topologies [146]

Note that these topologies are used for grouping in one line. Several platoons may interact with each other during a platoon operation or lose communication with the present topology. So, a dynamic or switching topology should be considered to balance string stability and flexibility of the topology.

4.1 DMPC strategy for vehicle platoons

The vehicle platoon features, namely the chain structure of the involved sub-systems (vehicles), are suitable for an application of DMPC.

In DMPC, a large-scale system (the entire vehicle platoon) can be divided into separate sub-systems which are dynamically linked through state and inputs [149]. The local controller configures each sub-system (vehicle) using nearby available information and associated data gained through communication between neighboring agents. DMPC can improve the system control performance [139141, 150] by explicitly predicting the future control input and state sequences, and effectively estimating the interaction among sub-systems.

At present, many scholars have focused on collaborative control of vehicle platoons, i.e., designing distributed control strategies according to different performance requirements, with the consideration of coupling constraints, and analyzing stability, safety, i.e., protection against uncertainties, and feasibility [151153]. In [145], a distributed control method is proposed for heterogeneous commercial vehicle formation to achieve a consistent speed and keep gap difference between adjacent vehicles. In [154], a two-layer control strategy is used for vehicle platoons, where the lower control is used to counteract the system’s nonlinear characteristics and the upper control uses a linear DMPC method to optimize the minimum tracking error, fuel consumption, and car-following characteristics. In [155], for the case where the speed of the leader vehicle in the platoon is constant and only longitudinal characteristic are considered, a DMPC scheme is adopted to realize consistency and string stability of heterogeneous vehicle platoons. In [156], an NMPC is designed which can smoothly switch between adaptive cruise control and cruise control. Furthermore, in terms of the state of the front vehicle, it can predict the reference trajectory according to the expected speed and distance. A formation controller based on DMPC is designed in [157] to achieve consistency and string stability of heterogeneous vehicle platoons. In [158], an MPC algorithm for a vehicle platoon is designed which can ensure the named gain stability (a new concept proposed in [158], which is an extension of platoon staring stability). In [159], a new DMPC strategy with guaranteed fuel economy is proposed, which can guarantee trajectory convergence and minimize fuel consumption [127]. A distributed economy MPC approach is presented in [160] to solve the problem of the vehicle platoon, where the string stability of the platoon is guaranteed.

4.2 Plug in or out maneuvers

The vehicle platoon plug in or out strategy refers to the formation of a hybrid flexible platoon through interaction and cooperation according to different road environments and a wireless self-organizing network. This strategy increases traffic flow due to improved platoon system flexibility.

Control of plug in and out maneuvers of vehicle platoons mainly focuses on two aspects:

  1. 1

    The control strategy for calculating the vehicles’ speed and position takes the influence of multiple lanes, several vehicle types, different destinations, and traffic density into account [161].

  2. 2

    According to the upper decision-making information of vehicle speed and position, vehicle speed and path tracking control strategies are designed for vehicle stability and platoon security.

A distributed control strategy to select lanes for platoons using inter-vehicle communication is proposed in [162] to enhance traffic safety and increase lane capacities. While cooperating control for single vehicle lane assignments already leads to decrease travel times, implementing a cooperative lane assignment for platooning vehicles leads to an even greater reduction of travel times. Seeing the leader-follower platoon and the overtaking maneuver, a decentralized PID control approach is proposed, where the control inputs for each vehicle are the traction force and steering angle [163]. Considering all practical limitations and constraints, workspace geometry, and steering specifications, a nonlinear time-invariant motion planner is proposed that guarantees collision-free lane changing, merging and overtaking maneuvers. The motion planner derived from the Lyapunov-based control scheme works within an overarching leader-follower scheme [164]. In view of the problem of vehicles plugging in and out at different speeds, two adaptive lateral trajectory generation techniques are proposed and compared. This scheme can effectively avoid high lateral acceleration [165]. In [166], a scheme is proposed that guides and controls the vehicles’ longitudinal motion, which considers the entry of vehicles onto automated highways, e.g., an on-ramp vehicle is to rendezvous with a designated space on the highway at a merging point; or a vehicle in the transition lane is to pursue a target space in the automated lane and intercept it smoothly at an automated highway entry gate. Algorithms for merging control of vehicles using the concept of a virtual vehicle, and inter-vehicle communication for the control are presented in [167], which greatly increased safety and decreased traffic congestion. A decentralized merging assistant is proposed for mixed traffic situations to increase traffic flow by minimizing the conflict and limiting speed changes [168].

Research has been carried out on controlling vehicle platoon plug in or out maneuvers in traffic flow characteristics. DMPC has been, however, not yet implemented in the plug in or out scenario. Since DMPC has the advantages of a simple structure and the ability to deal with constraints, it is likely to become a popular research topic with respect to vehicle platoon plug in and out maneuvers.

5 Current challenges and prospects in using MPC for AGVs

Despite the widely existing applications of MPC in AGVs, some open challenges in theoretical and implementation aspects still exist. Thus, in this section, the current challenges in the aforementioned topic areas are reviewed and some indications for future developments are provided.

5.1 MPC applications in individual AGVs

The following is the main challenges for future study.

  1. 1

    Integration of decision making, trajectory planning and motion control in an MPC framework: Vehicle dynamics directly determine the vehicle’s motion and thus have crucial effects on vehicle stability, safety and comfortability. To achieve safe and comfortable autonomous driving, traditional MPCs consider the vehicle dynamics mainly in motion control and recent work further extends the vehicle dynamics to trajectory planning. However, the vehicle dynamics are still ignored in decision making which directly affects the trajectory planning, further are the motion control and the vehicle motion. Especially in high-speed or low-friction scenarios, decision making without vehicle dynamics may lead the vehicle to uncontrollable modes from the very beginning before trajectory planning and motion control, and thus seriously deteriorates the stability, safety and comfort of AGVs. It is still an open challenge, how the decision making, trajectory planning and motion control based on vehicle dynamics can be integrated into a unifying MPC framework.

  2. 2

    Balancing of model accuracy, prediction horizon and control performance: The MPC-based AGV controllers are full of trade-offs. Simple vehicle models are not enough in MPC. However, the more complex the vehicle model is, the heavier the computational complexity becomes. Furthermore, too short prediction horizon will cause the AGVs short-sighted, but too long horizons will bring prediction inaccuracy.

    Thus, the challenge is how the model accuracy, the prediction horizon and the control performance according to different driving scenarios, different accuracy demands and on-board computational limits can be balanced.

  3. 3

    Ensuring recursive feasibility of MPC in AGVs: Recursive feasibility is of the greatest significance since it ensures sensible control inputs to the vehicle. Feasibility has very close relationship with the objective function, the references errors, the weights, and the state and control constraints. How to systematically describe the characteristics of the driving behavior together with the above four factors to achieve recursive feasibility is still challenging.

  4. 4

    Considering uncertainties: In real driving, the vehicle model and the motion of traffic participants are inevitably uncertain, which may deteriorate the prediction accuracy and the control performance of the model predictive controllers. How to deal with the uncertainties of the model, the constraints and the objective function for AGV controllers in the MPC framework is still a challenge.

  5. 5

    Adaption to every scenario in a unifying MPC framework: Current MPC-based trajectory planning and motion control only consider typical driving behaviors in sample scenarios such as lane keeping, lane change, etc., which is however far from implementation in real complex traffic. Thus, the design of an MPC framework that can adapt to every scenario by adapting the objective function and having flexible constraints is still a challenge.

  6. 6

    Human-and-passengers-like model predictive controller: Current research pays more attention on function while the experience of drivers and passengers is ignored, which makes the AGVs just a rigid robot that might lose the human trust. How to finely design the weights, the constraints as well as the objective function of the model predictive controller to make it more human-like and passengers-acceptable is still a challenge.

  7. 7

    On limited working conditions: Limited working conditions, such as icy roads, dramatically increase the risk of vehicle instability. How to figure out the instability boundary and incorporate the highly nonlinear vehicle dynamics from a predicted perspective in an MPC framework is of great significance and still an open challenge.

5.2 MPC applications in multi-AGVs

Several technical and practical challenges are listed here, which play a vital role in the cooperation between multi-autonomous ground vehicles in platoons.

  1. 1

    Data transfer: Wireless communication is a key feature in the process of vehicle platooning. Typically, a vehicle will send information including speed-data, sensor-readings, and current-position to the other vehicles. Communication is completed through broadcast or multicast transmission with a handshake protocol. Communication problems between vehicles in a platoon include loss of information, error messages, spam, communication equipment failure, and transmission delays. The communication topology must be able to connect in lousy weather or insufficient bandwidth access.

  2. 2

    Cybercrime security: A vehicle platoon is a collection of networked sensors and computers wirelessly linked to other vehicles and frames; therefore, the system must be secure from network attacks by hackers or invaders.

  3. 3

    Platooning: Formation control of platoons is essential when autonomous vehicles need to keep distance between themselves and their neighbors. Dynamic platoons must determine the target by solving the following scenarios:

    • If a vehicle wants to leave a platoon or links with another platoon, the other vehicles must reorder their positions to fill the platoon space.

    • If the leader leaves the platoon, the direct follower in the platoon must take the leader’s role instead.

    • There is a limit on the number of vehicles for platoon formation; if the number is exceeded, a new platoon for autonomous vehicles should be generated.

    • The demand for “fast” control of information transmission and “long” forecast time for the vehicle. Thus, feasibility of high dimensional complex nonlinear optimization problems [147] has to be considered.

  4. 4

    Plug in or out: In an uncoordinated traffic environment, vehicle mergers and lane changes are another key target area requiring inter-vehicle interaction. For these operations, assessing the intentions of other vehicles and sharing information between them are vital.

  5. 5

    Emergency response: Providing access to emergency vehicles such as ambulances and police cars is an additional challenge requiring the development of dedicated controllers for vehicle platooning. Currently, human drivers park on the side of the road and provide a way to ambulances. A similar behavior needs to be implemented for autonomous vehicles in platoons.

Although DMPC has been widely applied to AGVs, most of the studies are still in the laboratory stage. The critical problem is the conflict between low-cost hardware and the tremendous computational complexity in solving the optimization problem. This is especially worth addressing in energy-efficient control with a longer prediction horizon, for instance, velocity trajectory optimization in eco-driving systems. To address this problem, [169171] used the indirect shooting method in energy management systems and a lateral stability control system to realize real-time control under a low-cost microcontroller. Although the prediction step is up to 80-100, by combing Pontryagin’s Minimum Principle and prior knowledge of a specific AGV, the optimization problem can be solved at the millisecond level. However, the issue that remains to be solved is to find a first estimate of the adjoint variables for high-order systems. In real-world control tasks, it is not unusual for the numerical integration to produce infeasible trajectories in the state or adjoint space with poor initial guesses.

6 Conclusions

This paper reviews theoretical aspects of centralized and distributed MPC. Distributed MPC can handle complex systems with the price of requiring coordinated communication between subsystems. Then, the related MPC algorithms in autonomous ground vehicles are reviewed when operating as individuals and as multiple (cooperating) systems. The conclusion is that MPC can be used in such systems in terms of different scenarios, functions and missions. Finally, some open challenges are highlighted for future research to improve the performance of MPC for AGVs.