Next Article in Journal
Towards a Comprehensive Hydrodynamic Model for the Feasibility Study of Motor Yachts
Previous Article in Journal
Influence of Snow Redistribution and Melt Pond Schemes on Simulated Sea Ice Thickness During the MOSAiC Expedition
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Review

Overview of Path Planning and Motion Control Methods for Port Transfer Vehicles

1
Academy for Engineering and Technology, Fudan University, Shanghai 200433, China
2
Shanghai International Port (Group) Co., Ltd., Shanghai 200080, China
3
Department of Mechanical Engineering, The Hong Kong Polytechnic University, Hong Kong 999077, China
4
School of Automation and Intelligent Sensing, Shanghai Jiao Tong University, Shanghai 200240, China
*
Author to whom correspondence should be addressed.
J. Mar. Sci. Eng. 2025, 13(7), 1318; https://doi.org/10.3390/jmse13071318
Submission received: 9 June 2025 / Revised: 5 July 2025 / Accepted: 8 July 2025 / Published: 9 July 2025
(This article belongs to the Section Ocean Engineering)

Abstract

Recent advancements have been made in unmanned freight systems at ports, effectively improving port freight efficiency and being widely promoted and popularized in the field of cargo transportation in major ports around the world. The path planning and motion control of port transfer vehicles are the key technology for automatic transportation of vehicles. How to integrate cutting-edge unmanned driving control technology into port unmanned freight transportation and improve the level of port automation is currently an important issue. This article introduces the three-layer control operation architecture of unmanned freight systems in ports, as well as the challenges of applying path planning and motion control technology for unmanned freight vehicles in port environments. It focuses on the mainstream algorithms of path planning and motion control technology, introduces their principles, provides a summary of their current development situation, and elaborates on the improvement and integration achievements of current researchers on algorithms. The algorithms are reviewed and contrasted, highlighting their respective strengths and weaknesses. Finally, this article looks ahead to the development trend of unmanned cargo transportation in ports and provides reference for the automation and intelligent upgrading of unmanned cargo transportation in ports in the future.

1. Introduction

With the continuous advancement of autonomous driving technology, autonomous intelligent vehicles (AIVs) have gradually replaced automated guided vehicles (AGVs) to become a smarter and more flexible transportation solution in the logistics sector. Traditional AGVs rely on pre-programmed paths and centralized scheduling, limiting their operation to enclosed environments. In contrast, AIVs, leveraging artificial intelligence (AI) and multi-sensor fusion, possess dynamic environmental adaptability, enabling trackless autonomous navigation while supporting real-time decision-making and route optimization [1]. Capable of operating not only in enclosed settings but also in mixed traffic with manned container trucks, AIVs are well-suited for automating traditional transportation systems and have been widely adopted in industries such as industrial manufacturing [2], warehousing logistics [3], and port terminals [4]. Currently, more than 80% of global trade is transported by sea, with global container throughput exceeding 800 million twenty-foot equivalent unit (TEU) [5]. Automation, known for its high efficiency and strong safety, has become an inevitable trend in the transformation of global ports [6]. In port scenarios, AIVs are primarily used for transporting various types of containers and play a key role in bridging sea and land transport [7]. They contribute to easing port freight congestion, cutting energy consumption, and reducing labor costs, making them a crucial element in driving the automation and modernization of ports [8].
The main components of current mainstream unmanned freight systems in ports are shown in Figure 1. This system is composed of three parts: the scheduling control layer, the execution monitoring layer, and the perception–computation layer. Among them, the system for task scheduling, as the top-level system, is responsible for issuing scheduling control instructions based on port freight demands and setting up firewalls to prevent abnormal system operations caused by malicious attacks. The wireless communication system [9], motion control system [10], and safety monitoring system [11] jointly form the execution monitoring segment of the unmanned transport system. After receiving task instructions from the top-level system, the wireless communication system sends the instructions, the motion control system controls the AIV for transportation, and during the operation, the safety monitoring system monitors the working status of the entire link in real time. The monitoring data is uploaded to the task scheduling center to ensure the safety of the transport system.
The perception–computation segment consists of the environment perception system [12], the positioning and navigation system [13], and the path planning system [14]. The environment perception system detects the surrounding environmental information of the vehicles, combined with positioning information from the positioning and navigation system, provides references for the path planning system to dynamically adjust transport routes.
Based on the composition of the unmanned freight system in ports, it can be concluded that path planning and motion control provide control information for the AIV’s driving path, speed, and heading. Accurate and efficient path planning and motion control not only reduce the cost of unmanned freight and save transportation time but also ensure safe transportation [15,16]. Although autonomous driving technology has advanced rapidly in recent years, and algorithms for path planning and motion control have become increasingly mature in the field of autonomous driving, unique challenges remain in path planning and motion control within the complex environments of ports. Many well-established algorithms still need to be adapted and optimized according to the specific requirements of port scenarios. In port scenarios, the challenges of path planning primarily include large-scale operational areas [17] and complicated dynamic surroundings [18], along with substantial computational requirements [19]. For motion control, the main difficulties lie in achieving high-precision vehicle control [20] and adaptive control for varying loads and environmental conditions [21], as illustrated in Figure 2.
This paper provides a comprehensive discussion on the two core control technologies of port AIVs: algorithms for route planning and movement control. First, it introduces the challenges and difficulties faced in path planning and motion control within the port environment. Next, it conducts a comparative analysis of the two core control technologies, presenting the development and current applications of specific algorithms while evaluating their advantages and disadvantages. Finally, the paper offers an outlook on future AIV control technologies, exploring topics such as intelligent planning based on scene semantics and digital twin-based virtual simulation control, followed by a summary.

2. Path Planning Algorithms for Port AIVs

In the field of path planning, with the rapid development of multi-agent systems, path planning technology has become a core component in achieving intelligent navigation and collaborative operations [22]. The primary task of path planning is to find a feasible path from the start point to the goal point for AIVs in complex environments, while meeting the requirements of safety, efficiency, and dynamic adaptability [23]. Based on the scope and objectives of planning, path planning methods can be categorized into three major classes: global path planning, local path planning, and multi-vehicle cooperative planning. Global path planning focuses on generating globally optimal or suboptimal paths in known environments, relying on complete prior environmental information [24]. Local path planning, on the other hand, addresses real-time obstacle avoidance and path adjustments in dynamic environments, depending on local environmental information acquired through sensors [25]. Multi-vehicle cooperative planning further extends the dimension of path planning by enabling collaboration among multiple agents to resolve path conflicts, optimize resource allocation, and enhance overall system efficiency [26]. These three types of methods are not only independent but also complementary and synergistic in practical applications, collectively driving the development and innovation of path planning technologies.

2.1. Global Path Planning Method

Global path planning methods typically exhibit strong global search and optimization capabilities, enabling them to effectively avoid falling into local optima. These methods are suitable for scenarios where environmental information is known and relatively stable. In recent years, with the continuous development of graph search methods [27], numerical optimization methods [28], intelligent bionic methods [29], and intelligent learning optimization methods [30], significant progress has been made in the efficiency, accuracy, and applicability of global path planning.

2.1.1. Graph Search Method

Graph search methods use existing map information and obstacle position data to find a path from the starting point to the destination. Among them, Dijkstra and A* algorithms are representative examples of graph search methods [31]. The Dijkstra algorithm is designed to solve the single-source shortest path problem within both weighted directed and undirected graphs. It employs a greedy strategy, traversing the nearest unvisited vertex to the starting point and expanding its adjacent nodes until the destination is reached. The optimal path is identified by evaluating the cost from the starting point to the destination. However, this algorithm is inefficient due to its traversal-based approach [32]. The A* algorithm builds upon Dijkstra by introducing a distance heuristic function, improving pathfinding directionality while balancing efficiency and completeness [33]. Figure 3 demonstrates a path planning result using the A* algorithm. Obstacles are shown in black, the gradient ranging from blue to red indicates the cost from the starting point to every grid cell, and white indicates unvisited points during the algorithm’s computation. The accuracy of graph search-based path planning depends on the resolution of the map grid. Nevertheless, a substantial increase in the quantity of grid cells leads to a marked elevation in the computational load, making traditional graph search methods unsuitable for large-scale port operations. In order to address these limitations, researchers have modified graph search algorithms and integrated them with other methods to improve efficiency: Fransen et al. [34] proposed a dynamic path planning method tailored for dense, large-grid AIV systems. By updating the vertex weights in the graph representation and utilizing an improved A* algorithm combined with dynamic programming, they enhanced system throughput and recovery from vehicle deadlocks. Guo et al. [35] improved the Dijkstra algorithm using a priority queue method to generate conflict-free paths for AIVs, reducing computation time. They integrated the enhanced path planning algorithm with AIV task scheduling, effectively solving multi-AIV conflict-free path planning problems. Experimental results showed an average congestion rate of only 0.13% in scenarios involving 42 AIVs. Liu et al. [36] proposed a sector-based path planning method using traffic prediction. The A* algorithm was applied for local collaborative path planning within each sector. When combined with conflict-based search strategies, it enabled the generation of conflict-free paths for all robots in the sector simultaneously. Simulation outcomes indicated that the method possessed strong real-time performance, with computation times within 1.7 s. Zhou et al. [37] developed an AIV path optimization model combining ant colony optimization (ACO) and the Dijkstra algorithm. The ACO algorithm was initially employed for task sequencing, and then the Dijkstra algorithm was used for path planning. Simulation results indicated that this model reduced path lengths by 2–6% compared to traditional methods.

2.1.2. Numerical Optimization Method

In autonomous driving scenarios, numerical optimization techniques treat vehicle path planning as a multi-objective optimization problem with constraints. First, an objective function is defined to quantify the goal of the path planning problem, such as minimizing travel distance [38], minimizing travel time [39], or reducing energy consumption [40]. Simultaneously, a series of constraints, such as avoiding obstacles [41] or preventing multi-AIV collisions and deadlocks [42], are considered to construct a mathematical model. The optimal solution is then sought within this model framework. Algorithm 1 introduces the pseudo code of autonomous vehicle dynamic path planning based on convex constraints. The input consists of the port layout, the starting and destination points of the AIV, and the locations of obstacles. By updating the convex feasible domain, the algorithm evaluates whether the generated path is valid and plans a feasible path for the AIV. Numerical optimization methods can consider more constraints and optimization objectives, making them well-suited for large-scale port AIV operations, challenges like limitations in battery energy supply, and also providing assistance in AIV task allocation and scheduling [43]. Currently, researchers mainly focus on using convex constraints and model predictive methods to study numerical optimization-based path planning. Ren et al. [44] applied convex constraints to identify the core idea of the convex feasible set for optimization problems. In AIV dynamic path planning, obstacle avoidance and path re-planning constraints were convexified and addressed through numerical optimization. Simulation results showed that this method enabled the AIV to avoid obstacles within a predefined safety margin and proactively reduce speed during sharp turns, improving the safety and reliability during AIV operations. Liu et al. [45] proposed an optimization problem with the objectives of minimizing total travel time and path conflicts. They converted the integrated optimization problem into a quadratic assignment problem (QAP), and then into a linear programming (LP) problem, using an approximate optimal greedy algorithm to significantly reduce computational complexity. Experiments demonstrated that this method improved system performance by over 20% while ensuring real-time performance and scalability. Wu et al. [46], relying on model predictive control (MPC) theory, designed a dynamic path planning control system that predicted the movement of mobile obstacles, enabling long-range, highly accurate collision prevention. Experimental results showed that this collision avoidance method performed well in preventing collisions and ensured smooth AIV operation. Ren et al. [47] combined dominance principles and sub-dimensional expansion to create a Multi-objective M* algorithm (MOM*). This algorithm effectively calculates a set of Pareto optimal solutions for AIV multi-objective search problems, balancing suboptimal solutions with computational efficiency. Numerical experiments confirmed that MOM* is thorough, exhibiting higher planning success rates, more planned paths, and shorter planning times compared to existing algorithms.
Algorithm 1. AIVs path planning based on convex constraints in numerical optimization
Input: Port layout information, initial position coordinates of the AIV, target position coordinates of the AIV, static or dynamic obstacle locations
Output: The optimal path from the start to the destination (sequence of path points).
1: Function AIVDynamicPathPlanning(portLayout, AIVStart, AIVGoal, obstacles):
2: convexRegions = GenerateConvexRegions(portLayout, obstacles)
3: currentPath = InitializePath(AIVStart, AIVGoal, convexRegions)
4: timeStep = 0
5: While NotReachedGoal(AIVStart, AIVGoal):
6:   dynamicObstacles = UpdateDynamicObstacles(timeStep)
7:   feasibleRegions = UpdateFeasibleRegions(convexRegions, dynamicObstacles)
8:   optimalPath = SolveOptimizationProblem(AIVStart, AIVGoal, feasibleRegions)
9:   If Not IsPathValid(optimalPath, dynamicObstacles):
optimalPath = ReplanPath(AIVStart, AIVGoal, feasibleRegions)
10:   AIVStart = MoveAlongPath(optimalPath, timeStep)
11:   timeStep + = 1
12: Return optimal Path

2.1.3. Intelligent Bionic Method

In recent years, with the rapid development of artificial intelligence technology, bio-inspired path planning algorithms have gradually become a research hotspot. These algorithms simulate the intelligent behaviors of biological groups in nature, such as genetics, evolution, foraging, and migration, providing new approaches to solving path planning problems in complex environments. Common intelligent bionic path planning algorithms are: genetic algorithm (GA) [48], ACO algorithm [49] and grey wolf optimization (GWO) algorithm [50]. Algorithm 2 introduces a multi AIV path planning algorithm based on genetic algorithm. The algorithm optimizes by simulating biological principles such as gene evolution, natural selection, and inheritance. Through iterative optimization, individuals with higher fitness are selected, new paths are created through crossover, and diversity is enhanced through mutation. The path planning result is returned after evaluating the fitness of the new population and meeting the termination condition. Liu et al. [51] designed a dual-layer GA based on a spatiotemporal greedy strategy to solve the port AIV scheduling and path planning problem. The upper layer utilizes GA for task scheduling, while the lower layer applies greedy strategies and collision avoidance techniques for path planning. Experimental results show that this algorithm performs effectively in large-scale transportation task scenarios.
The ACO algorithm simulates the foraging behavior of ants, where they select paths and transfer information through pheromones. In the initial state, ants are randomly placed, and they choose paths based on pheromone concentration and heuristic information. After completing a path, each ant updates the pheromone based on the path quality, repeatedly constructing paths and updating pheromones until termination conditions are met. Li et al. [52] proposed an improved multi-step ACO algorithm based on terminal distance indicators (TDI-MSACO). The algorithm uses MSACO to enhance the ants’ movement flexibility, resulting in shorter paths. Additionally, TDI is used to replace pheromone concentration, reducing the convergence time of MASCO. In a 20 × 20 grid model, compared to traditional ant colony algorithms, TDI-MSACO reduced the number of iterations by 7 and the optimal path length by 2 m. When the model’s complexity increased to a 50 × 50 grid, TDI-MSACO reduced the shortest path length by 10 m compared to traditional ant colony algorithms and exhibited significantly faster convergence. Wang et al. [53] addressed inefficiencies and local optimum issues in path planning caused by complex 3D terrains by proposing a parallel chaotic search method using multi-colony ants (MACPCS). They also designed a shortsighted evaluation model to assess the slope variations of 3D terrain. By allowing each ant to search globally with different parameters, the algorithm avoids local optima and improves the efficiency of path planning in 3D terrain. Simulation experiments showed that, under the same conditions, MACPCS reduced energy consumption by 6% and 8% compared to A* and RRT algorithms, respectively, and reduced the path length by 2% and 4%.
The GWO algorithm simulates the social hierarchy and hunting behavior of gray wolves. The α, β, and δ wolves represent the best solutions and guide other wolves (candidate solutions) in their search. The algorithm begins by randomly generating a wolf population, then updates the positions of other wolves based on the positions of the α, β, and δ wolves. By continuously adjusting the wolf pack’s positions, the algorithm gradually converges to the optimal solution, repeatedly hunting and updating positions until the termination condition is met, resulting in an optimal path. Liu et al. [54] proposed an improved gray wolf optimization (IGWO) algorithm to address the slow convergence speed and susceptibility to local optima in the original GWO algorithm. The IGWO algorithm incorporates the lion optimization algorithm, introducing an interference salary during the update of the α, β, and δ wolf positions, which allows the wolves to have proactive search capabilities. Additionally, dynamic weights are added during the position update process of the wolves to enhance diversity. In path planning experiments, compared to the traditional GWO algorithm, IGWO demonstrated a 6% improvement in average convergence speed in both simple environments (21 obstacles) and complex environments (51 obstacles). Zhang et al. [55] improved the traditional GWO algorithm for the application of mobile robots in complex environments, integrating it with self-powered sensor technology to optimize path planning and energy-driven methods for mobile robots. Simulation experiments showed that, when compared to the RRT and the improved bee colony algorithm (IMABC), the optimized algorithm achieved a 14.84% better performance. The pareto optimal solution boundary plot of the IGWA algorithm closely approached the ideal optimization curve for the corresponding function, and the distribution of solutions was more uniform, demonstrating that the IGWA algorithm has strong optimization capabilities for multi-objective problems.
Algorithm 2. AIVs path planning based on genetic algorithm
Input: Port layout information, number of AIVs, list of initial positions of AIVs, list of target positions of AIVs, list of obstacle positions;
Output: List of optimal paths for each AIV.
1: Function GAPathPlanning(portLayout, numAIV, AIVStartPositions, AIVGoals, obstacles):
2:   population = InitializePopulation(numAIV, AIVStartPositions, AIVGoals, portLayout, obstacles)
3: for generation in 1 to maxGenerations:
4:   selectedPopulation = Selection(population)
5:   crossedOverPopulation = Crossover(selectedPopulation)
6:   mutatedPopulation = Mutation(crossedOverPopulation)
7:   for individual in mutatedPopulation:
8:     fitness = EvaluateFitness(individual, obstacles)
9:   population = UpdatePopulation(population, mutatedPopulation)
10:   bestSolution = GetBestSolution(population)
11:   if CheckConvergence(bestSolution):
12:     break
13: return bestSolution

