Next Article in Journal
Camera-Based Sow (Sus scrofa domesticus Erxleben) Posture Analysis and Prediction of Artificial Insemination Timing
Previous Article in Journal
Assessment of Emerging Contaminants in Treated Wastewater Through Plant-Based Biotests
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Review

Research Progress on Path Planning and Tracking Control Methods for Orchard Mobile Robots in Complex Scenarios

School of Electrical and Information Engineering, Jiangsu University, Zhenjiang 212013, China
*
Author to whom correspondence should be addressed.
Agriculture 2025, 15(18), 1917; https://doi.org/10.3390/agriculture15181917
Submission received: 15 August 2025 / Revised: 5 September 2025 / Accepted: 9 September 2025 / Published: 10 September 2025
(This article belongs to the Section Agricultural Technology)

Abstract

Orchard mobile robots (OMR) represent a critical research focus in the field of modern intelligent agricultural equipment, offering the potential to significantly enhance operational efficiency through the integration of path planning and tracking control navigation methods. However, the inherent complexity of orchard environments presents substantial challenges for robotic systems. Researchers have extensively investigated the robustness of various path planning and tracking control techniques for OMR in complex scenes, aiming to improve the robots’ security, stability, efficiency, and adaptability. This paper provides a comprehensive review of the state-of-the-art path planning and tracking control strategies for OMR in such environments. First, it discusses the advances in both global and local path planning methods designed for OMR navigating through complex orchard scenes. Second, it examines tracking control approaches in the context of different motion models, with an emphasis on the application characteristics and current trends in various scene types. Finally, the paper highlights the technical challenges faced by OMR in autonomous tasks within these complex environments and emphasizes the need for further research into navigation technologies that integrate artificial intelligence with end-to-end control systems. This fusion is identified as a promising direction for achieving efficient autonomous operations in orchard environments.

1. Introduction

1.1. Research Background and Objectives

Orchards are of significance in their role as an essential component in agricultural production. They fulfill a pivotal function by ensuring human dietary needs are met, whilst concomitantly enhancing the economic efficiency of agricultural produce [1,2,3]. Orchards are multi-stage, labor-intensive workplaces. During the entire operational stages, including fruit tree planting [4], weeding [5], fertilization [6], spraying [7,8,9], pruning [10], pollination [11,12], harvesting [13,14], and fruit transportation [15], if manual operations are adopted, the resulting labor production and management costs are relatively high. Moreover, the effect of manual operations is directly influenced by work experience, making it difficult to ensure fruit yield and quality [16,17]. Therefore, in combination with the development needs of green and smart agriculture, to ensure cost reduction and efficiency improvement in orchard production management processes, it is urgent to research and apply intelligent OMR to promote the development process of smart agriculture [18,19,20,21].
Path planning and tracking control technology are key technologies for autonomous navigation, which can ensure that OMR meets the requirements of different assignment tasks and boosts the efficiency and quality of orchard production administration [22], as shown in Figure 1. Efficient path planning is the hub that pledges upper-layer perception and lower-layer tracking control. By studying the interaction between the robot itself and the environment, an operation path compliant with OMR’s safety and efficiency requirements is planned [23,24]; Robust tracking control technology is the implementation section of OMR. By real-time and stably controlling the robot’s driving mechanism, it realizes driving operations and obstacle avoidance quests adapted to different road environments [25,26,27,28].
Many institutions have developed different functional types of OMR, as shown in Figure 2. The GUSS spray robot developed by GUSS Automation Company of the United States is the world’s first autonomous driving orchard sprayer, which adopts a multi-sensor fusion navigation scheme such as GPS and LiDAR, can automatically adjust the spray volume and spray extent according to the growth of fruit trees, and is suitable for large-scale standardized planting orchards [29]. The French Vitirover orchard weeding robot adopts a solar-driven scheme, leverages a vision and GPS anchoring system to check whether its location is in the designated operation area, is equipped with flexible haptic sensors to recognize the main stem of grapevines, and has autonomous path planning and obstacle avoidance functions [30]. The R150 small agricultural robot developed by China’s XAG is based on RTK centimeter-level anchoring technology, combined with 4D imaging radar and a multi-camera vision system, enabling fixed-point, omnidirectional autonomous precise assignments and intelligent planning of driving directions [31]. The intelligent agricultural picking robot RS-AGR developed by TAObotics is equipped with various sensors such as lasers and depth stereo cameras and adopts the SLAM method to build an orchard navigation map, featuring unmanned path planning and fixed-point dock functions [32].
It can be seen that the autonomous navigation technology of OMR has become the development direction and research content of efficient and intelligent production management in orchards. Current OMR have initially achieved a certain degree of autonomous navigation operation function and can be applied to orchard environment operations in simple scenarios by fusing environmental information perceived by multiple sensors [33,34,35,36,37]. However, due to the fact that actual orchard planting scenarios are mostly unstructured environments, where typical features such as fruit tree growth and unpaved orchard roads exhibit high dynamics and uncertainty, coupled with complex factors such as narrow spacing between orchard fruit tree rows and the presence of dynamic and static obstacles (Figure 3) [38,39,40], OMR still have problems such as low planning operation accuracy, insufficient adaptability of control strategies, and low level of intelligent autonomy in these scenario applications. These issues have greatly affected the operational safety and efficiency of OMR in real orchard environments [41,42]. Therefore, researching path planning and tracking control technology of OMR in complex scenarios is an important way to solve the key technologies of orchard robots and the problems of integrated application of equipment.
Although extensive research has been conducted on OMR path planning and tracking control technologies in complex scenarios both domestically and internationally, and many OMR path planning and tracking control methods have been published, based on which OMR prototypes with autonomous navigation operation capabilities have been developed, there is a lack of detailed and systematic summaries of the latest research achievements in this field, which is not conducive to the intelligentization development of OMR and the promotion of autonomous navigation technologies. Therefore, to promote the development and application of OMR equipment and path planning and tracking control technologies, this paper conducts a comprehensive literature review on the research status of OMR path planning and tracking control technologies in complex scenarios.

1.2. The Composition of This Paper

This review is organized as follows: Section 2 introduces global and local path planning methods for OMR in complex orchard environments. Section 3 presents OMR tracking control technologies in complex scenarios, encompassing the development of motion models for different robot chassis and research on tracking control methods. Section 4 focuses on discussing the challenges and development trends in applying OMR autonomous navigation technologies. Section 5 summarizes the work presented in this paper. The framework of this paper is illustrated in Figure 4.

2. Path Planning Method for OMR in Complex Scenarios

Path planning refers to the process by which a robot determines the movement route of an orchard mobile robot using an onboard processor and path planning algorithms while integrating orchard environmental information and operational requirements [43]. Path planning can be categorized into global path planning and local path planning, and this chapter will provide a detailed overview of these two approaches.

2.1. Global Path Planning Methods

Global path planning involves generating an optimal or suboptimal path for the robot from the starting point to the target point based on a known orchard environment map (including fruit tree distribution, obstacle positions, terrain, etc.). Specifically, this path must optimize safety, distance, smoothness, and energy consumption to ensure the robot performs its tasks efficiently and safely [44]. Research on global path planning methods constitutes the most fundamental and essential component of OMR autonomous navigation operations. From the perspective of path planning methodologies, this section categorizes commonly used OMR global path planning algorithms into graph search-based algorithms (Dijkstra, A*, Hybrid A*, etc.), point sampling-based algorithms (RRT, PRM, etc.), and intelligent optimization algorithms (genetic algorithm, particle swarm optimization, ant colony algorithm, etc.), while analyzing their performance in complex orchard environments.

2.1.1. Path Planning Method Based on Graph Search

A graph is a mathematical structure composed of nodes and edges, whose structural properties allow it to clearly represent real-world environmental map information. When these structural properties are mapped to path planning problems, each node in the graph represents a state or position, while edges represent feasible movements between these states. In other words, the graph depicts all possible paths from the start point to the target point, and a search algorithm is defined as a method for finding target solutions through the nodes and edges of the graph.
Dijkstra is a typical graph search algorithm widely used in path planning for OMR [45,46]. The algorithm performs node expansion using a greedy selection approach, where the node expansion process consistently adheres to the principle of selecting the lowest-cost unvisited node for expansion. Therefore, the shortest path from the starting point to the destination point can always be found by the Dijkstra algorithm. Xu et al. [47] implemented global path planning for OMR using an improved Dijkstra method based on detected feasible paths in orchards. Liu et al. [48] employed the Dijkstra method to enable autonomous navigation of pasture-pushing robots, addressing the global path planning requirements of complex outdoor environments. Jin et al. [49] utilized a global path planning module based on the Dijkstra algorithm to determine the shortest path for OMR from the current position to the target position on a semantic topological graph.
However, because the Dijkstra algorithm only focuses on finding the shortest current path, it performs poorly in terms of search efficiency when dealing with a large number of nodes. To maintain the optimality of the paths found by the Dijkstra algorithm while boosting its search efficiency, the A* algorithm has been developed and used for global path planning in orchard mobile robots [50]. The A* algorithm first takes a high-precision 2D grid map of the orchard as input. In this map, each grid cell is labeled as either a passable area, an obstacle, or an unknown area. The grid resolution is typically set to be slightly smaller than the width of the robot to guarantee safe movement. Second, the algorithm builds on the Dijkstra algorithm by adding a heuristic evaluation function to guide the entire path search process. Typically, the heuristic cost value of the algorithm is determined by the estimated distance costs from the current node to both the start node and the target node. This allows the algorithm to balance path length and directional guidance toward the expected endpoint during the search process, thereby enhancing its search efficiency [51,52]. The A* algorithm is mathematically expressed as
f ( n ) = g ( n ) + h ( n ) ,
where f ( n ) is the actual cost of the optimal path from the start point to the end point when this path goes through node n; g ( n ) stands for the actual cost of the optimal path from the starting node to node n; h ( n ) represents the actual cost of the optimal path from node n to the target node.
In complex orchard environments, the heuristic function has been shown to effectively guide the search direction and significantly improve planning efficiency. Ultimately, a globally optimal or suboptimal path is output by the algorithm, either from the starting point to the target point within a row or from one working area to another. This path ensures the robot can safely avoid known trunk obstacles and prioritizes the selection of inter-row main roads with higher driving efficiency, providing a reliable reference trajectory for subsequent local tracking control. Because the A* algorithm searches for paths directly and efficiently, it is widely used in global path planning for OMR [53]. Wang et al. [54] proposed an orchard path fitting and navigation method that combines an improved A* algorithm with support vector regression. By introducing a redundant point removal strategy to optimize paths, high-precision path planning results are achieved. To smoothly optimize the full coverage operation path, an improved A* path planning algorithm based on multi-constraint Bessel curves was proposed by Kong et al. [55]. Multiple constraints, including minimum turning radius and continuous curvature, are comprehensively considered in this algorithm, and a global path meeting the driving requirements of orchard fertilization robots is generated, as shown in Figure 5. To enhance the search performance of the A* algorithm, Chatzisavvas et al. [56] introduced a dynamic weighting mechanism. This mechanism enables the algorithm to adjust and prioritize relevant components of route planning according to different agricultural environments and needs, thereby achieving the navigation of mobile robots with optimized obstacle avoidance for intelligent agriculture.
Paths generated by the standard A* series of algorithms usually consist of multiple polyline segments. However, these paths cannot be directly executed by conventional Ackerman or differential-drive OMR due to their composition of multiple polyline segments. An additional optimization step is necessary to ensure that the resulting path complies with the robot’s actual kinematic constraints. The hybrid A* algorithm introduces a heading angle state variable into the A* algorithm’s search state space, thereby transforming the original discrete state space into a continuous one. This allows the node expansion process to account for all vehicle kinematic constraints. On this foundation, the Reeds-Shepp curve is used to extend paths and ensure search completeness [57,58]. Meng et al. [59] proposed an improved hybrid A* path planning method based on multi-stage dynamic optimization. They significantly enhanced search efficiency, both temporally and spatially, by integrating Voronoi field potentials into the path search phase through safety-enhanced design and employing a multi-stage dynamic optimization strategy.

2.1.2. Path Planning Method Based on Point Sampling

Unlike classical graph-search-based path planning methods, sampling-based approaches do not require explicit discretization of the entire search space; instead, they explore feasible path spaces by randomly selecting points within the map environment. These algorithms can operate effectively in dynamic and partially unknown environments using only partial environmental information or local data acquired via sensors. However, because path points are generated through random sampling, the resulting paths may be relatively coarse and lack guaranteed optimality. Additionally, generating an adequate number of sampling points and performing path connections can demand substantial computational resources.
The Probabilistic Roadmap (PRM) algorithm enables rapid path planning in high-dimensional spaces and complex environments [60]. The core concept involves constructing a probabilistic graph through random sampling. First, nodes are randomly sampled in the configuration space. Then, a probabilistic road network graph is built by connecting the nodes with straight lines and performing path feasibility checks. The Dijkstra or A* algorithm is used to find a path from the start to the endpoint [61,62]. To improve PRM’s performance in environments with complex obstacles, Tian et al. [63] introduced artificial potential field modeling. This approach considers obstacles, environmental hazards, and road conditions comprehensively, using probabilistic graph algorithms to optimize multidimensional passage costs between nodes for path planning. Mahmud et al. [64] designed a PRM-based algorithm to plan paths for pesticide spraying robots in greenhouses. This algorithm determines optimal paths with minimal navigation costs, as illustrated in Figure 6.
Due to the low efficiency of the computational framework of the PRM algorithm, LaValle et al. [65] proposed the Rapidly exploring Random Tree (RRT) algorithm, as shown in Figure 7. RRT is ideal for navigating robots in unknown or partially known environments, especially in unstructured settings like orchards. This algorithm enhances a robot’s adaptability in dynamic environments by employing random sampling and tree-based expansion to handle complex obstacle distributions. The main idea of this algorithm is to create a random search tree starting from a given initial point. Path points are randomly sampled within the planning space, and the sampled point closest to the current end node is identified. After the sampled point passes feasibility screening, the random tree is extended towards this sampled point by a specified step size. Once the extended node is sufficiently close to the target endpoint, the random tree is backtracked to form a complete connected path. To enhance the navigation efficiency of apple tree pruning robots, Li et al. [66] proposed an improved RRT algorithm that enhances directional guidance during the expansion process by introducing a goal bias strategy. Then, a greedy strategy is employed to accelerate the algorithm’s search speed. Finally, the path is pruned by removing unnecessary nodes, further shortening its length.
To improve planning efficiency and adaptability, Li and Ma [68] proposed an improved RRT-Connect algorithm, as shown in Figure 8. To address the randomness drawback in the expansion phase of the RRT-Connect algorithm, a goal-biased strategy was introduced. This method enables the apple tree pruning robot to rapidly generate collision-free paths. Zhang et al. [69] proposed a heuristic dynamic RRT-Connect motion planning algorithm for fast picking path planning of fruit-picking robots. This approach effectively reduces path planning time while ensuring planning success rates. Chen et al. [70] proposed an improved RRT-Connect algorithm to enable obstacle avoidance for fruit tree pruning robots in unstructured and complex natural environments. This approach effectively reduces path planning time and path length while achieving obstacle avoidance planning.
Karaman et al. [71] proposed the RRT* algorithm as a solution to the poor path quality generated by the RRT algorithm. The RRT* algorithm is better suited to orchard scenarios that require global optimization and complex obstacle avoidance. Unlike the basic RRT, the RRT* algorithm incorporates a reconnection optimization step. After adding a new node, the RRT* algorithm searches among its neighboring nodes for a lower-cost parent node. This process optimizes the path cost of the entire tree continuously, asymptotically approaching the optimal solution. For OMB, this means that when the initial global path is temporarily blocked by obstacles, RRT* can rapidly generate a new path that bypasses the obstacles smoothly and optimize the path’s length and smoothness. This ensures the robot’s autonomy and flexibility in complex orchard environments. Figure 9 illustrates the algorithmic principle. Zeeshan et al. [72] developed an orange-picking robot based on an improved RRT* algorithm for real-time operation in unstructured orchard environments. Wang et al. [73] proposed the Pre-Harvesting Guide Informed-RRT* (PGI-RRT*) motion planning algorithm for citrus harvesting. Building upon the Progressive Optimal Informed RRT*, this algorithm selects a third point between the start and goal as the pre-harvest guide point. The PGI-RRT* enhances the speed and flexibility with which unknown spaces are explored to find optimal paths. Hu et al. [67] proposed a novel HPS-RRT* algorithm adapted to unstructured orchard environments through a hybrid exploration and optimization mechanism. By incorporating pruning strategies, the algorithm improves tree exploration efficiency and reduces unnecessary expansions.
The bidirectional RRT* (Bi-RRT*) algorithm effectively addresses the inefficiency of path searching caused by random point sampling. It does so by constructing independent random search trees at both the start and end points. Ye et al. [74] proposed a continuous bidirectional Quick-RRT* algorithm based on Bi-RRT and Quick-RRT*, which introduces an extended cost function that evaluates path smoothness and length. Their CreateConnectNode optimization method effectively resolves path smoothness issues at tree junctions, enabling efficient path planning for mobile robots in complex orchard environments. Wu et al. [75] proposed an improved kinematics-constrained bidirectional rapidly exploring random tree (IKB-RRT) algorithm to address the need for navigation paths that comply with mobile robot kinematic constraints in obstacle-laden environments. They introduced a motion control parameter sampling method tailored to robot configurations that guides the random extended tree to generate path nodes and trajectories satisfying mobile robot constraints. Liu et al. [76] proposed an improved bidirectional RRT* motion planning algorithm for orchard spraying robots. This method combines dynamic terminal node guidance and potential field guidance for biased sampling. Then, it removes path point redundancy and processes adjacent polyline segment corner constraints on the initially generated path. This approach enhances the working efficiency and autonomy of orchard spraying robots.

