Next Article in Journal
Transmission Control Protocol (TCP)-Based Delay Tolerant Networking for Space-Vehicle Communications in Cislunar Domain: An Experimental Approach
Previous Article in Journal
MR-FuSN: A Multi-Resolution Selective Fusion Approach for Bearing Fault Diagnosis
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Scene-Adaptive Loader Trajectory Planning and Tracking Control

1
Key Laboratory of CNC Equipment Reliability, Ministry of Education, School of Mechanical and Aerospace Engineering, Jilin University, Changchun 130022, China
2
XCMG Construction Machinery Co., Ltd., Xuzhou 221004, China
*
Author to whom correspondence should be addressed.
Sensors 2025, 25(4), 1135; https://doi.org/10.3390/s25041135
Submission received: 29 December 2024 / Revised: 5 February 2025 / Accepted: 11 February 2025 / Published: 13 February 2025
(This article belongs to the Section Physical Sensors)

Abstract

:
Wheel loaders play a crucial role in daily production and transportation. With the rapid development of intelligence in passenger vehicles, freeing loader operators from high-risk and repetitive tasks has become a pressing issue. This paper presents a novel and efficient path planning and tracking framework tailored to the unique body structure and specific operating environment of loaders. We improve the Hybrid A* search algorithm based on the operational characteristics of loaders and integrate it with dynamically updated grid maps to enable the autonomous planning of loader operating paths in unstructured environments, meeting the efficiency requirements of production. Additionally, to address the challenge of poor trajectory tracking control accuracy caused by hydraulic articulated steering, we propose a new loader trajectory tracking controller based on the idea of hierarchical control. We use an extended state observer to compensate for unknown disturbances in the steering execution layer and employ fuzzy fractional-order PID to handle the nonlinearity of loaders. Field experiments using the proposed approach demonstrate that loaders can autonomously and in real-time complete tasks in dynamically changing operating scenarios.

1. Introduction

Wheel loaders are widely used in unstructured terrains such as mines, mixing stations, and construction sites due to their unique articulated steering structure [1], which provides greater flexibility during transportation. The unmanned autonomous operation of wheel loaders has garnered significant attention from scholars, given challenges like harsh working environments and high operational repeatability. However, the wheel loader’s unique steering structure and specialized operational scenarios render traditional passenger vehicle trajectory planning and tracking algorithms unsuitable. Thus, developing adaptive trajectory planning and tracking control solutions tailored to loader operational scenarios is crucial for achieving unmanned loader operations [2,3].
The foundation of autonomous operation lies in the rational planning of a feasible path for the loader. W. Yossawee et al. [4] proposed a semi-optimal path generation scheme comprising three line segments and two clothoid curves. This scheme demands high symmetry in the loader’s operating path, a condition challenging to maintain in the real world. Alshaer et al. [5] extended and improved the shortest path calculation method of the Reeds–Shepp algorithm to propose a V-shaped path generation scheme. However, the use of fixed-radius arcs hinders the ability to plan a reasonable path when facing boundary constraints in operating scenarios. Choi and Huhtala [6] addressed this challenge by employing Bezier curves as feasible motion primitives and combining them with an online search algorithm like A* to achieve loader trajectory generation in semi-structured environments. While this scheme enhances the loader’s adaptability to the scene, its real-time performance still falls short of meeting the efficiency requirements of loader production. Chen et al. [7] proposed a method that combines dynamic window path planning with model predictive control (MPC) to help articulated vehicles working in underground tunnels avoid collisions on their own. This strategy effectively addresses the obstacle avoidance difficulties encountered by articulated vehicles traversing limited pathways.
Despite previous research, achieving a loader motion trajectory that adapts to both the environment and operational conditions still requires addressing several challenges. Firstly, during loader operations, new obstacles may appear (such as pedestrians or other cooperative vehicles), while existing obstacles may disappear (such as diminishing material piles). Secondly, the planned path must adhere to loader kinematic constraints. This paper presents a method based on the improved Hybrid A* algorithm with dynamic grid maps. This method combines global navigation and local planning layers to allow for the real-time planning of autonomous loader operation paths in environments that are not structured.
Ensuring the safe, efficient, and accurate tracking of predefined trajectories is a critical aspect of enhancing the autonomous operation capabilities of loaders. Nayl et al. [8,9] used an improved sliding mode control and model predictive control algorithm based on the nonlinear motion model of loaders to achieve the lateral control of articulated vehicles. Bai et al. [10] proposed a nonlinear model predictive control scheme to enhance the tracking performance of articulated vehicles at high speeds, and validated the effectiveness of their approach under simulation conditions. Chen et al. [11] improved path tracking on uneven terrain by adding iterative learning as a feedforward control component to the current MPC framework. This made the MPC control more accurate. The precision of control depends on the ongoing optimization of a singular trajectory through iterative learning. Wei et al. [12] solved the problem of route tracking on surfaces with low traction by creating a hierarchical cascaded control (HCC) framework that estimates the ground adhesion coefficient. Chen et al. [13] showed a model predictive control (MPC) algorithm that uses fuzzy switching logic to help articulated vehicles handle different road conditions and speeds better. Yu et al. [14] studied how to improve the parameters for articulated wheel loader route tracking using LQR by testing how well different intelligent clustering algorithms (AGA, QPSO, and ACA) worked with LQR. This gave us a lot of information for future research. Wang et al. [15] came up with a reinforcement learning-based control strategy for loaders’ front and back axles that makes it easier to follow a path. However, this method is not very useful in real life because it does not take into account how topography and changes in load affect tracking performance.
After examining the aforementioned contributions, the subsequent observations might be articulated: (1) Rarely has the literature examined the practical performance of route tracking control techniques for articulated loaders. (2) The issues with keeping an eye on large curves and handling sudden changes in curves, which are common in the real world, have not been looked into in depth. (3) In the past, researchers have mostly ignored the influence of pressure fluctuations and disturbances in hydraulic steering systems on tracking performance. The main contributions of this paper are as follows:
(1)
To address the unique scenarios of loader operations, an improved Hybrid A* planning algorithm based on dynamic grid maps is proposed, enhancing the adaptability of trajectory planning.
(2)
To improve loader tracking performance, a hierarchical trajectory tracking control scheme is employed. Firstly, in the upper-layer control, a fuzzy fractional-order PID controller with preview control incorporating curvature speed adaptation is selected. Secondly, to mitigate the impact of the unique articulated steering structure on tracking, a PD controller based on a nonlinear extended state observer (NLESO) is utilized in the lower-layer control.
(3)
The application of the proposed planning and control scheme to actual vehicles has been supported by a large number of experimental results, which thoroughly demonstrate the effectiveness of this strategy.
The remaining sections of this paper are organized as follows: Section 2 establishes the kinematic model of the loader and provides a detailed introduction to the characteristics of autonomous loader operations. In Section 3, an improved Hybrid A* planning scheme based on dynamic grid maps is presented. Section 4 details the trajectory tracking control scheme for the loader. Section 5 presents specific experimental results and discussions. Finally, Section 6 provides a summary of this paper.