2.1.4. Intelligent Learning Optimization Method

With the ongoing advancement of computing power, intelligent optimization methods have seen significant progress and are widely applied in the field of path planning. These methods take the vehicle’s current state and surrounding environmental information as input and output the path planning results based on the given constraints [56]. Intelligent learning optimization methods have strong learning abilities and can achieve multi-objective constrained optimization. Common intelligent learning optimization algorithms include: deep reinforcement learning (DRL) [57], particle swarm optimization (PSO) [58]. DRL combines reinforcement learning with deep learning, enabling agents to learn optimal strategies by interacting with the environment. The agent takes actions based on the current state, receives rewards, and aims to maximize cumulative rewards. DRL uses deep neural networks to approximate value or policy functions, handling high-dimensional spaces. The PSO algorithm is a swarm intelligence-based optimization method that finds optimal solutions through collaborative search by a swarm of particles. Algorithm 3 introduces the pseudocode of PSO path planning method. The algorithm initializes a group of particles, each representing a potential path solution. Particles evaluate solution quality using a fitness function and track individual and global best solutions. Based on these, particles update their velocities and positions, gradually converging toward the optimum. The process iterates until convergence criteria are met, and the global best solution is returned. In recent years, researchers have introduced various fusion and enhancement methods for intelligent learning optimization path planning algorithms: Li et al. [59] proposed an algorithm that integrates long short-term memory (LSTM) neural networks and reinforcement learning for AIVs transporting hazardous materials at ports. This ensures that AIVs transporting dangerous goods can effectively reach their destination while avoiding ordinary AIVs. The method uses LSTM’s ability to transmit information over long time sequences to predict the trajectories of regular AIVs and then employs reinforcement learning to plan the routes for hazardous material AIVs. Experimental tests show that the efficiency of avoidance improved by 3.11%. Zhang et al. [60] proposed an improved algorithm to address the issues of local minima and premature convergence in traditional PSO. This algorithm prevents the PSO from getting trapped in local minima by using inertial weights and localized improvements. It also uses fitness variance to measure particle diversity, which helps overcome the premature convergence problem. Comparing this algorithm with traditional PSO and A* algorithms shows that it outperforms both in terms of path planning length and computation time and exhibits better robustness.
Algorithm 3. AIVs path planning based on particle swarm optimization algorithm
Input: Port layout information, number of AIVs, list of initial positions of AIVs, list of target positions of AIVs, list of obstacle positions;
Output: List of optimal paths for each AIV.
1: Function PSOPathPlanning(portLayout, numAIV, AIVStartPositions, AIVGoals, obstacles):
2:  particles = InitializeParticles(numAIV, AIVStartPositions, AIVGoals, portLayout, obstacles)
3:  globalBest = FindGlobalBest(particles)
4:  for iteration in 1 to maxIterations:
5:   for particle in particles:
6:    fitness = EvaluateFitness(particle, obstacles)
7:    UpdatePersonalBest(particle)
8:    UpdateGlobalBest(particle, globalBest)
9:    UpdateVelocity(particle, globalBest)
10:    UpdatePosition(particle)
11:    if CheckConvergence(globalBest):
12:    break
13: return globalBest

2.2. Local Path Planning Method

After the global path planning method determines the overall path from the start to the target point, the local path planning method is responsible for adjusting and optimizing the path in real-time during the robot’s or vehicle’s actual motion, based on the real-time environmental information sensed, such as obstacles and dynamic changes [61]. Unlike global path planning, local path planning focuses more on real-time responsiveness and dynamic adaptability, ensuring safe and efficient navigation in complex, dynamic environments [62]. Currently, the mainstream local path planning methods primarily include artificial potential field methods [63], curve interpolation methods [64], and sampling-based methods [65]. These methods are often combined with global path planning to form a “global–local” two-layer planning framework, which ensures global optimality while also being flexible to adapt to changes in the local environment. In addition, the improvement and innovation of local path planning methods are also supplemented

2.2.1. Artificial Potential Field Method

The principle of the artificial potential field (APF) method originates from the concept of potential fields in physics. Figure 4 illustrates the basic principle of APF-based path planning. In this method, the vehicle moves in a virtual potential field where obstacles exert repulsive forces and the target point exerts an attractive force. The interaction between the repulsive and attractive forces guides the vehicle’s movement [66]. The APF method is simple, requires fewer parameters, and is easy to implement, making it widely used in collision avoidance and autonomous driving path planning [67]. Recent studies have aimed at enhancing the traditional APF method by tackling issues like local minima, often through the integration of APF with predictive control or deep learning techniques. Szczepanski et al. [68] introduced future motion prediction into the APF, enabling the AIV to predict and evade obstacles, solving the path oscillation problem of the traditional APF and reducing energy consumption. They also proposed placing virtual obstacles in key areas to provide additional repulsive forces, which helps avoid local minima. Simulation results showed that, compared to the original algorithm, this approach generated smoother motion trajectories, reducing energy consumption by 21.4%, shortening the path length by 8.73%, and cutting the time to reach the destination by 40.23%. Chen et al. [69] addressed the path smoothness and safety issues of AIVs in port environments by proposing a path planning model based on the artificial potential field and twin delayed deep deterministic policy gradient (APF-TD3) framework. This model uses the AIV’s position as input data for the reinforcement learning algorithm, incorporates the potential field within the TD3 algorithm, and calculates the optimal strategy for each step to derive the entire path. In the same experimental setting, the total lengths of the paths planned by the APF-TD3 algorithm, the APF algorithm, the APF deep deterministic policy gradient (APF-DDPG) algorithm, and the rapidly exploring random tree (RRT)-based APF algorithm were 496.389 m, 501.062 m, 524.168 m, and 521.625 m in sequence. The outcomes of the experiments verified that the method put forward could efficiently cut down the length of the planned path. Wang et al. [70] proposed a multi-AIV online coverage path planning method based on the APF (APF-CPP), which uses the principles of attraction and repulsion in the APF to promote decentralized coverage between AIVs and assigns a unified motion direction to reduce turning frequency. This results in more efficient task allocation and deadlock resolution. With the growth in the number of robots, the advantages of APF-CPP in task completion time and total coverage path length become more apparent. Compared to traditional methods, APF-CPP reduces completion time by 17.25% and the total coverage path length by 32.18%.

2.2.2. Curve Optimization Method

The intensive computation of graph search methods results in low computational efficiency. Moreover, for port heavy-load AIV path planning, it is essential to minimize the turning angle and frequency of turns [71]. The path planning of graph search methods struggles to meet these requirements. To address this, researchers have presented the curve interpolation approach [72] and curve fitting method [73]. The principle of curve interpolation is as follows: based on the traffic environment and the start and end points, a selection of discrete nodes is made from feasible paths. These nodes are then used to fit a continuous and smooth curve, resulting in a transportation path. Therefore, the selection of nodes is critical for the curve fitting process [74]. It is evident that the lane change trajectory becomes significantly smoother and more continuous after curve fitting, making it well-suited for the transport operations of port heavy-duty AIVs. The curve fitting method does not necessarily pass through all the nodes, but instead generates an optimal approximation curve based on the data points, focusing on fitting the overall trend. It can be applied to more complex operation paths, such as turning and reversing, and is widely used in port vehicle applications [75].
Currently, curve interpolation methods primarily use Bézier curves and B-spline curves for fitting. Chen et al. [76] proposed a path and velocity planning method for intelligent vehicle lane changes and collision avoidance using cubic 3D Bézier curves. This method uses cubic 3D Bézier curves to establish a relationship between the path and real-time velocity, performing nonlinear optimization on the coordinates of path nodes based on dynamic constraints and driving requirements. Simulation results show that the method significantly reduces lateral acceleration at a speed of 72 km/h during lane changes, improving vehicle driving stability. You et al. [77] adopted a hybrid approach of quadratic and cubic Bézier curves for trajectory fitting, enabling the optimal selection of control points according to the specified maximum curvature requirement. Simulation results demonstrate that the quadratic Bézier curve is only C1 continuous, while the cubic Bézier curve is C2 continuous, producing a smoother lane change path. The path planning algorithm using cubic Bézier curves performs better. Bulut [78] addressed the limitations of traditional geometric-based path planning methods in handling complex obstacle environments by proposing a general framework that uses quintic triangular Bézier curves with two shape parameters and C3 continuity for path planning. Simulation experiments demonstrated that, in the same scenario, the path curvature variation range of this method was reduced by 75% compared to traditional methods, and the vehicle travel time was shortened by 20%. Wu et al. [79] proposed a path optimization algorithm based on cubic B-spline curves and gradient descent. The algorithm calculates the curvature cost of each path point in the current path sequence, forming an overall objective function. By using the gradient of the objective function, coordinates are iteratively adjusted until convergence to the optimized path. Simulation results revealed that, in comparison to the Hybrid A* algorithm, the average minimum curvature of the path decreased by 0.005 m−1, greatly enhancing the smoothness of the generated path.
In motion-constrained path planning, the curve fitting method is often used to generate efficient, smooth paths that comply with system dynamics constraints through Dubins curves and Reeds–Shepp curves. In response to different scenario requirements, researchers have proposed various innovative fusion methods: Yang et al. [80] proposed a collaborative framework integrating Dubins path planning with an improved virtual target guidance strategy. By using Dubins curves to plan transition paths between sub-regions and combining the guidance strategy, the framework achieves autonomous robot recovery functionality. Simulations show that the path generated by this method has continuous and smooth curvature, demonstrating significant engineering value in port area AIV path planning. Essuman et al. [81] designed a two-stage optimal trajectory planning method based on Reeds–Shepp curves. In the first stage, incremental sampling combined with Reeds–Shepp curves quickly generates feasible paths; in the second stage, dual reconstruction transforms non-convex obstacle constraints into convex optimization problems to achieve multi-obstacle avoidance. Experimental data shows that compared to single-stage planning, this method reduces time by 61.4% in narrow areas and improves angular positioning calculation efficiency by 70.3%, significantly enhancing adaptability in complex environments. Yao et al. [82] proposed an adaptive parking algorithm based on multi-segment arc fitting. This method replaces the traditional Dubins curve or quintic polynomial with a segmented arc combination, significantly reducing computational complexity while ensuring path smoothness. Real-world tests show that it supports parking operations from any initial vehicle pose and has robust response capabilities to dynamic obstacles.

2.2.3. Sampling-Based Method

The core idea of sampling-based path planning is to randomly sample the AIV’s workspace to obtain landmark points, connect these landmark points to form a path, and evaluate the generated path based on planning requirements. The path is then iteratively optimized and filtered until a final path that meets the requirements is established [83]. The advantage of sampling methods is that they consider global map information while avoiding the complexity of a full map search [84]. Common sampling methods include the probabilistic roadmap method (PRM) [85] and the rapidly-exploring random tree (RRT) [86]. Figure 5 shows a schematic diagram of RRT path planning results, where a feasible path from the start to the goal is found by generating a random tree iteratively. In path planning using sampling methods, Novosad et al. [87] proposed a clustering-topology PRM algorithm to find multiple different path planning results in a 3D cluttered environment, improving the effectiveness of path planning in narrow passage environments. This method clusters the dense initial sampled roadmap and creates a sparse roadmap with centroids of the clusters as vertices. This simplified path graph facilitates fast path searching. By adjusting parameters, a balance can be achieved between computation time and the number of paths found. In the same testing environment, this method improved the probability of discovering all distinct paths by 20% compared to existing methods. Jiang et al. [88] first proposed two metrics to quantify AIV reliability: state maneuver reliability (SMR) and mission maneuver reliability (MMR). Based on this, they proposed a reliable and robust rapidly-exploring random tree (R2-RRT*) algorithm to find the optimal path that satisfies reliability requirements and travel time. The proposed model and algorithm were validated through experiments. Ma et al. [89] proposed a risk-based bidirectional search sampling algorithm (Bi-Risk-RRT) to achieve efficient AIV navigation in dynamic environments. Based on the RRT using forward tree search, the reverse tree is used as a heuristic algorithm. In the first stage, both the forward and reverse trees expand towards each other, and in the second stage, the forward tree grows along the heuristic trajectory generated by the reverse tree. In simulations, compared to the traditional Risk-RRT algorithm, Bi-Risk-RRT reduces the path generation time by 33%, while performing similarly to Risk-RRT in terms of average navigation time and average trajectory length. Zhang et al. [90] proposed the neural-sampling rapidly-exploring random tree (NS-RRT*) algorithm, a global path planning method for AIVs with fast convergence properties. The algorithm uses a two-layer approach: the first layer uses the target-area adaptive RRT* (TAA-RRT*) algorithm to build a path collection containing noise, and the second layer trains a deep neural network to learn the relationship between states and sampling strategies. The third layer uses the learned model to guide RRT* sampling. Numerical and experimental results show that this method reduces the number of sampled points by 96.3% compared to the classic RRT algorithm, proving its high efficiency and real-time performance.

2.2.4. Improvements and Innovations in Local Path Planning

In recent years, researchers have continuously proposed and improved local path planning algorithms, integrating multidisciplinary methods and innovative algorithm designs to continuously break through technical bottlenecks in complex environment adaptability, computational efficiency, and constraint satisfaction capabilities, further promoting the development of path planning: Fan et al. [91] proposed a method combining dynamic programming and spline-based quadratic path planning. This approach constructs a scalable and adjustable framework that can simultaneously handle traffic rules, obstacle decision-making, and path smoothness. It is suitable for both high-speed and low-speed driving scenarios. The system has been deployed in Baidu Apollo’s autonomous vehicles, where it underwent 3380 h of testing, covering approximately 68,000 km (42,253 miles). During testing, the system effectively considered safety, comfort, and scalability, achieving good application results. Ding et al. [92] proposed a new unified spatiotemporal semantic corridor (SSC) structure to address the limitations of semantic elements in autonomous vehicles within complex environments. This structure provides a common abstract level for different semantic elements and adjusts the effects of different combinations of semantic elements to achieve stable and scalable behavior. Additionally, they abstracted the local path planning problem as a quadratic programming formulation. By using convex hulls and sagittal characteristics parameterized by piecewise Bézier curves, the method theoretically ensures the safety of the trajectory and satisfaction of constraints. Experimental results show that this method fully utilizes vehicle maneuverability, guarantees collision avoidance in chaotic environments, and ensures accurate parking at high driving speeds (13 m/s). Li et al. [93] abstracted the path planning problem for heavy-duty autonomous vehicles as a mixed-integer nonlinear programming scheme (C-MINLP) with conditional constraints, and developed a two-stage solution framework consisting of coarse and fine search phases. In the coarse search phase, they proposed an enhanced hybrid A* search algorithm for global optimality, while in the refinement stage, the coarse trajectory was further corrected, simplifying the C-MINLP to a small-scale NLP for easier solving. Simulation results indicated that the enhanced hybrid A* search algorithm improved the average computation frequency by 33 times and reduced the average computation overhead by 49% compared to the traditional hybrid A* algorithm. Li et al. [94] addressed the optimization problem of autonomous driving in chaotic environments by proposing an adaptive pure pursuit (APP) planner. This planner generates feasible paths by simulating virtual vehicle closed-loop tracking control and uses adaptive refinement steps to address obstacles encountered along the derived path. During the computation, the APP planner introduces zero-degree-of-freedom calculations, significantly improving computation speed and solving the “curse of dimensionality” problem. Simulation comparison experiments showed that the APP planner achieved path planning success rates of 68.1% and 86.3% higher than the dynamic programming (DP) path planner and the lightweight iterative optimization method (LIOM), respectively, with average computation time reduced by nearly 400 ms and 900 ms. These studies have systematically improved the path decision-making ability of autonomous driving in complex scenarios, from algorithm theory innovation to engineering application verification. They provide diversified technical paths for solving key problems such as dynamic obstacle avoidance, high-speed trajectory optimization, and adaptation to different vehicle models, promoting local path planning technology to move towards safer, more efficient, and more robust directions.