2.1.3. Path Planning Method Based on Intelligent Algorithms

The core of intelligent algorithms involves referencing the phenomena, laws, and behavioral characteristics of organisms or ecosystems in nature, simulating these processes, and applying them to algorithm design. By imitating biological mechanisms such as learning, adaptation, and evolution, and simulating the optimization-seeking processes of ecological phenomena, they find approximate optimal solutions, thereby possessing strong global search capabilities.
The Genetic Algorithm (GA) was proposed as a solution to highly complex problems that traditional optimization methods struggle to handle. In OMR path planning, each individual represents an independent and feasible path solution. The raw solutions of the initial population undergo optimization through selection, crossover, mutation, and replacement steps, which converge iteratively toward a globally optimal solution [77]. Zhang et al. [78] proposed an adaptive picking sequence planning method for apple-harvesting robots by integrating self-organizing maps (SOMs) with GA. This approach dynamically adjusts planning strategies based on fruit quantity thresholds, achieving highly efficient path planning in high-density scenarios. Liao and Deng [79] focused on GA optimization for the picking task planning of OMR. They constructed a GA optimization model that considers path length, picking efficiency, energy consumption, and operational costs comprehensively. Using roulette wheel selection, partial mapping crossover, and reverse mutation, they intelligently planned and optimized picking tasks. Hizata and Noguchi [80] proposed an optimal work control algorithm for autonomous orchard spraying robots based on a multi-layer genetic algorithm (LGA). Unlike traditional spatial planning, this method focuses on temporal planning for OMR and establishes work control strategies for these robots under various field conditions.
The Ant Colony Optimization (ACO) algorithm is applied to robotic path planning to achieve rapid solutions for combinatorial optimization problems [81]. The algorithm uses a pheromone-based heuristic function to update paths, which enables global exploration of feasible routes. Paths of higher quality accumulate higher levels of pheromones, which makes subsequent ants more likely to deposit pheromones along these routes. This positive feedback loop continues until it gradually converges to the optimal path [82]. Tian et al. [83] improved the ACO heuristic function by incorporating angular and distance costs to optimize multiple nodes. They also introduced a sorting optimization mechanism to accelerate algorithm iteration, enabling multi-objective planning for orchard spraying UAVs. To address visual misjudgment and obstacle avoidance challenges caused by foliage shading in complex orchard terrains, Niu et al. [84] considered kinematic models and robotic motion path constraints. They incorporated robot access costs into the objective function for node search using an improved ACO-DWA algorithm and performed online path planning based on environmental grid maps. These improvements significantly enhanced the navigational effectiveness of mobile orchard robots within tree-row and inter-row areas.
The particle swarm optimization (PSO) algorithm is based on the parallel search mechanism of swarm intelligence. Through information sharing and collaboration among individual particles, it can rapidly converge to a global or near-global optimal path. PSO is particularly suitable for multi-constraint optimization problems in unstructured orchard environments [85,86]. Xu et al. [87] proposed a real-time path planning algorithm for agricultural machinery that uses PSO-optimized parametric kinematic models to define paths that satisfy the kinematic model through parametric equations. Considering constraints from obstacles, acceleration, and turning angles, two objective functions were formulated. The PSO algorithm searched for paths near the initial route that satisfied the obstacle avoidance conditions while achieving favorable objective function values. To address frequent collisions between orchard robots and surrounding branches during harvesting, which are caused by the robots’ inability to adapt to fruit growth environments, Gao et al. [88] proposed an improved PSO-based path planning algorithm for apple-picking robots. This algorithm dynamically adjusts velocity weights based on trends in particle fitness values and the position of the particle swarm’s center of mass.

2.2. Local Path Planning Methods

Global path planning algorithms can generate a global reference path that comprehensively considers path distance, curvature, safety, and robot kinematic constraints when provided with prior map inputs. However, orchard environments exhibit complex dynamic characteristics, such as uncertain obstacles and dynamic environmental changes, which make it difficult for global planning algorithms to adjust OMR paths in real time. Additionally, global path planning algorithms have limited capacity to account for robot constraints, and the dynamic characteristics of robots during movement along with their physical performance constraints cannot be adequately reflected in global paths [89]. Therefore, research on local trajectory planning methods for OMR in complex scenarios is indispensable. The core objective of local trajectory planning is to rapidly respond to environmental changes and generate safe, smooth paths. Based on their underlying principles and varying applications in complex orchard scenarios, common approaches include velocity space-based trajectory planning algorithms, potential field-based trajectory planning algorithms, and optimal control-based trajectory optimization algorithms.

2.2.1. Trajectory Planning Method Based on Velocity Space

The Dynamic Window Approach (DWA) is a simple and efficient algorithm for local trajectory planning that accounts for robotic kinematic constraints [90]. Based on the robot’s current velocity state and position information, the DWA algorithm calculates a dynamic window to predict positions the robot can reach within a given time interval. It then evaluates the optimal local trajectory using a user-defined system cost function [91,92].
To address the challenges of uneven tree distribution and GNSS signal attenuation in complex orchard environments, Cong-Thanh et al. [93] designed a novel hybrid controller based on DWA. This enables the robot to effectively follow tree rows even when positioning signals are interrupted or trees are undetectable in certain areas. They validated the feasibility of the proposed method in real orchard scenarios. Li et al. [94] proposed a path planning and navigation method for robots in densely planted red jujube orchards. This method implements global and real-time local path planning based on the improved A* and DWA algorithms, while a map of dense jujube orchards is constructed using lidar. Experimental results demonstrate that the accuracy of the navigation and positioning system meets the requirements for plant protection operations in densely planted orchards. To quickly search for a globally optimal collision-free path and avoid unknown obstacles in a timely manner, He et al. [95] proposed a path planning method that integrates the A* and DWA approaches. By optimally designing the prediction function, weight coefficients, search neighborhood, and path smoothing process of the A* algorithm, critical point information from the global path is incorporated into the DWA computational framework, enabling rapid path planning for robots. Wang et al. [96] proposed a fusion path planning algorithm that combines the improved A* algorithm and the fuzzy DWA. An A* algorithm incorporating the environmental obstacle rate is designed to generate global paths in orchards. The search strategy can be adjusted according to the number of obstacles in the environment. Then, a rule for optimizing the search neighborhood is proposed, which adjusts the search neighborhood to a five-neighborhood structure, thereby enhancing node search efficiency. Furthermore, a local path planning strategy integrated with fuzzy control is developed, enabling the robot to maintain a safe distance from obstacles and improving the stability of obstacle avoidance, as shown in Figure 10.

2.2.2. Trajectory Planning Method Using Artificial Potential Field

The Artificial Potential Field (APF) method solves the efficiency and real-time issues that traditional local trajectory planning algorithms encounter in multi-obstacle and complex dynamic environments [97]. Figure 11 illustrates its algorithmic principle. Based on concepts in mechanics, the algorithm constructs a gravitational field at the target point and repulsive fields around environmental obstacles, generating a resultant guiding force to direct robot movement [98].
The APF method offers strong real-time performance and ease of implementation; however, it tends to get trapped in local minima and may fail to avoid obstacles when operating in close proximity to them [99,100]. To meet the operational safety requirements of mowing robots in complex orchard terrains, Zhang et al. [97] proposed an improved APF-based local path planning algorithm, which introduces an elliptical repulsive potential field to define the boundary potential field range. The potential field function adopts a modified variable polynomial and incorporates a distance factor, effectively resolving the issues of target inaccessibility and local minima. Additionally, by modifying the repulsive potential field range to an elliptical shape and adding a fruit tree boundary potential field, the complexity of the environmental potential field is significantly reduced. This allows the robot to avoid obstacles proactively without crossing fruit tree boundaries, thereby enhancing safety during autonomous operation. Zhuang et al. [101] proposed an obstacle avoidance path planning method for apple-picking robotic arms that integrates the APF and A* algorithm to address the path planning requirements of apple fruit picking in complex environments. The APF operates on the mechanism of treating the robotic arm as a moving particle, abstracting its surrounding environment into a region composed of potential fields, and calculating the force acting on the particle in each direction based on the position and velocity of the moving particle. The A* algorithm achieves autonomous navigation by finding the shortest path to avoid obstacles. The artificial potential field method proposed by Yuan et al. [102] simulates the force exerted on the UGV using equations derived from Coulomb’s law, which characterizes a strong repulsive force relative to the distance between the robot and obstacles, thereby enabling obstacle avoidance navigation for agricultural robots. Wu et al. [103] considered vehicle stability during obstacle avoidance path planning and proposed a two-layer obstacle avoidance path planning algorithm incorporating path pre-planning and re-planning. In the path pre-planning layer, they developed an improved APF algorithm constrained by road boundary functions. In the path re-planning layer, with rollover stability indices as constraints, they proposed a pre-planning result optimization method based on particle swarm optimization. This approach significantly enhances the robot’s stability during obstacle avoidance maneuvers.

2.2.3. Trajectory Optimization Method Based on Optimal Control

The trajectory optimization algorithm based on optimal control enables OMR to achieve optimal performance in terms of time, energy consumption, or stability under specified constraints. This method constructs a system cost function by establishing a control system model. It then incorporates both inherent system constraints and user-defined constraints, selecting an appropriate control input sequence to minimize the cost function while satisfying all system constraints.
The Timed Elastic Band (TEB) algorithm proposed by Rösmann et al. [104] treats the trajectory as an elastic band incorporating both temporal and system state information. Trajectory optimization is achieved by constructing a cost function to adjust the control points along this elastic band, and the algorithm has been widely applied in local path planning for orchard mowing robots [105,106]. Han et al. [107] addressed the issues of excessive local optimization and collision handling in the TEB algorithm during the path planning phase of agricultural robots in chili fields. They combined the A* algorithm with the TEB algorithm and optimized the weight parameters based on environmental characteristics, thereby reducing errors in determining the optimal path and enabling autonomous obstacle avoidance navigation in narrow, unattended areas. Li et al. [108] employed the TEB local path planning algorithm to iteratively search for path points that minimize a predefined cost function, ensuring the OMR is navigated along the operation path, as shown in Figure 12.
The fundamental concept of the Differential Dynamic Programming (DDP) algorithm involves decomposing a global optimal control problem into local optimization problems. It linearizes the nonlinear system dynamics within the trajectory optimization problem, transforming the original optimization problem into a quadratic optimization problem for iterative optimization and solution. Due to the extremely high computational cost associated with second-order terms in the DDP algorithm, Li and Todorov [109] developed the iterative Linear Quadratic Regulator (iLQR) algorithm. By performing first-order linearization on the local system dynamics model during each iteration, the iLQR algorithm avoids calculating second derivatives of the nonlinear model, thereby significantly enhancing computational efficiency and reducing implementation complexity. Pinto et al. [110] employed the iLQR algorithm, an optimization-based nonlinear system control method, to compute control commands for smooth and accurate trajectory tracking, ensuring the robot is robustly guided along the desired trajectory. They enhanced the navigation capability of agricultural robots by integrating LiDAR perception with ResNet-based deep learning approaches and iLQR control.
Howell et al. [111] proposed the Augmented Lagrangian Trajectory Optimizer (ALTRO) algorithm based on the iLQR algorithm. By introducing Lagrange multipliers and penalty parameters, they constructed the Lagrangian equation to achieve real-time optimization and constraint handling, ensuring the algorithm can effectively respond to system hard constraints and thus generate an optimal trajectory with minimal cost that satisfies all constraint conditions. Liu et al. [112] proposed a real-time local trajectory optimization algorithm for orchard robots based on improved ALTRO to address the real-time local trajectory optimization requirements of OMR, as shown in Figure 13. They adopted an accelerated augmented Lagrangian algorithm, improved the multiplier iteration strategy within the ALTRO algorithm, and achieved accelerated convergence; incorporated feasible region projection for multipliers to prevent numerical ill-conditioning caused by excessive iterations, thereby enhancing algorithm stability; and introduced an adaptive scaling factor based on trajectory time steps to adjust terminal weights in the original algorithm, ensuring superior local obstacle response capability.

2.3. Summary

Table 1 compares the advantages and disadvantages of OMR path planning methods in complex scenarios.
The performance of the aforementioned methods in OMR path planning demonstrates that while global path planning algorithms lack sufficient adaptability to dynamic environments, they can still serve as crucial references for local path planning to achieve rapid path planning objectives. Dijkstra’s and A* algorithms, based on graph search approaches, exhibit global optimality and completeness. Furthermore, the A* algorithm can account for multiple constraints in known complex environments, and its efficiency can be enhanced by integrating optimization algorithms. However, terrain variations and dynamic obstacles necessitate frequent replanning, limiting their current application primarily to global reference path planning in orchards with known maps and predominantly static scenarios. The PRM algorithm, capable of handling high-dimensional complex spaces during global path planning, can enhance efficiency and optimality in intricate orchard environments when integrated with graph search or APF algorithms. The RRT algorithm, with its ability to explore unknown areas through random sampling, is well-suited for uneven terrain and occluded environments. Consequently, it is widely applied in robot planning for complex orchard environments. Most studies have further improved the RRT algorithm to address issues such as suboptimal paths and slow convergence. By integrating multi-objective optimization strategies into the global planning process, intelligent path planning algorithms ensure both efficiency and safety for orchard mobile robots navigating complex environments. This approach represents a current research hotspot in global path planning, though it still requires integration with local path planning algorithms to achieve adaptability to dynamic environments.
Local path planning algorithms are primarily used for real-time obstacle avoidance and trajectory optimization, making them more suitable for dynamic scenarios in complex orchard environments. The DWA algorithm is highly effective in orchard settings with dynamic obstacles and uneven terrain. However, relying solely on DWA for end-to-end path planning cannot guarantee global optimality. Consequently, current research focuses on integrating DWA with global path planning algorithms. References [94,95,96] demonstrate the reliability of this approach. The APF algorithm enhances path planning efficiency in complex scenarios through potential field guidance. However, it is prone to local minima and exhibits unstable performance in dynamic environments. Consequently, integrating it with globally optimal path planning algorithms represents a primary research direction. The TEB algorithm demonstrates outstanding advantages in handling dynamic obstacles and optimizing paths and time. Further incorporating terrain information through cost functions enables adaptation to diverse complex terrain conditions, making it suitable for path planning in complex orchard environments. Researchers have achieved efficient planning for OMR under complex multi-constraint scenarios by integrating the TEB algorithm with graph search algorithms. Optimal control-based trajectory optimization algorithms demonstrate strong performance in nonlinear systems, enabling paths that better align with robotic motion characteristics. However, research in this area remains limited due to challenges in accurately constructing terrain and robotic dynamics models.
Therefore, research should comprehensively consider path information, kinematic constraints, static and dynamic obstacles, path curvature constraints, and time-energy tradeoffs as optimal objectives. This will enable the development of a hierarchical path planning architecture balancing global optimality and real-time obstacle avoidance. This approach ensures search efficiency and enhances path quality, enabling safe and efficient autonomous planning for OMR. Specifically, when positioning data are reliable, the robot generates the shortest reference path through the global layer. When dynamic obstacles or unreliable positioning information are encountered, the global layer provides only directional guidance. Real-time obstacle avoidance and planning then rely on locally optimized path planning algorithms with strong dynamic performance to ensure system robustness.

