Next Article in Journal
Demonstrating a Scenario-Based Safety Assurance Framework in Practice
Previous Article in Journal
Revealing the Impact Factors of the Electric Bike Riders’ Violation Riding Behaviors in China: Integrating SEM with RP-Logit Model
Previous Article in Special Issue
Game-Theoretic Cooperative Task Allocation for Multiple-Mobile-Robot Systems
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Research on Path Planning and Control of Intelligent Spray Carts for Greenhouse Sprayers

1
School of Intelligent Manufacturing, Chengdu Technological University, Chengdu 611730, China
2
School of Engineering Training and Innovation Practice Center, Chengdu Technological University, Chengdu 611730, China
*
Author to whom correspondence should be addressed.
Vehicles 2025, 7(4), 123; https://doi.org/10.3390/vehicles7040123
Submission received: 21 August 2025 / Revised: 5 October 2025 / Accepted: 18 October 2025 / Published: 28 October 2025
(This article belongs to the Special Issue Intelligent Connected Vehicles)

Abstract

To address the challenges of inefficient path planning, discontinuous trajectories, and inadequate safety margins in autonomous spraying vehicles for greenhouse environments, this paper proposes a hierarchical motion control architecture. At the global path planning level, the heuristic function of the A* algorithm was redesigned to integrate channel width constraints, thereby optimizing node expansion efficiency. A continuous reference path is subsequently generated using a third-order Bézier curve. For local path planning, a state-space sampling method was adopted, incorporating a multi-objective cost function that accounts for collision distance, curvature change rate, and path deviation, enabling the real-time computation of optimal obstacle-avoidance trajectories. At the control level, an adaptive look-ahead distance pure pursuit algorithm was designed for trajectory tracking. The proposed framework was validated through a Simulink-ROS co-simulation environment and deployed on a Huawei MDC300F computing platform for real-world vehicle tests under various operating conditions. Experimental results demonstrated that compared with the baseline methods, the proposed approach improved the planning efficiency by 38.7%, reduced node expansion by 16.93%, shortened the average path length by 6.3%, and decreased the path curvature variation by 65.3%. The algorithm effectively supports dynamic obstacle avoidance, multi-vehicle coordination, and following behaviors in diverse scenarios, offering a robust solution for automation in facility agriculture.

1. Introduction

Agricultural spraying robots serve as a key enabler of agricultural digitization and intelligence, playing an irreplaceable role in modern precision agriculture systems [1]. They effectively alleviate manual labor intensity while enhancing operational efficiency and quality. Path planning for mobile spraying platforms in greenhouse environments must meet three core performance criteria: comprehensive coverage, dual optimization of time and energy efficiency, and dynamic safety margins (in compliance with ISO 18497:2018 safety standards) [2]. Its technical implementation framework includes constructing an environmental topology map through multi-sensor fusion, calculating the target work domain based on task requirements, and solving the optimal path using a constraint optimization model. The path planning algorithm must have real-time re-planning capabilities to respond to mobile obstacle disturbances. Especially in complex greenhouse planting scenarios, path planning specifically refers to generating safe operational paths under continuous trajectory constraints [3]. Based on differences in decision-making scales, it can be divided into global path planning and local path planning [4].
Current path planning research primarily encompasses four categories of methods: search-based planning methods, artificial potential field methods, random sampling-based planning methods, and discrete optimization-based planning methods [5,6]. Common graph search algorithms include Dijkstra, A*, and D*, with the A* algorithm being considered the most comprehensive graph search algorithm [7]. Sun Xiaojie et al. [8], based on the A* algorithm, introduced two-sided obstacle tendency factors and added a path evaluation function term, thereby improving the search efficiency. Ma Quankun et al. [9] fused the A* algorithm with memory-based simulated annealing, reducing the search path by 9.4%. Zhao Hui et al. [10] combined the A* algorithm with the beetle antenna search algorithm, shortening the path length and reducing the number of turning points. The artificial potential field method [11] was first proposed by Khatib in 1986. This algorithm is simple to calculate and produces smooth paths, but is prone to getting stuck in local optima. Planning methods based on random sampling include the probabilistic road map (PRM) and the rapidly exploring random tree (RRT) [12]. Chen Zhi-yong et al. [13] proposed an improved PRM method that combined global goal-oriented sampling and local node enhancement, improving the path planning success rates and reducing path nodes. Planning methods based on discrete optimization [14] improve sampling efficiency and reduce computational complexity through the sequential sampling of structured roads. Song Chunlei et al. [15] optimized dynamic programming results using quadratic programming, reducing planning time and decreasing the path curvature changes by 77.13%.
Horizontal control mainstream methods include PID (proportional-integral-derivative) control, predictive control, fuzzy control, pure pursuit control, sliding mode control, and optimal control, among others [16]. Wang Hongwei et al. [17] proposed using a particle swarm optimization (PSO) algorithm to optimize the PID algorithm, enhancing the robot’s adaptability to navigate complex environments such as tunnel intersections. Wei Lingtao et al. [18] adaptively determined the anticipatory distance based on vehicle dynamics and road surface adhesion characteristics, and used the PSO algorithm to optimize the parameters of the anticipatory distance adaptive model. Xiao Shide et al. [19] proposed a two-stage pure pursuit algorithm considering lateral deviation and lateral angle, and set a transition zone lag switching strategy, improving the tracking accuracy by 30.9%.
To address the safety and smoothness requirements of greenhouse spraying platforms in complex environments, this paper introduced a hierarchical path planning and control architecture. At the global path planning layer, the A* heuristic function was reconstructed, and road width constraints were integrated to improve the node selection mechanism and enhance search efficiency. Second-order derivatives combined with third-order Bessel curves were added to eliminate path curvature changes and redundant turning points. At the local path planning layer, candidate trajectory sets were generated based on state space sampling, and the optimal path was selected using a multi-objective evaluation function to input into the control layer. The execution layer used a pure pursuit algorithm to achieve trajectory tracking, and the algorithm’s effectiveness was verified through the Simulink-ROS joint simulation framework. Finally, multi-modal scenario real-vehicle testing was completed on the Huawei MDC300F computing platform to verify the system’s robustness in dynamic obstacle avoidance and collaborative operation scenarios.