2.2.5. Combination of Global and Local Path Planning

The combination of global and local path planning in autonomous intelligent vehicles (AIVs) is a core strategy for handling complex dynamic environments. Global path planning, based on complete environmental information, generates an optimal path from start to goal—minimizing distance or energy consumption—but struggles to react to obstacle changes in real time. Local path planning, in contrast, relies on sensor feedback to swiftly respond to dynamic obstacles, complementing the global planner’s broader perspective. Together, they ensure both goal-oriented guidance and adaptability to real-world uncertainties, thus balancing “global optimality” with “real-time responsiveness.” Wang et al. [95] proposed a dynamics-constrained global–local (DGL) hybrid path-planning scheme for autonomous vehicles. The global planner ensures waypoints comply with safety constraints and optimizes the trajectory’s smoothness, while the local planner handles near-and-far obstacles and enforces emergency-stop conditions based on vehicle dynamics. Compared to traditional methods, DGL achieves macro-level path guidance via waypoint sequences and real-time obstacle avoidance and constraint adjustment through dynamic feedback, preventing the generation of infeasible paths. Wen et al. [96] introduced the three-layer E3Mop framework, integrating global planning, local planning, and time-optimal velocity planning. During operation, the global planner generates a base waypoint sequence for AIV motion; when a local planner detects an obstacle, it inserts virtual waypoints into the global trajectory to avoid it and then returns to the original sequence. For velocity control, the planner uses current speed and acceleration constraints to define a feasible set that limits speed changes, ensuring physically achievable adjustments. Versus traditional methods, E3Mop reduced the number of extended states by 66.21%, cut planning time to one-third, and shrank graph size to 33.87%. Li et al. [97] presented the forward-search optimization (FSO) and sub-goal-based hybrid path-planning (SHPP) framework. Their hierarchical strategy combines global optimization and local smoothing, producing paths approximately 10.2% shorter than original search-based routes, with maximum curvature below 0.15 and around 30% less mechanical wear.

2.3. Multi-Vehicle Cooperative Planning

Due to the complex characteristics of port operations—such as a high density of vehicles, intricate work areas, diverse task requirements, and strict timeliness constraints—single-AIV path planning can no longer meet the demands of efficient operations. This has necessitated the development of multi-vehicle collaborative path planning algorithms. These algorithms are designed to holistically optimize the travel trajectories of multiple autonomous intelligent vehicles (AIVs), leveraging intelligent cooperative scheduling to prevent collisions and achieve optimal task allocation and path optimization [98]. The core objective is to maximize overall transportation efficiency while adhering to critical port constraints, including loading/unloading point layouts, road capacity limitations, and vehicle speed regulations.
Moreover, a scientifically designed AIV path planning system not only minimizes equipment energy consumption to foster sustainable port development [99] but also streamlines the entire ship-loading process by optimizing container loading/unloading sequences [100]. Regarding the “re-entry/re-exit” characteristic in AIV task execution—whereby new tasks are dynamically assigned in the vicinity as an AIV nears or completes its current task—this approach significantly reduces idle travel time. In collaborative multi-quay crane loading/unloading scenarios, the path planning further integrates a “simultaneous loading–unloading” strategy: for instance, an AIV proceeds directly from completing a loading task at quay crane A to executing an unloading task at quay crane B. Such path optimization designs further minimize equipment idle time and enhance operational efficiency. Advanced optimization methodologies, including the multi-agent pathfinding (MAPF) algorithm [101], distributed model predictive control (DMPC) algorithm [102], and leader–follower collaboration (LFC) algorithm [103], are employed to conduct global search and optimization of multi-vehicle routes. This ensures each AIV follows an optimal trajectory—completing individual transport tasks while coordinating with fleet members to minimize waiting times and congestion. The implementation of these algorithms significantly enhances the smoothness and timeliness of port logistics, reduces operational costs, and strengthens the port’s overall competitive edge.

2.3.1. Multi-Agent Path Finding Algorithm

The MAPF algorithm coordinates the movement of multiple agents to find collision-free paths from their start positions to their targets. Algorithm 4 provides pseudocode for MAPF: The algorithm first initializes paths for each agent and creates a priority queue to manage the agents to be processed. It iteratively optimizes the path for each agent. For the current agent, the algorithm checks whether it has reached its target; if not, it retrieves feasible neighboring nodes from its current position. For each neighbor, the algorithm checks if moving to that node would cause a collision with other agents’ paths. If no collision is detected, the agent’s path is updated, and the agent is re-added to the priority queue for further optimization. This process repeats until all agents find collision-free paths or termination conditions are met. Finally, the algorithm returns the optimal path for each agent. Since the MAPF algorithm was proposed, researchers have continuously optimized and improved it: Honig et al. [104] improved the existing MAPF planners by introducing an execution framework independent of the underlying MAPF solver. This framework ensures that AIVs can operate robustly in environments with dynamic obstacles and unforeseen slowdowns of other AIVs. Moreover, this execution framework does not require communication between the AIVs and the centralized planner. In a working scenario involving fifty robots, six hundred shelves, and eight workstations, simulation results show that the proposed MAPF execution framework improves the average site utilization by approximately 10% compared to the basic method. Skrynnik et al. [105] addressed the partially observable MAPF (PO-MAPF), where each AIV can only observe obstacles and other agents within a limited field of view, and proposed two solution strategies: a heuristic-based search method and a reinforcement learning-based method. Simulation results demonstrate that a hybrid strategy combining both methods performs optimally, generalizing well to unseen maps and problem instances. The hybrid algorithm outperforms state-of-the-art reinforcement learning and imitation-based multi-agent pathfinding methods, including pathfinding with reinforcement and imitation learning v2 (PRIMAL2) and prioritized communication learning (PICO). Hua et al. [106] applied the life-long evaluation-based large neighborhood search (LEB-LNS) algorithm to address the challenges of planning paths across different priority levels in life-long adaptive multi-priority multi-agent pathfinding (LAMP-MAPF) under limited computation time. Through simulations on the map of a distribution sorting center, along with real-world experimental validation, they demonstrated the effectiveness of the LEB-LNS algorithm. Experimental results showed that compared to the rolling-horizon collision resolution (RHCR) method, throughput increased by 70.1%, and the delay rate was reduced by 58.2%.
Algorithm 4. AIVs path planning based on multi-agent path finding algorithm
Input: Grid map, list of agents with start positions, list of target positions, list of obstacles;
Output: List of collision-free paths for each agent.
1: Function MAPF(gridMap, agents, targets, obstacles):
2:  paths = InitializePaths(agents, targets)
3:  openSet = InitializeOpenSet(agents)
4:  while openSet is not empty:
5:   agent = openSet.pop()
6:   currentNode = agent.currentNode
7:   if currentNode == agent.target:
8:    continue // Agent has reached its target
9:   neighbors = GetNeighbors(currentNode, gridMap, obstacles)
10:   for neighbor in neighbors:
11:    if IsCollisionFree(neighbor, paths, agent):
12:     UpdatePath(agent, neighbor)
13:     openSet.push(agent)
14:     break
15: return paths

2.3.2. Distributed Model Predictive Control Algorithm

The DMPC algorithm achieves global control objectives by coordinating local optimizations of multiple subsystems. Algorithm 5 introduces the pseudocode of DMPC: The algorithm first initializes the states for each subsystem and performs iterative optimization over the prediction horizon. For each subsystem, it solves a local MPC problem based on the current state, local cost function, and constraints to obtain the optimal control input. The subsystem then broadcasts its optimal control input to neighboring subsystems and receives optimal control inputs from them. The subsystem updates its state according to the system dynamics model. This process repeats over the prediction horizon until optimization is completed for all time steps. Finally, the algorithm returns the optimal control input sequence for each subsystem, achieving coordinated control of the global system. In recent years, researchers have also proposed various improvements to the DMPC algorithm: Mi et al. [107] addressed the problem of cooperative control of dynamically decoupled agents with resource constraints by proposing a self-triggered mechanism combined with DMPC. This method incorporates communication costs into the cost function, achieving an ideal trade-off between control performance and communication cost. The method also establishes enough conditions for the design parameters related to the predicted states of neighboring AIVs, ensuring the stability of the entire system. Simulation results show that the proposed self-triggered DMPC (ST-DMPC) outperforms the traditional time-triggered DMPC (TT-DMPC) by 3.12% in terms of performance metrics. Wei et al. [108] proposed a self-triggered min–max distributed MPC method to solve the formation problem of asynchronous nonlinear multi-agent systems (MAS) with external disturbances, parameter uncertainties, and bounded time-varying communication delays. At the trigger moment, the method solves a local min–max optimization problem using the local system state and the predicted states of neighbors to determine the next trigger moment and broadcasts its predicted trajectory to nearby agents. Numerical simulations demonstrate that this method significantly reduces communication load compared to periodic DMPC, with minimal impact on closed-loop performance. Cai et al. [109] addressed the challenges of complex dynamic coupling, multi-control inputs, and computational burdens in AIVs by proposing a multi-agent cooperative control architecture based on cooperative distributed model predictive control (CO-DMPC). By defining predicted, hypothetical, and optimal trajectories for states and control inputs, the method provides conditions for coupling information exchange between agents and evaluates the impact of different agents on global performance metrics. Simulation results show that compared to centralized control, this method reduces the maximum tracking error by 0.17 m and increases the maximum lateral velocity by 0.09 m/s, significantly improving tracking accuracy and stability.
Algorithm 5. AIVs path planning based on distributed model predictive control algorithm
Input: System dynamics, local cost functions, constraints, initial states, prediction horizon N;
Output: Optimal control inputs for each subsystem.
1: Function DMPC(systemDynamics, costFunctions, constraints, initialStates, N):
2:  for each subsystem i:
3:  xi(0) = initialStates[i]
4:  for k = 0 to N-1:
5:   ui*(k) = SolveLocalMPC(xi(k), costFunctions[i], constraints[i])
6:   Broadcast ui*(k) to neighboring subsystems
7:   Receive uj*(k) from neighboring subsystems
8:   xi(k+1) = UpdateState(xi(k), ui*(k), uj*(k), systemDynamics)
15:  return {ui*(k)}i,k

2.3.3. Leader–Follower Collaboration Algorithm

The leader–follower collaboration (LFC) algorithm designates one or more leader vehicles and enables follower vehicles to adjust their behavior based on the leader’s state (position, angle) and the distance to the leader using a relative-state feedback mechanism, thereby achieving coordinated motion, as shown in Figure 6. Additionally, the algorithm incorporates a local path planning method to handle situations where follower vehicles encounter dynamic obstacles or the leader vehicle fails. In recent years, researchers have improved the computational time and efficiency of LFC: Ning et al. [110] designed a protocol for tracking the leader’s state within a fixed time, based on AIV observers and a constructed nonlinear manifold. This protocol integrates with a linear manifold to ensure leader–follower consensus under any initial conditions, solving the singularity problem. They conducted formation control experiments with six wheeled robots, and the results showed that the tracking error converged to zero in 168 s, and the formation control was achieved around 221 s, demonstrating the effectiveness of the protocol. An et al. [111] designed a reference controller for nonlinear multi-agent systems under unreliable communication conditions, specifically for collision-free leader–follower coordination (CF-LFC). To address transient coordination errors caused by irregular communication topology switches and agent collisions, they proposed an event-triggered reference controller. This controller allows the AIV to perform leader–follower tasks when the tracking error satisfies closed-loop performance requirements. However, if the tracking error fails to meet the requirements, the task is temporarily abandoned, focusing instead on collision avoidance. They proved, using a heterogeneous switched Lyapunov function, that this controller can achieve CF-LFC even in the presence of unreliable communication. Wang et al. [112] addressed the issue of time-varying delays in leader–follower nonlinear multi-agent systems by constructing switching topologies in the form of general uncertain Markov jump processes. This approach minimizes the impact of uncertainties and data loss in information transmission. Compared to previous methods, this approach improves practicality, reduces conservatism, and effectively decreases network communication burden.

2.3.4. AIV Task Scheduling Algorithm

In addition to multi-vehicle collaborative path planning, task scheduling for AIVs has also become a subject of in-depth research by scholars in recent years. Efficient and rational AIV task scheduling serves as a core component for enhancing port transportation efficiency and reducing labor and operational costs. Its scheduling logic must integrate the complex operational processes of ports, dynamic task demands, and equipment collaboration mechanisms to form a systematic intelligent decision-making system. Existing research typically abstracts AIV task scheduling as a mixed-integer linear programming (MILP) or combinatorial optimization problem [113]. For dynamic scenarios, researchers have introduced reinforcement learning frameworks, such as the DDPG algorithm, transforming task scheduling into a Markov decision process (MDP) to achieve real-time resource allocation and path adjustment. Wu et al. [114] constructed a mathematical model aimed at minimizing total energy consumption for multi-AIV scheduling problems, considering constraints such as delay, bandwidth, and power. They solved the problem using a two-step iterative algorithm that combines convex optimization for the resource allocation sub-task (RA) and MILP transformation for the offloading allocation sub-task (OA). Simulation results show that compared with traditional Mobile Edge Computing (MEC) offloading, this method reduces total energy consumption by 20% to 35% and stabilizes within six iterations, demonstrating strong adaptability to dynamic scenarios. Wei et al. [115] modeled the multi-task scheduling problem as a simplified MDP, realizing task allocation decisions in dynamic environments by defining states, actions, reward functions, and transition mechanisms. By integrating self-attention mechanisms, multimodal network structures, and invalid action masking, they enhanced the decision-making efficiency of the algorithm in dynamic scenarios. Experimental results verify that this method reduces energy consumption by 35% to 65% compared with other methods, effectively alleviates traffic congestion, and its joint scheduling strategy exhibits strong robustness. Li et al. [116] established a dynamic mathematical model for AIV multi-task scheduling that considers real-time special cases, integrating multi-dimensional costs including travel costs, AIV operation costs, and operation time factors. They introduced an adaptive discrete invasive weed optimization (DIWO) algorithm to improve solution efficiency in dynamic scenarios through parameter adaptability and computation time adaptability. Experimental results indicate that compared with static models and traditional algorithms, this model reduces costs by 27.4% to 61.95%.

2.4. Overview and Evaluation of AIV Path Planning Methods