3. Tracking Control Method for OMR in Complex Scenarios

Path tracking control serves as the core technology enabling OMR to achieve autonomous navigation. Its objective is to ensure the mobile robot’s actual position and attitude closely adhere to the pre-planned target path while satisfying dynamic constraints and safety requirements during motion [113]. Although environmental factors and the robot’s inherent constraints are considered during OMR path planning, complex dynamic scenarios can still disrupt the OMR’s real-time attitude, potentially causing inaccurate path tracking. Therefore, achieving high-precision path tracking in complex orchard environments forms the foundation for ensuring robots complete operational tasks with high quality and efficiency. Currently, the commonly used OMR path tracking control methods mainly include geometry model-based control methods, kinematics model-based control methods, and model-free intelligent control methods.

3.1. Control Methods Based on Geometry Model

3.1.1. Pure Pursuit Control

The pure pursuit control algorithm is a computational method based on geometric principles. Its core idea involves converting the corresponding lateral error into a lateral control quantity by regulating the geometric relationship between the orchard robot’s current position and the look-ahead point on the target path. A proportional controller is then designed to adjust the wheel steering angle, enabling tracking of the desired path [114,115,116]. The principle of the pure pursuit control algorithm is illustrated in Figure 14.
To reach the target point G with a look-ahead distance of l d along the reference trajectory, the rear wheel of the vehicle needs to satisfy
l d s i n ( 2 α ) = R s i n π 2 α .
Simplification leads to
R = l d 2 sin α .
Further, the control law for the front wheel steering angle δ f that meets the turning radius R is derived as
δ f = arctan 2 l sin α l d .
Among them, α is the angle between the vehicle body and the preview point, and l is the wheelbase of the vehicle.
Based on the above derivation, it is evident that the pure pursuit control algorithm relies solely on geometric relationships and does not require complex dynamic modeling. This makes it suitable for OMR with low-computational-power hardware platforms [117,118]. However, its performance is heavily dependent on the tuning of the look-ahead distance. The look-ahead distance determines the selection of target points. An excessively short distance may cause the robot to oscillate at high frequencies, while an excessively long distance may lead to tracking lag. Furthermore, since the look-ahead distance requires extensive experimentation to determine, the robot necessitates recalibration when operating in orchards with different layouts, resulting in high computational and operational costs [119]. Consequently, recent studies have proposed dynamic strategies for determining the look-ahead distance. Huang et al. [120] developed a flatland turning control method for agricultural machinery that dynamically adjusts the look-ahead distance using a BP neural network, thereby improving the traditional pure pursuit model. Wang et al. [121] proposed a pure pursuit controller based on adaptive look-ahead distance. The process enables the system to determine the look-ahead distance based on the positions of the optimal target points, thereby enhancing the rapidity and stability of the navigation controller. Wen et al. [122] dynamically adjusted the velocity and look-ahead distance of a pure pursuit model by constructing a function related to these parameters and applying an improved sparrow search algorithm. This approach achieved faster convergence speeds for robots in complex agricultural environments. The improved algorithm demonstrated significant enhancements in path tracking accuracy, pose correction speed, and path tracking efficiency.
Numerous factors influence the look-ahead distance, such as vehicle speed, control frequency, and vehicle stability. The inability to precisely describe the logical relationship between the look-ahead distance and these multiple factors makes it difficult to determine its optimal value. Simultaneously, the core limitation of pure pursuit control lies in its open-loop feedforward characteristics based on geometric models, rendering it highly sensitive to dynamic disturbances [123]. In orchard environments, localized slippage caused by irrigation or rainwater may occur on the ground. This leads to deviations between the vehicle’s actual heading and the model prediction, while pure pursuit algorithms lack feedback mechanisms to correct such internal state errors. When encountering uneven terrain, the vehicle experiences continuous jolts, causing abrupt changes in the pre-aiming point. This triggers high-frequency jitter in steering commands, severely impacting tracking smoothness and actuator lifespan [124]. Furthermore, the pure pursuit control algorithm assumes the vehicle can instantly achieve the calculated steering angle, disregarding the dynamic delay inherent in steering systems. This oversight can cause significant overshoot or even instability when precisely tracking high-curvature turns at the end of a path.
Therefore, the limitations of pure pursuit control algorithms in complex orchard environments are evident. Future research could focus on two approaches: first, integrating machine learning algorithms to learn from extensive orchard driving data and dynamically adjust the control parameters of pure pursuit. Second, developing cascade controllers that use pure pursuit as the outer loop to generate a desired front-wheel steering angle or curvature. The inner loop would employ model-based dynamic controllers to compensate for errors caused by terrain undulations and wheel slippage.

3.1.2. Stanley Control

The Stanley control algorithm calculates the steering wheel control input based on the path tracking deviation measured at the center of the robot’s front wheels [125,126]. It employs a nonlinear feedback function where lateral tracking error is defined as the distance from the front axle center to the nearest path point, enabling exponential convergence of lateral tracking error to zero. Steering wheel angle control inputs can be intuitively derived from the geometric relationship between vehicle pose and the reference path. The principle of the Stanley control algorithm is illustrated in Figure 15.
It can be seen from the geometric relationship in the figure that the included angle δ e between the direction of the front wheel velocity and the tangent direction of the target point satisfies
δ e = arctan y e d = arctan k y e v .
Among them, the look-ahead distance d is positively correlated with the vehicle speed v, where k is a positive coefficient. The relationship among them is
d = v k .
The control law for the front wheel steering angle δ f is obtained as
δ f = θ e + arcsin k y e v ,
where θ e is the heading deviation between the vehicle body and the target point.
In contrast, the Stanley algorithm introduces velocity v as the denominator, enabling more responsive steering at low speeds and smoother steering at high speeds. The heading angle error term θ e allows the robot to preemptively adjust its direction during turns, reducing tracking lag. It demonstrates superior performance in lateral error correction compared to pure pursuit [127,128]. Stanley control does not require determining the look-ahead distance, but its control performance is significantly influenced by the adjustable parameter k [116]. If the k value remains fixed, the robot cannot quickly adapt to varying ground conditions in the orchard. Therefore, it is necessary to develop a dynamic k value adjustment strategy based on orchard environments (such as row spacing variations and slopes), which increases the k value in narrow orchard areas to enhance tracking precision and decreases the k value in open orchard areas to minimize steering jitter. Meanwhile, when the path curvature is large, the Stanley method may cause the robot to deviate toward the inner side of the reference path, a phenomenon known as “cutting the corner,” which requires optimization through the integration of feedforward control or dynamic adjustment of k.
Wang et al. [129] incorporated the tractor yaw rate into the Stanley algorithm and then optimized the parameters of the extended Stanley algorithm using a multiple-population genetic algorithm, significantly enhancing the tracking capability of autonomous navigation tractors along target paths. Cui et al. [130] utilized lateral deviation and heading deviation as input variables to construct membership functions, design fuzzy reasoning and defuzzification processes, and determine the gain coefficients of the control model in real time. This approach improved the adaptability of the Stanley model to paths with varying curvatures, enabling its application in straight path switching and short guidance trajectories while achieving accurate tracking control of agricultural robots. Sun et al. [131] proposed an improved fuzzy Stanley model based on PSO. This model adaptively modifies control gains according to tracking error, speed, and steering actuator saturation, thereby enhancing the adaptability of the path tracking algorithm.
The Stanley control method demonstrates excellent performance in structured orchard environments due to its simplicity and adaptive speed adjustment. However, Stanley’s control effectiveness is highly dependent on accurate vehicle heading information. In orchards, sensor noise—particularly multipath effects from low-cost GNSS and IMU jitter noise—directly contaminates heading angle estimates. Its differential component can even amplify noise, causing high-frequency chattering in steering control. Furthermore, the nonlinear feedback law becomes overly aggressive at high speeds or low traction conditions, potentially inducing instability. When encountering large-scale slippage, the absence of an integral term prevents effective compensation for steady-state errors caused by sustained slippage. Consequently, in dynamically changing, complex unstructured orchard scenarios, further optimization through integration with other methods remains necessary [131].

3.2. Control Methods Based on Kinematic Model

3.2.1. Construction of OMR Kinematic Model

The kinematic model of OMR is mathematically formulated to describe the relationship between the robot’s pose and actuator inputs. Establishing such a kinematic model serves as the foundation for precise path-tracking control of the robot. Particularly in complex orchard environments, the kinematic model directly influences the robot’s positioning accuracy, motion stability, and operational efficiency. To meet the requirements for passability and stability in orchard settings, the most commonly employed OMR chassis structures are the Ackermann steering type and the tracked differential type.
Ackermann-type OMR utilize a steering mechanism similar to that of automobiles, where the steering angles of the front wheels are optimized based on Ackermann geometry to minimize tire sideslip. This design is well-suited for orchard operations demanding large-range, high-speed, and stable movement, such as orchard transport vehicles and automatic spraying vehicles [132,133]. Meanwhile, its small tire contact area makes it suitable for hard orchard roads. When traveling straight on flat surfaces, it exhibits superior heading stability compared to differential drive systems, rendering it well-suited for inter-row navigation. However, its minimum turning radius is constrained by wheelbase and steering angle, resulting in reduced maneuverability in narrow orchard rows or densely planted regions. Furthermore, it tends to slip on soft, muddy, or uneven terrain, demonstrating weak adaptability to varying ground conditions. The simplified kinematic model of the Ackermann-type OMR is illustrated in Figure 16.
The two front wheels of the robot chassis converge at point A, and the two rear wheels converge at point B, while C denotes the position of the robot’s center of mass. In the figure, D A and D B represent the respective steering radii of the robot’s front and rear axles, with point D being the instantaneous center of the entire robot during steering. θ is the robot’s current heading angle, and β is the angular deviation between the robot’s instantaneous velocity and its actual heading angle, known as the sideslip angle. δ f and δ r are the steering angles of the front and rear wheels, respectively. l f and l r are the distances from the robot’s front and rear axles to its center of mass, respectively. It can be obtained from the simplified model and the sine theorem
sin ( π 2 δ f ) R = sin ( δ f β ) l f sin ( β δ r ) l r = sin ( π 2 + δ r ) R .
Thus, the kinematic model with the robot centroid as the reference point in the world coordinate system is obtained as
x ˙ = v cos ( θ + β ) y ˙ = v sin ( θ + β ) θ ˙ = v cos β l f + l r ( tan δ f tan δ r ) .
The expression for the slip angle is
β = tan 1 ( l f tan δ r + l r tan δ f l f + l r ) .
Since the Ackerman steering is converted to the front wheel steering structure, the angle of the rear axle remains constant, i.e., δ r = 0 . When the robot slip is not taken into account, it can be assumed that the slip angle β = 0 . In the actual control process, the overall motion of the robot is usually adjusted via the rear axle position, and the kinematic model is transformed into a form based on the center of the rear axle
x ˙ = v cos θ y ˙ = v sin θ θ ˙ = v tan δ L .
Among them, L = l f + l r . v is the actual linear velocity of the robot’s rear axle, and δ is the steering angle of the robot’s front wheel.
Due to the significantly increased ground contact area provided by the tracks, the tracked differential OMR can still move stably on muddy, slippery, and rough orchard terrains, exhibiting strong terrain adaptability and enabling heavy-load operations, such as carrying fruit collection boxes and large-scale spraying equipment [134]. Additionally, an extremely small turning radius can be achieved through the reverse movement of the left and right tracks, making it suitable for operations in densely planted orchards or narrow spaces. The kinematic model of the tracked differential OMR is shown in Figure 17.
In Figure 17, v 1 and v 2 are the linear velocities of the two side tracks, respectively. v is the linear velocity of the mass center. θ is the actual heading angle. R is the turning radius. ω is the turning angular velocity. θ r and v r are the planned heading angle and the planned velocity, respectively.
A kinematic model of a track-type robot can be established as
X ˙ Y ˙ θ ˙ = cos θ 0 sin θ 0 0 1 v ω = cos θ 2 cos θ 2 sin θ 2 sin θ 2 1 L 1 L v 1 v 2 .

3.2.2. PID Control

Proportional-Integral-Derivative (PID) control is commonly employed for path tracking and local obstacle avoidance in orchard mobile robots. As the robot traverses its planned route, PID control continuously calculates the error between its actual position and the target path. This error is then linearly combined through proportional, integral, and derivative components to generate a control signal that adjusts the robot’s motion [135,136,137]. The principle diagram of the PID control algorithm is shown in Figure 18.
Output control parameters after proportional, integral, and derivative operations on the error. The calculation formula is
u ( t ) = K p e ( t ) + 1 T i 0 t e ( t ) d t + T d d e ( t ) d t ,
where K p , T i and T d are the proportional coefficient, integral coefficient and differential coefficient, respectively. e is the tracking deviation.
Taking Ackerman OMR as an example, the path tracking deviation formula is derived based on the kinematic model as
e = γ y e + η θ e ,
where γ and η are, respectively, the lateral and heading deviation coefficients.
PID controllers are widely used due to their simple structure and intuitive parameter tuning [138,139], but their performance in complex orchard environments is constrained by their linear characteristics [140]. The performance of PID controllers heavily relies on the precise tuning of their gain parameters. However, the adhesion coefficient and roughness of orchard surfaces are time-varying, leading to constantly changing vehicle-ground dynamics. This makes it difficult for a fixed set of PID parameters to maintain optimal performance under all operating conditions [141,142]. Sensor noise particularly adversely affects the derivative term D, as directly differentiating noisy error signals injects substantial high-frequency noise into the control command. This forces controllers to reduce derivative gain, sacrificing system response speed and control accuracy. Although the integral term I eliminates steady-state error, it rapidly accumulates during large disturbances such as slippage. This causes significant overshoot or even oscillation after system recovery.
Therefore, researchers have integrated intelligent algorithms with PID algorithms, thereby enhancing the adaptability of the improved PID algorithm to complex orchard environments. Wan et al. [143] proposed an adaptive PID controller based on PSO and a BP neural network. By combining the BP neural network algorithm with PID control, the controller improves the poor control performance of PID in nonlinear systems. Furthermore, PSO is employed to optimize the initial weights of the BP neural network, avoiding local optima caused by the random selection of initial weights and enhancing the control accuracy of the orchard fertilization robot system. Li et al. [144] addressed the problem that mowing robots are prone to slipping in complex orchard environments and proposed a cascaded path tracking controller integrating model predictive control and PID control. Additionally, an adaptive time-domain model for the orchard mowing robot based on the kinematic model was established. A fuzzy controller based on slip ratio was constructed using the real-time mower speed and reference driving wheel speeds solved by the model predictive controller, with anti-slip driving control implemented through the combination of the PID controller and tire dynamics model. Zhang et al. [145] proposed a multi-parameter optimized heading feedback algorithm combined with nonlinear PID control, which decouples the path tracking problem into a single-input single-output system for motor control. Furthermore, the dynamic performance and robustness of the algorithm are enhanced through adaptive gain design to optimize control response speed.

3.2.3. Model Predictive Control