2. Kinematic Modeling and Problem Statement

2.1. Kinematic Modeling

As shown in Figure 1, the mechanical structure of an articulated loader differs from conventional passenger vehicles. It utilizes an articulated steering device to divide the vehicle into front and rear sections, enabling more flexible steering by adjusting the angle of the joint (articulated angle γ ). This design is particularly advantageous for operations in narrow terrains. The vehicle structure described in this paper is extensively detailed and analyzed in [16], which explains the kinematics of the loader. The kinematic model of the loader can be represented as
x ˙ f y ˙ f θ ˙ f γ ˙ = cos θ f sin θ f sin γ l f cos γ + l r 0 v f + 0 0 l r l f cos γ + l r 1 ω r

2.2. Problem Statement

When operating in transportation tasks, V-shaped trajectories are favored by many drivers due to the characteristic of short operating cycles and high efficiency [17]. The specific workflow of this operating condition is illustrated in Figure 2. Firstly, the loader advances to the loading point and loads materials (trajectory 1); then, it reverses to the turning point (trajectory 2); next, it moves forward to the unloading point (such as a truck or hopper) and unloads materials (trajectory 3); and finally, it reverses back to the turning point (trajectory 4).

3. Trajectory Planner

During actual loader operations, changes in obstacle information can render paths planned based on global navigation maps inadequate for safe passage. While some scholars have addressed similar issues using quadratic programming algorithms [18], the specialized nature of loader operating scenarios, such as the need for long-term parking of cooperative vehicles like self-dumping trucks, requires the re-execution of quadratic programming after each global planning, impacting loader operational efficiency. Additionally, traditional dynamic search algorithms [19], which require significant trial and error time in the initial planning stage, are unsuitable for the point-to-point operation mode of loaders.
To address these challenges, this paper first plans the loader’s global navigation path using an improved Hybrid A* algorithm based on a pre-established global navigation map. During loader operation, real-time updates of local grid maps are performed. These updates, combined with the global navigation path, allow for the identification of obstacle information affecting loader passage and determining the need for re-planning. The updated grid map is then applied in the next global navigation planning cycle. The specific planning process is illustrated in Figure 3.

3.1. Path Planning Based on Improved Hybrid A* Algorithm

To address the phenomenon that the A* algorithm [20] performs poorly when dealing with planning problems in the presence of motion constraints, Dolgov et al. [21] proposed a hybrid A* search algorithm with heuristic components to solve incomplete constraints.

3.1.1. Collision Avoidance

In the global planning process, it is crucial to consider not only the length of the path but also its effectiveness in obstacle avoidance. To achieve this, distance maps are commonly employed [22]. However, when dealing with narrow passages in loader operating scenarios, this approach may lead to sub-optimal solutions and fail to plan a viable path.
In recent years, Voronoi diagrams [23] have been widely applied in obstacle avoidance path planning. While this method does not directly yield the shortest path between two points, it partitions obstacles into cells, allowing for the maximum utilization of gaps between obstacles to generate a drivable path that stays as far away from obstacles as possible. To ensure the safety and efficiency of loader operations, this paper incorporates Voronoi diagrams into the expansion of nodes in the Hybrid A* algorithm, using the resulting potential values as part of the cost function for the heuristic function. Based on the size parameters of the loader equipment, the following Voronoi potential field function is constructed:
ρ v x , y = α α + d 0 x , y d v x , y d v x , y + d 0 x , y d 0 x , y d 0 max d 0 max 2 , d 0 d 0 max 0 , d 0 > d 0 max
where, setting the rate of potential energy α to be decreased to 0.5, the maximum control range of potential energy d 0 max is 5 m.