This section provides an overview of ten commonly used path planning methods and compares their advantages and disadvantages in Table 1. Each method has its own characteristics and application scope, and by combining multiple methods, the strengths of each can be leveraged to solve path planning difficulties in complex port environments. In global path planning, graph search methods ensure path completeness by traversing grids and are highly adaptable, but they suffer from poor real-time performance and struggle with large-scale scenarios. Numerical optimization methods support multi-objective optimization through mathematical models, offering flexibility in handling complex constraints, but they come with high computational costs and reduced real-time performance in complex environments. Intelligent bionic methods, based on bionic principles, possess global search capabilities and are suitable for solving complex nonlinear problems, but they have low computational efficiency and may fall into local optima. Intelligent learning optimization methods are highly adaptable and capable of global optimization, but they rely heavily on data training, have high algorithmic complexity, and exhibit poor real-time performance.
In local path planning, APF is simple to implement and suitable for dynamic obstacle avoidance, but it is prone to local minima and performs poorly in large-scale environments. Curve optimization methods generate smooth paths, ideal for stable operation of AIVs, but they are sensitive to noise and depend on the quality of the initial path. Sampling-based methods, based on random sampling strategies, efficiently complete path planning and are suitable for high-dimensional spaces, but the paths may lack smoothness and require additional optimization in large-scale scenarios.
In multi-vehicle collaborative planning, MAPF resolves path conflicts among multiple vehicles and supports global coordination and priority planning, but it has high computational complexity and limited scalability. DMPC supports dynamic adjustments, adapts to complex environments, and improves efficiency through distributed computing, but it demands significant computational resources and complex parameter tuning. LFC is simple in structure and easy to implement, making it suitable for formation scenarios, but it lacks flexibility, relies heavily on the leader’s path, and struggles with sudden obstacles.
In summary, global path planning algorithms are suitable for generating rough paths but have their limitations. Local path planning algorithms are used for dynamic obstacle avoidance and path optimization but need to be combined with global planning to avoid local optima. Multi-vehicle collaborative planning algorithms address conflicts and coordination among multiple vehicles but require a balance between computational complexity and real-time performance. By combining multiple algorithms, efficient and safe path planning can be achieved in complex scenarios such as ports.
Compare the path length, computation time, and planning results of eight common AIV path planning methods by constructing the same obstacle environment. The experimental results are shown in Table 2: within the 100 × 100 area, the path planning length ranges from 142.4952-180, with the PSO method having the shortest path length; the calculation time ranges from 0.014 to 19.5868 s, the curve optimization method has the shortest calculation time, and the driving trajectory is more in line with the motion constraints of AIV.

3. Port AIV Motion Control Algorithms

After an AIV receives a path planning instruction, motion control algorithms are required to control the vehicle, helping the AIV adjust its speed and posture, driving it along the planned path with minimal deviation to ensure safe and precise operation [117]. Therefore, the accuracy of motion control determines whether the path planning result can be accurately implemented. In practical applications, different operating scenarios and load conditions lead to uncertainty in the motion control of AIVs, challenging control accuracy and robustness. When docking at designated port positions, both lateral and longitudinal positioning errors of AIVs must be confined within ±3 cm to ensure high-precision container alignment. Currently, common AIV motion control algorithms include PID control [118], robust control [119], sliding mode control [120], MPC [121], fuzzy control [122], and neural network control [123].

3.1. Proportional-Integral-Derivative Control

Proportional-integral-derivative (PID) control is a fundamental yet effective feedback method, commonly used in autonomous driving due to its straightforward structure and ease of implementation [124]. PID control can combine longitudinal and lateral control of the AIV. For instance, PID control can regulate the vehicle’s acceleration based on feedback from the speed difference, ensuring smooth and efficient motion [125]. It can also be used for path tracking and deviation correction [126]. Figure 7 illustrates the motion control principle of PID. In this diagram, visual sensors, encoders, and LiDAR are utilized to detect lane deviation, vehicle speed, and obstacles, respectively. The collected information is merged with path planning data and input into the PID controller. The PID controller adjusts the control signal in real-time by modifying the proportional, integral, and derivative gains. The output control signal is used to adjust the vehicle speed and steering actuators for motion state adjustments. To enhance PID vehicle motion control, researchers have integrated it with intelligent optimization algorithms, numerical optimization techniques, and robust observers. Moshayedi et al. [127] first modeled the AIV, combining traditional and intelligent optimization algorithms such as Ziegler–Nichols, empirical methods, PSO, and beetle antenna search (BAS) to optimize PID parameters, and then compared the control results for circular, elliptical, spiral, and figure-eight trajectories. Experiments showed that BAS, after parameter adjustment, outperformed other methods in vehicle speed and trajectory deviation. Shi et al. [128] transformed the PID gain tuning problem for path tracking into a static output feedback (SOF) controller design problem for a time-varying linear parameter varying (LPV) model. The PID gains were segmented into constant values based on road curvature, leading to improved tracking performance. Finally, simulations based on the CarSim–Simulink platform demonstrated that within a range of 35–55 km/h, the vehicle’s lateral offset was reduced to a level of 10−1 m, verifying the effectiveness of the proposed control strategy. Chen et al. [129] proposed a robust PID path tracking control strategy based on an H observer, which effectively suppresses the effects of external disturbances and sensor/actuator failure signals. This strategy introduces an observer to estimate the vehicle’s state, combined with a PID controller to enhance control performance and robustness to uncertainty. Simulation and real vehicle experiments showed that this method outperforms traditional PID control in terms of control accuracy, robustness, and stability, with a maximum trajectory deviation of just 0.3 m.

3.2. Robust Control

Robust control is a strategy focused on ensuring the system’s resilience to uncertainties and external disturbances. The goal is to ensure that the AIV maintains good control performance and stability in the presence of model inaccuracies, environmental changes, and sensor errors [130]. Robust control often involves the use of robust observers and other methods to estimate and compensate for various uncertainties faced by the system [131]. Figure 8 illustrates the components of a robust control system. The process begins with analyzing the system model and uncertainties: constructing the vehicle’s kinematic model, which includes the vehicle’s geometry, speed, and steering relationships; developing the vehicle’s dynamic model, establishing relationships between load, vehicle acceleration, ground friction, and driving force; and analyzing uncertainties related to variations in load and ground friction. Performance metrics are then set, including stability requirements for the AIV’s motion state under disturbances, as well as the tracking performance requirements for path deviation and velocity errors. The robust controller outputs control commands based on these parameters, adjusting the vehicle’s speed and direction. The vehicle state detector gathers the vehicle’s status, which, along with external disturbances, is fed back into the robust controller, enabling real-time adjustments to the vehicle’s state. For robust motion control of AIVs, researchers have studied solutions to challenges in complex ground environments, signal interference, and system parameter uncertainties: Shin et al. [132] addressed the challenge of AIV motion in complex ground environments by proposing a robust path controller that integrates an interference observer with the AIV nominal system controller. The method uses CVXGEN to solve the tire force distribution problem under constraint conditions for optimization. Numerical and real-world tests indicate that the AIV’s autonomous navigation direction and speed control achieve the desired outcomes at a speed of 6.0 m/s, demonstrating the algorithm’s effectiveness. Lee et al. [133] proposed a robust H network observer-based anti-jamming path tracking control design to address external noise interference and sensor/actuator signal impacts. This design uses the estimated states and attack signals to mitigate the influence of unknown disturbances on path tracking errors, eliminating the impact of attack signals. The design conditions of this observer were derived using a convex Lyapunov function, and the Takagi-Sugeno (T-S) fuzzy interpolation method was applied to simplify the solution process. Experimental results demonstrate that the proposed robust observer enhances the AIV’s ability to perform lane change tasks, improving motion control performance. Xu et al. [134] introduced a reinforcement learning (RL) technique to replace direct robust control problem solving for finding the optimal controller, addressing uncertainties in system parameters and ensuring global optimality of the controller parameters. Numerical simulations confirmed the effectiveness of the RL method in solving the optimal path tracking control problem.

3.3. Sliding Mode Control

Sliding mode control (SMC) is a robust control method that works by introducing a sliding surface, onto which the system states rapidly converge [135]. Once the system reaches this surface, an appropriate control law is designed to maintain the system’s stability on the sliding surface, making the design of the sliding surface the core of the control process [136]. SMC is widely used due to its fast response and strong robustness [137]. Figure 9 illustrates the block diagram of sliding mode control. In the diagram, the equivalent control rate and switching control law constitute the design of the sliding mode controller. The equivalent control ensures the system reaches and remains on the sliding surface, while the switching control rapidly drives the system state back to the sliding mode after disturbances, thus forming the sliding surface equation. By designing the sliding mode variables, the sliding surface is formed, and the parameters for the sliding mode controller are determined. The sensor collects information on lane detection, vehicle position, and motion states, detects the current error signal, and inputs this into the vehicle controller. The vehicle controller then outputs control commands based on the expected path and vehicle state. For sliding mode control, researchers have focused on lateral motion stability, control difficulties caused by system complexity, and how to rapidly return to the sliding surface after disturbances. Some notable studies include: Hajjami et al. [138] proposed a robust adaptive non-singular fast terminal sliding mode control (RANFTSMC) for lateral control in lane-change maneuvers, utilizing a meta-heuristic optimization algorithm to determine the optimal controller parameters. Numerical experiments showed that this method could maintain lateral stability during lane changes even under harsh conditions at 120 km/h. Jiang et al. [139] addressed the control difficulties caused by the complexity of sliding mode control’s nonlinearities. They developed a novel backstepping sliding mode control with an innovative approaching law, enhancing both convergence speed and accuracy. Through numerical analysis, they compared this method to existing methods in tracking simulations for linear trajectories and circular paths. The results demonstrated that this method could track paths effectively, with the maximum position error remaining at the level of 10−4 m after convergence. Chen et al. [140] proposed a non-singular fast terminal sliding mode (NFTSM) controller based on the AIV’s dynamic model. This controller quickly converges tracking errors and utilizes finite-time disturbance observation (FDO) methods to mitigate disturbances and suppress vibrations. The combination of NFTSM and FDO led to the proposed NFTSM-FDO AIV control method. Theoretical and numerical validation showed that this method had less overshoot, smaller chattering, and a 25.5% reduction in recovery time compared to using NFTSM alone.

3.4. Model Predictive Control

AIV motion control and path planning can both be formulated as constrained optimal control problems [141]. MPC is another widely used algorithm in AIV motion control [142]. The core idea of MPC is to build a dynamic model to predict the vehicle’s future behavior and optimize control commands based on the predictions. It is primarily used for controlling nonlinear and highly coupled complex systems [143]. Algorithm 6 illustrates the motion control process of AIV based on MPC through pseudocode: The inputs to the MPC algorithm include the current state of the AIV, the kinematic model, the model’s constraints, the cost function, and the desired trajectory. Using the current state and motion model, the algorithm calculates the cost function for the AIV trajectory over the next N steps and checks the constraints. The control inputs are iteratively updated, and once the convergence condition is met, the optimized AIV control parameters are output. Compared to other algorithms, MPC offers significant advantages in solving multi-objective constrained optimization problems [144]. Researchers have integrated MPC with adaptive learning, robust MPC, and hierarchical control strategies to enhance AIV control performance: Zhang et al. [145] proposed an adaptive learning model predictive control (ALMPC) approach for AIV trajectory tracking with input constraints. They designed a parameter estimation method based on set membership and used the recursive least squares (RLS) technique to ensure that the estimation error did not increase. The estimated system parameters were integrated into the MPC, and robustness constraints were added to address uncertainties. Numerical verification showed that this method reduced both the computational cost and position tracking error by 32.18% and 33.82%, respectively, in comparison to robust model predictive control (RMPC). Liu et al. [146] proposed a real-time nonlinear model predictive control (NMPC) to address the load transfer effects when AIVs carry heavy equipment. This method can control a four-wheel-steering AIV. By introducing continuous/generalized minimal residual (C/GMRES) methods and semi-smooth variations based on CHKS functions, the NMPC handles both equality and inequality constraints and enables real-time online computation. This method was tested on an AIV carrying 13 tons of steel, demonstrating high accuracy and safety. Li et al. [147] introduced a hierarchical control strategy, where the high-level controller uses MPC for high-level path planning and trajectory tracking control, while the low-level controller, based on a reduced-order extended state observer (RESO), executes speed commands and handles uncertainties. This hierarchical control method requires minimal AIV motion information and is easy to implement. Experimental results confirmed its effectiveness in managing large loads, with average tracking errors of 0.019 m for a 0 kg load and 0.029 m for a 60 kg load.
Algorithm 6. AIV motion control based on MPC
Input: Current position, motion direction, load weight, speed, and other states of the AIV; AIV kinematic model; constraints on speed, acceleration, and control inputs; cost function; desired trajectory.
Output: Optimal control commands for the AIV.
1: Function MPC_AIVControl(currentState, kinematicModel, constraints, costFunction, referenceTrajectory):
2:   for iteration in 1 to maxIterations:
3:   predictedTrajectory = []
4:   predictedState = currentState
5:   for t in 1 to N:
6:     predictedState = kinematicModel(predictedState, controlInputs[t])
7:     predictedTrajectory.append(predictedState)
8:   cost = costFunction(predictedTrajectory, referenceTrajectory, controlInputs)
9:   if CheckConstraints(predictedTrajectory, controlInputs, constraints):
10:    if cost < optimalCost:
11:      optimalCost = cost
12:      optimalControl = controlInputs[0]
13:   controlInputs = UpdateControlInputs(controlInputs, costFunction, constraints)
14:  if CheckConvergence(optimalCost):
15:     break
16: return optimalControl

3.5. Fuzzy Control

Fuzzy control is a contemporary control method that combines sensing technology, computer technology, and automatic control theory [148], utilizing fuzzy mathematical theories such as fuzzy reasoning and fuzzy linguistic variables [149]. A fuzzy controller mainly comprises four components: fuzzification, knowledge base, fuzzy inference, and defuzzification. Since it does not require precise system modeling, it offers high tolerance for error [150]. Figure 10 shows the flowchart of AIV fuzzy control: First, a fuzzy knowledge base is constructed to generate fuzzy control commands corresponding to the input information. The vehicle’s motion state is compared with the expected direction and speed to obtain the direction and speed errors. These error signals are then fuzzified based on the fuzzy knowledge base and input into the fuzzy controller. The fuzzy controller generates corresponding fuzzy commands based on expert-defined settings and rules. These commands are then defuzzified and used to drive the AIV motion controller for the appropriate adjustment. Regarding improvements in fuzzy control for AIV applications, Yang et al. [151] designed a Mamdani-type adaptive neuro-fuzzy controller through neural network training. This controller was incorporated into the dynamic window approach (DWA), resulting in the creation of an Adaptive DWA (ADWA) to overcome challenges in obstacle avoidance and path planning for AIVs in complex environments. Simulation results showed that this method reduced the average computation time by 4.6% in simple dynamic obstacle environments and by 17.5% in integrated obstacle environments, in comparison to the traditional DWA algorithm. Ren et al. [152] and others designed a novel fuzzy switching controller and introduced D-stability optimization to improve the control response speed of the vehicle in curves. They also developed switching rules for the coordinated control of multiple fuzzy controllers, which significantly improved the AIV’s control performance. Experimental comparisons between the D-stability optimized fuzzy controller and traditional fuzzy controllers showed that the root mean square values of path tracking errors were 0.1115 and 0.9222, respectively, proving that the method effectively reduced control errors. Cai et al. [153] and others proposed a path tracking strategy based on an adaptive event-triggered (AET) method for vehicle stability control, particularly in environments where GPS is temporarily unavailable and AIV network resources are constrained. This strategy enhances network resource utilization and employs a T-S fuzzy state observer to solve system disturbance information. Furthermore, the Lyapunov–Krasovski method, which accounts for delays, is employed to guarantee closed-loop stability and H performance. Full vehicle model simulations were performed in different dynamic scenarios using CarSim–Simulink. The results indicated a 7.71% reduction in lateral position error and a 1.3% decrease in heading angle error, with a modest 2.05% increase in transmission rate cost.

3.6. Neural Network Control