Model Predictive Control (MPC) is a closed-loop control strategy based on system dynamic models and optimization algorithms. Its core idea is to achieve target tracking, constraint satisfaction, and optimal performance by predicting future system behavior and optimizing control inputs [146]. Compared with traditional PID control, MPC offers superior handling of nonlinear, time-varying, and constrained problems through receding horizon optimization and multi-step prediction, making it well-suited for complex orchard terrain and uncertain disturbances [147,148]. The block diagram illustrating the principle of the model predictive control algorithm is shown in Figure 19.
The core steps of MPC are prediction model, receding horizon optimization and feedback correction. The prediction model, based on the robot’s kinematic model, predicts the robot’s state in the future period. A discrete-time state-space equation is established,
x k + 1 = A x k + B u k ,
where x k is the state vector (position, velocity, attitude, etc.), u k is the control input (motor torque, steering angle, etc.). A and B are system matrices.
Rolling optimization involves setting optimization objectives to solve a finite-horizon optimization problem in each control cycle. This process minimizes the objective function (e.g., tracking error, control variable variation, energy consumption) while considering constraints (e.g., speed limits, steering angle limits). The objective function can be defined as
min J = k = 0 N 1 x k x r e f 2 Q + u k 2 R ,
where Q and R are weight matrices, respectively, penalizing the state error and the control input variation.
Feedback correction only performs the first-step control input in the optimization sequence, and then re-predicts and optimizes based on the actual state in the next cycle to form closed-loop control.
MPC is theoretically well-suited to handle constraints and uncertainties with its forward-looking rolling optimization capability in orchard navigation. However, its performance is constrained by model accuracy and computational resources [149,150]. The core of MPC relies on an accurate internal prediction model. The roughness of orchard terrain and slip effects can cause actual vehicle dynamics to deviate significantly from prediction models based on ideal kinematics or dynamics, leading to model mismatch. This mismatch directly reduces prediction accuracy, resulting in suboptimal or even ineffective control sequences derived from optimization; while MPC can partially mitigate this issue by incorporating disturbance observers or robust forms, this further increases the already substantial computational burden. Computational demands for solving online optimization problems require substantial resources, limiting control frequency. For small orchard mobile robot platforms, this poses significant challenges, particularly when handling long prediction horizons or complex constraints, where computational latency compromises real-time control performance.
To further enhance the control stability and robustness of MPC in complex environments, Liu et al. [151] proposed a fuzzy adaptive MPC method that adjusts the prediction horizon in real time through fuzzy adaptation of errors. This approach demonstrated robustness under uncertain disturbance conditions. Sperti et al. [152] proposed a nonlinear MPC strategy considering the kinematic model and obstacle avoidance constraints of orchard mobile robots to adapt to various crop spacings. The proposed solution demonstrated versatility in handling different crop densities, environmental factors, and multiple navigation tasks. Zhou et al. [153] proposed an MPC adaptive time-domain parameter for orchard articulated steering tractors. Using a genetic algorithm to compute optimal time-domain parameters in real-time based on vehicle speed, posture, and road conditions, they achieved adaptive MPC, enhancing path tracking control accuracy and real-time performance. To enhance the efficiency of agricultural robot tracking control, Xu et al. [154] proposed an Efficiency-Oriented Model Predictive Control (EfiMPC) approach. This method establishes an unreachable pseudo-tracking point to indicate operational efficiency objectives through a recursive horizon approach. Compared with the traditional NMPC algorithm, EfiMPC increases the operational efficiency of agricultural machinery by 8.56%.

3.2.4. Sliding Mode Control

Sliding Mode Control (SMC) is a nonlinear control strategy widely employed to address system nonlinearities, disturbances, and modeling uncertainties. Its core principle involves designing a sliding mode surface along which system states are forced to slide, thereby ensuring system stability and achieving desired dynamic performance [155]. Compared with traditional PID and model predictive control algorithms, sliding mode control boasts higher robustness, tracking control precision, and stronger anti-interference capability. This approach can better adapt to complex orchard scenarios where there are strong interference, model uncertainty, and sudden changes in model parameters due to load transfer during ramp steering [156,157].
SMC implementation in complex orchard environments still faces significant challenges from chattering issues. Theoretically, SMC can effectively handle model uncertainty and bounded disturbances caused by slippage and roughness variations. However, this robustness is achieved through high-frequency switching control laws, which can lead to severe chattering phenomena [158,159]. In practical systems, this chattering excites unmodeled steering system dynamics, exacerbating actuator wear. Furthermore, sensor noise directly enters the switching function, further intensifying chattering as the controller attempts to respond to measurement noise; while numerous methods exist to smooth control laws and mitigate chattering, these come at the expense of robustness and tracking accuracy.
Given the uncertainties and nonlinear characteristics inherent in complex orchard environments, developing variable-structure SMC controllers that align with robotic motion models has become a key research focus. Yan et al. [160] proposed an SMC method incorporating the road-sliding robot dynamics model. By designing a sliding-mode factor observer to estimate sliding-mode variable-structure parameters and integrating adaptive laws with nonlinear control techniques, they effectively resolved high-frequency chattering issues. Liu et al. [161] developed a tracking controller based on globally optimal sliding mode variable structure control (GO-SMC). By establishing a kinematic model for wheeled orchard mowers, they designed a globally stable GO-SMC controller using hyperbolic tangent functions within the SMC framework, ensuring stable reference path tracking. Ding et al. [162] developed an output-feedback SMC that transforms path-tracking-bias dynamics into a canonical system, treating unmodeled dynamics, external disturbances, and parameter variations as lumped effects. A second-order robust precise differentiator then reconstructs unknown system states within finite time. An improved power-integrator technique designed the second-order sliding-mode controller, demonstrating high-precision path-tracking performance. To enhance the adaptability of navigation control systems, Mancini et al. [163] designed an artificial potential field adaptive sliding mode controller. When directional errors are large, this controller reduces the aggressiveness of the translational velocity command, enabling the robot to rapidly rotate to the desired orientation before tracking the target trajectory.

3.3. Model-Free Intelligent Control Methods

Although geometry model-based and kinematics model-based control methods currently under research have been widely applied to OMR path tracking control, they still face challenges in constructing accurate kinematic and dynamic models of robots within highly uncertain orchard environments. This issue results in the inability of robots to meet expected adaptability and safety requirements in complex orchard settings, thereby limiting the practical application and development of OMR equipment [164]. Therefore, integrating model-free intelligent control methods with applications in intelligent perception and control, this section introduces reinforcement learning-based control strategies, transfer learning-based perception and control strategies, and DCEE-based learning and control strategies.

3.3.1. Control Strategy Based on Reinforcement Learning

Reinforcement learning is a model-free, data-driven machine learning method. Its core principle involves interacting with the environment and utilizing collected data and reward mechanisms to learn optimal control strategies. In complex and dynamically changing orchard environments, robots can adjust navigation control strategies through real-time reward feedback, enabling rapid autonomous planning and operational control when prior planning information is unavailable or unreliable [165,166,167]. For instance, Wang et al. [168] proposed a deep reinforcement learning-based coverage path planning method for kiwifruit-picking robots. This approach updates the action values of each iteration globally by establishing a path quality evaluation function and an empirical knowledge base. To correctly guide model training, an experience replay mechanism is also implemented to select high-quality paths for experience replay. Experimental results demonstrate that this algorithm effectively enhances the navigation efficiency of kiwifruit-picking robots. Furthermore, reinforcement learning can integrate multi-sensor data, including visual, force, and lidar inputs; generate control commands directly from raw sensor data; simplify the perception-planning-execution pipeline in traditional control systems; and enable end-to-end real-time control [169,170,171]. The principle of the reinforcement learning control strategy is illustrated in Figure 20.
However, relying solely on reinforcement learning strategies to achieve OMR navigation control also presents some issues. Reinforcement learning models tend to overfit to specific tasks and environments, leading to limited generalization capabilities. Therefore, Navone et al. [172] proposed a GPS-free autonomous navigation strategy for complex fruit tree rows based on deep semantic segmentation. By performing semantic segmentation on RGB frames and integrating depth data into the segmented frames, the robot’s spatial understanding of surrounding vegetation is enhanced. Using the front information, the direction of the vegetation row towards the endpoint is determined, and speed commands for the robot to follow the row are ultimately generated. This method trains an efficient segmentation neural network using only synthetic multi-crop data, demonstrating the fast inference and generalization performance of the deep learning pipeline. To address the contradiction between the long runtime of large reinforcement learning models and the high real-time requirements of OMR, Martini et al. [173] proposed a lightweight solution that combines edge AI with deep reinforcement learning to solve the autonomous navigation problem of vineyard robots. This solution directly maps noisy depth images and position-agnostic robot state information to velocity commands, guides the robot to the end of a row, and continuously adjusts its heading to maintain a collision-free central trajectory. Zhang et al. [174] proposed a deep reinforcement learning path tracking control algorithm that incorporates path curvature. A deep Q-network (DQN) based on a five-layer backpropagation (BP) neural network was constructed to achieve a lightweight and highly portable algorithm. The input state of the network is optimized by integrating the average path curvature within a set distance ahead of the vehicle, thereby improving the path tracking accuracy of the UGV.

3.3.2. Perception and Control Strategy Based on Transfer Learning

Traditional control methods heavily rely on precise environmental models and numerous manual rules. When confronting complex factors such as terrain changes, crop obstructions, and evolving fruit growth cycles, their generalization, robustness, and adaptability prove significantly inadequate. This results in high deployment costs, low efficiency, and challenges for large-scale application. Research on control strategies based on transfer learning (TL) holds core significance in overcoming this bottleneck. This strategy overcomes data distribution disparities across diverse orchard environments through knowledge transfer. The framework typically involves a source domain and a target domain, where domains are defined by data feature spaces and marginal probability distributions, and tasks are characterized by label spaces and target prediction functions [175,176]. Its technical core lies in narrowing distribution gaps between domains via specific algorithms, enabling effective application of models or knowledge learned in the source domain to the target domain.
Traditional machine learning (ML) methods train each task from scratch, treating source and target tasks as equally important starting points in the learning process. In contrast, the fundamental distinction of TL lies in leveraging knowledge acquired from one or more source tasks to enhance performance on the target task. This approach eliminates the need for a fresh start on every task [177]. Consequently, training requires significantly less time and cost compared to conventional ML.
TL employs prior knowledge as guidance, achieving efficient transfer and rapid adaptation of control intelligence through model reuse or feature alignment. This endows OMR with core capabilities to handle complex scenarios [178]. TL significantly enhances the operational efficiency and deployment speed of OMR by leveraging its data efficiency and rapid learning capabilities. Devanna et al. [179] proposed a novel multi-stage TL approach. Under controlled conditions, it fine-tunes pre-trained networks using fruit images for target tasks, then progressively expands to more complex scenarios. This achieves accurate and efficient on-site image segmentation of pomegranates for OMR. Xue et al. [180] employed TL to accurately and rapidly obtain tree canopy parameters, enabling efficient target recognition and precise spraying operations for orchard spray robots. Enhancing model generalization and adaptability further justifies TL’s suitability for complex orchard environments. Cao et al. [181] applied data augmentation and TL techniques to improve model accuracy and generalization, enabling orchard harvesting robots to achieve high-precision fruit detection and grasping control with accuracy rates ranging from 83.86% to 93.64%.
Perception and control strategies based on TL offer an efficient, intelligent, and highly promising technical pathway for OMR to tackle complex and dynamic working environments. Its advantages in high data efficiency and strong generalization capabilities make it pivotal for achieving large-scale practical application of agricultural robots. However, the risks of negative transfer and the gap between simulation and real-world performance constrain TL deployment on OMR platforms. Future research should focus on developing robust TL algorithms and constructing high-quality, multimodal orchard datasets.

3.3.3. Learning and Control Strategy Based on DCEE

DCEE is the next-generation control system theory proposed in 2021 by Professor Wen-Hua Chen, a renowned international scholar in the field of control from Loughborough University [182,183]. Unlike reinforcement learning, which employs model training to iteratively approximate optimal solutions, DCEE addresses complex uncertain environments by transforming the autonomous search problem in unknown environments into a control problem. The cost function is defined as the expected error between the robot’s future position and the predicted estimate of the target position and consists of two components: the first drives the robot toward the predicted target position using assumed measurements, while the second quantifies the uncertainty level of the predicted target position. By balancing exploration and exploitation, DCEE enhances environmental learning efficiency, solves the optimal solution online, and exhibits higher stability. To address unknown target positions, the target position is estimated via Bayesian inference at each step. A control action is then implemented to minimize the error between the robot’s predicted future position and the anticipated future estimate of the target position [184]. Professor Wen-Hua Chen detailed the principles of the DCEE control algorithm in [185]. By applying DCEE to mobile robots tasked with locating atmospheric hazardous substance release sources in unknown complex environments, the high reliability of the DCEE autonomous search algorithm was validated. Meanwhile, the algorithm exhibits strong compatibility and can be integrated with control algorithms such as PID and MPC to enable precise tracking control of mobile robots in complex environments.
Considering the impact of complex multifaceted factors in unstructured orchard environments on robotic trajectory tracking accuracy and integrating the core DCEE control strategy, the research team presents a conceptual framework for OMR path planning and tracking control based on active exploration and utilization of environmental information. The schematic structure of this framework is illustrated in Figure 21. First, real-time learning is performed on the positions of fruit trees and obstacles along with ground conditions in traversed areas to construct a spatiotemporal correlation model for orchard environmental features. Second, the path planning module combines known and real-time positional information of the OMR, employs probability density functions to predict robotic motion states in unknown environments, dynamically plans local paths in real time, and implements cyclic optimization with environmental model-robot information interaction to adaptively respond to environmental variations. Finally, the tracking module develops an environmental disturbance model using OMR multi-sensor information and integrates MPC trajectory tracking control based on disturbance prediction to actively compensate for internal and external uncertain disturbances.
The proposed scheme is designed to achieve robust autonomous navigation for OMR in complex, dynamic, and unknown environments by integrating DCEE with MPC control strategies. Considerations have been made regarding the interaction between OMR and its environment, offering researchers an approach to active learning-based path planning and control for robots. However, only an idealized environmental model has been established thus far, and challenges remain in accurately constructing a correlation model for feature information in complex orchard environments.

3.4. Summary

Table 2 compares the advantages and disadvantages of OMR tracking control methods in complex scenarios.
Comparing the performance of different control methods for OMR path tracking in complex environments reveals that path tracking algorithms must address multiple challenges in orchard settings, including uneven terrain, canopy obstruction, and dynamic obstacles. This imposes higher demands on the adaptability, robustness, and real-time capabilities of various approaches. Traditional control methods like pure pursuit control, Stanley control, and PID control exhibit significant limitations. Pure pursuit control relies on curvature estimation of predefined paths. In orchards’ narrow, irregular inter-row passages, sudden curvature changes caused by tree obstructions and terrain undulations easily lead to tracking lag or even instability, while Stanley control improves path tracking accuracy through front-wheel steering angle compensation; it remains highly sensitive to variations in orchard surface friction coefficients. PID control is widely adopted due to its simple structure and easily adjustable parameters. However, the nonlinearity of complex orchard environments makes it difficult to simultaneously meet dynamic response and disturbance rejection requirements. Integral saturation phenomena further reduce control robustness. Although these methods offer high computational efficiency and ease of implementation, their reliance on precise models and fixed parameters results in poor adaptability within highly unstructured orchards.
In contrast, kinematic model-based and model-free intelligent control methods are better suited for handling multiple constraints in complex orchards. MPC can explicitly address path constraints through rolling optimization and state prediction while accommodating multivariable coupling. However, its computational burden increases with problem complexity, potentially posing challenges for real-time orchard operations. SMC effectively suppresses uncertain disturbances on orchard terrain due to its strong robustness, but high-frequency chattering in control outputs may accelerate mechanical wear, hindering long-term stable operation. RL autonomously learns optimal control strategies through environmental interaction, excelling at handling unstructured obstacles and dynamic changes in orchards. However, it requires substantial training data and carries convergence risks. Integrating TL mitigates data dependency by accelerating model training through transferring existing scenario knowledge, thereby enhancing generalization capabilities. DCEE demonstrates strong adaptability and multi-objective optimization capabilities, yet its performance heavily relies on the accuracy and completeness of environmental information.
Overall, traditional robust trajectory tracking control with passive disturbance compensation cannot actively adapt to unstructured orchard environments. In such scenarios, the highly nonlinear nature of the robotic system model and the adverse effects of internal and external uncertain disturbances are further amplified, thereby reducing tracking accuracy and potentially compromising the stability of the control system. Traditional robust feedback control strategies rely on state feedback to estimate and suppress disturbances after they occur, introducing inherent compensation delays that hinder high-precision trajectory tracking in complex environments. Therefore, there is an urgent need to explore intelligent control methods such as deep RL, TL, or DCEE to construct information models for complex orchard environments. This involves establishing uncertainty models for both internal and external disturbances, researching disturbance prediction and active compensation techniques for trajectory tracking control, and ultimately achieving high-precision, active interference-resistant, robust trajectory tracking control for OMR in complex environments.

4. Challenges and Future Trends