3.1.2. Cost Function

With the above potential energy values as safety terms, the cost function is designed as follows:
F x , y = w 1 g x , y + w 2 h x , y + w 3 v x , y
where w 1 , w 2 , and w 3 are the weighting factors, g x , y indicates the cost of movement from the initial point to the current point, h x , y represents the estimated cost from the current point to the termination point, v x , y is the cost of avoiding obstacles, and F x , y is the total cost value.
Referring to the trajectories of experienced drivers, when planning the motion trajectory of a loader, it is important to ensure that the loader moves forward as much as possible to avoid frequent steering changes that could lead to path fluctuations, while also minimizing the number of turning maneuvers. Therefore, this paper designs the motion cost function as follows:
g x , y = P f s l f s + P f t l f t + P b s l b s + P b r l b r + P r e v l r e v
where l f s is the total step length for forward straight movement, l f t is the total step length for forward turning, l b s is the total step length for backward straight movement, l b t is the total step length for backward turning, and l r e v is the number of turning maneuvers. P f s , P f t , P b s , P b t and P r e v are the corresponding cost coefficients for each form.
The heuristic cost h x , y is defined as follows:
h ( x , y ) = max Cos t W i t h o u t O b s t Cos t W i t h O b s t
Here, Cos t W i t h o u t O b s t ignores the influence of obstacles in the environment, connects the current point to the target point through a Reeds–Shepp curve, and calculates the length of the optimal curve as the heuristic cost value, but Cos t W i t h O b s t is necessary to consider the information of obstacles in the environment, while also taking into account the influence of the motion direction of parent and child nodes, and determining the new cost value by executing the Hybrid A* algorithm.
The loader exhibits a ‘bending’ phenomenon during actual movement, and a detailed description can be found in this reference [24]. Therefore, to ensure that the loader does not experience collision accidents during operation, the obstacle avoidance cost v x , y should be designed as follows:
v x , y = max ρ v 1 x , y , ρ v 2 x , y , ρ v 3 x , y , ρ v 4 x , y , ρ v 5 x , y , ρ v 6 x , y , ρ v 7 x , y , ρ v 8 x , y
When the vehicle reaches point x , y , ρ v i x , y represents the Voronoi potential values of the eight corners in the bounding boxes of the front and rear bodies of the loader. To ensure safe driving, the obstacle avoidance cost should be set as the maximum potential value among them.

3.2. Path Post-Processing

3.2.1. Smoothing Process

The path generated by the planning program consists of numerous discrete points, forming an initial planned path that may not ensure smooth vehicle travel along the designated route in the operating environment. Therefore, this paper employs gradient descent to smooth the initial path. The specific optimization principles and process are detailed below.
Smoothness is defined as shown in Figure 4, where P 1 P 5 is the five discrete points in the initial planning path, P A is the midpoint of P 1 and P 3 , P B is the midpoint of P 2 and P 4 , and P C is the midpoint of P 3 and P 5 . Therefore, the smoothing degree is calculated as
f s = P A P 2 2 + P B P 3 2 + P C P 4 2
From Figure 4, it is evident that the smoothness changes with the position P 3 , and there is always a position P 3 that minimizes the smoothness. Therefore, the optimized position points can be obtained using the gradient descent algorithm. Initially, the optimal displacement Δ P of P 3 is set in the gradient direction. By setting the first derivative of smoothness with respect to Δ P to zero, Δ P can be calculated using the following formula:
f s Δ P = P 1 + P 3 + Δ P 2 P 2 2 + P 2 + P 4 2 P 3 2 Δ P 2 Δ P + P 3 + Δ P + P 5 2 P 4 2 Δ P
Δ P = 1 6 P 1 4 P 2 + 6 P 3 4 P 4 + P 5
Moving the path points according to (9) and iterating through multiple calculations, a fully smooth path can be obtained.

3.2.2. Path Connection at Turning Points

Analysis of the optimized smooth driving trajectory reveals that at turning points, the loader’s articulated steering, which connects the front and rear bodies, can cause an abrupt change in the heading of the front body, leading to unstable vehicle control [5]. In practical tracking tests of articulated vehicles, this instability often manifests as serpentine movements and poor tracking accuracy during subsequent tracking, significantly limiting the loader’s tracking performance. To address these issues, this paper introduces a straight line segment at the turning point, equal in length to the distance between the front and rear axles of the vehicle. The specific implementation is as follows.
Extract the coordinates and heading angle at the turning point x r e v , y r e v , θ r e v based on the turning flag. Assuming the length of the straight line segment added at this point is L and it contains N path points, the distance between adjacent path points is L n . Therefore, the coordinates of the i _ t h path point can be calculated as follows:
x ( i ) = x r e v i · L n · cos θ r e v y i = y r e v i · L n · sin θ r e v 1 i n θ i = θ r e v
Substituting i = 1 n into (10) provides the coordinates for all path points along the connecting straight line path. These points are then sequentially inserted after the turning point x r e v , y r e v , θ r e v to complete the path connection at the turning point.