2. Global Path Planning

Using the A* algorithm as the base algorithm, the heuristic function was re-engineered, the search point selection method was modified to enhance search efficiency, a road width factor was added to improve driving safety, and a third-order Bessel curve was employed to smooth the global path. Through a simulation experiment data comparison, it was concluded that the improved A* algorithm, when performing path planning, compared with the traditional A* algorithm, reduced the average path length by 6.3%, the path angle was reduced by 65.3%, and the number of dangerous collisions was reduced by 100%. The new global path planning algorithm improves vehicle safety, smoothness, and operational efficiency.

2.1. Traditional A* Algorithm

The A* algorithm has become the most widely used heuristic search algorithm for solving optimal paths in static road networks due to its speed, efficiency, and accuracy. The evaluation function is:
f ( k ) = g ( k ) + h ( k )
In Equation (1), f(k) is the predicted total cost from the starting point through node k to the destination point, g(k) is the actual cost from the starting point to node k, and h(k) is the best estimate of the cost from the current node k to the destination point.

2.2. A* Algorithm Optimization

For the application scenario of intelligent spray carts in greenhouses described in this article, due to the operational characteristics of the traditional A* algorithm, there were issues such as low optimization efficiency, a large number of inflection points passing through obstacle corners, uneven paths, and paths that were too close to the edge of the road. Therefore, the following optimizations were made to the A* algorithm:
(1)
Improve Search Efficiency
In the traditional A* algorithm, the search is conducted in eight directions centered on the current node [10], which increases the number of searches for the same node and reduces the search efficiency. As shown in Figure 1, for greenhouse applications, the number of search directions per node was reduced from 8 to 5 to improve the search efficiency, with the discarded rules listed in Table 1. Additionally, considering that the sides of the greenhouse intelligent vehicle’s travel path are both crops, the generated optimal path should be in the center line area of the road to avoid damaging crops, thereby enhancing safety and reliability.
f ( k ) = g ( k ) + D 1 + β d + 1 h ( k )
In Equation (2), D is the distance from the current node k to the destination, β is the weight coefficient, and d is the road width.
(2)
Eliminate Unnecessary Inflection Points
Considering the actual application of intelligent spraying carts in greenhouse nurseries, to avoid damage to crops when the cart turns, the static path is straightened to eliminate unnecessary turning points. As shown in Figure 2, first, the second derivative is used to detect turning points, and then, starting from the starting point, each turning point is connected. If there are obstacles on the connecting line, the original path is retained; otherwise, the original path is deleted and the connecting line is retained until the endpoint is reached. A comparison before and after optimization is shown in Figure 3, with blue representing the starting point and red the endpoint.
(3)
Path Smoothing
The planning path uses third-order Bézier curves for adaptive piecewise smoothing fitting. As shown in Figure 4, the curve is uniquely determined by control points P0, P1, P2, and P3.
Analyze its relevant characteristics:
(1)
Parametric expression of a third-order Bézier curve:
q ( τ i ) = ( 1 τ i ) 3 P 0 + 3 τ i ( 1 τ i ) 2 P 1 + 3 τ i 2 ( 1 τ i ) P 2 + τ i 3 P 3
In Equation (3), q(τi) is the interpolation point at parameter τi.
(2)
The curve passes through the first and fourth control points:
q ( 0 ) = P 0 q ( 1 ) = P 3 = 3 ( P 1 P 0 )
(3)
The tangential vectors of the first and fourth control points are:
q ( 0 ) = 3 ( P 1 P 0 ) q ( 1 ) = 3 ( P 3 P 2 )
(4)
The curvature of a curve at any point is:
k ( τ i ) = x ( τ i ) y ( τ i ) y ( τ i ) x ( τ i ) ( x 2 ( τ i ) + y 2 ( τ i ) ) 3 / 2
(5)
The curvature of the curve at the initial endpoint is:
k ( 0 ) = 3 4 × ( P 1 P 0 ) × ( P 2 P 1 ) P 1 P 0 3
(6)
Curves have the property of being invariant under affine transformations.
As illustrated in Figure 5, the green point denotes the starting location, while the red point represents the target location. The traditional A* algorithm generated 31 path expansion nodes, taking 0.176 s. The improved A* algorithm generated only 23 path expansion nodes, taking 0.109 s. The enhanced A* algorithm incorporates a heuristic function with dynamic weighting, reducing the computational time for subsequent operations. Combined with the elimination of redundant turning points, this further shortens the path length while decreasing the computational overhead of path smoothing. Consequently, the planned paths exhibit greater smoothness and shorter overall length, with reduced collision probability at corners. This better aligns with the path requirements for intelligent spraying vehicles operating within greenhouse structures. Relevant data are presented in Table 2.