Despite recent breakthroughs in the development of mobile robot equipment and key technologies, robots still exhibit insufficient adaptability in autonomous navigation when operating in complex and uncertain environments, leading to relatively slow progress in their intelligent deployment and application. In particular, the robust, accurate, and real-time performance requirements of autonomous navigation systems in unstructured and dynamically changing orchard environments must be comprehensively considered for OMR, which poses significant obstacles to its widespread adoption and application. Based on a review of relevant literature and the developmental landscape of mobile robots, this paper summarizes the current status and future key research directions of OMR autonomous navigation systems as follows:
  • The existing OMR autonomous navigation control system adopts a hierarchical architecture combining path planning and tracking control, directly decoupling global decision-making from local execution. This facilitates separate algorithm optimization for varying levels of complexity. However, autonomous navigation systems with such hierarchical structures are highly susceptible to cumulative errors between layers; while deep learning and RL can learn complex control strategies through data-driven methods, they face challenges such as low sample efficiency, high training costs, and the complexity of state spaces in outdoor environments. Therefore, deeply integrating TL with RL or DCEE control strategies represents a key future research direction. Accelerating RL training using sparse expert demonstration data, coupled with a simulation-to-reality transfer learning framework, enables the safe and efficient transfer of strategies trained in high-fidelity virtual orchards to physical robots. Furthermore, frontier research is carried out to explore AI and end-to-end models, empowering robots to predict environmental changes and adaptively adjust control parameters using minimal online interaction data. This ultimately achieves strong generalization and high-robustness autonomous operations across crops and seasons.
  • The complex terrain and continuous operational tasks in orchard environments lead to a significant increase in robotic energy consumption; while traditional global path planning algorithms can identify the shortest path, they do not necessarily yield the most energy-efficient route and fail to adequately account for the energy costs associated with actuator start-stop cycles and steering maneuvers. Development trends focus on developing multi-objective optimized energy-saving navigation strategies. The core lies in constructing a refined energy consumption model that integrates terrain elevation, soil hardness, steering angle, and motor efficiency. This model is then incorporated into a model predictive control framework for rolling optimization, achieving the optimal balance between path length and energy consumption. Simultaneously, integrating SLAM technology enables real-time identification of navigable areas, avoiding high-energy-consumption zones. This significantly extends the operational duration per charge, enhancing the economic viability and sustainability of orchard operations.
  • Single-robot operation modes have limited efficiency in large-scale orchards, making multi-robot collaboration a key development direction for high-efficiency operations. However, coordinating and controlling multi-robot systems is highly complex. Existing centralized scheduling systems carry the risk of single points of failure, while fully distributed coordination faces challenges of communication latency and data consistency. The future trend lies in adopting a hierarchical hybrid architecture that integrates top-level task planning with bottom-level distributed real-time obstacle avoidance. By incorporating highly robust communication technologies such as Ultra-Wideband (UWB) and 5G to establish self-organizing networks and leveraging digital twin technology for virtual mapping and collaborative simulation of orchard environments and robot states, the overall operational efficiency and resource utilization of robot clusters can be maximized while ensuring safety.
  • Multi-sensor fusion currently serves as the primary method for processing perception information in OMR. However, constrained by the conflict between the volume of perception data requiring processing and limited onboard computational resources, OMR cannot process vast amounts of environmental information data in real-time on the vehicle itself. The developmental trend is to establish a collaborative “end-edge-cloud” intelligent computing paradigm: deploying lightweight neural networks on the robot edge to handle low-latency tasks such as real-time obstacle avoidance and navigation. Edge servers deployed within orchards handle multi-robot data fusion, large-scale semantic mapping, offline computation for precision operations, and model updates. The cloud manages global data and conducts iterative algorithm training. This architecture achieves an optimal balance of computational resources, communication overhead, and system responsiveness through task offloading and collaborative reasoning.

5. Conclusions

It is an indisputable fact that orchards constitute a vital component of agriculture and thus represent a key factor in the enhancement of profits for agricultural operators whilst driving socio-economic development. The modern orchard is congruent with China’s developmental strategy for green and intelligent agriculture. Research into the application of autonomous navigation technology for mobile robots in complex orchard environments is of significant practical and strategic value. This technology has the potential to address the following issues in traditional orchard management: high labor costs, low operational efficiency, and imprecise pesticide application. The implementation of intelligent path planning and precise control, automated inspection, targeted plant protection, and intelligent harvesting has the potential to enhance the intelligence level of orchard management to a significant degree. The objective of this paper is to provide a comprehensive overview of the most recent research advancements in the core technologies of OMR autonomous navigation within complex scenarios, specifically focusing on path planning and tracking control. These advancements will provide a solid foundation for the mature application of intelligent OMR systems and the rapid improvement of comprehensive orchard production and management capabilities.
Due to the significant performance differences among various autonomous navigation technologies in unstructured, complex orchard environments, algorithm selection in practical applications necessitates complex trade-offs between accuracy, robustness, efficiency, and environmental adaptability. Traditional architectures relying on hierarchical decoupling and single sensors exhibit inherent limitations when confronting the high uncertainty and unstructured nature of orchard environments. The cumulative error effects across these layers severely constrain overall system performance, while advanced algorithms like MPC and RL demonstrate potential; their practical deployment remains constrained by high computational costs, reliance on precise models, and insufficient generalization capabilities in real-world scenarios. These constraints collectively determine that no single universal navigation algorithm can achieve autonomous OMR operation in complex environments. An efficient autonomous navigation control system must therefore be a highly integrated multimodal solution.
Therefore, future research should focus on developing highly collaborative heterogeneous fusion navigation architectures. Key areas include designing tightly coupled multimodal perception-decision-control integrated frameworks that minimize error propagation between layers through real-time interaction between front-end environmental semantic understanding and back-end model predictive control. Exploring lightweight and adaptive learning mechanisms, such as combining online adaptive MPC with meta-reinforcement learning, to enhance rapid adaptation in unknown environments while reducing computational overhead. Constructing a system-level solution for “sensor-algorithm-platform” co-optimization, dynamically allocating computational resources based on tasks to achieve a balance between accuracy, efficiency, and robustness.

Author Contributions

Conceptualization, Y.S. (Yayun Shen) and H.L.; methodology, Y.S. (Yayun Shen) and Y.Z.; software, C.H. and Z.S.; validation, Y.S. (Yayun Shen) and W.S.; formal analysis, Y.S. (Yayun Shen); investigation, Y.S. (Yayun Shen); resources, Y.S. (Yue Shen); data curation, Y.S. (Yayun Shen) and Z.S.; writing—original draft preparation, Y.S. (Yayun Shen), Y.Z., C.H. and W.S.; writing review and editing, Y.S. (Yayun Shen); visualization, Y.S. (Yayun Shen); supervision, Y.S. (Yayun Shen), H.L. and Y.S. (Yue Shen); project administration, H.L.; funding acquisition, H.L. All authors have read and agreed to the published version of the manuscript.

Funding

This study was supported by the National Natural Science Foundation of China under Grant 32171908 and Jiangsu Agricultural Science and Technology Innovation Fund under Grant CX(24)3025.

Institutional Review Board Statement

Not applicable.

Data Availability Statement

No new data were created or analyzed in this study.

Acknowledgments

The authors would like to thank the editor and reviewers for their valuable suggestions for improving this paper.

Conflicts of Interest

The authors declare no conflicts of interest.