As neural networks have rapidly developed, control methods that incorporate neural networks have gradually emerged [154]. Neural network control (NNC) is mainly applied in two aspects: perception and decision-making [155]. As illustrated in Figure 11, in terms of perception, neural networks assist the vehicle in more accurately interpreting its surrounding environment by processing direction and speed errors from the vehicle’s sensors, along with external disturbances [156]. In the decision-making aspect, neural networks learn driving strategies to respond to different traffic scenarios and driving situations [157], and ultimately output vehicle control commands to drive the vehicle’s operation. Researchers have used NNC for various AIV control studies, such as parking maneuver control and real-time perception of the vehicle’s center of gravity under different loads. Chai et al. [158] proposed a control scheme based on deep neural networks (DNN) that can predict the optimal motion commands for AIV parking maneuvers. The design employs a two-layer structure: the first layer uses a desensitized trajectory optimization method to generate a time-optimal parking trajectory. This trajectory is then provided to the second layer, which constructs a DNN to learn the optimal state–control relationship. Additionally, a data aggregation (DA) strategy is introduced to further improve network approximation performance. Simulation results validate that this control scheme can efficiently provide real-time AIV automatic parking planning information and control commands. Quan et al. [159] focused on the challenges of AIV safety under varying load conditions and established a multi-sensor perception system for real-time detection of AIV motion status and load center of gravity. Neural network algorithms were trained to accurately assess different motion states and provide real-time feedback on current acceleration constraints. The neural network achieved a test set accuracy rate of 99.4%, and the platform effectively monitored the AIV’s motion state in actual freight transportation, ensuring real-time acceleration constraints to guarantee cargo safety and stability. Lv et al. [160] developed a deep neural network framework for optimizing new control problems related to AIVs. The framework uses a separate feedforward sub-network to compute the optimal controller, effectively addressing the gradient vanishing problem. By training with deep residual networks, an optimal control method was developed that applies to various nonlinear dynamic systems. Experimental comparisons between this control method and linearized and nonlinear model predictive control (LMPC/NMPC) algorithms showed that the new method reduced maximum distance error by 0.031 m and 0.012 m, maximum velocity error by 0.003 m/s and 0.001 m/s, and front wheel steering angle error by 3.92° and 0.97°, respectively.
Table 3 presents a comparison of the pros and cons of the six motion control algorithms mentioned earlier. From traditional PID control algorithms to more complex neural network-based control, each algorithm has its unique features. PID control, as the most classic control method, is simple in principle, easy to implement, and straightforward in parameter tuning. However, due to its proportional-integral-derivative mechanism, it can easily lead to integral saturation and is sensitive to noise. Robust control is recognized for its excellent stability and resistance to interference, while also enhancing system performance. However, its design is more complex and demands significant computational resources. Sliding mode control, one of the most powerful nonlinear control methods, offers fast response speed and high control accuracy but can also cause chattering and is difficult to tune. MPC, due to its principle of transforming control objectives into numerical optimization problems, is effective at handling multivariable coupling and constraints. However, its results are highly dependent on the accuracy of the model, and any inaccuracies in the model can significantly impact the outcome. Fuzzy control is designed based on expert knowledge and does not require an accurate mathematical model, making it easier to address nonlinear and uncertain problems. However, since it relies on expert experience, its control accuracy is limited, and it is challenging to control complex systems. NNC, due to its robust learning capability, offers excellent adaptability to complex dynamic systems. However, it heavily depends on training data, and overfitting can occur. Additionally, its network structure and parameter design can become increasingly complex when dealing with more complicated scenarios.

4. Development Prospects and Trends

As the variety and accuracy of sensing devices continue to improve, the environmental perception capabilities of port AIVs will be significantly enhanced, greatly improving the adaptability of path planning and motion control technologies. In the future, the integration of path planning and motion control technologies with multi-source sensing will promote the development of port AIVs in directions such as end-to-end large model, 3D path planning, preemptive control and digital twins.
  • End-to-End Large Models: With continual advances in multimodal sensing hardware—high-resolution LiDAR, event-driven cameras, and ultra-compact inertial measurement units—end-to-end large models are poised to redefine how AIVs perceive and reason about their surroundings. Future work will focus on designing unified Transformer backbones that ingest raw point-cloud streams, vision frames, and inertial signals simultaneously, rather than in isolated pipelines. Through massive self-supervised pre-training on synthetic and real port-operation datasets, these models will learn to encode spatiotemporal patterns of cranes, vehicles, and pedestrian flows into a single, continuously updating 4D semantic representation. On top of that, emerging reinforcement-learning paradigms—such as offline RL from logged port-operation trajectories—will enable these large models to refine their decision-making policies without costly real-world trial runs. By enhancing autonomous driving technology through end-to-end lager models, RL training data can be reduced by 95%, inference speed can be increased by 600 times, and task success rate can be increased by 40% [161].
  • 3D Environmental Path Planning: Traditional 2D path-planning techniques struggle in the highly cluttered, three-dimensional corridors of container terminals and automated warehouses. The next generation of AIVs will leverage dense 3D reconstructions from LiDAR and RGB-D scanners to build on-the-fly octree or voxel maps, feeding these directly into deep neural planners [162]. These planners—based on graph-convolutional networks or differentiable occupancy grids—will evaluate feasibility, clearance, and dynamic stability constraints simultaneously in full 3D. In practice, an AIV approaching a stack of high-bay racks will not only find the shortest route in the bird’s-eye view but will also judge vertical clearance margins and possible sway of suspended loads. Coupled with real-time map updates at 10 Hz, this approach promises a two-fold increase in planning robustness and a 25% reduction in dead-heading—especially critical in narrow, multi-level storage environments [163].
  • Preemptive Control Based on Multi-source Sensing: As sensor miniaturization continues, low power radar chips, surface acoustic wave dust sensors, and road surface microphones will join cameras and inertial units on AIV platforms [164]. Beyond obstacle detection and localization, these heterogeneous streams will converge in a probabilistic sensor fusion engine that not only labels the scene but also infers future terrain quality and friction coefficients [165]. For instance, by correlating subtle radar echo signatures with known pothole patterns, the system can predict a rough patch 5–10 m ahead, commanding the drive controller to reduce speed and adjust suspension damping proactively [166]. Preliminary field trials suggest this “look ahead” control can reduce maintenance costs by minimizing shock loads on chassis components [167].
  • Digital Twins and Virtual Debugging: Digital twin frameworks for port AIVs will evolve from static replicas to dynamic, physics informed simulation platforms [168]. By ingesting real-time telemetry—position, actuator forces, battery health—and coupling it with a high-fidelity finite element model of the vehicle, operators will be able to run “what if” analyses in milliseconds. Upcoming toolchains will integrate domain randomized virtual sensors, so that edge case scenarios can be stress tested without endangering hardware [169]. Furthermore, closed loop co-simulation with industrial PLCs (Programmable Logic Controllers) and MES (Manufacturing Execution Systems) will allow control system prototypes to be validated against digital replicas of the entire terminal. This end-to-end virtual debugging cycle will shorten commissioning times by up to 50% and enable continuous in-service calibration, ensuring that AIVs maintain peak performance even as physical infrastructure evolves [170].

5. Conclusions

As a key transport hub in the global logistics and transportation network, the efficiency of port operations is vital to the growth of the maritime transport industry. This paper provides a comprehensive review of the path planning and motion control methods for port transfer vehicles. Vehicle path planning and motion control are key to realizing autonomous transport for AIVs. They face challenges such as large working environments and complex dynamic scenarios in the port, requiring solutions for path planning and high-precision, adaptive motion control. This paper presents the principles of AIV path planning and motion control algorithms, offers a thorough review of the current developments in these areas, and compares the strengths and weaknesses of various algorithms. In path planning, traditional approaches like graph search and artificial potential field methods are discussed, alongside numerical optimization and optimization algorithms based on intelligent learning. In the field of motion control, classic control methods such as PID control, robust control, and new neural network-based control methods are discussed. In the future, port AIV path planning and motion control will move toward intelligent planning based on scene semantics, 3D environmental path planning, preemptive control through multi-source sensing, and virtual debugging using digital twin technology. Advancements in port AIV path planning and motion control algorithms will contribute to the development of highly intelligent, unmanned freight systems at ports, driving the maritime transport industry toward a more efficient and environmentally friendly future.

Author Contributions

Conceptualization, M.Y. and D.Z.; investigation, M.Y.; resources, D.Z.; writing—original draft preparation, M.Y.; writing—review and editing, D.Z.; visualization, H.W.; supervision, D.Z.; project administration, D.Z. All authors have read and agreed to the published version of the manuscript.

Funding

This research received no external funding.

Conflicts of Interest

Author Mei Yang was employed by Shanghai International Port (Group) Co., Ltd. The remaining authors declare that the research was conducted in the absence of any commercial or financial relationships that could be construed as a potential conflict of interest.