4. Trajectory Tracking and Control

To ensure the loader can follow the planned trajectory, this paper proposes a hierarchical controller for its path tracking. Figure 5 illustrates the system framework. Initially, the trajectory tracking layer designs a preview error model with curvature and speed adaptive capabilities. This model enhances tracking precision using a fuzzy fractional-order PID controller. Next, this study uses a PD controller based on the nonlinear extended state observer (NLESO) to solve the problem of the steering actuator not being able to accurately respond to the upper control layer’s steering demands when disturbances are unknown.

4.1. Preview Error Model

By analyzing the driving habits of loader operators, it is evident that drivers typically concentrate their attention on an imagined “target point” in front of the vehicle, known as the “look-ahead point” [25]. Referring to driver behavior, when there is no driver in the loader, it is also necessary to provide a look-ahead point to help the controller better track the planned trajectory. The specific articulated vehicle preview error model is shown in Figure 6.
The selection of the conventional preview distance [26] is typically based solely on changes in the vehicle speed, which results in poor adaptability to changes in curvature. Considering that loaders often track large curvature and significant curvature changes at turning points in “V” shaped operating curves, ensuring the stability and smoothness of loader travel, this paper introduces a curvature factor into the original preview distance formula to adjust the impact of curvature on the tracking accuracy. The specific curvature and speed-adaptive preview distance adjustment algorithm is shown in (11):
L = L min v < v min L 0 + k 1 v k 2 S + σ v min v v max L max v > v max
Considering the safety of the loader, when the speed exceeds the specified maximum speed v max , it is usually kept in a straight line, so only the maximum preview distance L max when the curvature is 0 needs to be considered. At the same time, through a large number of experiments, it has been proven that when the speed is lower than the minimum travel speed v min , the curvature has little effect on the performance of the preview control [27] and is typically based solely on changes in the vehicle speed, which results in poor outcomes. Therefore, only the minimum preview distance L min should be set according to the conventional preview distance formula. When the speed is in the range of v min v v max , this paper introduces the weight factor k 2 and σ to reflect the degree of correlation between the degree of road curvature and the preview distance, and the weight factor k 1 is used to reflect the degree of correlation between the speed and the preview distance. The parameters of the preview error model are set as follows: v min = 0.5 , v max = 2 , L min = 1.74 , L 0 = 1.2 , k 1 = 1.08 , k 2 = 40 , σ = 1 , and L max = 3.36 .

4.2. Lateral Control Deviation

From Section 4.1, it is clear that the objective of lateral control for the unmanned loader is to ensure that the loader satisfies the conditions of e y 0 and e θ 0 . Here, the preview lateral deviation e ϕ is defined as shown in Figure 6. Based on this, Theorem 1 can be formulated.
Theorem 1
The entire proof is divided into the following two parts.
Part 1: Proving that e ϕ 0 e y 0 , e θ 0 .
In Figure 6, e ϕ = B A C (Lateral control deviation). Meanwhile, in Δ A B C , sin e ϕ = B E A B . Since e ϕ 0 and A B L d min 0 , it can be inferred that B E 0 , i.e., e y 0 . Moreover, because sin A C B = B E B C and B E 0 , it can be inferred that A C B = e θ 0 . Consequently, the conclusion is proven.
Part 2: Proving that e ϕ 0 e y 0 , e θ 0 . Since in Δ A B C , sin e ϕ = B E A B , if B E 0 , it has e ϕ 0 . The conclusion is proven.
In summary, lateral control deviations are defined as follows:
e ϕ = arctan H e y , e θ L e θ

4.3. Fuzzy Fractional-Order PID Controller

Loaders typically operate on unstructured surfaces, with the uncertainty of the objects being handled and the unique hydraulic articulated steering. These factors make loaders highly nonlinear, uncertain, and subject to time delays. In certain highly nonlinear and uncertain systems, conventional PID controllers may fail to deliver satisfactory tracking performance, particularly when precise path tracking is essential. Therefore, this paper proposes improvements to the PID controller by introducing fractional-order PID and fuzzy control.

4.3.1. Fractional-Order PID Controller

The transfer function of the FOPID controller is expressed as follows [28]:
C s = k p + k i s λ + k d s μ
Here, k p , k i and k d are the corresponding gain coefficients, all of which are positive. To ensure effective control execution, it is necessary to perform a finite-order approximation of the FO-differ-integral within a specific frequency range. This paper adopts Outstaloup’s fractional calculus finite approximation technique [29]. Specifically, when the frequency range is ω b , ω h , the filter’s transfer function is expressed as follows:
G f i l t e r s = ω h β Π l = n n s + ω l s + ω l
ω l = ω b ( ω h ω h ω b ω b ) l + N + l l β 2 2 N + 1
ω l = ω b ( ω h ω h ω b ω b ) l + N + l l + β 2 2 N + 1
where 2 N + 1 and β represent the orders of the filter and the integrator, respectively.

4.3.2. Fuzzy Rules