References

  1. Chakraborty, S.; Elangovan, D.; Govindarajan, P.L.; ELnaggar, M.F.; Alrashed, M.M.; Kamel, S. A comprehensive review of path planning for agricultural ground robots. Sustainability 2022, 14, 9156. [Google Scholar] [CrossRef]
  2. Binbin, X.; Jizhan, L.; Meng, H.; Jian, W.; Zhujie, X. Research progress on autonomous navigation technology of agricultural robot. In Proceedings of the 2021 IEEE 11th Annual International Conference on CYBER Technology in Automation, Control, and Intelligent Systems (CYBER), Jiaxian, China, 27–31 July 2021; pp. 891–898. [Google Scholar]
  3. Mhamed, M.; Zhang, Z.; Yu, J.; Li, Y.; Zhang, M. Advances in apple’s automated orchard equipment: A comprehensive research. Comput. Electron. Agric. 2024, 221, 108926. [Google Scholar] [CrossRef]
  4. Jiangyi, H.; Fan, W. Design and testing of a small orchard tractor driven by a power battery. Eng. Agrícola 2023, 43, e20220195. [Google Scholar] [CrossRef]
  5. Wu, M.; Ou, M.; Zhang, Y.; Jia, W.; Dai, S.; Wang, M.; Dong, X.; Wang, X.; Jiang, L. Development and Evaluation of a Monodisperse Droplet-Generation System for Precision Herbicide Application. Agriculture 2024, 14, 1885. [Google Scholar] [CrossRef]
  6. Zhu, C.; Hao, S.; Liu, C.; Wang, Y.; Jia, X.; Xu, J.; Guo, S.; Huo, J.; Wang, W. An Efficient Computer Vision-Based Dual-Face Target Precision Variable Spraying Robotic System for Foliar Fertilisers. Agronomy 2024, 14, 2770. [Google Scholar] [CrossRef]
  7. Wang, G.; Li, Z.; Jia, W.; Ou, M.; Dong, X.; Zhang, Z. A Review on the Evolution of Air-Assisted Spraying in Orchards and the Associated Leaf Motion During Spraying. Agriculture 2025, 15, 964. [Google Scholar] [CrossRef]
  8. Wang, Y.; Zhang, Z.; Jia, W.; Ou, M.; Dong, X.; Dai, S. A review of environmental sensing technologies for targeted spraying in orchards. Horticulturae 2025, 11, 551. [Google Scholar] [CrossRef]
  9. Liu, H.; Du, Z.; Shen, Y.; Du, W.; Zhang, X. Development and evaluation of an intelligent multivariable spraying robot for orchards and nurseries. Comput. Electron. Agric. 2024, 222, 109056. [Google Scholar] [CrossRef]
  10. Dong, X.; Kim, W.Y.; Yu, Z.; Oh, J.Y.; Ehsani, R.; Lee, K.H. Improved voxel-based volume estimation and pruning severity mapping of apple trees during the pruning period. Comput. Electron. Agric. 2024, 219, 108834. [Google Scholar] [CrossRef]
  11. Wu, P.; Lei, X.; Zeng, J.; Qi, Y.; Yuan, Q.; Huang, W.; Ma, Z.; Shen, Q.; Lyu, X. Research progress in mechanized and intelligentized pollination technologies for fruit and vegetable crops. Int. J. Agric. Biol. Eng. 2024, 17, 11–21. [Google Scholar] [CrossRef]
  12. Wu, S.; Liu, J.; Lei, X.; Zhao, S.; Lu, J.; Jiang, Y.; Xie, B.; Wang, M. Research progress on efficient pollination technology of crops. Agronomy 2022, 12, 2872. [Google Scholar] [CrossRef]
  13. Chen, K.; Li, T.; Yan, T.; Xie, F.; Feng, Q.; Zhu, Q.; Zhao, C. A soft gripper design for apple harvesting with force feedback and fruit slip detection. Agriculture 2022, 12, 1802. [Google Scholar] [CrossRef]
  14. Zhou, K.; Xia, L.; Liu, J.; Qian, M.; Pi, J. Design of a flexible end-effector based on characteristics of tomatoes. Int. J. Agric. Biol. Eng. 2022, 15, 13–24. [Google Scholar] [CrossRef]
  15. Zhou, Z.; Zahid, U.; Majeed, Y.; Nisha; Mustafa, S.; Sajjad, M.M.; Butt, H.D.; Fu, L. Advancement in artificial intelligence for on-farm fruit sorting and transportation. Front. Plant Sci. 2023, 14, 1082860. [Google Scholar] [CrossRef]
  16. He, Y.; Huang, Z.; Yang, N.; Li, X.; Wang, Y.; Feng, X. Research Progress and Prospects of Key Navigation Technologies for Facility Agricultural Robots. Smart Agric. 2024, 6, 1–19. [Google Scholar]
  17. Wu, M.; Liu, S.; Li, Z.; Ou, M.; Dai, S.; Dong, X.; Wang, X.; Jiang, L.; Jia, W. A review of intelligent orchard sprayer technologies: Perception, control, and system integration. Horticulturae 2025, 11, 668. [Google Scholar] [CrossRef]
  18. Xu, Z.; Liu, J.; Wang, J.; Cai, L.; Jin, Y.; Zhao, S.; Xie, B. Realtime picking point decision algorithm of trellis grape for high-speed robotic cut-and-catch harvesting. Agronomy 2023, 13, 1618. [Google Scholar] [CrossRef]
  19. Liu, J.; Liang, J.; Zhao, S.; Jiang, Y.; Wang, J.; Jin, Y. Design of a virtual multi-interaction operation system for hand–eye coordination of grape harvesting robots. Agronomy 2023, 13, 829. [Google Scholar] [CrossRef]
  20. Ji, W.; He, G.; Xu, B.; Zhang, H.; Yu, X. A new picking pattern of a flexible three-fingered end-effector for apple harvesting robot. Agriculture 2024, 14, 102. [Google Scholar] [CrossRef]
  21. Yu, Y.; Xie, H.; Zhang, K.; Wang, Y.; Li, Y.; Zhou, J.; Xu, L. Design, development, integration, and field evaluation of a ridge-planting strawberry harvesting robot. Agriculture 2024, 14, 2126. [Google Scholar] [CrossRef]
  22. Jiang, L.; Xu, B.; Husnain, N.; Wang, Q. Overview of Agricultural Machinery Automation Technology for Sustainable Agriculture. Agronomy 2025, 15, 1471. [Google Scholar] [CrossRef]
  23. Ji, W.; Zhang, T.; Xu, B.; He, G. Apple recognition and picking sequence planning for harvesting robot in a complex environment. J. Agric. Eng. 2024, 55, 1549. [Google Scholar]
  24. Syed, T.N.; Zhou, J.; Lakhiar, I.A.; Marinello, F.; Gemechu, T.T.; Rottok, L.T.; Jiang, Z. Enhancing Autonomous Orchard Navigation: A Real-Time Convolutional Neural Network-Based Obstacle Classification System for Distinguishing ‘Real’and ‘Fake’Obstacles in Agricultural Robotics. Agriculture 2025, 15, 827. [Google Scholar] [CrossRef]
  25. Wang, Q.; He, J.; Lu, C.; Wang, C.; Lin, H.; Yang, H.; Li, H.; Wu, Z. Modelling and control methods in path tracking control for autonomous agricultural vehicles: A review of state of the art and challenges. Appl. Sci. 2023, 13, 7155. [Google Scholar] [CrossRef]
  26. Jiang, Y.; Wang, R.; Ding, R.; Sun, Z.; Jiang, Y.; Liu, W. Research Review of Agricultural Machinery Power Chassis in Hilly and Mountainous Areas. Agriculture 2025, 15, 1158. [Google Scholar] [CrossRef]
  27. Yao, Z.; Zhao, C.; Zhang, T. Agricultural machinery automatic navigation technology. Iscience 2024, 27, 108714. [Google Scholar] [CrossRef]
  28. Yu, S.; Zhu, J.; Zhou, J.; Cheng, J.; Bian, X.; Shen, J.; Wang, P. Key technology progress of plant-protection uavs applied to mountain orchards: A review. Agronomy 2022, 12, 2828. [Google Scholar] [CrossRef]
  29. Staff, A. Coming soon to an orchard near you: The Global Unmanned Spray System (GUSS). Resour. Mag. 2019, 26, 9–10. [Google Scholar]
  30. Gallou, J.; Lippi, M.; Galle, M.; Marino, A.; Gasparri, A. Modeling and Control of the Vitirover Robot for Weed Management in Precision Agriculture. In Proceedings of the 2024 10th International Conference on Control, Decision and Information Technologies (CoDIT), Valletta, Malta, 1–4 July 2024; pp. 2670–2675. [Google Scholar]
  31. Wu, T.; Liu, D.; Li, X. Designing Hybrid Mobility for Agricultural Robots: Performance Analysis of Wheeled and Tracked Systems in Variable Terrain. Machines 2025, 13, 572. [Google Scholar] [CrossRef]
  32. Xin, Q.; Luo, Q.; Zhu, H. Key issues and countermeasures of machine vision for fruit and vegetable picking robot. In Mechatronics and Automation Technology; IOS Press: Amsterdam, The Netherlands, 2024; pp. 69–78. [Google Scholar]
  33. Su, Z.; Zou, W.; Zhai, C.; Tan, H.; Yang, S.; Qin, X. Design of an Autonomous Orchard Navigation System Based on Multi-Sensor Fusion. Agronomy 2024, 14, 2825. [Google Scholar] [CrossRef]
  34. Liu, W.; Hu, J.; Liu, J.; Yue, R.; Zhang, T.; Yao, M.; Li, J. Method for the navigation line recognition of the ridge without crops via machine vision. Int. J. Agric. Biol. Eng. 2024, 17, 230–239. [Google Scholar] [CrossRef]
  35. Zhenyu, C.; Hanjie, D.; Yuanyuan, G.; Changyuan, Z.; Xiu, W.; Wei, Z. Research on an orchard row centreline multipoint autonomous navigation method based on LiDAR. Artif. Intell. Agric. 2025, 15, 221–231. [Google Scholar] [CrossRef]
  36. Pi, J.; Liu, J.; Zhou, K.; Qian, M. An octopus-inspired bionic flexible gripper for apple grasping. Agriculture 2021, 11, 1014. [Google Scholar] [CrossRef]
  37. Ji, W.; Qian, Z.; Xu, B.; Tang, W.; Li, J.; Zhao, D. Grasping damage analysis of apple by end-effector in harvesting robot. J. Food Process. Eng. 2017, 40, e12589. [Google Scholar] [CrossRef]
  38. Zhong, W.; Yang, W.; Zhu, J.; Jia, W.; Dong, X.; Ou, M. An Improved UNet-Based Path Recognition Method in Low-Light Environments. Agriculture 2024, 14, 1987. [Google Scholar] [CrossRef]
  39. Jia, W.; Zheng, Y.; Zhao, D.; Yin, X.; Liu, X.; Du, R. Preprocessing method of night vision image application in apple harvesting robot. INternational J. Agric. Biol. Eng. 2018, 11, 158–163. [Google Scholar] [CrossRef]
  40. Zhang, H.; Ji, W.; Xu, B.; Yu, X. Optimizing contact force on an apple picking robot end-effector. Agriculture 2024, 14, 996. [Google Scholar] [CrossRef]
  41. Cui, L.; Mao, H.; Xue, X.; Ding, S.; Qiao, B. Optimized design and test for a pendulum suspension of the crop spray boom in dynamic conditions based on a six DOF motion simulator. Int. J. Agric. Biol. Eng. 2018, 11, 76–85. [Google Scholar]
  42. Jin, Y.; Liu, J.; Xu, Z.; Yuan, S.; Li, P.; Wang, J. Development status and trend of agricultural robot technology. Int. J. Agric. Biol. Eng. 2021, 14, 1–19. [Google Scholar] [CrossRef]
  43. Katona, K.; Neamah, H.A.; Korondi, P. Obstacle avoidance and path planning methods for autonomous navigation of mobile robot. Sensors 2024, 24, 3573. [Google Scholar] [CrossRef] [PubMed]
  44. Liu, H.; Zeng, X.; Shen, Y.; Xu, J.; Khan, Z. A single-stage navigation path extraction network for agricultural robots in orchards. Comput. Electron. Agric. 2025, 229, 109687. [Google Scholar] [CrossRef]
  45. Wang, H.; Yu, Y.; Yuan, Q. Application of Dijkstra algorithm in robot path-planning. In Proceedings of the 2011 Second International Conference on Mechanic Automation and Control Engineering, Inner Mongolia, China, 15–17 July 2011; pp. 1067–1069. [Google Scholar]
  46. Husain, Z.; Al Zaabi, A.; Hildmann, H.; Saffre, F.; Ruta, D.; Isakovic, A. Search and rescue in a maze-like environment with ant and dijkstra algorithms. Drones 2022, 6, 273. [Google Scholar] [CrossRef]
  47. Xu, Y.; Xue, X.; Sun, Z.; Gu, W.; Cui, L.; Jin, Y.; Lan, Y. Global path planning for navigating orchard vehicle based on fruit tree positioning and planting rows detection from UAV imagery. Comput. Electron. Agric. 2025, 236, 110446. [Google Scholar] [CrossRef]
  48. Liu, Z.; Fang, J.; Zhao, Y. DynaFusion-SLAM: Multi-Sensor Fusion and Dynamic Optimization of Autonomous Navigation Algorithms for Pasture-Pushing Robot. Sensors 2025, 25, 3395. [Google Scholar] [CrossRef]
  49. Jin, P.; Li, T.; Pan, Y.; Hu, K.; Xu, N.; Ying, W.; Jin, Y.; Kang, H. A Context-Aware Navigation Framework for Ground Robots in Horticultural Environments. Sensors 2024, 24, 3663. [Google Scholar] [CrossRef] [PubMed]
  50. Xu, X.; Zeng, J.; Zhao, Y.; Lü, X. Research on global path planning algorithm for mobile robots based on improved A. Expert Syst. Appl. 2024, 243, 122922. [Google Scholar] [CrossRef]
  51. Shen, Y.; Liu, Z.; Liu, H.; Du, W. Orchard spray robot planning algorithm based on multiple constraints. Trans. CSAM 2023, 54, 56–67. [Google Scholar]
  52. Hua, W.; Heinemann, P.; He, L. Multi-agent Path Planning in Apple Orchard with Tight Tree Rows Based on Improved A-Star Algorithm for Frost Protection. In Proceedings of the 2023 ASABE Annual International Meeting, Omaha, NE, USA, 9–12 July 2023; p. 1. [Google Scholar]
  53. Zhang, M.; Li, X.; Wang, L.; Jin, L.; Wang, S. A path planning system for orchard mower based on improved A* algorithm. Agronomy 2024, 14, 391. [Google Scholar] [CrossRef]
  54. Wang, M.; Xu, J.; Zhang, J.; Cui, Y. An autonomous navigation method for orchard rows based on a combination of an improved a-star algorithm and SVR. Precis. Agric. 2024, 25, 1429–1453. [Google Scholar] [CrossRef]
  55. Kong, F.; Liu, B.; Han, X.; Yi, L.; Sun, H.; Liu, J.; Liu, L.; Lan, Y. Path Planning Algorithm of Orchard Fertilization Robot Based on Multi-Constrained Bessel Curve. Agriculture 2024, 14, 979. [Google Scholar] [CrossRef]
  56. Chatzisavvas, A.; Dossis, M.; Dasygenis, M. Optimizing mobile robot navigation based on A-star algorithm for obstacle avoidance in smart agriculture. Electronics 2024, 13, 2057. [Google Scholar] [CrossRef]
  57. Chi, Z.; Yu, Z.; Wei, Q.; He, Q.; Li, G.; Ding, S. High-efficiency navigation of nonholonomic mobile robots based on improved hybrid A* algorithm. Appl. Sci. 2023, 13, 6141. [Google Scholar] [CrossRef]
  58. 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]
  59. Meng, T.; Yang, T.; Huang, J.; Jin, W.; Zhang, W.; Jia, Y.; Wan, K.; Xiao, G.; Yang, D.; Zhong, Z. Improved hybrid A-star algorithm for path planning in autonomous parking system based on multi-stage dynamic optimization. Int. J. Automot. Technol. 2023, 24, 459–468. [Google Scholar] [CrossRef]
  60. Schlapbach, J.; Schopferer, S. Time-Aware Probabilistic Roadmaps for Multi-Query Path Planning in Dynamic Environments. In Proceedings of the 2024 Eighth IEEE International Conference on Robotic Computing (IRC), Tokyo, Japan, 11–13 December 2024; pp. 9–16. [Google Scholar]
  61. Zeeshan, S.; Aized, T. Performance analysis of path planning algorithms for fruit harvesting robot. J. Biosyst. Eng. 2023, 48, 178–197. [Google Scholar] [CrossRef]
  62. Suravarapu, A.; Surampudi, S.S.; Potnuru, S.D.; Desai, R.P. Bidirectional Path Planning for Autonomous Robot Using Dijkstra Algorithm with PRM. In Proceedings of the 2024 IEEE 21st India Council International Conference (INDICON), Kharagpur, India, 19–21 December 2024; pp. 1–6. [Google Scholar]
  63. Tian, H.; Wang, J.; Huang, H.; Ding, F. Probabilistic roadmap method for path planning of intelligent vehicle based on artificial potential field model in off-roadenvironment. Acta Armamentarii 2021, 42, 1496. [Google Scholar]
  64. Mahmud, M.S.A.; Abidin, M.S.Z.; Mohamed, Z.; Abd Rahman, M.K.I.; Iida, M. Multi-objective path planner for an agricultural mobile robot in a virtual greenhouse environment. Comput. Electron. Agric. 2019, 157, 488–499. [Google Scholar] [CrossRef]
  65. LaValle, S.M.; Kuffner, J.J. Rapidly-exploring random trees: Progress and prospects: Steven m. lavalle, iowa state university, a james j. kuffner, jr., university of tokyo, tokyo, japan. In Algorithmic and Computational Robotics; A K Peters: Natick, MA, USA, 2001; pp. 303–307. [Google Scholar]
  66. Li, Y.; Ma, S.; Li, L.; Su, C.; Ding, Z. Path planning of apple tree pruning robot based on improved RRT algorithm. In Proceedings of the 2023 ASABE Annual International Meeting, Omaha, NE, USA, 9–12 July 2023; p. 1. [Google Scholar]
  67. Hu, M.; Huang, Q.; Cai, J.; Chen, Y.; Li, J.; Shi, L. HPS-RRT*: An Improved Path Planning Algorithm for a Nonholonomic Orchard Robot in Unstructured Environments. Agronomy 2025, 15, 712. [Google Scholar] [CrossRef]
  68. Li, Y.; Ma, S. Navigation of apple tree pruning robot based on improved RRT-connect algorithm. Agriculture 2023, 13, 1495. [Google Scholar] [CrossRef]
  69. Zhang, B.; Yin, C.; Fu, Y.; Xia, Y.; Fu, W. Harvest motion planning for mango picking robot based on improved RRT-Connect. Biosyst. Eng. 2024, 248, 177–189. [Google Scholar] [CrossRef]
  70. Chen, Y.; Fu, Y.; Zhang, B.; Fu, W.; Shen, C. Path planning of the fruit tree pruning manipulator based on improved RRT-Connect algorithm. Int. J. Agric. Biol. Eng. 2022, 15, 177–188. [Google Scholar] [CrossRef]
  71. Karaman, S.; Frazzoli, E. Incremental sampling-based algorithms for optimal motion planning. Robot. Sci. Syst. VI 2010, 104, 267–274. [Google Scholar]
  72. Zeeshan, S.; Aized, T.; Riaz, F. In-depth evaluation of automated fruit harvesting in unstructured environment for improved robot design. Machines 2024, 12, 151. [Google Scholar] [CrossRef]
  73. Wang, Y.; Liu, D.; Zhao, H.; Li, Y.; Song, W.; Liu, M.; Tian, L.; Yan, X. Rapid citrus harvesting motion planning with pre-harvesting point and quad-tree. Comput. Electron. Agric. 2022, 202, 107348. [Google Scholar] [CrossRef]
  74. Ye, L.; Li, J.; Li, P. Improving path planning for mobile robots in complex orchard environments: The continuous bidirectional Quick-RRT* algorithm. Front. Plant Sci. 2024, 15, 1337638. [Google Scholar] [CrossRef]
  75. Ye, L.; Wu, F.; Zou, X.; Li, J. Path planning for mobile robots in unstructured orchard environments: An improved kinematically constrained bi-directional RRT approach. Comput. Electron. Agric. 2023, 215, 108453. [Google Scholar] [CrossRef]
  76. Hui, L.; Shiyi, Z.; Yunpeng, D.; Weidong, J.; Yue, S. Orchard Robot Motion Planning Algorithm Based on Improved Bidirectional RRT. In Nongye Jixie Xuebao/Transactions of the Chinese Society of Agricultural Machinery; Chinese Society of Agricultural Machinery: Beijing, China, 2022; Volume 53. [Google Scholar]
  77. Lamini, C.; Benhlima, S.; Elbekri, A. Genetic algorithm based approach for autonomous mobile robot path planning. Procedia Comput. Sci. 2018, 127, 180–189. [Google Scholar] [CrossRef]
  78. Zhang, L.; He, Z.; Zhu, H.; Wei, Z.; Lu, J.; He, X. Adaptive SOM-GA Hybrid Algorithm for Grasping Sequence Optimization in Apple Harvesting Robots: Enhancing Efficiency in Open-Field Orchards. Agronomy 2025, 15, 1230. [Google Scholar] [CrossRef]
  79. Liao, T.; Deng, S. Research on Genetic Algorithm Optimization of Agricultural Robot Picking Task Planning. In Proceedings of the 2025 International Conference on Electrical Drives, Power Electronics & Engineering (EDPEE), Athens, Greece, 26–28 March 2025; pp. 810–815. [Google Scholar]
  80. Hizatate, T.; Noguchi, N. Work schedule optimization for electric agricultural robots in orchards. Comput. Electron. Agric. 2023, 210, 107889. [Google Scholar] [CrossRef]
  81. Li, S.; Zhang, M.; Wang, N.; Cao, R.; Zhang, Z.; Ji, Y.; Li, H.; Wang, H. Intelligent scheduling method for multi-machine cooperative operation based on NSGA-III and improved ant colony algorithm. Comput. Electron. Agric. 2023, 204, 107532. [Google Scholar] [CrossRef]
  82. Yu, Y.; Hao, S.; Guo, S.; Tang, Z.; Chen, S. Motor torque distribution strategy for different tillage modes of agricultural electric tractors. Agriculture 2022, 12, 1373. [Google Scholar] [CrossRef]
  83. Tian, H.; Mo, Z.; Ma, C.; Xiao, J.; Jia, R.; Lan, Y.; Zhang, Y. Design and validation of a multi-objective waypoint planning algorithm for UAV spraying in orchards based on improved ant colony algorithm. Front. Plant Sci. 2023, 14, 1101828. [Google Scholar] [CrossRef] [PubMed]
  84. Niu, J.; Shen, C.; Zhang, L.; Gao, G.; Zheng, J. Study on Multiobjective Path Optimization of Plant Protection Robots Based on Improved ACO-DWA Algorithm. Eng. Rep. 2025, 7, e70009. [Google Scholar] [CrossRef]
  85. Xu, Y.; Xue, X.; Sun, Z.; Cui, L.; Cai, C.; Zhou, Q.; Chen, C.; Gu, W. Path planning and scheduling of multiple unmanned Ground vehicles for orchard plant protection operations. Comput. Electron. Agric. 2025, 237, 110615. [Google Scholar] [CrossRef]
  86. Li, Y.; Xu, L.; Lv, L.; Shi, Y.; Yu, X. Study on modeling method of a multi-parameter control system for threshing and cleaning devices in the grain combine harvester. Agriculture 2022, 12, 1483. [Google Scholar] [CrossRef]
  87. Xu, L.; You, J.; Yuan, H. Real-time parametric path planning algorithm for agricultural machinery kinematics model based on particle swarm optimization. Agriculture 2023, 13, 1960. [Google Scholar] [CrossRef]
  88. Gao, R.; Zhou, Q.; Cao, S.; Jiang, Q. Apple-picking robot picking path planning algorithm based on improved PSO. Electronics 2023, 12, 1832. [Google Scholar] [CrossRef]
  89. Liu, L.; Wang, X.; Yang, X.; Liu, H.; Li, J.; Wang, P. Path planning techniques for mobile robots: Review and prospect. Expert Syst. Appl. 2023, 227, 120254. [Google Scholar] [CrossRef]
  90. Wang, J.; Yang, L.; Cen, H.; He, Y.; Liu, Y. Dynamic obstacle avoidance control based on a novel dynamic window approach for agricultural robots. Comput. Ind. 2025, 167, 104272. [Google Scholar] [CrossRef]
  91. Huang, P.; Huang, P.; Wang, Z.; Wu, X.; Liu, J.; Zhu, L. Deep-learning-based trunk perception with depth estimation and DWA for robust navigation of robotics in orchards. Agronomy 2023, 13, 1084. [Google Scholar] [CrossRef]
  92. Zhu, F.; Chen, J.; Guan, Z.; Zhu, Y.; Shi, H.; Cheng, K. Development of a combined harvester navigation control system based on visual simultaneous localization and mapping-inertial guidance fusion. J. Agric. Eng. 2024, 55, 1583. [Google Scholar] [CrossRef]
  93. Vu, C.T.; Chen, H.C.; Liu, Y.C. Toward Autonomous Navigation for Agriculture Robots in Orchard Farming. In Proceedings of the 2024 IEEE International Conference on Recent Advances in Systems Science and Engineering (RASSE), IEEE, Taichung, Taiwan, 6–8 November 2024; pp. 1–8. [Google Scholar]
  94. Li, Y.; Li, J.; Zhou, W.; Yao, Q.; Nie, J.; Qi, X. Robot path planning navigation for dense planting red jujube orchards based on the joint improved A* and DWA algorithms under laser SLAM. Agriculture 2022, 12, 1445. [Google Scholar] [CrossRef]
  95. He, Q.; Wang, Z.; Li, K.; Zhang, Y.; Li, M. Research on autonomous navigation of mobile robots based on IA-DWA algorithm. Sci. Rep. 2025, 15, 2099. [Google Scholar] [CrossRef]
  96. Wang, Y.; Fu, C.; Huang, R.; Tong, K.; He, Y.; Xu, L. Path planning for mobile robots in greenhouse orchards based on improved A* and fuzzy DWA algorithms. Comput. Electron. Agric. 2024, 227, 109598. [Google Scholar] [CrossRef]
  97. Zhang, W.; Zeng, Y.; Wang, S.; Wang, T.; Li, H.; Fei, K.; Qiu, X.; Jiang, R.; Li, J. Research on the local path planning of an orchard mowing robot based on an elliptic repulsion scope boundary constraint potential field method. Front. Plant Sci. 2023, 14, 1184352. [Google Scholar] [CrossRef]
  98. Tang, Z.; Xu, L.; Wang, Y.; Kang, Z.; Xie, H. Collision-free motion planning of a six-link manipulator used in a citrus picking robot. Appl. Sci. 2021, 11, 11336. [Google Scholar] [CrossRef]
  99. Yang, D.; Dong, L.; Dai, J.K. Collision avoidance trajectory planning for a dual-robot system: Using a modified APF method. Robotica 2024, 42, 846–863. [Google Scholar] [CrossRef]
  100. Das, M.S.; Sanyal, S.; Mandal, S. Navigation of multiple robots in formative manner in an unknown environment using artificial potential field based path planning algorithm. Ain Shams Eng. J. 2022, 13, 101675. [Google Scholar] [CrossRef]
  101. Zhuang, M.; Li, G.; Ding, K. Obstacle avoidance path planning for apple picking robotic arm incorporating artificial potential field and A* algorithm. IEEE Access 2023, 11, 100070–100082. [Google Scholar] [CrossRef]
  102. Wei, Y.; Lee, K.; Lee, K. Autonomous field navigation of mobile robots for data collection and monitoring in agricultural crop fields. In Proceedings of the 2024 21st International Conference on Ubiquitous Robots (UR), New York, NY, USA, 24–27 June 2024; pp. 707–712. [Google Scholar]
  103. Wu, H.; Zhang, Y.; Huang, L.; Zhang, J.; Luan, Z.; Zhao, W.; Chen, F. Research on vehicle obstacle avoidance path planning based on APF-PSO. Proc. Inst. Mech. Eng. Part D J. Automob. Eng. 2023, 237, 1391–1405. [Google Scholar] [CrossRef]
  104. Rösmann, C.; Feiten, W.; Wösch, T.; Hoffmann, F.; Bertram, T. Trajectory modification considering dynamic constraints of autonomous robots. In Proceedings of the ROBOTIK 2012; 7th German Conference on Robotics, VDE, Munich, Germany, 21–22 May 2012; pp. 1–6. [Google Scholar]
  105. Inoue, K.; Kaizu, Y.; Igarashi, S.; Furuhashi, K.; Imou, K. Autonomous navigation and obstacle avoidance in an orchard using machine vision techniques for a robotic mower. Eng. Agric. Environ. Food 2022, 15, 87–99. [Google Scholar] [CrossRef]
  106. Zhang, M.; Pengcheng, L.; Jie, L.; Lei, L.; Huibin, Z.; Lili, Y. Local path planning method based on smooth time elastic band algorithm for orchard robotic lawn mower. INMATEH-Agric. Eng. 2024, 73, 249–262. [Google Scholar] [CrossRef]
  107. Han, W.; Gu, Q.; Gu, H.; Xia, R.; Gao, Y.; Zhou, Z.; Luo, K.; Fang, X.; Zhang, Y. Design of Chili Field Navigation System Based on Multi-Sensor and Optimized TEB Algorithm. Agronomy 2024, 14, 2872. [Google Scholar] [CrossRef]
  108. Li, Z.; Liu, X.; Wang, H.; Song, J.; Xie, F.; Wang, K. Research on robot path planning based on point cloud map in orchard environment. IEEE Access 2024, 12, 54853–54865. [Google Scholar] [CrossRef]
  109. Li, W.; Todorov, E. Iterative linear quadratic regulator design for nonlinear biological movement systems. In Proceedings of the First International Conference on Informatics in Control, Automation and Robotics, Setúbal, Portugal, 25–28 August 2004; Volume 2, pp. 222–229. [Google Scholar]
  110. Pinto, F.A.; Tommaselli, F.A.G.; Gasparino, M.V.; Becker, M. Navigating with finesse: Leveraging neural network-based lidar perception and ilqr control for intelligent agriculture robotics. In Proceedings of the 2023 Latin American Robotics Symposium (LARS), 2023 Brazilian Symposium on Robotics (SBR), and 2023 Workshop on Robotics in Education (WRE), Salvador, Bahia, Brazil, 9–11 October 2023; pp. 502–507. [Google Scholar]
  111. Howell, T.A.; Jackson, B.E.; Manchester, Z. Altro: A fast solver for constrained trajectory optimization. In Proceedings of the 2019 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Hangzhou, China, 19–25 October 2025; pp. 7674–7679. [Google Scholar]
  112. Li, T.; Guo, Y.; Liu, H.; Shen, Y.; Yayun, S. Real-time local trajectory optimization of an orchard robot using improved ALTRO. Trans. Chin. Soc. Agric. Eng. 2025, 41, 1–10. [Google Scholar]
  113. Wu, H.; Wang, X.; Chen, X.; Zhang, Y.; Zhang, Y. Review on Key Technologies for Autonomous Navigation in Field Agricultural Machinery. Agriculture 2025, 15, 1297. [Google Scholar] [CrossRef]
  114. Yang, Y.; Li, Y.; Wen, X.; Zhang, G.; Ma, Q.; Cheng, S.; Qi, J.; Xu, L.; Chen, L. An optimal goal point determination algorithm for automatic navigation of agricultural machinery: Improving the tracking accuracy of the Pure Pursuit algorithm. Comput. Electron. Agric. 2022, 194, 106760. [Google Scholar] [CrossRef]
  115. 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]
  116. Raikwar, S.; Fehrmann, J.; Herlitzius, T. Navigation and control development for a four-wheel-steered mobile orchard robot using model-based design. Comput. Electron. Agric. 2022, 202, 107410. [Google Scholar] [CrossRef]
  117. Song, Y.; Xue, J.; Zhang, T.; Sun, X.; Sun, H.; Gao, W.; Chen, Q. Path tracking control of crawler tractor based on adaptive adjustment of lookahead distance using sparrow search algorithm. Comput. Electron. Agric. 2025, 234, 110219. [Google Scholar] [CrossRef]
  118. Hu, C.; Ru, Y.; Li, X.; Fang, S.; Zhou, H.; Yan, X.; Liu, M.; Xie, R. Path tracking control for brake-steering tracked vehicles based on an improved pure pursuit algorithm. Biosyst. Eng. 2024, 242, 1–15. [Google Scholar] [CrossRef]
  119. Liu, W.; Zhou, J.; Liu, Y.; Zhang, T.; Yan, M.; Chen, J.; Zhou, C.; Hu, J.; Chen, X. An ultrasonic ridge-tracking method based on limiter sliding window filter and fuzzy pure pursuit control for ridge transplanter. Agriculture 2024, 14, 1713. [Google Scholar] [CrossRef]
  120. Huang, P.C.; Luo, X.W.; Zhang, Z.G. Control method of headland turning based on improved pure pursuit model for agricultural machine. Jisuanji Gongcheng yu Yingyong (Comput. Eng. Appl.) 2010, 46, 216–219. [Google Scholar]
  121. Wang, X.; Zhang, B.; Du, X.; Hu, X.; Wu, C.; Cai, J. An Adaptive Path Tracking Controller with Dynamic Look-Ahead Distance Optimization for Crawler Orchard Sprayers. Actuators 2025, 14, 154. [Google Scholar] [CrossRef]
  122. Wen, J.; Yao, L.; Zhou, J.; Yang, Z.; Xu, L.; Yao, L. Path Tracking Control of Agricultural Automatic Navigation Vehicles Based on an Improved Sparrow Search-Pure Pursuit Algorithm. Agriculture 2025, 15, 1215. [Google Scholar] [CrossRef]
  123. Zhou, J.; Wen, J.; Yao, L.; Yang, Z.; Xu, L.; Yao, L. Agricultural machinery path tracking with varying curvatures based on an improved pure-pursuit method. Agriculture 2025, 15, 266. [Google Scholar] [CrossRef]
  124. Wang, X.; Zhang, B.; Du, X.; Chen, H.; Zhu, T.; Wu, C. Self-Adjusting Look-Ahead Distance of Precision Path Tracking for High-Clearance Sprayers in Field Navigation. Agronomy 2025, 15, 1433. [Google Scholar] [CrossRef]
  125. Al-Jumaili, M.H.; Özok, Y.E. New control model for autonomous vehicles using integration of Model Predictive and Stanley based controllers. Sci. Rep. 2024, 14, 19872. [Google Scholar] [CrossRef]
  126. 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] [CrossRef] [PubMed]
  127. Zheng, S.; Xu, S.; Rai, R. Trailer-referenced autonomous navigation of agricultural tractor–trailer systems. Comput. Electron. Agric. 2025, 237, 110514. [Google Scholar] [CrossRef]
  128. Huang, S.; Pan, K.; Wang, S.; Zhu, Y.; Zhang, Q.; Su, X.; Yu, H. Design and test of an automatic navigation fruit-picking platform. Agriculture 2023, 13, 882. [Google Scholar] [CrossRef]
  129. Wang, L.; Zhai, Z.; Zhu, Z.; Mao, E. Path tracking control of an autonomous tractor using improved Stanley controller optimized with multiple-population genetic algorithm. Actuators 2022, 11, 22. [Google Scholar] [CrossRef]
  130. Cui, B.; Cui, X.; Wei, X.; Zhu, Y.; Ma, Z.; Zhao, Y.; Liu, Y. Design and Testing of a Tractor Automatic Navigation System Based on Dynamic Path Search and a Fuzzy Stanley Model. Agriculture 2024, 14, 2136. [Google Scholar] [CrossRef]
  131. Sun, Y.; Cui, B.; Ji, F.; Wei, X.; Zhu, Y. The full-field path tracking of agricultural machinery based on PSO-enhanced fuzzy stanley model. Appl. Sci. 2022, 12, 7683. [Google Scholar] [CrossRef]
  132. Jiang, A.; Ahamed, T. Navigation of an autonomous spraying robot for orchard operations using LiDAR for tree trunk detection. Sensors 2023, 23, 4808. [Google Scholar] [CrossRef] [PubMed]
  133. Shih, C.H.; Lin, C.J.; Jhang, J.Y. Ackerman unmanned mobile vehicle based on heterogeneous sensor in navigation control application. Sensors 2023, 23, 4558. [Google Scholar] [CrossRef]
  134. Lu, E.; Ma, Z.; Li, Y.; Xu, L.; Tang, Z. Adaptive backstepping control of tracked robot running trajectory based on real-time slip parameter estimation. Int. J. Agric. Biol. Eng. 2020, 13, 178–187. [Google Scholar] [CrossRef]
  135. Farkh, R.; Aljaloud, K. Vision navigation based PID control for line tracking robot. Intell. Autom. Soft Comput. 2023, 35, 901–911. [Google Scholar] [CrossRef]
  136. Li, X.; Liu, X.; Wang, G.; Gu, K.; Che, H. Discrete open-closed-loop PID-type iterative learning control for trajectory tracking of tracked mobile robots. Int. J. Adv. Robot. Syst. 2022, 19, 17298806221137247. [Google Scholar] [CrossRef]
  137. Li, Y.; Feng, Q.; Ji, C.; Sun, J.; Sun, Y. GNSS and LiDAR Integrated Navigation Method in Orchards with Intermittent GNSS Dropout. Appl. Sci. 2024, 14, 3231. [Google Scholar] [CrossRef]
  138. Li, C.; Wu, J.; Pan, X.; Dou, H.; Zhao, X.; Gao, Y.; Yang, S.; Zhai, C. Design and experiment of a breakpoint continuous spraying system for automatic-guidance boom sprayers. Agriculture 2023, 13, 2203. [Google Scholar] [CrossRef]
  139. Yuexia, C.; Long, C.; Ruochen, W.; Xing, X.; Yujie, S.; Yanling, L. Modeling and test on height adjustment system of electrically-controlled air suspension for agricultural vehicles. Int. J. Agric. Biol. Eng. 2016, 9, 40–47. [Google Scholar]
  140. Zou, T.; Angeles, J.; Hassani, F. Dynamic modeling and trajectory tracking control of unmanned tracked vehicles. Robot. Auton. Syst. 2018, 110, 102–111. [Google Scholar] [CrossRef]
  141. Peicheng, S.; Li, L.; Ni, X.; Yang, A. Intelligent vehicle path tracking control based on improved MPC and hybrid PID. IEEE Access 2022, 10, 94133–94144. [Google Scholar] [CrossRef]
  142. Zhu, Y.; Cui, B.; Yu, Z.; Gao, Y.; Wei, X. Tillage Depth Detection and Control Based on Attitude Estimation and Online Calibration of Model Parameters. Agriculture 2024, 14, 2130. [Google Scholar] [CrossRef]
  143. Wan, C.; Yang, J.; Zhou, L.; Wang, S.; Peng, J.; Tan, Y. Fertilization control system research in orchard based on the PSO-BP-PID control algorithm. Machines 2022, 10, 982. [Google Scholar] [CrossRef]
  144. Li, J.; Wang, S.; Zhang, W.; Li, H.; Zeng, Y.; Wang, T.; Fei, K.; Qiu, X.; Jiang, R.; Mai, C.; et al. Research on Path Tracking for an Orchard Mowing Robot Based on Cascaded Model Predictive Control and Anti-Slip Drive Control. Agronomy 2023, 13, 1395. [Google Scholar] [CrossRef]
  145. Zhang, S.; Wei, X.; Liu, C.; Ge, J.; Cui, X.; Wang, F.; Wang, A.; Chen, W. Adaptive path tracking and control system for unmanned crawler harvesters in paddy fields. Comput. Electron. Agric. 2025, 230, 109878. [Google Scholar] [CrossRef]
  146. Stano, P.; Montanaro, U.; Tavernini, D.; Tufo, M.; Fiengo, G.; Novella, L.; Sorniotti, A. Model predictive path tracking control for automated road vehicles: A review. Annu. Rev. Control. 2023, 55, 194–236. [Google Scholar] [CrossRef]
  147. Wang, S.; Guo, J.; Mao, Y.; Wang, H.; Fan, J. Research on the model predictive trajectory tracking control of unmanned ground tracked vehicles. Drones 2023, 7, 496. [Google Scholar] [CrossRef]
  148. Liu, H.; Yan, S.; Shen, Y.; Li, C.; Zhang, Y.; Hussain, F. Model predictive control system based on direct yaw moment control for 4WID self-steering agriculture vehicle. Int. J. Agric. Biol. Eng. 2021, 14, 175–181. [Google Scholar] [CrossRef]
  149. Hu, K.; Cheng, K. Trajectory planning for an articulated tracked vehicle and tracking the trajectory via an adaptive model predictive control. Electronics 2023, 12, 1988. [Google Scholar] [CrossRef]
  150. Villemazet, A.; Durand-Petiteville, A.; Cadenat, V. Autonomous navigation strategy for orchards relying on sensor-based nonlinear model predictive control. In Proceedings of the 2022 IEEE/ASME International Conference on Advanced Intelligent Mechatronics (AIM), Sapporo, Hokkaido, Japan, 11–15 July 2022; pp. 744–749. [Google Scholar]
  151. Liu, G.; Li, C.; Shen, Y. Trajectory tracking and fuzzy adaptive model predictive control of high clearance synchronous-steering sprayer. Trans. Chin. Soc. Agric. Mach. 2021, 52, 389–399. [Google Scholar]
  152. Sperti, M.; Ambrosio, M.; Martini, M.; Navone, A.; Ostuni, A.; Chiaberge, M. Non-linear Model Predictive Control for Multi-task GPS-free Autonomous Navigation in Vineyards. In Proceedings of the 2024 IEEE 20th International Conference on Automation Science and Engineering (CASE), Bari, Italy, 28 August–1 September 2024; pp. 96–101. [Google Scholar]
  153. Zhou, B.; Su, X.; Yu, H.; Guo, W.; Zhang, Q. Research on path tracking of articulated steering tractor based on modified model predictive control. Agriculture 2023, 13, 871. [Google Scholar] [CrossRef]
  154. Xu, J.; Lai, J.; Guo, R.; Lu, X.; Xu, L. Efficiency-oriented MPC algorithm for path tracking in autonomous agricultural machinery. Agronomy 2022, 12, 1662. [Google Scholar] [CrossRef]
  155. Wang, P.; Gao, S.; Li, L.; Cheng, S.; Zhao, L. Automatic steering control strategy for unmanned vehicles based on robust backstepping sliding mode control theory. IEEE Access 2019, 7, 64984–64992. [Google Scholar] [CrossRef]
  156. Sekban, H.T.; Basci, A. Designing new model-based adaptive sliding mode controllers for trajectory tracking control of an unmanned ground vehicle. IEEE Access 2023, 11, 101387–101397. [Google Scholar] [CrossRef]
  157. Lu, E.; Xue, J.; Chen, T.; Jiang, S. Robust trajectory tracking control of an autonomous tractor-trailer considering model parameter uncertainties and disturbances. Agriculture 2023, 13, 869. [Google Scholar] [CrossRef]
  158. Ma, B.; Pei, W.; Zhang, Q. Trajectory tracking control of autonomous vehicles based on an improved sliding mode control scheme. Electronics 2023, 12, 2748. [Google Scholar] [CrossRef]
  159. Sun, J.; Wang, Z.; Ding, S.; Xia, J.; Xing, G. Adaptive disturbance observer-based fixed time nonsingular terminal sliding mode control for path-tracking of unmanned agricultural tractors. Biosyst. Eng. 2024, 246, 96–109. [Google Scholar] [CrossRef]
  160. Yan, X.; Wang, S.; He, Y.; Ma, A.; Zhao, S. Autonomous Tracked Vehicle Trajectory Tracking Control Based on Disturbance Observation and Sliding Mode Control. Actuators 2025, 14, 51. [Google Scholar] [CrossRef]
  161. Liu, L.; Wang, X.; Xie, J.; Wang, X.; Liu, H.; Li, J.; Wang, P.; Yang, X. Path planning and tracking control of orchard wheel mower based on BL-ACO and GO-SMC. Comput. Electron. Agric. 2025, 228, 109696. [Google Scholar] [CrossRef]
  162. Ding, C.; Ding, S.; Wei, X.; Mei, K. Output feedback sliding mode control for path-tracking of autonomous agricultural vehicles. Nonlinear Dyn. 2022, 110, 2429–2445. [Google Scholar] [CrossRef]
  163. Mancini, M.; Trombetta, E.I.; Carminati, D.; Capello, E. Adaptive sliding mode control with artificial potential field for ground robots in precision agriculture. In Proceedings of the 2023 IEEE International Workshop on Metrology for Agriculture and Forestry (MetroAgriFor), Pisa, Italy, 6–8 November 2023; pp. 325–330. [Google Scholar]
  164. Ji, X.; Wang, A.; Wei, X. Precision control of spraying quantity based on linear active disturbance rejection control method. Agriculture 2021, 11, 761. [Google Scholar] [CrossRef]
  165. Ma, J.; Xie, H.; Song, K.; Liu, H. Self-optimizing path tracking controller for intelligent vehicles based on reinforcement learning. Symmetry 2021, 14, 31. [Google Scholar] [CrossRef]
  166. BAI, Q. Deep reinforcement learning-driven decision support system design for precision agriculture: Optimizing farming and resource use. Turk. J. Agric. For. 2025, 49, 598–611. [Google Scholar] [CrossRef]
  167. Guo, Z.; Fu, H.; Wu, J.; Han, W.; Huang, W.; Zheng, W.; Li, T. Dynamic Task Planning for Multi-Arm Apple-Harvesting Robots Using LSTM-PPO Reinforcement Learning Algorithm. Agriculture 2025, 15, 588. [Google Scholar] [CrossRef]
  168. Wang, Y.; He, Z.; Cao, D.; Ma, L.; Li, K.; Jia, L.; Cui, Y. Coverage path planning for kiwifruit picking robots based on deep reinforcement learning. Comput. Electron. Agric. 2023, 205, 107593. [Google Scholar] [CrossRef]
  169. Zhao, J.; Fan, S.; Zhang, B.; Wang, A.; Zhang, L.; Zhu, Q. Research Status and Development Trends of Deep Reinforcement Learning in the Intelligent Transformation of Agricultural Machinery. Agriculture 2025, 15, 1223. [Google Scholar] [CrossRef]
  170. Zhu, H. Reinforcement learning-based state space dimensionality reduction and optimal control strategy design in robot navigation systems. J. Combin. Math. Combin. Comput. 2025, 127, 9239–9261. [Google Scholar]
  171. Vashisth, A.; Rückin, J.; Magistri, F.; Stachniss, C.; Popović, M. Deep reinforcement learning with dynamic graphs for adaptive informative path planning. IEEE Robot. Autom. Lett. 2024, 9, 7747–7754. [Google Scholar] [CrossRef]
  172. Navone, A.; Martini, M.; Ambrosio, M.; Ostuni, A.; Angarano, S.; Chiaberge, M. GPS-free autonomous navigation in cluttered tree rows with deep semantic segmentation. Robot. Auton. Syst. 2025, 183, 104854. [Google Scholar] [CrossRef]
  173. Martini, M.; Cerrato, S.; Salvetti, F.; Angarano, S.; Chiaberge, M. Position-agnostic autonomous navigation in vineyards with deep reinforcement learning. In Proceedings of the 2022 IEEE 18th International Conference on Automation Science and Engineering (CASE), Mexico City, Mexico, 22–26 August 2022; pp. 477–484. [Google Scholar]
  174. Zhang, L.; Zhang, R.; Zhang, D.; Yi, T.; Ding, C.; Chen, L. Path curvature incorporated reinforcement learning method for accurate path tracking of agricultural vehicles. Comput. Electron. Agric. 2025, 234, 110243. [Google Scholar] [CrossRef]
  175. Fukada, K.; Hara, K.; Cai, J.; Teruya, D.; Shimizu, I.; Kuriyama, T.; Koga, K.; Sakamoto, K.; Nakamura, Y.; Nakajo, H. An automatic tomato growth analysis system using YOLO transfer learning. Appl. Sci. 2023, 13, 6880. [Google Scholar] [CrossRef]
  176. Attri, I.; Awasthi, L.K.; Sharma, T.P.; Rathee, P. A review of deep learning techniques used in agriculture. Ecol. Inform. 2023, 77, 102217. [Google Scholar] [CrossRef]
  177. Hossen, M.I.; Awrangjeb, M.; Pan, S.; Mamun, A.A. Transfer learning in agriculture: A review. Artif. Intell. Rev. 2025, 58, 97. [Google Scholar] [CrossRef]
  178. Bai, Y.; Guo, Y.; Zhang, Q.; Cao, B.; Zhang, B. Multi-network fusion algorithm with transfer learning for green cucumber segmentation and recognition under complex natural environment. Comput. Electron. Agric. 2022, 194, 106789. [Google Scholar] [CrossRef]
  179. Devanna, R.P.; Milella, A.; Marani, R.; Garofalo, S.P.; Vivaldi, G.A.; Pascuzzi, S.; Galati, R.; Reina, G. In-field automatic identification of pomegranates using a farmer robot. Sensors 2022, 22, 5821. [Google Scholar] [CrossRef]
  180. Xue, X.; Luo, Q.; Bu, M.; Li, Z.; Lyu, S.; Song, S. Citrus tree canopy segmentation of orchard spraying robot based on RGB-D image and the improved DeepLabv3+. Agronomy 2023, 13, 2059. [Google Scholar] [CrossRef]
  181. Cao, B.; Zhang, B.; Zheng, W.; Zhou, J.; Lin, Y.; Chen, Y. Real-time, highly accurate robotic grasp detection utilizing transfer learning for robots manipulating fragile fruits with widely variable sizes and shapes. Comput. Electron. Agric. 2022, 200, 107254. [Google Scholar] [CrossRef]
  182. Li, Z.; Chen, W.H.; Yang, J.; Yan, Y. Dual control of exploration and exploitation for auto-optimization control with active learning. IEEE Trans. Autom. Sci. Eng. 2024, 22, 2145–2158. [Google Scholar] [CrossRef]
  183. Li, Z.; Chen, W.H.; Yang, J.; Liu, C. Cooperative active learning-based dual control for exploration and exploitation in autonomous search. IEEE Trans. Neural Netw. Learn. Syst. 2024, 36, 2221–2233. [Google Scholar] [CrossRef] [PubMed]
  184. Chen, W.H. Perspective view of autonomous control in unknown environment: Dual control for exploitation and exploration vs reinforcement learning. Neurocomputing 2022, 497, 50–63. [Google Scholar] [CrossRef]
  185. Chen, W.H.; Rhodes, C.; Liu, C. Dual control for exploitation and exploration (DCEE) in autonomous search. Automatica 2021, 133, 109851. [Google Scholar] [CrossRef]