3. Local Path Planning

This paper established a vehicle kinematic model based on the driving characteristics of intelligent vehicles. A state space sampling method was used to generate paths that complied with the kinematic constraints, and a multi-objective evaluation function was designed to obtain the optimal candidate path.

3.1. Vehicle Kinematic Model

This paper established a kinematic model based on Ackerman steering geometry theory [20], as shown in Figure 6.
In the inertial coordinate system XOY, the position coordinates of the front axle center of the vehicle are (Xf, Yf), the position coordinates of the rear axle center of the vehicle are (Xr, Yr), φ is the heading angle of the vehicle, point C is the instantaneous center of rotation, δf is the steering angle of the front axle center point, Lw is the wheelbase of the vehicle, vr is the speed of the rear axle center of the vehicle, and Rw is the turning radius of the rear axle of the vehicle.
The vehicle speed and vehicle heading angle were used as state variables K = [Xr, Yr, δ]T, and the yaw rate and vehicle speed were used as control variables f = [vr, w]T. The vehicle’s kinematic model is expressed as:
X ˙ r Y ˙ r φ ˙ = cos φ sin φ 0 v r + 0 0 1 w

3.2. Local Path Generation

To meet dynamic local obstacle avoidance requirements while adhering to the global reference path, this paper proposes a sampling-driven local path planning algorithm. Its core principle involves using discrete lane center line path points as a basis to generate multiple state sampling points in both lateral and longitudinal directions. To ensure that the generated trajectories possessed active obstacle avoidance characteristics, the algorithm sequentially connected and fit the initial states of each sampling point with their corresponding desired terminal states, constructing multiple alternative driving trajectories. Finally, the cost of each trajectory was calculated based on a predefined comprehensive evaluation function, and the trajectory with the lowest cost was selected as the optimal solution and input into the vehicle controller.

3.2.1. State Space Sampling

Sampling the target state of the vehicle at the next moment in the state space not only significantly reduces the probability of generating invalid paths, but also ensures the completeness of the coverage of the vehicle’s end pose in space. Use state Z to describe the vehicle’s kinematic model:
Z = x , y , φ , k
In Equation (9), x, y represents the horizontal and vertical coordinates of the vehicle’s position, φ represents the angle between the vehicle’s forward direction and the horizontal direction, and k represents the curvature of the vehicle’s trajectory.
The sampling process in this study (algorithm flow shown in Algorithm 1) was based on the planned global reference path and real-time driving environment information [21,22]. The input variables were the vehicle’s current pose information and environmental parameters, while the output variables were the vehicle’s end-state. The sampling mechanism was as follows: first, a center point was located on the reference path using a sampling distance of dhorizon; second, the lateral offset of this center point was calculated; third, a sampling set of vehicle end-states was generated based on this offset; and finally, the path curvature was calculated for each sampled end-state.
Algorithm 1. Sampling.
1: for i = 0 n v l 1 do
2:   for j = 0 n l 1 do
3:    X c e n t e r C o m p u t e S t a t e s ( S s a f e , X c , d h o r i z o n )
4:    n i n l + j
5:    δ 0.5 ( L w i d t h V w i d t h ) + ( L w i d t h V w i d t h ) i / ( n v l 1 )
6:    φ S , n φ c e n t e r
7:    x S , n x c e n t e r δ sin ( φ S , n )
8:    y S , n y c e n t e r + δ cos ( φ S , n )
9:    k S , n ( k c e n t e r 1 d o f f ) 1
10:  X S , n = [ x S , n , y S , n , φ S , n , k S , n ]
11: end for
12: end for
In Algorithm 1: P e —environmental parameters;
X c —current vehicle status;
X u —vehicle sampling terminal status;
X c e n t e r —coordinates of the reference path;
φ c e n t e r —angle between the reference path and the horizontal direction;
k c e n t e r —curvature of the reference path;
L w i d e h —lane width;
V w i d e h —vehicle width;
n l —sampling lateral offset number;
n v l —number of lanes;
d h o r i z o n —sampling distance, related to the current vehicle speed.
This paper selected vehicle curvature k as the control input variable of the system and arc length s as the state parameter of the trajectory. Based on this, the initial state was defined as (x(s0), y(s0), j (s0)), and the terminal state was defined as (x(sf), y(sf), j (sf)). Subsequently, combining the given curvature k and the vehicle kinematic differential equations, the analytical expression of the trajectory can be derived through integration, as shown in Formula (10):
X ˙ = v s cos ( φ ) Y ˙ = v s sin ( φ ) φ ˙ = k v
Considering the vertical height of the spraying equipment, the continuity of curvature along the arc length should be ensured to make the turning path smoother and reduce vehicle roll. As shown in Equation (11):
k ( s ) = a + b s + c s 2 + d s 3
In Equation (11), parameter a = k(0) is denoted as p = (b, c, d, sf). Equations (10) and (11) are combined to obtain Equation (12).
x ( s f ) = 0 s f cos ( a s + b s 2 2 + c s 3 3 + d s 4 4 ) d s y ( s f ) = 0 s f sin ( a s + b s 2 2 + c s 3 3 + d s 4 4 ) d s φ ( s f ) = a s f + b s f 2 2 + c s f 3 3 + d s f 4 4 k ( s f ) = a + b s f + c s f 2 + d s f 3 k ( s f ) k m a x
After state space sampling is completed, the generated candidate paths must simultaneously satisfy the vehicle start and end state constraints and executability requirements. Among them, executability is verified using Formula (13).
X ( t s ) = X s X ( t f ) = X f X ˙ = f ( X , u , t )
In Equation (13), Xs and Xf represent the initial and final states of the vehicle, respectively, f(X,u,t) represents the vehicle model, and u represents the control input.
As shown in Figure 7, aligning the end state of the generated path with the reference path can effectively prevent the vehicle from reaching a dangerous position and provide efficient guidance for the sampling process. In addition, given the inherent parallelism of candidate path calculations, using parallel computing technology to increase the density of longitudinal and lateral sampling points can significantly improve the quality of the generated optimal path. The blue, green, and white lines denote the global path, candidate paths, and the optimal path, respectively.
Although the operating speed of intelligent spray carts is generally low, speed restrictions (v, w) must still be imposed in scenarios such as turning, following other vehicles, and emergency obstacle avoidance. This paper comprehensively considered three key factors: the speed characteristics of the cart itself, the performance limits of the motor, and the safe braking distance, as shown in Table 3. Ultimately, the maximum allowable speed of the intelligent cart is determined by the minimum value of the corresponding limits of the above constraints.
v max = min ( { v m a x l , v c r o s s , v l e n g t h } )