To simplify the design process, this paper optimizes the fractional-order parameters λ and μ based on experience. As a result, the fuzzy control system for the wheel loader only has two input variables and three output variables. The input variables are the deviations in preview distance e y and preview heading angle e θ , while the output variables are the three gain parameters of the FOPID2D controller.
It is very important to come up with the right fuzzy intervals so that the loader can quickly adjust to the right position and orientation and then fine-tune within a small range to find the best balance between the response speed and control accuracy. Through preliminary experimental tests, the corresponding optimization interval ranges are shown in Table 1. We divide fuzzy sets into five levels: NB (Negative Big), NS (Negative Small), Z (Zero), PS (Positive Small), and PB (Positive Big). Consequently, the fuzzy rules for the construction of the control system utilizing linguistic variables are presented in Table 2. Figure 7 illustrates the relationship between the input and output of the loader’s path tracking fuzzy controller.

4.4. Extended State Observer

Following the hydraulic steering system [30], the system state space can be described as
x ˙ 1 = x 2 x ˙ 2 = d x 1 , x 2 , t + b u y = x 1
where x 1 x 2 = γ ω r , δ x 1 , x 2 , t denotes the unknown perturbation. The expression for estimating the unknown perturbation in nonlinear ESO is as follows:
e 1 = x ^ 1 x r e f x ^ ˙ 1 = x ^ 2 β 1 e x ^ ˙ 2 = x ^ 3 β 2 f a l ( e , α , δ ) + b u x ^ ˙ 3 = β 3 f a l ( e , α , δ )
In the ESO, x 3 = d x 1 , x 2 , t represents the extended state variable used to estimate the total sum of unknown disturbances and model errors. To mitigate its impact on control performance, u E S O = b · x 3 is introduced into the original control law:
f a l ( e , α , δ ) = e δ 1 α e δ e α s i g n ( e ) e > δ
where β 1 = 3 ω 0 , β 1 = 3 ω 0 2 , β 1 = ω 0 3 , α, ω0, and δ are parameters of ESO.

5. Results and Discussion

We conducted experiments using a 5 ton loader in a mixing plant scenario to validate the effectiveness of the proposed trajectory planning and tracking control strategy. The experimental setup and platform are depicted in Figure 8. This section aims to address three key questions: (1) Can the trajectory planner generate collision-free and dynamically feasible trajectories in complex operational environments in real-time (see Section 5.1)? (2) Can the hydraulic steering controller withstand unknown disturbances and meet the steering requirements of the upper control layer (see Section 5.2)? (3) How does the trajectory tracking controller perform in real-world scenarios (see Section 5.3)? The parameters of the proposed controller are presented in Table 3.

5.1. Planning Performance

This paper evaluates the proposed planning module in a real transportation scenario shown in Figure 9a. The loader’s LiDAR captures the obstacle point cloud, which we project onto the ground to create the black lines in Figure 9b–d. First, Figure 9b shows the loader planning a drivable unloading path based on the previously established global navigation map before transportation. Secondly, Figure 9c demonstrates that during driving, the loader encounters a temporary parking obstacle (a truck) and can effectively plan an avoidance path. Finally, in Figure 9d, the loader generates a reasonable shovel avoidance path based on the updated grid map.

5.2. Steering Performance

To address the second question, this paper evaluates the performance of the proposed controllers using two steering trajectories. Considering that loaders are primarily affected by front-end loads during steering, we examine the basic performance of the controllers under varying loads.
The results indicate that the PD controller with NLESO performs better. Overall, introducing NLESO can effectively compensate for the effects of unknown disturbances on steering. As shown in Figure 10 and Figure 11, even under full load conditions, the controller with NLESO can maintain performance similar to that without additional loading. Conversely, without disturbance compensation, the tracking error significantly increases. Table 4 evaluates the performance of steering tracking sinusoidal curves using ME, MAE, and RMSE.

5.3. Trajectory Tracking Performance

This study evaluates the proposed framework by demonstrating the controller’s superiority and efficacy through tests and simulations.

5.3.1. Simulation Results

To validate the efficacy of the proposed path tracking system in curvature challenges, a dual-shift path is formulated as follows:
Y r e f x = d n 1 2 1 + tanh 2 · r 1 d n 2 2 1 + tanh 2 · r 2 θ r e f ( x ) = arctan d n 1 1 cosh r 1 2 1.2 d m 1 d n 2 1 cosh r 2 2 1.2 d m 2
where d m 1 = 35 , d m 2 = 40 , d n 1 = 7 , d n 2 = 9 , r 1 = 4 d m 1 x 27.19 1.2 and r 2 = 4 d m 2 x 54.46 1.2 .
Figure 12a illustrates that the path curvature is variable over time, reaching a maximum of 0.1. When comparing with popular path tracking controllers (PID and MPC), it is clear that while MPC has rolling prediction capabilities that allow it to maintain good tracking performance during scopes with slow changes in curvature, its maximum error may rise to 67 cm in scopes with sudden changes in curvature. This fails to comply with the safety standards for loader operation. Although the proposed strategy in this work leads to a bigger error within the curvature mutation interval, the biggest error stays at just 12.8 cm, which is a lot less than the other two controllers. To evaluate the steady-state performance of the controller, Figure 13 illustrates that the error of the proposed control scheme mainly lies within the range of −1.5 to 2 cm, while the interquartile range (IQR) is from −6.9 to 7.4 cm, which means that the error is more concentrated. The outlier range is limited to −11.8 to 12.8, thereby ensuring the loader’s operational safety.