Figure 1. Path planning and tracking control technology for OMR of different function types.
Figure 1. Path planning and tracking control technology for OMR of different function types.
Agriculture 15 01917 g001
Figure 2. OMR of different function types [29,30,31,32].
Figure 2. OMR of different function types [29,30,31,32].
Agriculture 15 01917 g002
Figure 3. Common orchard scenes with different complexities.
Figure 3. Common orchard scenes with different complexities.
Agriculture 15 01917 g003
Figure 4. Framework of path planning and tracking control methods for OMR in complex scenarios.
Figure 4. Framework of path planning and tracking control methods for OMR in complex scenarios.
Agriculture 15 01917 g004
Figure 5. Comparison of the effects of the improved A* path planning algorithm based on multi-constraint Bessel curves [55].
Figure 5. Comparison of the effects of the improved A* path planning algorithm based on multi-constraint Bessel curves [55].
Agriculture 15 01917 g005
Figure 6. Path planning process based on PRM [64].
Figure 6. Path planning process based on PRM [64].
Agriculture 15 01917 g006
Figure 7. Principle of RRT algorithm [67].
Figure 7. Principle of RRT algorithm [67].
Agriculture 15 01917 g007
Figure 8. RRT-Connect algorithm with target bias strategy [68].
Figure 8. RRT-Connect algorithm with target bias strategy [68].
Agriculture 15 01917 g008
Figure 9. Principle of RRT* algorithm [67].
Figure 9. Principle of RRT* algorithm [67].
Agriculture 15 01917 g009
Figure 10. Orchard inspection robot based on fuzzy DWA local path planning [96].
Figure 10. Orchard inspection robot based on fuzzy DWA local path planning [96].
Agriculture 15 01917 g010
Figure 11. Principle of APF and path planning effect.
Figure 11. Principle of APF and path planning effect.
Agriculture 15 01917 g011
Figure 12. Path planning of orchard robot using TEB [108].
Figure 12. Path planning of orchard robot using TEB [108].
Agriculture 15 01917 g012
Figure 13. Path optimization for orchard multi-obstacle scenario using improved ALTRO [112].
Figure 13. Path optimization for orchard multi-obstacle scenario using improved ALTRO [112].
Agriculture 15 01917 g013
Figure 14. Principle of pure pursuit control algorithm.
Figure 14. Principle of pure pursuit control algorithm.
Agriculture 15 01917 g014
Figure 15. Principle of Stanley control algorithm.
Figure 15. Principle of Stanley control algorithm.
Agriculture 15 01917 g015
Figure 16. Simplified Ackermann OMR kinematic model.
Figure 16. Simplified Ackermann OMR kinematic model.
Agriculture 15 01917 g016
Figure 17. Kinematic model of track differential OMR.
Figure 17. Kinematic model of track differential OMR.
Agriculture 15 01917 g017
Figure 18. Principle of PID control algorithm.
Figure 18. Principle of PID control algorithm.
Agriculture 15 01917 g018
Figure 19. Principle of MPC algorithm.
Figure 19. Principle of MPC algorithm.
Agriculture 15 01917 g019
Figure 20. Principle of RL control strategy.
Figure 20. Principle of RL control strategy.
Agriculture 15 01917 g020
Figure 21. Framework of OMR autonomous navigation system based on environmental exploration and exploitation [184].
Figure 21. Framework of OMR autonomous navigation system based on environmental exploration and exploitation [184].
Agriculture 15 01917 g021
Table 1. Comparison of OMR path planning methods in complex scenarios.
Table 1. Comparison of OMR path planning methods in complex scenarios.
TypeMethodsAdvantagesDisadvantagesReferences
Global path PlanningDijkstraGlobal optimal solution, Simple algorithmHigh computational complexity and low efficiency[46,47,48,49]
A*Shortest path, completenessLarge computational load, complex implementation[50,51,52,53,54,55,56,57,58,59]
PRMHigh dimensionality for handling complex spacesStatic-only; non-optimal; time-consuming[60,61,62,63,64]
RRTSimple structure, strong applicabilityNon-optimal paths, slow convergence[66,67,68,69,70,72,73,74,75,76]
GASuitable for nonlinear systems with strong parallelismComplex parameter tuning, slow convergence[77,78,79,80]
ACOSuitable for discrete path optimizationProne to local optimality, slow initial convergence[81,82,83,84]
PSOSimple implementation, fast convergencePremature convergence in high-dimensional problems[85,86,87,88]
Local path PlanningDWAStrong real-time performance, consider constraintsShort-sightedness, sensitive to parameters[90,91,92,93,94,95,96]
APFLow complexity, small computational loadProne to local minima, unstable dynamic spaces[97,98,99,100,101,102,103]
TEBAdaptability to dynamic environmentsSensitive to initialization[105,106,107,108]
iLQRIterative approximation of optimal solutionModel dependence and large computational load[110,111,112]
Table 2. Comparison of OMR tracking control methods in complex scenarios.
Table 2. Comparison of OMR tracking control methods in complex scenarios.
MethodsAdvantagesDisadvantagesReferences
Pure PursuitSimple and intuitive with few parametersSensitive to path curvature, without considering constraints[117,118,119,120,121,122,123,124]
StanleyAdjustable parameters, heading deviation consideredIncapable of handling complex constraints[127,128,129,130,131]
PIDSimple to implement, low computational loadRelies on parameter tuning, cannot handle nonlinear systems[78,138,139,140,141,142,143,144]
MPCMulti-objective optimization, predicts future statesDepends on accurate models, high computational complexity[147,148,149,150,151,152,153,154]
SMCStrong robustness, fast convergenceChattering issues, complex parameter tuning[155,156,157,158,159,160,161,162,163]
RLModel-free learning, adapts to high-dimensional spacesHigh training cost, limited real-time performance[168,169,170,171,172,173,174]
TLHigh data utilization efficiency and learning rateRisk of negative migration, high computational overhead[175,176,177,178,179,180,181]
DCEEStrong adaptability, multi-objective optimizationDepends on environment information[182,183,184,185]
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