3.2.2. Multi-Objective Evaluation Function Design

To ensure the safe operation of the spray cart, the first step is to perform collision detection to identify whether there are any obstacles on the planned path [23]. This paper used a multi-circle envelope method to approximate the vehicle contour: multiple circles are arranged at equal intervals along the longitudinal axis of the vehicle, and the union of these circles covers the entire spatial range of the vehicle, as shown in Figure 8:
As shown in Equation (15), the multi-objective cost function based on the design selects the candidate path with the minimum cost as the optimal trajectory. This function comprehensively considers driving safety, trajectory smoothness, and lateral deviation distance relative to the center line of the lane to ensure that the optimal path simultaneously meets the requirements of safety, smoothness, and path conformity.
J = arg min i = 1 N ( K C T )     = arg min i = 1 N ( k s C s + k r C r + k e C e )
In Equation (15), C = [Cs, Cr, Ce] represents the cost terms, specifically safety cost, smoothness cost, and other costs; ks, kr, and ke are the corresponding weight coefficients. In this paper, ks and kr were set to 0.3, and ke was set to 0.4. i and K represent the ID number and total number of candidate paths, respectively.
(1)
Safety Costs
For driving safety and real-time performance, this paper designed a safety cost function that combined vehicle motion status with a discrete Gaussian convolution function, as shown in Equation (16):
C s ( i ) = k = 1 N f d k g s ( i k ) g s ( j ) = 2 π 2 π σ s exp ( Δ ρ j 2 σ s )
In Equation (16), fdk is the collision detection result of the candidate path, gs(j) is the obstacle Gaussian convolution function, and σs is the standard deviation of the obstacle collision risk, which was set to 2.5 through simulation analysis.
(2)
Smoothness Cost
Smoothness cost Cr mainly refers to the smoothness of the candidate path and driving comfort. This paper used the curvature of path discrete sampling points and its derivative to represent smoothness cost, as shown in Equation (17):
C r = x s x e k 2 ( x 0 , y 0 )   d x
In Equation (17), k is the curvature of the discrete points of the candidate path.
(3)
Path Deviation Cost
In addition, the planned path of the intelligent spray cart should be as close as possible to the reference path. This paper used the lateral offset to design the evaluation function, as shown in Equation (18):
C e = x s x e y ( x 0 ) y r e f 2 d x
In Equation (18), y(x0) represents the y coordinates of the sampling points on the trajectory, and yref represents the y coordinates of the reference line. The parameter settings for the local path planner are shown in Table 4:

4. Lateral Control Design Based on the Pure Pursuit Algorithm

The pure pursuit algorithm is based on geometric constraints: the rear axle center point of the vehicle is used as the trajectory tangent point, and the longitudinal axis of the vehicle body is used as the instantaneous tangent direction. By adjusting the front wheel steering angle, the vehicle is guided to travel along a circular arc trajectory that converges on the target path point. The working principle is shown in Figure 9:
In Figure 9, (gx, gv) is the pre-aiming point of the current position of the autonomous vehicle; ld is the distance from the rear axle center to the pre-aiming point; α is the angle between the current vehicle heading and the pre-aiming point; R is the arc radius; and δ is the front wheel turning angle. From the geometric relationship in Figure 9, we can obtain:
l d sin ( 2 α ) = R sin ( π 2 α ) l d 2 sin α cos α = R cos α l d sin α = 2 R
From Equation (19), we obtain the curvature of the arc:
k = 1 R = 2 sin α l d
Turning from Ackman to geometric relations, we obtain:
tan δ = L R
By combining Equations (20) and (21), we obtain the relationship between the front wheel angle and time:
δ ( t ) = arctan ( 2 L sin ( α ( t ) ) l d )
Define the error ev between the current attitude and the target path point in the horizontal direction, from which the angle α can be obtained:
sin α = e y l d
Combining Equations (22) and (23) and considering the small angle assumption, we obtain:
e y l d 2 2 L δ ( t )
From the above, we can conclude that the essence of pure pursuit control is a P controller with lateral deviation, whose tracking effect is determined by ld. The functional relationship between ld and speed is:
l d = k v v + l d 0
Since the lead time varies with different vehicle speeds, it is necessary to limit the lead time, as shown in Equation (26):
l d = l min v x < v 1 k v v + l d 0 v 1 v x v 2 l max v x > v 2
In addition to the pure pursuit algorithm, this study also introduced the Stanley controller, LQR (linear quadratic regulator), and MPC (model predictive control) for the lateral control performance comparison. Figure 10a shows the tracking performance of each algorithm in a lane-changing scenario: the pure pursuit algorithm converges to the target path faster than other methods. The experimental data in Figure 10b–e further revealed its advantages: the pure pursuit algorithm exhibited superior control response convergence characterized by smaller lateral position offsets, lower amplitude changes in front wheel steering angles, and slower rates of change, indicating superior lateral control stability. Additionally, Figure 10f shows that the iterative computation time of pure pursuit is comparable to that of other algorithms. Comprehensive experimental data indicate that the intelligent spraying cart, when using the pure pursuit algorithm for lateral control, demonstrated a comprehensive advantage in terms of convergence speed, steady-state accuracy, control smoothness, and real-time performance.