5.3.2. Experimental Results

As shown in Figure 8, this experiment aimed to demonstrate that the proposed planning approach can generate drivable paths in real-time and achieve tracking in challenging operational conditions. The system can resist the effects of unknown disturbances and maintain good tracking performance.
The tracking performance in the real world is shown in Figure 14, where the position error is generally within ±0.15 m, with a maximum error of −0.235 m, and the heading error ranges from −0.21 rad to 0.16 rad. As shown in Figure 14b, the articulation angle remains stable throughout the tracking process, with an output range within ±0.4 rad, which is less than the loader’s steering constraint angle.

6. Conclusions

This paper presents a practical solution for planning and tracking in an unmanned loader system. By dynamically updating the grid map and using an improved Hybrid A* algorithm, the system achieves obstacle avoidance and transportation trajectory planning in loader operation scenarios. We also propose a layered controller with disturbance compensation to precisely track predefined motion trajectories. Extensive experiments have confirmed the effectiveness of this strategy. Based on the proposed strategy, our future research will focus on addressing the steering actuator delay and enhancing the adaptability of the trajectory tracking control scheme. Furthermore, we plan to further explore new control strategies and investigate how data-driven approaches can be integrated with traditional control techniques to address more complex environments and tasks.

Author Contributions

Y.L.: Writing—review and editing, validation, formal analysis, conceptualization. W.D.: Methodology and funding acquisition, data curation, formal analysis. T.Z.: Writing and editing, software, methodology. Y.W.: Experiment, validation, software. X.L.: Review and editing, funding acquisition, supervision, project administration. All authors have read and agreed to the published version of the manuscript.

Funding

This work was supported in part by the National Natural Science Foundation of China (Grant No. 52372428).

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

Data will be made available on request.

Conflicts of Interest