References

  1. Fragapane, G.; de Koster, R.; Sgarbossa, F.; Strandhagen, J.O. Planning and control of autonomous mobile robots for intralogistics: Literature review and research agenda. Eur. J. Oper. Res. 2021, 294, 405–426. [Google Scholar] [CrossRef]
  2. Fowler, D.S.; Mo, Y.K.; Evans, A.; Dinh-Van, S.; Ahmad, B.; Higgins, M.D.; Maple, C. A 5G Automated-Guided Vehicle SME Testbed for Resilient Future Factories. IEEE Open J. Ind. Electron. Soc. 2023, 4, 242–258. [Google Scholar] [CrossRef]
  3. Li, C.; Wu, W. Research on cooperative scheduling of AGV transportation and charging in intelligent warehouse system based on dynamic task chain. In Proceedings of the 2022 IEEE International Conference on Networking, Sensing and Control (ICNSC), Shanghai, China, 15–18 December 2022; pp. 1–6. [Google Scholar]
  4. Naeem, D.; Gheith, M.; Eltawil, A. Integrated Scheduling of AGVs and Yard Cranes in Automated Container Terminals. In Proceedings of the 2021 IEEE 8th International Conference on Industrial Engineering and Applications (ICIEA), Xi’an, China, 23–26 April 2021; pp. 632–636. [Google Scholar]
  5. Duan, Y.; Ren, H.; Xu, F.; Yang, X.; Meng, Y. Bi-Objective Integrated Scheduling of Quay Cranes and Automated Guided Vehicles. J. Mar. Sci. Eng. 2023, 11, 1492. [Google Scholar]
  6. Yang, Y.; Sun, S.; He, S.; Jiang, Y.; Wang, X.; Yin, H.; Zhu, J. Research on the Multi-Equipment Cooperative Scheduling Method of Sea-Rail Automated Container Terminals under the Loading and Unloading Mode. J. Mar. Sci. Eng. 2023, 11, 1975. [Google Scholar]
  7. Yang, X.; Hu, H.; Cheng, C.; Wang, Y. Automated Guided Vehicle (AGV) Scheduling in Automated Container Terminals (ACTs) Focusing on Battery Swapping and Speed Control. J. Mar. Sci. Eng. 2023, 11, 1852. [Google Scholar]
  8. Lu, T.; Sun, Z.H.; Qiu, S.; Ming, X. Time Window Based Genetic Algorithm for Multi-AGVs Conflict-free Path Planning in Automated Container Terminals. In Proceedings of the 2021 IEEE International Conference on Industrial Engineering and Engineering Management (IEEM), Singapore, 13–16 December 2021; pp. 603–607. [Google Scholar]
  9. Oyekanlu, E.A.; Smith, A.C.; Thomas, W.P.; Mulroy, G.; Hitesh, D.; Ramsey, M.; Kuhn, D.J.; Mcghinnis, J.D.; Buonavita, S.C.; Looper, N.A.; et al. A Review of Recent Advances in Automated Guided Vehicle Technologies: Integration Challenges and Research Areas for 5G-Based Smart Manufacturing Applications. IEEE Access 2020, 8, 202312–202353. [Google Scholar] [CrossRef]
  10. Tang, K.; Pan, X.; Guo, X.; Wu, C. A Cooperative Control Method of Differential AGV Based on Leader-Follower Strategy. In Proceedings of the 2023 42nd Chinese Control Conference (CCC), Tianjin, China, 24–26 July 2023; pp. 3012–3016. [Google Scholar]
  11. Ogorelysheva, N.; Vasileva, A.; Stadtler, J.; Roidl, M.; Howar, F. Mitigating Emergency Stop Collisions in AGV Fleets in Case of Control Failure. In Proceedings of the 2023 Seventh IEEE International Conference on Robotic Computing (IRC), Laguna Hills, CA, USA, 11–13 December 2023; pp. 314–322. [Google Scholar]
  12. Winkler, S.; Weidensager, N.; Brade, J.; Knopp, S.; Jahn, G.; Klimant, P. Use of an automated guided vehicle as a telepresence system with measurement support. In Proceedings of the 2022 IEEE 9th International Conference on Computational Intelligence and Virtual Environments for Measurement Systems and Applications (CIVEMSA), Chemnitz, Germany, 15–17 June 2022; pp. 1–6. [Google Scholar]
  13. Zhang, Y.; Li, B.; Sun, S.; Liu, Y.; Liang, W.; Xia, X.; Pang, Z. GCMVF-AGV: Globally Consistent Multiview Visual–Inertial Fusion for AGV Navigation in Digital Workshops. IEEE Trans. Instrum. Meas. 2023, 72, 5030116. [Google Scholar] [CrossRef]
  14. Xu, Y.; Qi, L.; Luan, W.; Guo, X.; Ma, H. Load-In-Load-Out AGV Route Planning in Automatic Container Terminal. IEEE Access 2020, 8, 157081–157088. [Google Scholar] [CrossRef]
  15. He, D.; Ouyang, B.; Fan, H.; Hu, C.; Zhang, K.; Yan, Z. Deadlock Avoidance in Closed Guide-Path Based MultiAGV Systems. IEEE Trans. Autom. Sci. Eng. 2023, 20, 2088–2098. [Google Scholar] [CrossRef]
  16. Zamora-Cadenas, L.; Velez, I.; Sierra-Garcia, J.E. UWB-Based Safety System for Autonomous Guided Vehicles Without Hardware on the Infrastructure. IEEE Access 2021, 9, 96430–96443. [Google Scholar] [CrossRef]
  17. Wang, W.; Li, J.; Bai, Z.; Wei, Z.; Peng, J. Toward Optimization of AGV Path Planning: An RRT*-ACO Algorithm. IEEE Access 2024, 12, 18387–18399. [Google Scholar] [CrossRef]
  18. Sha, B.; Zhu, L.; Zhu, Y.; Cheng, J. Path Planning of Agv Complex Environment Based on Ant Colony Algorithm. In Proceedings of the 2022 International Seminar on Computer Science and Engineering Technology (SCSET), Indianapolis, IN, USA, 8–9 January 2022; pp. 72–75. [Google Scholar]
  19. Zhang, Z.; Wu, R.; Pan, Y.; Wang, Y.; Wang, Y.; Guan, X.; Hao, J.; Zhang, J.; Li, G. A Robust Reference Path Selection Method for Path Planning Algorithm. IEEE Robot. Autom. Lett. 2022, 7, 4837–4844. [Google Scholar] [CrossRef]
  20. Liang, Z.; Wang, Z.; Zhao, J.; Wong, P.K.; Yang, Z.; Ding, Z. Fixed-Time and Fault-Tolerant Path-Following Control for Autonomous Vehicles With Unknown Parameters Subject to Prescribed Performance. IEEE Trans. Syst. Man Cybern. Syst. 2023, 53, 2363–2373. [Google Scholar] [CrossRef]
  21. Ren, Y.; Xie, X.; Li, Y. Lateral Control of Autonomous Ground Vehicles via a New Homogeneous Polynomial Parameter Dependent-Type Fuzzy Controller. IEEE Trans. Ind. Inform. 2024, 20, 11233–11241. [Google Scholar] [CrossRef]
  22. Lian, Y.; Xie, W.; Yang, Q.; Liu, Y.; Yang, Y.; Wu, A.G.; Eisaka, T. Improved Coding Landmark-Based Visual Sensor Position Measurement and Planning Strategy for Multiwarehouse Automated Guided Vehicle. IEEE Trans. Instrum. Meas. 2022, 71, 3509316. [Google Scholar] [CrossRef]
  23. Teng, S.; Hu, X.; Deng, P.; Li, B.; Li, Y.; Ai, Y.; Yang, D.; Li, L.; Xuanyuan, Z.; Zhu, F.; et al. Motion Planning for Autonomous Driving: The State of the Art and Future Perspectives. IEEE Trans. Intell. Veh. 2023, 8, 3692–3711. [Google Scholar] [CrossRef]
  24. Yin, J.; Li, L.; Mourelatos, Z.P.; Liu, Y.; Gorsich, D.; Singh, A.; Tau, S.; Hu, Z. Reliable Global Path Planning of Off-Road Autonomous Ground Vehicles Under Uncertain Terrain Conditions. IEEE Trans. Intell. Veh. 2024, 9, 1161–1174. [Google Scholar] [CrossRef]
  25. Xiang, L.; Li, X.; Liu, H.; Li, P. Parameter Fuzzy Self-Adaptive Dynamic Window Approach for Local Path Planning of Wheeled Robot. IEEE Open J. Intell. Transp. Syst. 2022, 3, 1–6. [Google Scholar] [CrossRef]
  26. Wang, Z.; Lu, G.; Tan, H.; Liu, M. A Risk-Field Based Motion Planning Method for Multi-Vehicle Conflict Scenario. IEEE Trans. Veh. Technol. 2024, 73, 310–322. [Google Scholar] [CrossRef]
  27. Ren, Z.; Rathinam, S.; Likhachev, M.; Choset, H. Multi-Objective Path-Based D* Lite. IEEE Robot. Autom. Lett. 2022, 7, 3318–3325. [Google Scholar] [CrossRef]
  28. Lim, W.; Lee, S.; Sunwoo, M.; Jo, K. Hybrid Trajectory Planning for Autonomous Driving in On-Road Dynamic Scenarios. IEEE Trans. Intell. Transp. Syst. 2021, 22, 341–355. [Google Scholar] [CrossRef]
  29. Alireza, M.; Vincent, D.; Tony, W. Experimental study of path planning problem using EMCOA for a holonomic mobile robot. J. Syst. Eng. Electron. 2021, 32, 1450–1462. [Google Scholar] [CrossRef]
  30. Yu, Z.; Zhu, M.; Chen, K.; Chu, X.; Wang, X. LF-Net: A Learning-Based Frenet Planning Approach for Urban Autonomous Driving. IEEE Trans. Intell. Veh. 2024, 9, 1175–1188. [Google Scholar] [CrossRef]
  31. Chu, L.; Gao, Z.; Dang, S.; Zhang, J.; Yu, Q. Optimization of Joint Scheduling for Automated Guided Vehicles and Unmanned Container Trucks at Automated Container Terminals Considering Conflicts. J. Mar. Sci. Eng. 2024, 12, 1190. [Google Scholar]
  32. Zhu, D.D.; Sun, J.Q. A New Algorithm Based on Dijkstra for Vehicle Path Planning Considering Intersection Attribute. IEEE Access 2021, 9, 19761–19775. [Google Scholar] [CrossRef]
  33. Lian, Y.; Xie, W.; Zhang, L. A Probabilistic Time-Constrained Based Heuristic Path Planning Algorithm in Warehouse Multi-AGV Systems. IFAC-Pap. 2020, 53, 2538–2543. [Google Scholar] [CrossRef]
  34. Fransen, K.J.C.; van Eekelen, J.A.W.M.; Pogromsky, A.; Boon, M.A.A.; Adan, I.J.B.F. A dynamic path planning approach for dense, large, grid-based automated guided vehicle systems. Comput. Oper. Res. 2020, 123, 105046. [Google Scholar] [CrossRef]
  35. Guo, K.; Zhu, J.; Shen, L. An Improved Acceleration Method Based on Multi-Agent System for AGVs Conflict-Free Path Planning in Automated Terminals. IEEE Access 2021, 9, 3326–3338. [Google Scholar] [CrossRef]
  36. Liu, Z.; Wang, H.; Wei, H.; Liu, M.; Liu, Y.H. Prediction, Planning, and Coordination of Thousand-Warehousing-Robot Networks With Motion and Communication Uncertainties. IEEE Trans. Autom. Sci. Eng. 2021, 18, 1705–1717. [Google Scholar] [CrossRef]
  37. Zhou, Y.; Huang, N. Airport AGV path optimization model based on ant colony algorithm to optimize Dijkstra algorithm in urban systems. Sustain. Comput. Inform. Syst. 2022, 35, 100716. [Google Scholar] [CrossRef]
  38. Singh, N.; Dang, Q.-V.; Akcay, A.; Adan, I.; Martagan, T. A matheuristic for AGV scheduling with battery constraints. Eur. J. Oper. Res. 2022, 298, 855–873. [Google Scholar] [CrossRef]
  39. Yang, Y.; Zhong, M.; Dessouky, Y.; Postolache, O. An integrated scheduling method for AGV routing in automated container terminals. Comput. Ind. Eng. 2018, 126, 482–493. [Google Scholar] [CrossRef]
  40. Zou, W.Q.; Pan, Q.K.; Wang, L.; Miao, Z.H.; Peng, C. Efficient multiobjective optimization for an AGV energy-efficient scheduling problem with release time. Knowl. Based Syst. 2022, 242, 108334. [Google Scholar]
  41. Gao, Y.; Chen, C.-H.; Chang, D. A Machine Learning-Based Approach for Multi-AGV Dispatching at Automated Container Terminals. J. Mar. Sci. Eng. 2023, 11, 1407. [Google Scholar]
  42. Sun, S.; Gu, C.; Wan, Q.; Huang, H.; Jia, X. CROTPN Based Collision-Free and Deadlock-Free Path Planning of AGVs in Logistic Center. In Proceedings of the 2018 15th International Conference on Control, Automation, Robotics and Vision (ICARCV), Singapore, 18–21 November 2018; pp. 1685–1691. [Google Scholar]
  43. Fanti, M.P.; Mangini, A.M.; Pedroncelli, G.; Ukovich, W. A decentralized control strategy for the coordination of AGV systems. Control Eng. Pract. 2018, 70, 86–97. [Google Scholar] [CrossRef]
  44. Ren, H.; Chen, S.; Yang, L.; Zhao, Y. Optimal Path Planning and Speed Control Integration Strategy for UGVs in Static and Dynamic Environments. IEEE Trans. Veh. Technol. 2020, 69, 10619–10629. [Google Scholar] [CrossRef]
  45. Liu, Z.; Wei, H.; Wang, H.; Li, H.; Wang, H. Integrated Task Allocation and Path Coordination for Large-Scale Robot Networks With Uncertainties. IEEE Trans. Autom. Sci. Eng. 2022, 19, 2750–2761. [Google Scholar] [CrossRef]
  46. Wu, Y.; Li, S.; Zhang, Q.; Sun-Woo, K.; Yan, L. Route Planning and Tracking Control of an Intelligent Automatic Unmanned Transportation System Based on Dynamic Nonlinear Model Predictive Control. IEEE Trans. Intell. Transp. Syst. 2022, 23, 16576–16589. [Google Scholar] [CrossRef]
  47. Ren, Z.; Rathinam, S.; Choset, H. Subdimensional Expansion for Multi-Objective Multi-Agent Path Finding. IEEE Robot. Autom. Lett. 2021, 6, 7153–7160. [Google Scholar] [CrossRef]
  48. Farooq, B.; Bao, J.; Raza, H.; Sun, Y.; Ma, Q. Flow-shop path planning for multi-automated guided vehicles in intelligent textile spinning cyber-physical production systems dynamic environment. J. Manuf. Syst. 2021, 59, 98–116. [Google Scholar] [CrossRef]
  49. Ma, J.; Ma, X.; Zang, S. Multidestination Path Planning Based on Ant Colony Decision and Rolling Control. IEEE Trans. Aerosp. Electron. Syst. 2024, 60, 8667–8681. [Google Scholar] [CrossRef]
  50. Zhang, J.; Wang, Z.; Han, G.; Qian, Y.; Li, Z. A Collaborative Path Planning Method for Heterogeneous Autonomous Marine Vehicles. IEEE Internet Things J. 2024, 11, 1465–1480. [Google Scholar] [CrossRef]
  51. Liu, W.; Zhu, X.; Wang, L.; Wang, S. Multiple equipment scheduling and AGV trajectory generation in U-shaped sea-rail intermodal automated container terminal. Measurement 2023, 206, 112262. [Google Scholar] [CrossRef]
  52. Li, D.; Wang, L.; Cai, J.; Ma, K.; Tan, T. Research on Terminal Distance Index-Based Multi-Step Ant Colony Optimization for Mobile Robot Path Planning. IEEE Trans. Autom. Sci. Eng. 2023, 20, 2321–2337. [Google Scholar] [CrossRef]
  53. Wang, J.; Yuan, X.; Huang, G.; Tan, W.; Wang, Y. Multi-Race Ant Colony Parallel Chaos Search Method for Path Planning on 3-D Terrain Considering Energy Consumption and Travel Distance. IEEE Trans. Veh. Technol. 2024, 73, 16201–16211. [Google Scholar] [CrossRef]
  54. Liu, J.; Wei, X.; Huang, H. An Improved Grey Wolf Optimization Algorithm and its Application in Path Planning. IEEE Access 2021, 9, 121944–121956. [Google Scholar] [CrossRef]
  55. Zhang, Q.; Zhao, J.; Pan, L.; Wu, X.; Hou, Y.; Qi, X. Optimal Path Planning for Mobile Robots in Complex Environments Based on the Gray Wolf Algorithm and Self-Powered Sensors. IEEE Sens. J. 2023, 23, 20756–20765. [Google Scholar] [CrossRef]
  56. Lin, S.; Liu, A.; Wang, J.; Kong, X. An intelligence-based hybrid PSO-SA for mobile robot path planning in warehouse. J. Comput. Sci. 2023, 67, 101938. [Google Scholar] [CrossRef]
  57. Zhang, J.; Li, Z.; Li, L.; Li, Y.; Dong, H.-r. A bi-level cooperative operation approach for AGV based automated valet parking. Transp. Res. Part C Emerg. Technol. 2021, 128, 103140. [Google Scholar]
  58. Julius Fusic, S.; Kanagaraj, G.; Hariharan, K.; Karthikeyan, S. Optimal path planning of autonomous navigation in outdoor environment via heuristic technique. Transp. Res. Interdiscip. Perspect. 2021, 12, 100473. [Google Scholar] [CrossRef]
  59. Li, F.; Cheng, J.; Mao, Z.; Wang, Y.; Feng, P. Enhancing Safety and Efficiency in Automated Container Terminals: Route Planning for Hazardous Material AGV Using LSTM Neural Network and Deep Q-Network. J. Intell. Connect. Veh. 2024, 7, 64–77. [Google Scholar] [CrossRef]
  60. Zhang, L.; Zhang, Y.; Li, Y. Mobile Robot Path Planning Based on Improved Localized Particle Swarm Optimization. IEEE Sens. J. 2021, 21, 6962–6972. [Google Scholar] [CrossRef]
  61. Jian, Z.; Zhang, S.; Chen, S.; Nan, Z.; Zheng, N. A Global-Local Coupling Two-Stage Path Planning Method for Mobile Robots. IEEE Robot. Autom. Lett. 2021, 6, 5349–5356. [Google Scholar] [CrossRef]
  62. Kumar, L.; Sadhu, A.K.; Dasgupta, R. Simultaneous Learning and Planning Within Sensing Range: An Approach for Local Path Planning. IEEE Trans. Artif. Intell. 2024, 5, 6399–6411. [Google Scholar] [CrossRef]
  63. Pan, Z.; Zhang, C.; Xia, Y.; Xiong, H.; Shao, X. An Improved Artificial Potential Field Method for Path Planning and Formation Control of the Multi-UAV Systems. IEEE Trans. Circuits Syst. II Express Briefs 2022, 69, 1129–1133. [Google Scholar] [CrossRef]
  64. Lu, M.K.; Ge, M.F.; Ding, T.F.; Zhong, L.; Liu, Z.W. Hierarchical Piecewise-Trajectory Planning Framework for Autonomous Ground Vehicles Considering Motion Limitation and Energy Consumption. IEEE Internet Things J. 2024, 11, 30145–30160. [Google Scholar] [CrossRef]
  65. Zhang, T.; Wang, J.; Meng, M.Q.H. Generative Adversarial Network Based Heuristics for Sampling-Based Path Planning. IEEE/CAA J. Autom. Sin. 2022, 9, 64–74. [Google Scholar] [CrossRef]
  66. Li, H.; Liu, W.; Yang, C.; Wang, W.; Qie, T.; Xiang, C. An Optimization-Based Path Planning Approach for Autonomous Vehicles Using the DynEFWA-Artificial Potential Field. IEEE Trans. Intell. Veh. 2022, 7, 263–272. [Google Scholar] [CrossRef]
  67. Zheng, X.; Li, H.; Zhang, Q.; Liu, Y.; Chen, X.; Liu, H.; Luo, T.; Gao, J.; Xia, L. Intelligent Decision-Making Method for Vehicles in Emergency Conditions Based on Artificial Potential Fields and Finite State Machines. J. Intell. Connect. Veh. 2024, 7, 19–29. [Google Scholar] [CrossRef]
  68. Szczepanski, R.; Tarczewski, T.; Erwinski, K. Energy Efficient Local Path Planning Algorithm Based on Predictive Artificial Potential Field. IEEE Access 2022, 10, 39729–39742. [Google Scholar] [CrossRef]
  69. Chen, X.; Liu, S.; Zhao, J.; Wu, H.; Xian, J.; Montewka, J. Autonomous port management based AGV path planning and optimization via an ensemble reinforcement learning framework. Ocean Coast. Manag. 2024, 251, 107087. [Google Scholar] [CrossRef]
  70. Wang, Z.; Zhao, X.; Zhang, J.; Yang, N.; Wang, P.; Tang, J.; Zhang, J.; Shi, L. APF-CPP: An Artificial Potential Field Based Multi-Robot Online Coverage Path Planning Approach. IEEE Robot. Autom. Lett. 2024, 9, 9199–9206. [Google Scholar] [CrossRef]
  71. Heinemann, T.; Riedel, O.; Lechler, A. Generating Smooth Trajectories in Local Path Planning for Automated Guided Vehicles in Production. Procedia Manuf. 2019, 39, 98–105. [Google Scholar] [CrossRef]
  72. Liu, Y.; Wang, L. AGV Path Planning: An Improved A* Algorithm Based on Bézier Curve Smoothing. In Proceedings of the 2024 39th Youth Academic Annual Conference of Chinese Association of Automation (YAC), Dalian, China, 7–9 June 2024; pp. 243–247. [Google Scholar]
  73. Zhao, B.; Shao, S.; Lei, L.; Wang, X.; Yang, X.; Wang, Q.; Hu, Y. Curve Fitting-Based Dynamic Path Planning and Tracking Control for Flexible Needle Insertion. IEEE Trans. Med. Robot. Bionics 2022, 4, 436–447. [Google Scholar] [CrossRef]
  74. Song, X.; Gao, H.; Ding, T.; Gu, Y.; Liu, J.; Tian, K. A Review of the Motion Planning and Control Methods for Automated Vehicles. Sensors 2023, 23, 6140. [Google Scholar] [CrossRef]
  75. Lin, P.; Javanmardi, E.; Tsukada, M. Clothoid Curve-Based Emergency-Stopping Path Planning With Adaptive Potential Field for Autonomous Vehicles. IEEE Trans. Veh. Technol. 2024, 73, 9747–9762. [Google Scholar] [CrossRef]
  76. Long, C.; Dongfang, Q.; Xing, X.; Yingfeng, C.; Ju, X. A path and velocity planning method for lane changing collision avoidance of intelligent vehicle based on cubic 3-D Bezier curve. Adv. Eng. Softw. 2019, 132, 65–73. [Google Scholar]
  77. You, C.; Lu, J.; Filev, D.; Tsiotras, P. Autonomous Planning and Control for Intelligent Vehicles in Traffic. IEEE Trans. Intell. Transp. Syst. 2020, 21, 2339–2349. [Google Scholar] [CrossRef]
  78. Bulut, V. Path planning for autonomous ground vehicles based on quintic trigonometric Bézier curve. J. Braz. Soc. Mech. Sci. Eng. 2021, 43, 104. [Google Scholar] [CrossRef]
  79. Wu, Y.; Li, X.; Gao, J.; Yang, X. Research on Automatic Vertical Parking Path-Planning Algorithms for Narrow Parking Spaces. Electronics 2023, 12, 4203. [Google Scholar] [CrossRef]
  80. Yang, X.; Zhu, X.; Liu, W.; Ye, H.; Xue, W.; Yan, C.; Xu, W. A Hybrid Autonomous Recovery Scheme for AUV Based Dubins Path and Non-Singular Terminal Sliding Mode Control Method. IEEE Access 2022, 10, 61265–61276. [Google Scholar] [CrossRef]
  81. Essuman, J.B.; Meng, X. Optimal Trajectory Planning for Autonomous Vehicles in Unstructured Environments. IEEE Control Syst. Lett. 2024, 8, 2673–2678. [Google Scholar] [CrossRef]
  82. Yao, Y.; Huang, X.; Huang, D.; Tian, C. Research on adaptive multi segment arc parking path fitting algorithm. In Proceedings of the 2023 3rd International Conference on Consumer Electronics and Computer Engineering (ICCECE), Guangzhou, China, 6–8 January 2023; pp. 362–367. [Google Scholar]
  83. Wang, J.; Jia, X.; Zhang, T.; Ma, N.; Meng, M.Q.H. Deep Neural Network Enhanced Sampling-Based Path Planning in 3D Space. IEEE Trans. Autom. Sci. Eng. 2022, 19, 3434–3443. [Google Scholar] [CrossRef]
  84. Qi, J.; Yang, H.; Sun, H. MOD-RRT*: A Sampling-Based Algorithm for Robot Path Planning in Dynamic Environment. IEEE Trans. Ind. Electron. 2021, 68, 7244–7251. [Google Scholar] [CrossRef]
  85. Francis, A.; Faust, A.; Chiang, H.T.L.; Hsu, J.; Kew, J.C.; Fiser, M.; Lee, T.W.E. Long-Range Indoor Navigation With PRM-RL. IEEE Trans. Robot. 2020, 36, 1115–1134. [Google Scholar] [CrossRef]
  86. Wang, X.; Wei, J.; Zhou, X.; Xia, Z.; Gu, X. AEB-RRT*: An adaptive extension bidirectional RRT* algorithm. Auton. Robot. 2022, 46, 685–704. [Google Scholar] [CrossRef]
  87. Novosad, M.; Penicka, R.; Vonasek, V. CTopPRM: Clustering Topological PRM for Planning Multiple Distinct Paths in 3D Environments. IEEE Robot. Autom. Lett. 2023, 8, 7336–7343. [Google Scholar] [CrossRef]
  88. Jiang, C.; Hu, Z.; Mourelatos, Z.P.; Gorsich, D.; Jayakumar, P.; Fu, Y.; Majcher, M. R2-RRT*: Reliability-Based Robust Mission Planning of Off-Road Autonomous Ground Vehicle Under Uncertain Terrain Environment. IEEE Trans. Autom. Sci. Eng. 2022, 19, 1030–1046. [Google Scholar] [CrossRef]
  89. Ma, H.; Meng, F.; Ye, C.; Wang, J.; Meng, M.Q.H. Bi-Risk-RRT Based Efficient Motion Planning for Autonomous Ground Vehicles. IEEE Trans. Intell. Veh. 2022, 7, 722–733. [Google Scholar] [CrossRef]
  90. Zhang, R.; Chai, R.; Chen, K.; Zhang, J.; Chai, S.; Xia, Y.; Tsourdos, A. Efficient and Near-Optimal Global Path Planning for AGVs: A DNN-Based Double Closed-Loop Approach With Guarantee Mechanism. IEEE Trans. Ind. Electron. 2024, 72, 681–692. [Google Scholar] [CrossRef]
  91. Fan, H.; Zhu, F.; Liu, C.; Zhang, L.; Zhuang, L.; Li, D.; Zhu, W.; Hu, J.; Li, H.; Kong, Q. Baidu Apollo EM Motion Planner. arXiv 2018, arXiv:1807.08048. [Google Scholar]
  92. Ding, W.; Zhang, L.; Chen, J.; Shen, S. Safe Trajectory Generation for Complex Urban Environments Using Spatio-Temporal Semantic Corridor. IEEE Robot. Autom. Lett. 2019, 4, 2997–3004. [Google Scholar] [CrossRef]
  93. Li, B.; Ouyang, Y.; Li, X.; Cao, D.; Zhang, T.; Wang, Y. Mixed-Integer and Conditional Trajectory Planning for an Autonomous Mining Truck in Loading/Dumping Scenarios: A Global Optimization Approach. IEEE Trans. Intell. Veh. 2023, 8, 1512–1522. [Google Scholar] [CrossRef]
  94. Li, B.; Wang, Y.; Ma, S.; Bian, X.; Li, H.; Zhang, T.; Li, X.; Zhang, Y. Adaptive Pure Pursuit: A Real-Time Path Planner Using Tracking Controllers to Plan Safe and Kinematically Feasible Paths. IEEE Trans. Intell. Veh. 2023, 8, 4155–4168. [Google Scholar] [CrossRef]
  95. Wang, N.; Xu, H. Dynamics-Constrained Global-Local Hybrid Path Planning of an Autonomous Surface Vehicle. IEEE Trans. Veh. Technol. 2020, 69, 6928–6942. [Google Scholar] [CrossRef]
  96. Wen, J.; Zhang, X.; Gao, H.; Yuan, J.; Fang, Y. E3MoP: Efficient Motion Planning Based on Heuristic-Guided Motion Primitives Pruning and Path Optimization With Sparse-Banded Structure. IEEE Trans. Autom. Sci. Eng. 2022, 19, 2762–2775. [Google Scholar] [CrossRef]
  97. Li, H.; Zhao, T.; Dian, S. Forward search optimization and subgoal-based hybrid path planning to shorten and smooth global path for mobile robots. Knowl. Based Syst. 2022, 258, 110034. [Google Scholar] [CrossRef]
  98. Huang, Z.; Chu, D.; Wu, C.; He, Y. Path Planning and Cooperative Control for Automated Vehicle Platoon Using Hybrid Automata. IEEE Trans. Intell. Transp. Syst. 2019, 20, 959–974. [Google Scholar] [CrossRef]
  99. Iris, Ç.; Lam, J.S.L. A review of energy efficiency in ports: Operational strategies, technologies and energy management systems. Renew. Sustain. Energy Rev. 2019, 112, 170–182. [Google Scholar] [CrossRef]
  100. Iris, Ç.; Christensen, J.; Pacino, D.; Ropke, S. Flexible ship loading problem with transfer vehicle assignment and scheduling. Transp. Res. Part B: Methodol. 2018, 111, 113–134. [Google Scholar] [CrossRef]
  101. Ren, Z.; Rathinam, S.; Choset, H. CBSS: A New Approach for Multiagent Combinatorial Path Finding. IEEE Trans. Robot. 2023, 39, 2669–2683. [Google Scholar] [CrossRef]
  102. An, G.; Talebpour, A. Vehicle Platooning for Merge Coordination in a Connected Driving Environment: A Hybrid ACC-DMPC Approach. IEEE Trans. Intell. Transp. Syst. 2023, 24, 5239–5248. [Google Scholar] [CrossRef]
  103. Zhang, B.; Huang, J.; Su, Y.; Wang, X.; Chen, Y.H.; Yang, D.; Zhong, Z. Safety-Guaranteed Oversized Cargo Cooperative Transportation With Closed-Form Collision-Free Trajectory Generation and Tracking Control. IEEE Trans. Intell. Transp. Syst. 2024, 25, 20162–20174. [Google Scholar] [CrossRef]
  104. Hönig, W.; Kiesel, S.; Tinka, A.; Durham, J.W.; Ayanian, N. Persistent and Robust Execution of MAPF Schedules in Warehouses. IEEE Robot. Autom. Lett. 2019, 4, 1125–1131. [Google Scholar] [CrossRef]
  105. Skrynnik, A.; Andreychuk, A.; Yakovlev, K.; Panov, A.I. When to Switch: Planning and Learning for Partially Observable Multi-Agent Pathfinding. IEEE Trans. Neural Netw. Learn. Syst. 2024, 35, 17411–17424. [Google Scholar] [CrossRef] [PubMed]
  106. Hua, Y.; Wang, Y.; Ji, Z. Adaptive Lifelong Multi-Agent Path Finding With Multiple Priorities. IEEE Robot. Autom. Lett. 2024, 9, 5607–5614. [Google Scholar] [CrossRef]
  107. Mi, X.; Zou, Y.; Li, S.; Karimi, H.R. Self-Triggered DMPC Design for Cooperative Multiagent Systems. IEEE Trans. Ind. Electron. 2020, 67, 512–520. [Google Scholar] [CrossRef]
  108. Wei, H.; Zhang, K.; Shi, Y. Self-Triggered Min–Max DMPC for Asynchronous Multiagent Systems With Communication Delays. IEEE Trans. Ind. Inform. 2022, 18, 6809–6817. [Google Scholar] [CrossRef]
  109. Cai, Y.; Li, Y.; Lian, Y.; Chen, L.; Zhong, Y.; Sun, X.; Yuan, C. Cooperative Control of Coupled Multiagent System of Autonomous Vehicle Chassis Based on Co-DMPC. IEEE Trans. Transp. Electrif. 2025, 11, 1875–1890. [Google Scholar] [CrossRef]
  110. Ning, B.; Han, Q.L.; Lu, Q. Fixed-Time Leader-Following Consensus for Multiple Wheeled Mobile Robots. IEEE Trans. Cybern. 2020, 50, 4381–4392. [Google Scholar] [CrossRef]
  111. An, L.; Yang, G.H.; Deng, C.; Wen, C. Event-Triggered Reference Governors for Collisions-Free Leader–Following Coordination Under Unreliable Communication Topologies. IEEE Trans. Autom. Control 2024, 69, 2116–2130. [Google Scholar] [CrossRef]
  112. Wang, J.; Zhang, H.; Wang, Z.; Fu, J.; Wang, W.; Meng, Q. Event-Triggered Leader-Following Consensus Control of Nonlinear Multiagent Systems With Generally Uncertain Markovian Switching Topologies. IEEE Trans. Syst. Man Cybern. Syst. 2024, 54, 4942–4954. [Google Scholar] [CrossRef]
  113. Li, Z.; Pan, Q.; Miao, Z.; Sang, H.; Li, W. Automated Guided Vehicle Scheduling Problem in Manufacturing Workshops: An Adaptive Parallel Evolutionary Algorithm. IEEE Trans. Autom. Sci. Eng. 2025, 22, 7361–7372. [Google Scholar] [CrossRef]
  114. Wu, Y.; Zhu, X.; Fei, J.; Xu, H. A Novel Joint Optimization Method of Multi-Agent Task Offloading and Resource Scheduling for Mobile Inspection Service in Smart Factory. IEEE Trans. Veh. Technol. 2024, 73, 8563–8575. [Google Scholar] [CrossRef]
  115. Wei, Q.; Yan, Y.; Zhang, J.; Xiao, J.; Wang, C. A Self-Attention-Based Deep Reinforcement Learning Approach for AGV Dispatching Systems. IEEE Trans. Neural Netw. Learn. Syst. 2024, 35, 7911–7922. [Google Scholar] [CrossRef] [PubMed]
  116. Li, Z.; Sang, H.; Pan, Q.; Gao, K.; Han, Y.; Li, J. Dynamic AGV Scheduling Model With Special Cases in Matrix Production Workshop. IEEE Trans. Ind. Inform. 2023, 19, 7762–7770. [Google Scholar] [CrossRef]
  117. Sierra-García, J.E.; Santos, M. AGV fuzzy control optimized by genetic algorithms. Log. J. IGPL 2024, 32, 955–970. [Google Scholar]
  118. Liu, W.; Li, M.; Liu, C. AGV Dual-wheel Speed Synchronous Control based on Adaptive Fuzzy PID. In Proceedings of the 2022 IEEE 5th Advanced Information Management, Communicates, Electronic and Automation Control Conference (IMCEC), Chongqing, China, 16–18 December 2022; pp. 564–569. [Google Scholar]
  119. Xin, M.; Yin, Y.; Zhang, K.; Lackner, D.; Ren, Z.; Minor, M. Continuous Robust Trajectory Tracking Control for Autonomous Ground Vehicles Considering Lateral and Longitudinal Kinematics and Dynamics via Recursive Backstepping. In Proceedings of the 2021 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Prague, Czech Republic, 27 September–1 October 2021; pp. 8373–8380. [Google Scholar]
  120. Gao, Z.; Zhang, Y.; Guo, G. Fixed-Time Prescribed Performance Adaptive Fixed-Time Sliding Mode Control for Vehicular Platoons With Actuator Saturation. IEEE Trans. Intell. Transp. Syst. 2022, 23, 24176–24189. [Google Scholar] [CrossRef]
  121. Liu, W.; He, C.; Ji, Y.; Hou, X.; Zhang, J. Active Disturbance Rejection Control of Path Following Control for Autonomous Ground Vehicles. In Proceedings of the 2020 Chinese Automation Congress (CAC), Shanghai, China, 6–8 November 2020; pp. 6839–6844. [Google Scholar]
  122. Zhou, X.; Jin, L.; Liu, Y. Modeling and Simulation Research of Heavy-duty AGV Tracking Control System Based on Magnetic Navigation. J. Phys. Conf. Ser. 2021, 1746, 012021. [Google Scholar] [CrossRef]
  123. Taghavifar, H. Neural Network Autoregressive With Exogenous Input Assisted Multi-Constraint Nonlinear Predictive Control of Autonomous Vehicles. IEEE Trans. Veh. Technol. 2019, 68, 6293–6304. [Google Scholar] [CrossRef]
  124. Zhao, D.; Wang, Z.; Liu, S.; Han, Q.L.; Wei, G. PID Tracking Control Under Multiple Description Encoding Mechanisms. IEEE Trans. Syst. Man Cybern. Syst. 2023, 53, 7025–7037. [Google Scholar] [CrossRef]
  125. Fu, W.; Liu, Y.; Zhang, X. Research on Accurate Motion Trajectory Control Method of Four-Wheel Steering AGV Based on Stanley-PID Control. Sensors 2023, 23, 7219. [Google Scholar] [PubMed]
  126. Anil, A.; Jisha, V.R. Trajectory Tracking Control of an Autonomous Vehicle using Model Predictive Control and PID Controller. In Proceedings of the 2023 International Conference on Control, Communication and Computing (ICCC), Thiruvananthapuram, India, 19–21 May 2023; pp. 1–6. [Google Scholar]
  127. Moshayedi, A.J.; Li, J.; Sina, N.; Chen, X.; Liao, L.; Gheisari, M.; Xie, X. Simulation and Validation of Optimized PID Controller in AGV (Automated Guided Vehicles) Model Using PSO and BAS Algorithms. Comput. Intell. Neurosci. 2022, 2022, 7799654. [Google Scholar] [CrossRef] [PubMed]
  128. Shi, Q.; Zhang, H. Road-Curvature-Range-Dependent Path Following Controller Design for Autonomous Ground Vehicles Subject to Stochastic Delays. IEEE Trans. Intell. Transp. Syst. 2022, 23, 17440–17450. [Google Scholar] [CrossRef]
  129. Chen, B.S.; Liu, H.T.; Wu, R.S. Robust H∞ Fault-Tolerant Observer-Based PID Path Tracking Control of Autonomous Ground Vehicle With Control Saturation. IEEE Open J. Veh. Technol. 2024, 5, 298–311. [Google Scholar] [CrossRef]
  130. Jin, X.; Yu, Z.; Yin, G.; Wang, J. Improving Vehicle Handling Stability Based on Combined AFS and DYC System via Robust Takagi-Sugeno Fuzzy Control. IEEE Trans. Intell. Transp. Syst. 2018, 19, 2696–2707. [Google Scholar] [CrossRef]
  131. Sariyildiz, E.; Oboe, R.; Ohnishi, K. Disturbance Observer-Based Robust Control and Its Applications: 35th Anniversary Overview. IEEE Trans. Ind. Electron. 2020, 67, 2042–2053. [Google Scholar] [CrossRef]
  132. Shin, J.; Kwak, D.; Lee, T. Robust path control for an autonomous ground vehicle in rough terrain. Control Eng. Pract. 2020, 98, 104384. [Google Scholar] [CrossRef]
  133. Lee, M.Y.; Chen, B.S. Robust H∞ Network Observer-Based Attack-Tolerant Path Tracking Control of Autonomous Ground Vehicle. IEEE Access 2022, 10, 58332–58353. [Google Scholar] [CrossRef]
  134. Xu, Y.; Wu, Z.G.; Pan, Y.J. Perceptual Interaction-Based Path Tracking Control of Autonomous Vehicles Under DoS Attacks: A Reinforcement Learning Approach. IEEE Trans. Veh. Technol. 2023, 72, 14028–14039. [Google Scholar] [CrossRef]
  135. Liang, Z.; Zhao, J.; Liu, B.; Wang, Y.; Ding, Z. Velocity-Based Path Following Control for Autonomous Vehicles to Avoid Exceeding Road Friction Limits Using Sliding Mode Method. IEEE Trans. Intell. Transp. Syst. 2022, 23, 1947–1958. [Google Scholar] [CrossRef]
  136. Qiang, Z.; Li, W.F.; Zhou, J.L. No-Load Formation Control of Dual AGVs Based on Container Terminals. In Proceedings of the 2022 IEEE International Conference on Networking, Sensing and Control (ICNSC), Shanghai, China, 15–18 December 2022; pp. 1–5. [Google Scholar]
  137. Zhong, Z.; Wang, X.; Lam, H.K. Finite-Time Fuzzy Sliding Mode Control for Nonlinear Descriptor Systems. IEEE/CAA J. Autom. Sin. 2021, 8, 1141–1152. [Google Scholar] [CrossRef]
  138. El Hajjami, L.; Mellouli, E.M.; Berrada, M. Robust adaptive non-singular fast terminal sliding-mode lateral control for an uncertain ego vehicle at the lane-change maneuver subjected to abrupt change. Int. J. Dyn. Control 2021, 9, 1765–1782. [Google Scholar] [CrossRef]
  139. Jiang, B.; Li, J.; Yang, S. An improved sliding mode approach for trajectory following control of nonholonomic mobile AGV. Sci. Rep. 2022, 12, 17763. [Google Scholar] [CrossRef]
  140. Chen, Z.; Pan, S.; Tang, X.; Meng, X.; Gao, W.; Yu, B. Design and application of finite-time tracking control for autonomous ground vehicle affected by external disturbances. Int. J. Robust Nonlinear Control 2024, 34, 12257–12285. [Google Scholar] [CrossRef]
  141. Li, X.; Sun, Z.; Cao, D.; Liu, D.; He, H. Development of a new integrated local trajectory planning and tracking control framework for autonomous ground vehicles. Mech. Syst. Signal Process. 2017, 87, 118–137. [Google Scholar] [CrossRef]
  142. Cheng, S.; Li, L.; Chen, X.; Wu, J.; Wang, H.d. Model-Predictive-Control-Based Path Tracking Controller of Autonomous Vehicle Considering Parametric Uncertainties and Velocity-Varying. IEEE Trans. Ind. Electron. 2021, 68, 8698–8707. [Google Scholar] [CrossRef]
  143. Qi, J.; Wu, Y. Trajectory Tracking Control for Double-steering Automated Guided Vehicle Based on Model Predictive Control. J. Phys. Conf. Ser. 2020, 1449, 012107. [Google Scholar] [CrossRef]
  144. Tang, M.; Lin, S.; Luo, Y. Mecanum Wheel AGV Trajectory Tracking Control Based on Efficient MPC Algorithm. IEEE Access 2024, 12, 13763–13772. [Google Scholar] [CrossRef]
  145. Zhang, K.; Sun, Q.; Shi, Y. Trajectory Tracking Control of Autonomous Ground Vehicles Using Adaptive Learning MPC. IEEE Trans. Neural Netw. Learn. Syst. 2021, 32, 5554–5564. [Google Scholar] [CrossRef]
  146. Liu, X.; Wang, G.; Chen, K. Nonlinear Model Predictive Tracking Control With C/GMRES Method for Heavy-Duty AGVs. IEEE Trans. Veh. Technol. 2021, 70, 12567–12580. [Google Scholar] [CrossRef]
  147. Li, J.; Ran, M.; Xie, L. Design and Experimental Evaluation of a Hierarchical Controller for an Autonomous Ground Vehicle With Large Uncertainties. IEEE Trans. Control Syst. Technol. 2022, 30, 1215–1227. [Google Scholar] [CrossRef]
  148. He, F.; Huang, Q. Time-Optimal Trajectory Planning of 6-DOF Manipulator Based on Fuzzy Control. Actuators 2022, 11, 332. [Google Scholar] [CrossRef]
  149. Fang, Y.; Wang, S.; Bi, Q.; Wu, G.; Guan, W.; Wang, Y.; Yan, C. Research on Path Planning and Trajectory Tracking of an Unmanned Electric Shovel Based on Improved APF and Preview Deviation Fuzzy Control. Machines 2022, 10, 707. [Google Scholar] [CrossRef]
  150. Lu, X.; Xing, Y.; Zhuo, G.; Bo, L.; Zhang, R. Review on Motion Control of Autonomous Vehicles. J. Mech. Eng. 2020, 56, 127–143. [Google Scholar]
  151. Yang, D.; Su, C.; Wu, H.; Xu, X.; Zhao, X. Construction of Novel Self-Adaptive Dynamic Window Approach Combined With Fuzzy Neural Network in Complex Dynamic Environments. IEEE Access 2022, 10, 104375–104383. [Google Scholar] [CrossRef]
  152. Ren, Y.; Xie, X.; Wu, J.; Xia, J. Enhanced H∞ Tracking Control of Autonomous Ground Vehicles via a Novel Fuzzy Switching Controller. IEEE Trans. Consum. Electron. 2024, 70, 1821–1832. [Google Scholar] [CrossRef]
  153. Cai, G.; Xu, L.; Zhu, X.; Liu, Y.; Feng, J.; Yin, G. Fuzzy Adaptive Event-Triggered Path Tracking Control for Autonomous Vehicles Considering Rollover Prevention and Parameter Uncertainty. IEEE Trans. Syst. Man Cybern. Syst. 2024, 54, 4896–4907. [Google Scholar] [CrossRef]
  154. Chai, R.; Tsourdos, A.; Savvaris, A.; Chai, S.; Xia, Y.; Chen, C.L.P. Six-DOF Spacecraft Optimal Trajectory Planning and Real-Time Attitude Control: A Deep Neural Network-Based Approach. IEEE Trans. Neural Netw. Learn. Syst. 2020, 31, 5005–5013. [Google Scholar] [CrossRef]
  155. Zhu, J.; Zhu, J.; Wang, Z.; Guo, S.; Xu, C. Hierarchical Decision and Control for Continuous Multitarget Problem: Policy Evaluation With Action Delay. IEEE Trans. Neural Netw. Learn. Syst. 2019, 30, 464–473. [Google Scholar] [CrossRef]
  156. Yanming, Q.; Huang, L.; Ma, L.; He, Y.; Wang, R. Neural Network-Based Indoor Autonomously-Navigated AGV Motion Trajectory Data Fusion. Autom. Control Comput. Sci. 2021, 55, 334–345. [Google Scholar] [CrossRef]
  157. Chen, Y.; Li, D.; Zhong, H.; Zhu, O.; Zhao, Z. The Determination of Reward Function in AGV Motion Control Based on DQN. J. Phys. Conf. Ser. 2022, 2320, 012002. [Google Scholar] [CrossRef]
  158. Chai, R.; Tsourdos, A.; Savvaris, A.; Chai, S.; Xia, Y.; Chen, C.L.P. Design and Implementation of Deep Neural Network-Based Control for Automatic Parking Maneuver Process. IEEE Trans. Neural Netw. Learn. Syst. 2022, 33, 1400–1413. [Google Scholar] [CrossRef] [PubMed]
  159. Quan, Y.; Lei, M.; Chen, W.; Wang, R. AGV Motion Balance and Motion Regulation Under Complex Conditions. Int. J. Control. Autom. Syst. 2022, 20, 551–563. [Google Scholar] [CrossRef]
  160. Lv, C.; Li, H.; Zhang, H.; Fu, M. Nonlinear Optimal Control Based on FBDEs and its Application to AGV. IEEE Trans. Cybern. 2024, 54, 6448–6457. [Google Scholar] [CrossRef] [PubMed]
  161. Cao, Y.; Zhao, H.; Cheng, Y.; Shu, T.; Chen, Y.; Liu, G.; Liang, G.; Zhao, J.; Yan, J.; Li, Y. Survey on Large Language Model-Enhanced Reinforcement Learning: Concept, Taxonomy, and Methods. IEEE Trans. Neural Netw. Learn. Syst. 2025, 36, 9737–9757. [Google Scholar] [CrossRef]
  162. Han, L.; He, L.; Sun, X.; Li, Z.; Zhang, Y. An enhanced adaptive 3D path planning algorithm for mobile robots with obstacle buffering and improved Theta* using minimum snap trajectory smoothing. J. King Saud Univ. Comput. Inf. Sci. 2023, 35, 101844. [Google Scholar] [CrossRef]
  163. Li, Y.; Wang, D.; Li, Q.; Cheng, G.; Li, Z.; Li, P. Advanced 3D Navigation System for AGV in Complex Smart Factory Environments. Electronics 2024, 13, 130. [Google Scholar]
  164. dos Reis, W.P.N.; Morandin Junior, O. Sensors applied to automated guided vehicle position control: A systematic literature review. Int. J. Adv. Manuf. Technol. 2021, 113, 21–34. [Google Scholar] [CrossRef]
  165. Huang, C.; Ma, Z. Research Progress and Application of Multi-Sensor Data Fusion Technology in AGVs. In Proceedings of the 2024 5th International Conference on Mechatronics Technology and Intelligent Manufacturing (ICMTIM), Nanjing, China, 26–28 April 2024; pp. 256–261. [Google Scholar]
  166. Jeong, Y. Self-Adaptive Motion Prediction-Based Proactive Motion Planning for Autonomous Driving in Urban Environments. IEEE Access 2021, 9, 105612–105626. [Google Scholar] [CrossRef]
  167. Ploeg, C.v.d.; Nyberg, T.; Sánchez, J.M.G.; Silvas, E.; Wouw, N.v.d. Overcoming Fear of the Unknown: Occlusion-Aware Model-Predictive Planning for Automated Vehicles Using Risk Fields. IEEE Trans. Intell. Transp. Syst. 2024, 25, 12591–12604. [Google Scholar] [CrossRef]
  168. Booyse, W.; Wilke, D.N.; Heyns, S. Deep digital twins for detection, diagnostics and prognostics. Mech. Syst. Signal Process. 2020, 140, 106612. [Google Scholar] [CrossRef]
  169. Feng, K.; Ji, J.C.; Zhang, Y.; Ni, Q.; Liu, Z.; Beer, M. Digital twin-driven intelligent assessment of gear surface degradation. Mech. Syst. Signal Process. 2023, 186, 109896. [Google Scholar] [CrossRef]
  170. Zhang, Y.; Gao, Y.; Zhang, X.; Song, L.; Zhao, B.; Liu, J.; Liang, L.; Jiao, J. Fault Diagnosis of Heavy-Loaded AGV Based on Digital Mirror. IEEE Access 2024, 12, 162894–162907. [Google Scholar] [CrossRef]