5. Real-Vehicle Path Planning Experiment

To achieve autonomous navigation capabilities for intelligent spraying vehicles in greenhouse environments and validate the stability, safety, and robustness of their core algorithms in real-world scenarios, this study established a comprehensive real-vehicle testing platform. The platform integrated multi-modal perception units such as the Huace CGI-610 high-precision GNSS receiver(Shanghai Huace Navigation Technology Ltd., Co. Huace Time-space Intelligent Industry Park, No. 577, Songying Road, Qingpu District, Shanghai, China), AXIS visual sensors(Axis Communications (Shanghai) Co., Ltd., Room 2606, Yueda 889 Center, No. 1111 Changshou Road, Jing’an District, Shanghai, China), and Beike Tianhui 32-line laser radar(Beijing Beike Tianhui Technology Co., Ltd.Building 1, Yard 5, Yongfeng Road, Haidian District, Beijing, China.), and was equipped with a Huawei MDC300F intelligent driving computing platform(Huawei Technologies Co., Ltd. Huawei Base, Bantian, Longgang District, Shenzhen, Guangdong, China) as the core processor. Communication and driving code were developed for the intelligent vehicle based on the ROS platform, loading the planned route into a pre-programmed container. The planned path and actual driving trajectory could be observed using RVIZ, which is a 3D visualization tool in the ROS ecosystem. The experiments were conducted in a controlled enclosed area, with multi-scenario tests designed and executed to cover typical greenhouse operation scenarios including lateral dynamic obstacle avoidance, multi-vehicle collaborative operation, longitudinal dynamic obstacle avoidance, and target following driving. These scenarios aimed to systematically validate the vehicle’s intelligent driving functions such as dynamic obstacle avoidance, queue following, and collaborative operation. During the experiment, comprehensive data collection and quantitative analysis were conducted on the vehicle’s operational state parameters under each scenario. The experimental system architecture and key vehicle configuration parameters are detailed in Figure 11 and Table 5, respectively.

5.1. Scenario 1: Laterally Approaching Obstacle Avoidance Scenario

This study designed specific experimental conditions to validate the dynamic obstacle avoidance capabilities of an intelligent spraying robot in greenhouse scenarios where animals or workers may cross the path laterally. Figure 12 shows the results of the interaction process analysis under this condition: when the intelligent cart is travelling at a constant speed of 4 km/h, it detects a lateral moving obstacle ahead. The time sequence analysis indicates that when the longitudinal distance between the cart and the obstacle is reduced to 2 m (corresponding to time T = 1 s), the system triggers a deceleration control strategy. At this point, the slope of the distance–time curve significantly decreases, indicating that the longitudinal approach rate is effectively suppressed. Concurrently, after perceiving the vehicle’s deceleration behavior, the pedestrian adopts an active crossing strategy, initiates a lateral crossing maneuver, and completes the crossing at T = 2.8 s. After the obstacle is cleared, the intelligent vehicle immediately resumes its baseline cruising speed.

5.2. Scenario 2: Forward Dynamic Obstacle Braking Scenario

To address the potential deceleration and stopping behavior of the intelligent spraying vehicle in response to moving obstacles in the forward direction within the operational area, this study designed specific test scenarios to validate the collision mitigation performance of the intelligent spraying vehicle. The experimental data analysis in Figure 13 indicates that when the intelligent vehicle (main vehicle) detects that the longitudinal distance to the forward-moving obstacle has decreased to the 2 m threshold (corresponding to time T = 2 s), the vehicle control system immediately activates the deceleration program. The deceleration process continues until the vehicle comes to a complete stop, maintaining the pre-set safety margin throughout. The experimental results demonstrate that the system can effectively maintain the dynamic safety distance during braking, achieving reliable collision avoidance.

5.3. Scenario 3: Co-Directional Moving Obstacle Evasion Scenario

In response to the scenario where non-structured trajectory-moving obstacles invade the forward passage space of the intelligent spraying vehicle and continue to move within the operational area, this study verified its dynamic safety distance maintenance capability through specialized experiments. The time-series analysis data in Figure 14 indicate that when the intelligent vehicle is in uniform cruising mode (initial speed of 4 km/h), it detects a moving obstacle intruding into the planned trajectory at T = 1 s. The control system immediately triggers a deceleration strategy to maintain a safety distance of ≥1 m from the obstacle in real-time. Once the obstacle accelerates out of the sensing area, the system resumes the baseline cruising state, with the entire process compliant with the ISO 13849 [24] safety standard requirements.

5.4. Scenario 4: Oncoming Obstacle Avoidance Scenario