Author Wenwen Dong was employed by the company XCMG Construction Machinery 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. Takita, Y.; Ohkawa, S.; Date, H. High Stability Lateral Guided Method for Articulated Vehicle Based on Sensor Steering Mechanism. In Proceedings of the World Congress on Engineering and Computer Science, San Francisco, CA, USA, 24–26 October 2012; Volume 1, pp. 351–356. [Google Scholar]
  2. Dadhich, S.; Bodin, U.; Andersson, U. Key challenges in automation of earth-moving machines. Autom. Constr. 2016, 68, 212–222. [Google Scholar] [CrossRef]
  3. Ghabcheloo, R.; Hyvönen, M.; Uusisalo, J.; Karhu, O.; Järä, J.; Huhtala, K. Autonomous motion control of a wheel loader. In Proceedings of the Dynamic Systems and Control Conference, Hollywood, CA, USA, 12–14 October 2009; Volume 48937, pp. 427–434. [Google Scholar]
  4. Yossawee, W.; Tsubouchi, T.; Kurisu, M.; Sarata, S. A semi-optimal path generation scheme for a frame articulated steering-type vehicle. Adv. Robot. 2006, 20, 867–896. [Google Scholar] [CrossRef]
  5. Alshaer, B.; Darabseh, T.; Alhanouti, M. Path planning, modeling and simulation of an autonomous articulated heavy construction machine performing a loading cycle. Appl. Math. Model. 2013, 37, 5315–5325. [Google Scholar] [CrossRef]
  6. Choi, J.-w.; Huhtala, K. Constrained global path optimization for articulated steering vehicles. IEEE Trans. Veh. Technol. 2015, 65, 1868–1879. [Google Scholar] [CrossRef]
  7. Chen, X.; Yang, C.; Hu, H.; Gao, Y.; Zhu, Q.; Shao, G. A Hybrid DWA-MPC Framework for Coordinated Path Planning and Collision Avoidance in Articulated Steering Vehicles. Machines 2024, 12, 939. [Google Scholar] [CrossRef]
  8. Nayl, T.; Nikolakopoulos, G.; Gustafsson, T.; Kominiak, D.; Nyberg, R. Design and experimental evaluation of a novel sliding mode controller for an articulated vehicle. Robot. Auton. Syst. 2018, 103, 213–221. [Google Scholar] [CrossRef]
  9. Nayl, T.; Nikolakopoulos, G.; Gustafsson, T. Effect of kinematic parameters on MPC based on-line motion planning for an articulated vehicle. Robot. Auton. Syst. 2015, 70, 16–24. [Google Scholar] [CrossRef]
  10. Bai, G.; Liu, L.; Meng, Y.; Luo, W.; Gu, Q.; Ma, B. Path tracking of mining vehicles based on nonlinear model predictive control. Appl. Sci. 2019, 9, 1372. [Google Scholar] [CrossRef]
  11. Chen, X.; Yang, C.; Cheng, J.; Hu, H.; Shao, G.; Gao, Y.; Zhu, Q. A novel iterative learning-model predictive control algorithm for accurate path tracking of articulated steering vehicles. IEEE Robot. Autom. Lett. 2024, 9, 7373–7380. [Google Scholar] [CrossRef]
  12. Qiang, W.; Yu, W.; Xu, Q.; Xie, H. Study on Robust Path-Tracking Control for an Unmanned Articulated Road Roller Under Low-Adhesion Conditions. Electronics 2025, 14, 383. [Google Scholar] [CrossRef]
  13. Chen, X.; Cheng, J.; Hu, H.; Shao, G.; Gao, Y.; Zhu, Q. A Novel Fuzzy Logic Switched MPC for Efficient Path Tracking of Articulated Steering Vehicles. Robotics 2024, 13, 134. [Google Scholar] [CrossRef]
  14. Yu, H.; Zhao, C.; Li, S.; Wang, Z.; Zhang, Y. Pre-work for the birth of driver-less scraper (Lhd) in the underground mine: The path tracking control based on an lqr controller and algorithms comparison. Sensors 2021, 21, 7839. [Google Scholar] [CrossRef]
  15. Wang, Y.; Liu, X.; Ren, Z.; Yao, Z.; Tan, X. Synchronized path planning and tracking for front and rear axles in articulated wheel loaders. Autom. Constr. 2024, 165, 105538. [Google Scholar] [CrossRef]
  16. Nayl, T.; Nikolakopoulos, G.; Guastafsson, T. Kinematic modeling and simulation studies of a LHD vehicle under slip angles. In Computational Intelligence and Bioinformatics/755: Modelling, Identification, and Simulation; ACTA Press: Pittsburgh, PA, USA, 2011. [Google Scholar]
  17. Kawabe, T.; Takei, T.; Imanishi, E. Path planning to expedite the complete transfer of distributed gravel piles with an automated wheel loader. Adv. Robot. 2021, 35, 1418–1437. [Google Scholar] [CrossRef]
  18. Penin, B.; Giordano, P.R.; Chaumette, F. Vision-based reactive planning for aggressive target tracking while avoiding collisions and occlusions. IEEE Robot. Autom. Lett. 2018, 3, 3725–3732. [Google Scholar] [CrossRef]
  19. Ren, Z.; Rathinam, S.; Likhachev, M.; Choset, H. Multi-objective safe-interval path planning with dynamic obstacles. IEEE Robot. Autom. Lett. 2022, 7, 8154–8161. [Google Scholar] [CrossRef]
  20. Zhang, G.; Liu, J.; Luo, W.; Zhao, Y.; Tang, R.; Mei, K.; Wang, P. A Shortest Distance Priority UAV Path Planning Algorithm for Precision Agriculture. Sensors 2024, 24, 7514. [Google Scholar] [CrossRef] [PubMed]
  21. Dolgov, D.; Thrun, S.; Montemerlo, M.; Diebel, J. Path planning for autonomous vehicles in unknown semi-structured environments. Int. J. Robot. Res. 2010, 29, 485–501. [Google Scholar] [CrossRef]
  22. Gao, P.; Xu, P.; Cheng, H.; Zhou, X.; Zhu, D. Hybrid Path Planning for Unmanned Surface Vehicles in Inland Rivers Based on Collision Avoidance Regulations. Sensors 2023, 23, 8326. [Google Scholar] [CrossRef] [PubMed]
  23. Lei, Z.; Tan, B.Y.; Garg, N.P.; Li, L.; Sidarta, A.; Ang, W.T. An intention prediction based shared control system for point-to-point navigation of a robotic wheelchair. IEEE Robot. Autom. Lett. 2022, 7, 8893–8900. [Google Scholar] [CrossRef]
  24. Li, X.; Wang, G.; Yao, Z.; Qu, J. Dynamic model and validation of an articulated steering wheel loader on slopes and over obstacles. Veh. Syst. Dyn. 2013, 51, 1305–1323. [Google Scholar] [CrossRef]
  25. Liu, S.; Hou, Z.; Tian, T.; Deng, Z.; Li, Z. A novel dual successive projection-based model-free adaptive control method and application to an autonomous car. IEEE Trans. Neural Netw. Learn. Syst. 2019, 30, 3444–3457. [Google Scholar] [CrossRef]
  26. Sotelo, M.A. Lateral control strategy for autonomous steering of Ackerman-like vehicles. Robot. Auton. Syst. 2003, 45, 223–233. [Google Scholar] [CrossRef]
  27. Yuan, X.; Huang, G.; Shi, K. Improved adaptive path following control system for autonomous vehicle in different velocities. IEEE Trans. Intell. Transp. Syst. 2019, 21, 3247–3256. [Google Scholar] [CrossRef]
  28. Tian, T.; Lv, J.; Tang, J. Stability comparison of different controllers for hydraulic turbine fractional order interval parameter time-delay system. Syst. Sci. Control Eng. 2023, 11, 2221309. [Google Scholar] [CrossRef]
  29. Hu, Y.; Liu, J.; Wang, Z.; Zhang, J.; Liu, J. Research on Electric Oil–Pneumatic Active Suspension Based on Fractional-Order PID Position Control. Sensors 2024, 24, 1644. [Google Scholar] [CrossRef] [PubMed]
  30. Haggag, S.; Alstrom, D.; Cetinkunt, S.; Egelja, A. Modeling, control, and validation of an electro-hydraulic steer-by-wire system for articulated vehicle applications. IEEE/ASME Trans. Mechatron. 2005, 10, 688–692. [Google Scholar] [CrossRef]