Shen, Y.; Shen, Y.; Zhang, Y.; Huo, C.; Shen, Z.; Su, W.; Liu, H. Research Progress on Path Planning and Tracking Control Methods for Orchard Mobile Robots in Complex Scenarios. Agriculture 2025, 15, 1917. https://doi.org/10.3390/agriculture15181917

AMA Style

Shen Y, Shen Y, Zhang Y, Huo C, Shen Z, Su W, Liu H. Research Progress on Path Planning and Tracking Control Methods for Orchard Mobile Robots in Complex Scenarios. Agriculture. 2025; 15(18):1917. https://doi.org/10.3390/agriculture15181917

Chicago/Turabian Style

Shen, Yayun, Yue Shen, Yafei Zhang, Chenwei Huo, Zhuofan Shen, Wei Su, and Hui Liu. 2025. "Research Progress on Path Planning and Tracking Control Methods for Orchard Mobile Robots in Complex Scenarios" Agriculture 15, no. 18: 1917. https://doi.org/10.3390/agriculture15181917

APA Style

Shen, Y., Shen, Y., Zhang, Y., Huo, C., Shen, Z., Su, W., & Liu, H. (2025). Research Progress on Path Planning and Tracking Control Methods for Orchard Mobile Robots in Complex Scenarios. Agriculture, 15(18), 1917. https://doi.org/10.3390/agriculture15181917

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