For conflict scenarios where oncoming moving obstacles intrude into the planned path within the operational area, the temporal analysis in Figure 15 shows that when the intelligent vehicle maintains a constant speed cruise state (speed: 4 km/h), the oncoming moving obstacle occupies the vehicle’s passage space at the initial moment. When the relative distance decreases to the pre-set safety threshold of 2 m, the intelligent vehicle activates the collision mitigation protocol and achieves complete stopping via closed-loop braking control at T = 2 s. Once the obstacle accelerates out of the perception domain and exits the planned path, the vehicle autonomously resumes its baseline cruising state, with the entire process adhering to dynamic collision avoidance safety criteria.

5.5. Scenario 5: Operator Following Operational Mode

Figure 16 shows the results of the temporal analysis of the interaction between the intelligent vehicle and the operator: in the steady-state cruising condition (speed: 4 km/h), the system detects the operator entering the planned trajectory at the initial moment. In accordance with the ISO 15066 [25] safety protocol, the control system triggers a deceleration command at T = 1.0 s to maintain a safe buffer distance. When T = 4.5 s, the personnel exit the trajectory threat zone. After the perception system confirms the obstacle has been cleared, the vehicle autonomously resumes its baseline cruising state. The entire process complies with the dynamic safety standards for human–machine collaboration.

5.6. Scenario 6: Leader AGV Tracking Scenario

For the scenario of multiple intelligent vehicles collaborating within the work area, Figure 17 validates the effectiveness of the dynamic queue control strategy. Experimental data analysis indicates that the lead vehicle perceives the motion state of the preceding vehicle (such as speed gradient changes) through a real-time coupled state monitoring system and autonomously triggers a speed regulation mechanism within the predefined operational interval. Quantitative observations show that the minimum relative distance between the lead vehicle and the preceding vehicle was consistently maintained above the safety threshold of ≥1 m throughout the entire operational cycle, in compliance with the safety distance requirements for mobile robots specified in ISO 8373:2021 [26].

6. Conclusions

This study addressed the path planning and control issues of intelligent spray carts in greenhouse environments by introducing a hierarchical decision-making architecture that integrated an improved A* algorithm with Bézier curve optimization. At the global path planning layer based on the A* algorithm, the heuristic function was restructured to improve node search efficiency, a safe check mechanism for inflection points with curvature continuity constraints as introduced, and third-order Bézier curves were used to achieve continuous path smoothing, ensuring full coverage of the working area. At the local behavior decision layer, a scene-adaptive evaluation function was constructed, real-time obstacle avoidance paths were generated based on state space sampling, and a pure pursuit controller was designed based on the vehicle dynamics model.
The experimental platform was built on the ROS-Simulink joint simulation architecture, and multi-modal obstacle scenario real-vehicle verification was conducted. Quantitative analysis showed that the graded deceleration strategy was triggered at a longitudinal threat distance of 2.0 m, dynamically maintaining a minimum safe distance of ≥1.2 m, with path tracking errors of ≤0.15 m in both dynamic and static obstacle scenarios. Empirical results validated the real-time obstacle avoidance capability and trajectory tracking robustness of the proposed algorithm within greenhouse structures, providing a reliable technical framework for agricultural automation equipment. This study was conducted within specific scenarios and thus possesses certain limitations. In future research, we shall consider investigations into intelligent agricultural vehicles operating in open environments.

Author Contributions

Conceptualization, J.Z.; methodology, J.Z.; software, Y.Z.; data curation, X.Z.; writing—original draft preparation, X.Z.; writing—review and editing, K.P.; funding acquisition, X.Z. and K.P. All authors have read and agreed to the published version of the manuscript.

Funding

This study was funded by the Industry-Academia Collaborative Education Project of China (No. 2410305217) and the Talent Program of Chengdu Technological University (2023RC041).

Data Availability Statement