Figure 1. Loader kinematics model.
Figure 1. Loader kinematics model.
Sensors 25 01135 g001
Figure 2. Transportation conditions of loaders.
Figure 2. Transportation conditions of loaders.
Sensors 25 01135 g002
Figure 3. Loader trajectory planning process.
Figure 3. Loader trajectory planning process.
Sensors 25 01135 g003
Figure 4. Path smoothing principle.
Figure 4. Path smoothing principle.
Sensors 25 01135 g004
Figure 5. Loader trajectory tracking control framework.
Figure 5. Loader trajectory tracking control framework.
Sensors 25 01135 g005
Figure 6. Loader preview error model.
Figure 6. Loader preview error model.
Sensors 25 01135 g006
Figure 7. Relationship between inputs and outputs of a fuzzy controller.
Figure 7. Relationship between inputs and outputs of a fuzzy controller.
Sensors 25 01135 g007
Figure 8. Experimental equipment and sites.
Figure 8. Experimental equipment and sites.
Sensors 25 01135 g008
Figure 9. Loader loading–unloading trajectory.
Figure 9. Loader loading–unloading trajectory.
Sensors 25 01135 g009
Figure 10. Step steering condition.
Figure 10. Step steering condition.
Sensors 25 01135 g010
Figure 11. Sinusoidal steering condition.
Figure 11. Sinusoidal steering condition.
Sensors 25 01135 g011
Figure 12. Simulation results for the dual-shift path.
Figure 12. Simulation results for the dual-shift path.
Sensors 25 01135 g012
Figure 13. Box plot of simulation results.
Figure 13. Box plot of simulation results.
Sensors 25 01135 g013
Figure 14. Trajectory tracking results (a) Trajectory comparison (b) Control input (c) Lateral error (d) Heading error.
Figure 14. Trajectory tracking results (a) Trajectory comparison (b) Control input (c) Lateral error (d) Heading error.
Sensors 25 01135 g014
Table 1. Fuzzy control optimization interval ranges.
Table 1. Fuzzy control optimization interval ranges.
Output ParametersRangeInput ParametersRange
k p [5.20, 6.00] e y [−0.6, 0.6]
k i [0.36, 0.42] e θ [−0.3, 0.3]
k d [0.60, 0.65]
Table 2. Fuzzy rules.
Table 2. Fuzzy rules.
k p / k i / k d e y
NBNSZPSPB
e θ NB k p 5 / k i 1 / k d 5 k p 4 / k i 1 / k d 4 k p 4 / k i 2 / k d 2 k p 3 / k i 2 / k d 3 k p 2 / k i 1 / k d 4
NS k p 4 / k i 1 / k d 3 k p 3 / k i 2 / k d 3 k p 3 / k i 3 / k d 2 k p 2 / k i 2 / k d 3 k p 1 / k i 1 / k d 4
Z k p 3 / k i 3 / k d 2 k p 2 / k i 4 / k d 1 k p 1 / k i 5 / k d 1 k p 2 / k i 4 / k d 1 k p 3 / k i 3 / k d 2
PS k p 1 / k i 1 / k d 3 k p 4 / k i 2 / k d 3 k p 3 / k i 3 / k d 2 k p 3 / k i 2 / k d 3 k p 4 / k i 1 / k d 3
PB k p 2 / k i 1 / k d 4 k p 3 / k i 1 / k d 4 k p 4 / k i 2 / k d 2 k p 4 / k i 1 / k d 4 k p 5 / k i 1 / k d 5
Table 3. Controller parameters.
Table 3. Controller parameters.
ModuleParameter Settings
Path planning w 1 = 1 , w 2 = 1 , w 3 = 10 , p f s = 1 , p f t = 1.3 , p b s = 2 , p b r = 2 , p r e v = 5
Path tracking λ = 0.86 , μ = 1.32 , α = 0.5 , ω 0 = 5.2 , δ = 0.05 , b = 14.5
Table 4. Steering performance under sinusoidal conditions.
Table 4. Steering performance under sinusoidal conditions.
MEMAERMSE
PD7.112.670.29
UnloadPD with NLESO6.242.370.22
PD10.25.640.43
LoadPD with NLESO6.262.220.22
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

Li, Y.; Dong, W.; Zheng, T.; Wang, Y.; Li, X. Scene-Adaptive Loader Trajectory Planning and Tracking Control. Sensors 2025, 25, 1135. https://doi.org/10.3390/s25041135

AMA Style

Li Y, Dong W, Zheng T, Wang Y, Li X. Scene-Adaptive Loader Trajectory Planning and Tracking Control. Sensors. 2025; 25(4):1135. https://doi.org/10.3390/s25041135

Chicago/Turabian Style

Li, Yingnan, Wenwen Dong, Tianhao Zheng, Yakun Wang, and Xuefei Li. 2025. "Scene-Adaptive Loader Trajectory Planning and Tracking Control" Sensors 25, no. 4: 1135. https://doi.org/10.3390/s25041135

APA Style

Li, Y., Dong, W., Zheng, T., Wang, Y., & Li, X. (2025). Scene-Adaptive Loader Trajectory Planning and Tracking Control. Sensors, 25(4), 1135. https://doi.org/10.3390/s25041135

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