Figure 1. Composition of port unmanned freight system.
Figure 1. Composition of port unmanned freight system.
Jmse 13 01318 g001
Figure 2. Challenges of port path planning and motion control.
Figure 2. Challenges of port path planning and motion control.
Jmse 13 01318 g002
Figure 3. Schematic diagram of A* algorithm path planning results.
Figure 3. Schematic diagram of A* algorithm path planning results.
Jmse 13 01318 g003
Figure 4. Schematic diagram of APF method path planning results.
Figure 4. Schematic diagram of APF method path planning results.
Jmse 13 01318 g004
Figure 5. RRT sampling method schematic diagram.
Figure 5. RRT sampling method schematic diagram.
Jmse 13 01318 g005
Figure 6. Leader–follower collaboration algorithm schematic diagram.
Figure 6. Leader–follower collaboration algorithm schematic diagram.
Jmse 13 01318 g006
Figure 7. PID motion control principle diagram.
Figure 7. PID motion control principle diagram.
Jmse 13 01318 g007
Figure 8. Block diagram of robust control.
Figure 8. Block diagram of robust control.
Jmse 13 01318 g008
Figure 9. Block diagram of SMC.
Figure 9. Block diagram of SMC.
Jmse 13 01318 g009
Figure 10. Fuzzy control flowchart for AIV.
Figure 10. Fuzzy control flowchart for AIV.
Jmse 13 01318 g010
Figure 11. AIV neural network control schematic.
Figure 11. AIV neural network control schematic.
Jmse 13 01318 g011
Table 1. Comparison of AIV path planning methods.
Table 1. Comparison of AIV path planning methods.
CategoryMethodAdvantageDisadvantageApplicable Scenarios
Global path planning methodGraph search methodCompleteness and adaptabilityPoor performance in wide-range searchDiscretized maps and static environments
Numerical optimizationMulti-objective joint optimizationPoor performance in large-scale searchContinuous spaces and trajectory smoothing
Intelligent bionic methodGlobal search capability, suitable for nonlinear problems Low computational efficiencyGlobal optimization in complex nonlinear environments
Intelligent learning optimizationAdaptability and globally optimizedRelies on model training, high algorithm complexityUnknown or dynamically changing environments.
Local path planning methodAPFAlgorithm simple, suitable for dynamic obstacleGet stuck in local minima, low real-time capabilityReal-time obstacle avoidance
Curve optimizationHighly intuitive, generates path smoothingSensitive to noise
and easy to overfit
Used to generate smooth paths
Sampling-based methodDeal with different types of path planning problemsRelatively high computing costHigh-dimensional unstructured path planning
Multi-vehicle Cooperative PlanningMAPFSupport global coordination and priority planningLimited scalability, poor real-time performance Handles collaborative path planning and optimizing overall efficiency
DMPCAdapt to dynamic environments and support real-time adjustmentsHigh computing resource requirements, complex parameter tuning Dynamic environments and adjusting paths in real time
LFCSimple structure Low flexibilityUsed for path tracking, suitable for linear system and minimal environmental disturbances
Table 2. Comparison of results of eight AIV path planning methods.
Table 2. Comparison of results of eight AIV path planning methods.
MethodA*GA
Length144.7500152.9603
Computing time/s0.14820.0170
Planning resultJmse 13 01318 i001Jmse 13 01318 i002
MethodACODRL
Length145.1904180.0000
Computing time/s19.58680.7700
Planning resultJmse 13 01318 i003Jmse 13 01318 i004
MethodPSOAPF
Length142.4952179.2324
Computing time/s0.01700.0387
Planning resultJmse 13 01318 i005Jmse 13 01318 i006
MethodCurve OptimizationRRT
Length175.4602178.4287
Computing time/s0.00700.0307
Planning resultJmse 13 01318 i007Jmse 13 01318 i008
Table 3. Comparison of classical control theories for AIV motion.
Table 3. Comparison of classical control theories for AIV motion.
MethodAdvantageDisadvantageApplicable Scenarios
PIDSimple principle, easy to implement;
Intuitive parameter adjustment
Integral saturation;
Sensitive to noise
Linear systems with known models and simple dynamic characteristics
Robust controlStability, anti-interference;
Optimize system performance
Complex design;
Computationally heavy
Systems with model uncertainties and incomplete modeling
SMCFast response speed;
High control precision
Prone to jitter;
Parameter adjustment difficulty
Strongly nonlinear systems with severe disturbances or uncertainties
MPCHandles multivariable coupling and constraintsStrong dependency on accurate modelsMulti-variable, constrained system control in dynamic environments
Fuzzy controlNo need for precise mathematical models;
Easily handles nonlinearity and uncertainty
Parameter and rule design rely on experience;
Limited accuracy struggles with complex systems
Complex nonlinear systems where precise mathematical modeling difficulty
NNCAdapts well to complex and dynamic systemsComplex network structure and parameter design;
Risk of overfitting
Highly nonlinear systems with unknown or dynamically changing models
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Share and Cite

MDPI and ACS Style

Yang, M.; Zhang, D.; Wang, H. Overview of Path Planning and Motion Control Methods for Port Transfer Vehicles. J. Mar. Sci. Eng. 2025, 13, 1318. https://doi.org/10.3390/jmse13071318

AMA Style

Yang M, Zhang D, Wang H. Overview of Path Planning and Motion Control Methods for Port Transfer Vehicles. Journal of Marine Science and Engineering. 2025; 13(7):1318. https://doi.org/10.3390/jmse13071318

Chicago/Turabian Style

Yang, Mei, Dan Zhang, and Haonan Wang. 2025. "Overview of Path Planning and Motion Control Methods for Port Transfer Vehicles" Journal of Marine Science and Engineering 13, no. 7: 1318. https://doi.org/10.3390/jmse13071318

APA Style

Yang, M., Zhang, D., & Wang, H. (2025). Overview of Path Planning and Motion Control Methods for Port Transfer Vehicles. Journal of Marine Science and Engineering, 13(7), 1318. https://doi.org/10.3390/jmse13071318

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Back to TopTop