The datasets generated and/or analyzed during the study are available from the corresponding author upon reasonable request.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Miao, Z.; Zhu, Z.; Zhang, W.; Xue, Z.; Sun, T.; Zhang, Y.; Xie, T.; He, C.; Li, N.; Zhao, C.; et al. Key Technologies and Development Trends of Embodied Intelligence Agricultural Robots. Trans. Chin. Soc. Agric. Mach. 2017, 8, 1–14. [Google Scholar]
  2. Liu, Q.; You, X.; Zhang, X.; Zuo, J.; Li, J. Review of Path Planning Algorithms for Mobile Robots. Comput. Sci. 2025, 52 (Suppl. S1), 159–168. [Google Scholar] [CrossRef]
  3. Zhou, K.; Jiang, S.; Li, C. Research progress on trajectory planning of agroforestry robots. Jiangsu J. Agric. Sci. 2024, 40, 1758–1767. [Google Scholar]
  4. Xie, F.; Li, Y.; Liu, C.; Mo, J.; Chen, K. Full Coverage Path Planning Method of Agricultural Machineryunder Multiple Constraints. Trans. Chin. Soc. Agric. Mach. 2022, 53, 17–26+43. [Google Scholar]
  5. Zhou, J.; He, Y. Research Progress on Navigation Path Planning of Agricultural Machinery. Trans. Chin. Soc. Agric. Mach. 2021, 52, 1–14. [Google Scholar]
  6. Wu, W.; Wang, T.; Sun, Y.; Gao, Q. Survey of Multi-agent Path Finding Technology. J. Beijing Univ. Technol. 2024, 50, 1263–1272. [Google Scholar]
  7. Pan, Z.; Shang, M. Path Planning Method of Agricultural Robot Based on A* Algorithm and Improved Sparrow Search Algorithm. Mach. Des. Res. 2022, 38, 31–37. [Google Scholar]
  8. Sun, X.; Wu, C.; Yang, G.; Lu, X. Study on field path planning based on novel A* algorithm. Agric. Equip. Veh. Eng. 2024, 62, 8–11+24. [Google Scholar]
  9. Ma, Q.; Zhang, Y.; Gong, J. Traversal path planning of agricultural robot based on memory simulated annealing and A* algorithm. J. South China Agric. Univ. 2019, 19, 185–190. [Google Scholar]
  10. Zhao, H.; Hao, M.; Wang, H.; Yue, Y. Research on path planning method of agricultural robot based on improved A*algorithm and beetle antennae search algorithm. Sci. Technol. Eng. 2019, 19, 185–190. [Google Scholar]
  11. Khatib, O. Real-time obstacle avoidance for manipulators and mobile robots. In Proceedings of the 1985 IEEE International Conference on Robotics and Automation, St. Louis, MO, USA, 25–28 March 1985; pp. 500–505. [Google Scholar]
  12. Chen, D.; Tan, Q.; Xu, Z. Robotic arm path planning based on sampling point optimization RRT algorithm. Control. Decis. 2024, 39, 2597–2604. [Google Scholar]
  13. Chen, Z.; Wu, J. Improved Probability Path Graph Method for Robots Based on Goal-oriented Sampling. Trans. Chin. Soc. Agric. Mach. 2023, 54, 410–418+426. [Google Scholar]
  14. Wei, M.; Teng, D.; Wu, S. Trajectory planning and optimization algorithm for automated driving based on frenet coordinate system. Control. Decis. 2021, 36, 815–824. [Google Scholar]
  15. Song, C.; Zhang, J.; Tian, X.; Xu, J.; Wu, X.; Zhang, Y. Optimisation-based algorithm for discrete space trajectory planning. J. Chin. Inert. Technol. 2023, 31, 1150–1156+1166. [Google Scholar]
  16. Xiong, L.; Yang, X.; Zhuo, G.; Leng, B.; Zhang, R. Review on Motion Control of Autonomous Vehicles. J. Mech. Eng. 2020, 56, 127–143. [Google Scholar]
  17. Wang, H.; Li, C.; Liang, W.; Yao, L.; Li, Y. Path planning of wheeled coal mine rescue robot based on improved A* and potential field algorithm. Coal Sci. Technol. 2024, 52, 159–170. [Google Scholar]
  18. Wei, L.; Wang, X.; Qiu, B.; Li, L.; Zhou, D.; Lin, J. Tracking and Collision Avoidance of Autonomous Vehicle Basedon Adaptive Preview Path. J. Mech. Eng. 2022, 58, 184–193. [Google Scholar]
  19. Xiao, S.; Jiang, H.; Du, J.; Wang, Y.; Meng, X.; Xiong, Y. Path Tracking Algorithm of Agricultural Vehicle Based on Two Stages Pure pursuit Model. Trans. Chin. Soc. Agric. Mach. 2023, 54, 439–446+458. [Google Scholar]
  20. Zhang, X.; Xu, F.; Zou, Y.; Guo, Y.; Zhang, Y. A local path planning algorithm for interlligent wheeled vehicle combining TangentBug and Dubins path. Automot. Eng. 2021, 43, 10. [Google Scholar]
  21. Shan, Y.; Guo, X.; Long, J.; Cai, B.; Li, B. Asymptotically sampling-based algorithm with applications to autonomous urban driving on structured road. China J. Highw. Transp. 2018, 31, 192–201. [Google Scholar]
  22. Zhang, Y.; Peng, Y. Development of autonomous vehicle trajectory planning used discrete optimization. J. Fuzhou Univ. (Nat. Sci. Ed.) 2021, 49, 508–515. [Google Scholar]
  23. Peng, X.; Xie, H.; Huang, J. Research on local path planning algorithm for unmanned vehicles. Automot. Eng. 2020, 42, 1–10. [Google Scholar]
  24. ISO Standard 13849-1; Safety of Machinery—Safety-Related Parts of Control Systems—Part 1: General Principles for Design. ISO: Geneva, Switzerland, 2023.
  25. ISO/TS 15066:2016; Robots and Robotic Devices—Collaborative Robots. ISO: Geneva, Switzerland, 2016.
  26. ISO Standard 8373:2021; Robotics—Vocabulary. ISO: Geneva, Switzerland, 2021.
Figure 1. Schematic diagram of the node search direction.
Figure 1. Schematic diagram of the node search direction.
Vehicles 07 00123 g001
Figure 2. Schematic diagram of inflection point removal.
Figure 2. Schematic diagram of inflection point removal.
Vehicles 07 00123 g002
Figure 3. Comparison before and after eliminating redundant inflection points. with blue representing the starting point and red the endpoint.
Figure 3. Comparison before and after eliminating redundant inflection points. with blue representing the starting point and red the endpoint.
Vehicles 07 00123 g003
Figure 4. Schematic diagram of generating a third-order Bezier curve.
Figure 4. Schematic diagram of generating a third-order Bezier curve.
Vehicles 07 00123 g004
Figure 5. The path before and after the improvement in the A* algorithm.
Figure 5. The path before and after the improvement in the A* algorithm.
Vehicles 07 00123 g005aVehicles 07 00123 g005b
Figure 6. Kinematics model based on Ackermann steering geometry.
Figure 6. Kinematics model based on Ackermann steering geometry.
Vehicles 07 00123 g006
Figure 7. Local path generation graph.
Figure 7. Local path generation graph.
Vehicles 07 00123 g007
Figure 8. Circle decomposition for vehicle shape and maneuvering area.
Figure 8. Circle decomposition for vehicle shape and maneuvering area.
Vehicles 07 00123 g008
Figure 9. Pure pursuit algorithm geometric diagram.
Figure 9. Pure pursuit algorithm geometric diagram.
Vehicles 07 00123 g009
Figure 10. Comparison of the simulation effects of trajectory tracking control.
Figure 10. Comparison of the simulation effects of trajectory tracking control.
Vehicles 07 00123 g010aVehicles 07 00123 g010b
Figure 11. Experimental flowchart.
Figure 11. Experimental flowchart.
Vehicles 07 00123 g011
Figure 12. Analysis of laterally moving obstacle avoidance performance.
Figure 12. Analysis of laterally moving obstacle avoidance performance.
Vehicles 07 00123 g012
Figure 13. Analysis of the frontal moving obstacle braking performance.
Figure 13. Analysis of the frontal moving obstacle braking performance.
Vehicles 07 00123 g013
Figure 14. Analysis of codirectional moving obstacle overtaking performance.
Figure 14. Analysis of codirectional moving obstacle overtaking performance.
Vehicles 07 00123 g014
Figure 15. Analysis of oncoming moving obstacle avoidance performance.
Figure 15. Analysis of oncoming moving obstacle avoidance performance.
Vehicles 07 00123 g015
Figure 16. Analysis of human operator tracking performance.
Figure 16. Analysis of human operator tracking performance.
Vehicles 07 00123 g016
Figure 17. Analysis of preceding AGV tracking performance.
Figure 17. Analysis of preceding AGV tracking performance.
Vehicles 07 00123 g017
Table 1. Schematic diagram of the node selection rules.
Table 1. Schematic diagram of the node selection rules.
αFive Directions of SearchThree Directions of Deletion
[330°, 360°) ∪ (0°, 30°] n1, n2, n3, n4, n5n6, n7, n8
[30°, 90°)n1, n2, n3, n5, n8n4, n6, n7
[90°, 150°)n3, n5, n6, n7, n8n1, n2, n4
[150°, 210°)n4, n5, n6, n7, n8n1, n2, n3
[210°, 270°)n1, n4, n6, n7, n8n2, n3, n5
[270°, 330°)n1, n2, n3, n4, n6n5, n7, n8
Table 2. Various data before and after the improvement in the A* algorithm.
Table 2. Various data before and after the improvement in the A* algorithm.
AlgorithmPath Length/mTurning Angle/°Number of Collisions
Traditional A* Algorithm36.2265857
Improved A* Algorithm34.729237.680
Table 3. Maximum speed limit parameter table.
Table 3. Maximum speed limit parameter table.
Limit TypePhysical RelationshipParameters
Maximum permissible speed in the environment (vmaxl)The maximum permissible speed is determined by the task requirements.
vm = {(v, w)|v ∈ [vmin, vmax], w ∈ [wmin, wmax]}
Motor performance constraints (velectrical)The speed range that smart cars can achieve.
ve = {(v, w)|v ∈ [vcvbΔt, vc + vaΔt], w ∈ [wcwbΔt, wc + waΔt]}
vc, wc—Current speed of smart car
va, wa—Maximum acceleration
vb, wb—Maximum deceleration
Maximum longitudinal speed (vlength)Ensure the safety of the smart car by ensuring that it stops before obstacles.
vlength = {(v, w)| v ≤ (2dist(v, w)vb)1/2, w ≤ (2dist(v, w)vb)1/2}
dist(v, w)—The minimum distance between the current trajectory and obstacles at this moment
Table 4. Local path planner settings.
Table 4. Local path planner settings.
ParametersParameter Value
v max ( km / h ) 2
a max ( m / s 2 ) 0.5
k max ( m 1 ) 1/8
D s ( m ) 2
Table 5. Information about the experimental vehicle.
Table 5. Information about the experimental vehicle.
Parameter NameParameter Value
Vehicle weight (kg)150
Vehicle length (mm)1200
Vehicle width (mm)850
Vehicle wheelbase (mm)790
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

Zhou, J.; Zheng, Y.; Zheng, X.; Peng, K. Research on Path Planning and Control of Intelligent Spray Carts for Greenhouse Sprayers. Vehicles 2025, 7, 123. https://doi.org/10.3390/vehicles7040123

AMA Style

Zhou J, Zheng Y, Zheng X, Peng K. Research on Path Planning and Control of Intelligent Spray Carts for Greenhouse Sprayers. Vehicles. 2025; 7(4):123. https://doi.org/10.3390/vehicles7040123

Chicago/Turabian Style

Zhou, Junchong, Yi Zheng, Xianghua Zheng, and Kuan Peng. 2025. "Research on Path Planning and Control of Intelligent Spray Carts for Greenhouse Sprayers" Vehicles 7, no. 4: 123. https://doi.org/10.3390/vehicles7040123

APA Style

Zhou, J., Zheng, Y., Zheng, X., & Peng, K. (2025). Research on Path Planning and Control of Intelligent Spray Carts for Greenhouse Sprayers. Vehicles, 7(4), 123. https://doi.org/10.3390/vehicles7040123

Article Metrics

Back to TopTop