Next Article in Journal
Soqia: A Responsive Web Geographic Information System Solution for Dynamic Spatio-Temporal Monitoring of Soil Water Status in Arboriculture
Previous Article in Journal
Design, Integration, and Experiment of Transplanting Robot for Early Plug Tray Seedling in a Plant Factory
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Improved Collision Avoidance Algorithm of Autonomous Rice Transplanter Based on Virtual Goal Point

1
College of Agricultural Engineering, Jiangsu University, Zhenjiang 212013, China
2
Key Laboratory of Modern Agricultural Equipment and Technology, Ministry of Education, Zhenjiang 212013, China
*
Authors to whom correspondence should be addressed.
Submission received: 18 December 2023 / Revised: 7 February 2024 / Accepted: 4 March 2024 / Published: 7 March 2024

Abstract

:
To ensure the operation safety and efficiency of an autonomous rice transplanter, a path planning method of obstacle avoidance based on the improved artificial potential field is proposed. Firstly, the obstacles are divided into circular or elliptic obstacles according to the difference between the length and width of an obstacle as well as the angle between the vehicle’s forward direction and the length direction of the obstacle. Secondly, improved repulsive fields for circular and elliptic models are developed. To escape the local minimum and goal inaccessibility of the traditional artificial potential field as well as meet the requirements of agronomy and vehicle kinematics constraints, the adaptive setting and adjusting strategy for virtual goal points is proposed according to relative azimuth between obstacle and vehicle. The path smoothing method based on the B-spline interpolation method is presented. Finally, the intelligent obstacle avoidance algorithm is designed, and the path evaluation rule is given to obtain the low-cost, non-collision, smooth and shortest obstacle avoidance path. To verify the effectiveness of the proposed obstacle avoidance algorithm, simulation and field experiments are conducted. Simulation and experimental results demonstrate that the proposed improved collision avoidance algorithm is highly effective and realizable.

1. Introduction

With the transfer of the rural labor force to cities and the increase in young and middle-aged laborers who are unwilling to engage in agricultural production, autonomous agricultural machinery covering plowing, planting, managing, and harvesting has been developed in China [1] and several runs of field demonstration tests have been carried out. However, it has not yet realized the full field coverage, long-term continuous, and reliable operations that are determined by the complex and dynamic farmland environment. Obstacles such as electric towers, pumping wells, pumping stations, trees, other operating machinery and implements, people, and animals can be often encountered in farmland.
Autonomous agricultural machinery moves along the global planning path during the process of field operations. After encountering obstacles, it is necessary to adopt different obstacle avoidance strategies and dynamic path planning according to the attributes of obstacles. After bypassing obstacles, it is necessary to return to the global path for continuing operation. Unfortunately, China’s unmanned agricultural machinery has not been equipped with an intelligent obstacle avoidance system and corresponding obstacle avoidance strategy, and thus it is impossible to plan a safe, collision-free, and low-cost operation path after encountering obstacles. This greatly restricts the safe and reliable operation of autonomous agricultural machinery. Therefore, autonomous obstacle avoidance systems and dynamic obstacle avoidance path planning technology are the key technologies for autonomous agricultural machinery to achieve stable, safe, high-efficiency, reliable, and continuous full coverage operation.
Many obstacle avoidance path planning algorithms have been investigated previously, including artificial potential field (APF) [2,3], fuzzy logic (FL) [4,5], dynamic window approach (DWA) [6], geometric method [7], A*, rapidly exploring random tree (RRT) [8,9], and deep learning [10]. A new rapid path planning algorithm for a mobile robot in a dynamic environment is proposed based on Dijkstra’s algorithm and the A* algorithm [11]. The A* algorithm is adopted in a six-dimensional space discretized into many grid points; however, the computation is extremely slow [12,13]. A novel coordinated nonlinear adaptive backstepping collision avoidance control strategy for autonomous ground vehicles was presented, and the tracking performance of the proposed collision avoidance control strategy was verified by simulation and experimental tests [14]. An improved RRT for litchi-picking robots was proposed [9], in which the exploration efficiency was improved by target gravity and then a genetic algorithm and heuristic smoothing algorithm were used to optimize the RRT path. A fast and robust collision-free path planning method based on deep reinforcement learning was proposed for a guava-harvesting robot [15]. A fast finite time sliding mode control (FFTSMC) with optimal reference trajectory was developed by MPC in robust Robotino motion planning with saturating inputs [16]. An obstacle avoidance system for unmanned ground vehicles was presented based on ultrasonic sensors [17]. Although these methods can be used to plan collision-free paths, they are somewhat inefficient computationally.
The computational load of the traditional collision-free path planning algorithms tends to be high and thus the computation is extremely slow [15]. Due to the complexity and randomness of agricultural operation environment information, obstacle avoidance planning algorithms with high real-time calculation speed and robustness are required. Compared with other algorithms, the APF method has the advantages of fast response, simple calculation, and strong real-time performance, which was widely applied in obstacle avoidance of mobile robots and manipulators. However, the inherent drawback of traditional APF is easily trapped in a local minimum and the inaccessibility of the target when the obstacles are in the vicinity of the target [11], which limited its application and performance in real-time mobile robot path planning, security, and accessibility in dynamic uncertain environments. To escape the local minimum and avoid goal inaccessibility, many improved APF algorithms for avoidance path planning were proposed. A modified repelling potential was presented to decrease oscillations and to avoid conflicts while the target is approaching the obstacles [18]. A virtual obstacle located around local minimums was developed to escape local minimums occurring in the local path planning of mobile robots [19]. An improved wall-following approach was proposed for real-time avoidance for mobile robots [11]. To improve the obstacle avoidance path planning ability of mobile robots in an environment with dynamic obstacles, the APF method was presented by modifying the repelling field function and adding the virtual goal points [3]. The local minimum was avoided by improving the attractive and the repulsion field functions [20]. The above-mentioned research aimed at finding a low-cost, safe, and collision avoidance path for mobile robots. Compared with mobile robots, the obstacle avoidance path planning of ground agricultural machinery is an optimal problem under multiple constraints in practical farmland operation. Besides ensuring that the path cost is as small as possible and is performed safely without collision, it also conforms to the constraints of kinematics and dynamics of agricultural machinery, agronomic requirement, and operation area. During the obstacle avoidance process, the rice transplanter is prohibited to traverse across the planted zones to avoid destroying the seedlings, and the harvester is forbidden from moving into the unharvested area to prevent the unharvested crop from being crushed. Moreover, minimum lateral and heading deviation after obstacle avoidance are expected so that vehicles can quickly return to the global operating path to continue operations. Therefore, to solve the path planning problem, it is imperative to design the improved path planning algorithms according to the actual operation scenarios.
In recent years, a few obstacle avoidance algorithms have been investigated for agricultural vehicles. An obstacle avoidance system was designed based on ultrasonic sensor and neural network algorithms for object recognition of unmanned vehicles [17]. An autonomous navigation and obstacle avoidance for a robotic mower was proposed based on a stereo camera and deep learning technique [21]. A detecting and tracking method for moving obstacles such as humans and water buffaloes was developed using machine vision with deep learning methods in a paddy field environment [22]. The method of dynamic obstacle detection was developed based on the panoramic vision in the moving state of the agricultural machinery and the performance was verified [23]. A fuzzy neural network obstacle avoidance algorithm for unmanned ground vehicles based on multi-sensor information fusion was provided [24]. However, in the above studies, the obstacle detection relied on neural network algorithms and machine vision. Thus, the computation load of the proposed algorithms tends to be high and the real-time performance of the algorithm is questionable. An obstacle winding strategy for rice transplanters based on an improved artificial potential field method was presented [25]. Regrettably, the kinematic constraints of the rice transplanter were not considered for the planning of the collision avoidance path. Moreover, the agronomic requirements regarding how the transplanter needs to avoid traveling across the transplanted area were not covered. The evaluation for path optimization solely depended on the lateral deviation and heading error; the distance and the curvature of the designed collision avoidance path were not considered. Finally, the improved artificial potential field method was achieved by setting the virtual target points. However, the setting for the virtual target points has a certain blindness. To make up for the deficiency of the current studies, an improved collision avoidance algorithm for unmanned rice transplanters is proposed in this study.
The objective of this study is to develop an efficient, low-cost, and real-time collision-free path planning algorithm based on improved APF for autonomous rice transplanters. The main contributions are as follows: (1) We propose a novel path planning method of obstacle avoidance based on the improved APF by establishing the circular or elliptic repulsive field for different obstacle models. On the premise of ensuring the safety of agricultural machinery to avoid obstacles, the lateral distance between agricultural machinery and obstacles is effectively reduced. (2) Path oscillation and local optimum in the traditional APF method are overcome by introducing the virtual goal points. (3) The path evaluation function, which is used to dynamically select the optimum obstacle avoidance path, is provided, and thus obstacle avoidance cost is effectively reduced. (4) The virtual target points are subtly set to guide vehicle obstacle avoidance along the path in line with the agronomic requirements and thus the crop is less destroyed.

2. Materials and Methods

2.1. Modification of Artificial Potential Field Method

2.1.1. Modification of Repulsive Force Field of Obstacles

In the traditional APF, robots and obstacles are assumed to be particles, without considering the external contours of obstacles and robots. However, in the actual scene of agricultural machinery, obstacles and agricultural machinery have their external dimensions, so there will be the risk of collision if the dimensions of the obstacles and the vehicles are not considered. Therefore, to decrease the lateral distance between vehicle and operation paths during obstacle avoidance, the elliptic and circular repulsive fields are developed based on the angle between the length direction and vehicle forward direction as well as the dimension and shape of an obstacle, respectively. The flow chart of determining the obstacle type is shown in Figure 1. Elliptic repulsive fields are applied when the difference between the length and width of the obstacle is larger than L t h and the angle between the length direction and vehicle forward direction is equal to or less than 45°. Otherwise, circular repulsive fields are used. Supposing x 1 , y 1 and x 0 , y 0 are the coordinates of the vehicle and obstacle, respectively. L 1 and W 1 are the length and width of the vehicle, respectively. L 0 and W 0 are the obstacle length and width measured by the LIDAR, respectively. L t h is the threshold. α is the angle between the long axis of the obstacle and the X-axis.

2.1.2. Development of Elliptic Repulsive Force Field

For the traditional APF method, the action scope of the repulsive field is mostly a circular area. In the actual working scene of agricultural machinery, the obstacles encountered such as working machinery (rice transplanter, plowing machine, harvester, etc.) or trees and telephone poles are nearly all the elliptic type, so it is necessary to establish an elliptic repulsive field for the obstacles to meet the requirements of agricultural machinery.
If the obstacle is elliptical, the elliptic obstacle model E0 is established as shown in Figure 2.
The equation of ellipse E0 can be described as
4 x x 0 cos α y y 0 sin α 2 W 2 0 + 4 x x 0 sin α + y y 0 cos α 2 L 2 0 = 1 π 4 < α < 3 π 4
In Figure 2, the four ellipses have the same symmetry axis. E3 is the influence zone of the obstacle, and E4 is the zone after the expansion of the obstacle. E2 denotes the vehicle position. L 4 and W 3 are the lengths for long axis and short axis of ellipse E4. The calculation of L 3 ,   L 4 , and W 3 can be expressed as
W 3 = W 0 2 + 3 4 W 1
L 4 = L 0 2 + 1 4 W 1
L 3 = L 0 2 + 1 2 L 1
The area of the ellipse E2, E3, and E4 can be expressed as
S 2 = π W 2 3 x x 0 sin α + y y 0 cos α W 2 3 x x 0 cos α y y 0 sin α 2
S 3 = π L 3 W 3
S 4 = π W 3 L 4
The repulsive force for elliptic obstacles can be described as
F E r e p = 1 2 k E r e p S m a x S i 2 , S t h < S i S m a x 1 2 k E r e p S m a x S t h 2 , S i S t h 0 , S m a x < S i
where k E r e p is the gain coefficient of the repulsive potential field, S m a x is the maximum influence range of the obstacle’s repulsive potential field on the vehicle, and S i is the area difference of E2 and E4. S t h is the threshold value for the elliptic obstacle. The calculation for S i and S m a x can be described as
S i = S 2 S 4
S m a x = S 3 S 4  
Considering the safety of the obstacle avoidance vehicle, the three-quarter vehicle width is transferred to the size of obstacle, and then the vehicle is taken as the particle. The corresponding expression of expanded obstacle can be described as
16 x x 0 cos α y y 0 sin α 2 2 W 0 + 3 W 1 2 + 16 x x 0 sin α + y y 0 cos α 2 2 L 0 + W 1 2 = 1 π 4 < α < 3 π 4
Compared with the circular repulsive field, the characteristic of the elliptic repulsive field is that the repulsive force of obstacles to the vehicle is variable at various positions of obstacles. The advantage is that vehicle can keep enough distance from obstacles along the forward direction of the vehicle and thus the lateral distance between the vehicle and the operation path can be reduced while ensuring safe passing around the obstacle. Compared with the traditional APF, the influence distance in the repulsive field is replaced by the influence area.

2.1.3. Development of Repulsive Force Field of a Circular Obstacle

To achieve safe obstacle avoidance, the obstacle model is developed in the following way (Figure 3). O x 0 , y 0 is the center of the circle and L 0 2 , L 0 + W 1 2 , L 0 + W 1 2 + D 0 are used as radii of obstacle model C0, dilated obstacle model C1, and obstacle influence area C2, respectively.
The circular repulsive force field is established for circular obstacles as shown:
U C r e p X = 1 2 k C r e p 1 D i X 1 D 0 2 0 < D i X D 0 0 D i X > D 0
where k C r e p is the gain coefficient of repulsive potential field, and D 0 is the influence area of repulsive potential field on the vehicle. D i X denotes the distance from the vehicle to the edge of dilated obstacle circle C1. D i X can be expressed as
D i X = x 1 x 0 2 + y 1 y 0 2 L 0 2 W 1 2
The negative gradient of the repulsive potential field of the obstacle is rewritten as
F C r e p X = U C r e p X = = k C r e p 1 D i X 1 D 0 1 D i 2 X D i X X 0 < D i X D 0 0 D i X > D 0

2.1.4. Development of Repulsive Force Field of a Circular Obstacle

If the goal point is too far from the current position of the agricultural machinery, the attraction force acting on the agricultural machinery is too large, and thus the repulsive force of the obstacle acting on the agricultural machinery may be less than the attraction. In this case, the agricultural machinery will collide with the obstacle, and the obstacle avoidance effect is not achieved. To meet the requirements of obstacle avoidance, the attractive force field is modified by introducing a distance threshold. The improved attractive force field can be expressed as [26]
U a t t x = 1 2 k a t t ρ g 2 x ρ g x ρ g * ρ g * k a t t ρ g x 1 2 k a t t ρ g * 2 ρ g x > ρ g *
where k a t t is the gain coefficient of the attractive force field; ρ g x is the distance between vehicle and target point; and ρ g * is the distance threshold. The corresponding negative gradient function of the attractive force field can be written as:
F a t t x = U a t t x = k a t t ρ g x ρ g X X , ρ g X ρ * g ρ * g k a t t ρ g x x , ρ g X > ρ * g
The comparison of simulation results between the improved attractive force field and the traditional attractive force field is shown in Figure 4.
It can be seen from Figure 4 that the force curve of agricultural machinery changes gently under the action of the improved attractive force field.

2.1.5. Calculation of Resultant Force of Improved Artificial Potential Field

The resultant force of improved APF can be expressed as
F S u m = F a t t X + F C r e p X ,   Quasi circular   obstacle F a t t X + F E r e p ( S i ) ,     obstacle

2.2. Determination of Virtual Goal Point

2.2.1. Analysis of Obstacle Avoidance Scene for Agriculture Machines

When agricultural machinery works in the field, most of the obstacles encountered are trees, telegraph poles, and the same type of working machinery. According to the external shape of obstacles, the circular obstacle and elliptical obstacle models described above are established. The relative azimuth between the obstacle and the vehicle in the field is shown in Figure 5.
In Figure 5, A 2 x a 2 , y a 2 is the closest point of agricultural machinery to the obstacle in the horizontal direction. The lateral distance between the vehicle and the obstacle can be described as
d x = x 1 x a 2
If the d x > d t h   (distance threshold, the specific definition can be seen in Table 1), as shown in Figure 5a,d, there is no need to set virtual target points to guide agricultural machinery to avoid obstacles. Otherwise, it is necessary to set virtual target points to achieve a smooth obstacle avoidance trajectory. The obstacle avoidance trajectory generated will oscillate during the obstacle avoidance process when the lateral distance between agricultural machinery and obstacles is too close (Figure 5b,e). For the case of Figure 5c,f, obstacles are located on the right side of the agricultural machinery, and the agricultural machinery needs to avoid obstacles in the unplanted area, so it is also necessary to set virtual target points to guide the agricultural machinery to avoid obstacles.

2.2.2. Setting and Adjusting Strategies of Virtual Target Points

The location of the virtual target point has an important effect on the path planning of obstacle avoidance. To acquire a safe, collision-free obstacle avoidance path and meanwhile meet the requirements of vehicle kinematics constraints and agronomic requirements, it is necessary to optimize the virtual goal point.
The schematic diagram of setting and adjusting for virtual target points is shown in Figure 6. E 0 and C 1 represent the contour of the obstacle; E 3 and C 3 are the influence zones of the obstacle. Given that the agricultural machinery normally runs at low speed, L 2 is set as one vehicle length to meet the emergency braking distance of the vehicle.
In Figure 6b, suppose that the maximum front wheel angle of the vehicle is δ m a x , and the angle step is θ t h . P i and T i i = 0,1 , 2,3 n 1 are the start and target points of obstacle avoidance, respectively. P i and T i are symmetric with respect to the obstacle. The angle between P i A 1 i = 0,1 , 2,3 n 1 and the positive direction of the Y-axis is δ i ( δ n 1 δ m a x ). The initial position of P n 1 is the intersection point between the influence area of the obstacle and the forward direction of the vehicle. The step size of the artificial potential field method is s t e p . A 1 x a 1 , y a 1 is the intersection point of E 3 and C 3 on the X-axis, respectively.
When the vehicle is two vehicle lengths away from the obstacle, the obstacle avoidance starting point, the actual target point, and the virtual target point start to be determined. The detailed steps are as follows:
(1)
Initial selection for start points
Along the direction from P 0 to P n 1 , P 0 is initially selected and the angle δ 0 between P 0 A 1 and the Y-axis is calculated. P 0 is set as the farthest starting point if δ 0 δ n 1 6 δ t h . Otherwise, the intersection point between the straight line with the slope k = tan δ n 1 6 δ t h through A 1 and the working path is taken as the farthest starting point.
(2)
Determination of P i i = 1,2 , n 1 start point and virtual goal point
After the point P 0 is determined, the length from P 0 to P n 1 is equally divided by n − 2 and the corresponding δ i is calculated. The virtual goal point is set as A i = x a 1 , y a i . The calculation of y a i can be described as
y a i = δ i δ 0 s t e p + y a 1
(3)
Switch between the virtual target point and the actual target point
The function of the actual target point is the same as that of the virtual target point. One and only one can exist at the same time. If the virtual target point is reached and then the actual target point is switched, the planned obstacle avoidance path will become tortuous. Therefore, the switch method between the virtual target point and the actual target point is provided by the Equations (20) and (21).
y 0 y 1 L 0 3
x 1 x 0 W 0 3
Equations (20) and (21) restrict the safe distance between the vehicle and obstacles in longitudinal and transverse directions, respectively. The two equations should be satisfied at the same time so that the vehicle can meet the requirement of safe distance when approaching the obstacle, and the vehicle can switch back to the actual target point before it reaches the virtual target point.

2.3. Path Smoothing

To avoid the sharp variation in the front wheel angle of the vehicle and the collision with obstacles in the process of path tracking, it is necessary to eliminate the points with sharp variations in curvature, and path smoothing is adopted in this study. Spline interpolation not only preserves the advantages of piecewise low-order interpolation polynomials, but also improves the smoothness of the interpolation function. Therefore, the B-spline interpolation method is applied. The B spline function is defined as
W t = i = 0 n W i B i , k t
where t is the vector node; W is the control point coordinates; and n is the number of control points. The recursive expression of the k-order B-spline function B i , k can be expressed as
B i , 0 t = 1 , t i t < t i + 1 0 , other
B i , k t = t t i t i + k t i B i , k 1 t + t i + k + 1 t t i + k + 1 t i + 1 B i + 1 , k 1 t
The order of the B-spline curve has an important effect on smoothness and computational complexity. To compromise between smoothness and computational complexity, the third-order B-spline curve ( k = 3 ) is selected, and the comparison of the smooth effect is shown in Figure 7.

2.4. Simulation Parameters

To validate the effectiveness of the proposed obstacle avoidance strategy, the simulation is conducted using Python 3.9.6 software. The rice transplanter (68CMD, Kubota Agricultural Machinery (Suzhou) Co., Ltd., Suzhou, Japan) with Ackerman steering gear is used in the simulations. The minimum turning radius ( R t h ) of the rice transplanter is 1.05 m. The length L 1 and width W 1 of the vehicle are 3.14 m and 2.20 m, respectively. According to different types of obstacle models encountered in the operation process and different obstacle avoidance measures taken in different directions of the vehicle with respect to the obstacle, the simulation verification is carried out. The detailed parameter settings of the simulation are shown in Table 1.

2.5. Test Platform

To validate the effectiveness of the proposed improved collision avoidance strategy, field tests were carried out at grain industrial park, Xinghua city, Jiangsu province. The designed device is shown in Figure 8. The rice transplanter (68CMD, Kubota Agricultural Machinery (Suzhou) Co., Ltd., Suzhou, Japan) with Ackerman steering gear was used. Two six-axis attitude sensors (HWT905, Shenzhen Wit Intelligent Co., Ltd., Shenzhen city, China), the combination navigation module NC502-D (Beijing BDStar Navigation Technology Co., Ltd., Beijing, China) of BEIDOU and INS (inertial navigation system), vehicle speed control unit, LIDAR (VLP-16, Velodyne lidar Co., Ltd., San Jose, CA, USA), as well as the AF300 electric steering wheel (Shanghai LIANSHI navigation Co., Shanghai, China) were assembled on the rice transplanter. One attitude sensor was adopted to sense the vehicle posture and the other was subtly used to obtain the front wheel angle of the vehicle. During transplanting operations, to achieve continuous and accurate navigation and reduce accumulated positioning error as well as ensure the stability of positioning system, the position information of the vehicle was provided by a combination navigation module. The HUAXIN full band antenna, supporting C201 receiver, and navigation reference station were selected as the navigation module. RTK horizontal positioning accuracy was ±2 cm, and the data update rate was set as 5 Hz. The electric steering wheel was adopted to steer the vehicle. The navigation controller and the vehicle control unit (VCR) were developed by the industrial control integrated computer with capacitive touch screen (Guangzhou Chongchang Computer Technology Co., Ltd., China) and the high-performance industrial control panel EMB8616I (Beijing Zhongembedded Lingyun Electronics Co., Ltd., China), respectively. The communication between the navigation controller and the vehicle control unit (VCR) was conducted by the RS-485 serial port. The detailed structure of vehicle speed control unit can be seen in Ref. [27] and is not repeated here. Two six-axis attitude sensors and the electric steering wheel were connected to the VCR by the RS-232 serial ports, while the navigation module communicated with the navigation controller by the RS-485 serial ports. The LIDAR that was used to sense the obstacles was connected to the navigation controller by the RJ-45 port. The program code was developed in C++ language.

3. Algorithm Design and Path Evaluation

3.1. Design of Obstacle Avoidance Algorithm

The improved algorithm flow chart is shown in Figure 9 and the detailed steps are as follows.
The detailed steps of the improved obstacle avoidance algorithm are as follows.
(1) Initialization of the algorithm
Obtain the current positions of the vehicle and obstacle using the navigation system and LIDAR, respectively. Input the following parameters: the length L 0 and width W 0 of the obstacle, α , L 1 the length and width W 1 of the vehicle, the threshold L t h , length and width difference of the obstacle, angle step θ t h , and the maximum front wheel angle δ m a x of vehicle.
(2) Develop an obstacle model according to obstacle parameters and afterwards determine the gain coefficients of the repulsive and attractive potential fields as well as a step based on the established obstacle model.
(3) Check whether the obstacle is on the right side of the operating path as shown in Figure 5c,f. If yes, go to Step (5); otherwise, calculate lateral distance d x between the vehicle and the obstacle.
(4) Calculate the distance threshold d t h = 2 W 0 + 3 W 1 8 ; if d x > d t h , go to step (8).
(5) According to Figure 6, set the start S i and target point T i of obstacle avoidance virtual goal points A i .
(6) According to the current position of the vehicle and algorithm parameters, calculate the attractive and repulsive forces and then obtain the resultant force at the current position.
(7) Derive the next waypoint according to the resultant force and the step length.
(8) According to Equations (20) and (21), determine whether the vehicle needs to switch from the virtual target point back to the actual target point.
(9) Judge whether the agricultural machine reaches the target point. If so, generate the obstacle avoidance path P a t h i and exit the algorithm; otherwise, go back to Step (6).

3.2. Evaluation Rule for the Obstacle Avoidance Path

To improve operational efficiency and reduce the obstacle avoidance cost of agricultural machinery, it is necessary to select the optimal obstacle avoidance path from the obstacle avoidance path point set P a t h i i = 1,2 , n . The evaluation of the obstacle avoidance path is conducted using path length, path curvature, and path smoothness. P a t h i can be expressed as
P a t h i = x 0 , y 0 , x 1 , y 1 , x 2 , y 2 , x n , y n

3.2.1. Estimation of the Path Curvature

During obstacle avoidance, the curvature of the obstacle avoidance path should be continuous and the curvature radius should not be less than the minimum turning radius of the vehicle. To evaluate the obstacle avoidance path, it is necessary to calculate its curvature. In the Euclidean plane, the change rate of the gradient with respect to arc length is defined as curvature. Assuming the curve equation of the obstacle avoidance path is y = f x , then the curvature k can be calculated as
k j = y 1 + y 2 3 / 2
y = d y d x j = y j y j 1 x j x j 1
y = d 2 y d x 2 j = d y d x j d y d x j 1 x j x j 1
The obstacle avoidance path is composed of discrete points. Therefore, the curvature of all waypoints is estimated based on the forward and backward directions of the reference points. The obstacle avoidance paths whose minimum curvature radii are less than the minimum turning radius of the vehicle are eliminated from the set of candidate paths. Since the length of the obstacle avoidance path is different, the average curvature is used to represent the smoothness J i of the obstacle avoidance path, as shown in Equation (29).
J i = 1 n 2 j = 1 n 1 k j

3.2.2. Evaluation of the Path Length

For the obstacle avoidance trajectory P a t h i , the length between two adjacent points is calculated and expressed as
D i = j = 0 n 1 x j + 1 x j 2 + y j + 1 y j 2

3.2.3. Evaluation of the Path Length

Path smoothness index J i and path length index D i have different dimensions. J i and D i need to be normalized to evaluate the obstacle avoidance path comprehensively. In Figure 6a,b, the closer the obstacle avoidance starting point is to the obstacle, the shorter the path length and the larger the path curvature; the farther the obstacle avoidance starting point is from the obstacle, the longer the path length and the smaller the path curvature. Therefore, the obstacle avoidance path starting from P n 1 and P 0 is selected as the reference path, and the maximum Q i is selected as the optimum obstacle avoidance path. The calculation of Q i is calculated as
Q i = ω 1 J n J i J n J 0 + ω 2 D 0 D i D 0 D n

4. Results and Discussion

4.1. Simulation and Analysis

4.1.1. Comparison of Obstacle Avoidance Path under the Action of the Elliptic and Circular Repulsive Force Fields

To validate the effectiveness of the proposed obstacle avoidance algorithm, the elliptic and circular repulsive force fields are compared, and the same attractive force field is used for two different repulsive force fields. The length, width, and position of the elliptical obstacle are 1.0 m, 0.5 m, and (4.0,5.0), respectively. The coordinates of starting point and goal point of obstacle avoidance are (5.1,0.4) and (5.1,9.0), respectively. α = 0.5 π . After the parameters are set, the simulation is conducted, and the corresponding result is shown in Figure 10.
In Figure 10, C 1 and E 0 represent the contour of the actual obstacle. C 2 and E 4 denote the non-collision boundary between agricultural machinery and obstacles. C 3 and E 3 signify the influence range of the obstacle. It can be seen from Figure 10 that the lateral distances of the obstacle avoidance path for circular and elliptic repulsive force fields are 1.0 m and 0.48 m, respectively. This signifies that the lateral distance reduces 52% by using the developed elliptic repulsive force field. Meanwhile, the minimum curvature radii for the two cases are 1.1 m and 1.3 m, respectively, which are greater than the minimum turning radius of the vehicle 1.05 m. Moreover, the length of the obstacle avoidance path for circular and elliptic repulsive force fields are 8.81 m and 8.51 m, respectively. Compared with the circular repulsive force field, the path length for the elliptic repulsive force field decreases by 3.4%. The above analysis implies that the vehicle can achieve safe obstacle avoidance under the action of the two different repulsive force fields and the path length and the lateral distance from the vehicle to the obstacle for the elliptic repulsive force field are both less than those of the circular repulsive force field.

4.1.2. Comparison of Obstacle Avoidance Effect for the Case of an Obstacle Located on the Left of the Operating Path

The simulation environment of obstacle avoidance is set based on the six different relative positions between the obstacle and the vehicle in Figure 5. The position of the obstacle is set as (4.0,4.0) and the lateral distance between the vehicle and the obstacle satisfies the Equation (32). According to above analysis, it is unnecessary to set virtual goal points and the vehicle can directly avoid obstacles under this circumstance. The angle α between the long axis of the obstacle and the X-axis is set as 0.55 π . The simulation results in Figure 11 are obtained by running the simulation procedure.
d x > d t h
d x d t h
It can be seen from Figure 11a that the maximum curvature of the planned obstacle avoidance path is 0.717 m 1 at point (5.4,2.85) and the corresponding minimum curvature radius ( R m c r ) is 1.39 m. Although R m c r > R t h , which meets the requirements of vehicle kinematic constraint, the curvature of the planned obstacle avoidance path is discontinuous. To obtain an obstacle avoidance path with continuous curvature, an improved trajectory is acquired by smoothing using the three-order spline curve. The maximum curvature of the improved trajectory is 0.342 m 1 at point (5.68,6.05) and the corresponding minimum curvature radius is 2.92 m. Figure 11b shows that the curvature of the planned obstacle avoidance path reaches the maximum 0.406 m 1 at point (5.42,2.6) and the corresponding R m c r is 2.46 m. Although R m c r > R t h , the path curvature is also discontinuous. Similarly, to obtain an obstacle avoidance path with continuous curvature, three-order spline curve smoothing is also used for the path. Figure 11b shows that the curvature of the improved obstacle avoidance trajectory reaches the maximum 0.406 m 1 at point (5.92,5.65) and the corresponding R m c r is 2.46 m. The minimum curvature radius for the two cases is greater than the minimum turning radius of the rice transplanter. Moreover, the curvature of the improved obstacle avoidance trajectory is also continuous. This signifies that the improved obstacle avoidance paths for elliptic and circular obstacles meet the requirements of the kinematical constraint of the vehicle.

4.1.3. Comparison of Obstacle Avoidance Effect for the Case of an Obstacle Located in the Operating Path

To verify the effectiveness for the cases of Figure 5b,e, the position of the obstacle is set as (4.8,4.0) and thus the lateral distance of the vehicle and the obstacle satisfies the Equation (33). The angle α between the long axis of the obstacle and the X-axis is set as 0.5 π . According to the analysis of Figure 5, it is necessary to set virtual goal points, and the vehicle can directly avoid obstacles under this circumstance. The simulation results in Figure 12 and Figure 13 are obtained by running the simulation procedure.
Figure 12a shows that the obstacle avoidance path oscillates when the vehicle approaches the obstacle area shown in the blue rectangle. The path curvature reaches its maximum 45.92 m 1 at point (5.4,2.35) and thus the corresponding R m c r is less than the minimum turning radius of the rice transplanter R t h . This implies that the planned path does not meet the kinematic constraints of the vehicle. It can be seen from Figure 12b that there is no significant oscillation in the planned path, whereas the path curvature reaches the maximum 9.04 m 1 at point (6.54,3.87). The R m c r is 0.11 m, which is less than R t h . An improved trajectory by path smoothing of the third-order B-spline curve is obtained to meet the kinematic constraints of vehicles. The maximum curvature of the improved trajectory by path smoothing of third-order B-spline curve is 0.33 m 1 at point (6.5,4.8) and the corresponding R m c r is 3.03 m, which is greater than R t h . This indicates that the improved trajectory by path smoothing meets the requirements of the kinematic constraints of the vehicle and the vehicle can avoid the obstacle along this obstacle avoidance path.
The obstacle avoidance path oscillates in the blue rectangular area as shown in Figure 13a. The path curvature reaches its maximum 6.75 m 1 at point (5.50,2.32) and thus the corresponding R m c r is 0.15 m, which is less than R t h . This implies that the planned path fails to meet the conditions of the vehicle kinematic constraints. It can be observed from Figure 13b, although the oscillation of the unoptimized obstacle avoidance path is obviously reduced, there are still noise waypoints in the path. The maximum curvature of the planned obstacle avoidance path is 11.67 m 1 at point (5.53,1.06) and the corresponding R m c r is 0.09 m, which is less than R t h . To eliminate the noise points and improve the smoothness, an improved trajectory is obtained using path smoothing. The maximum curvature of the improved trajectory by path smoothing of the third-order B-spline curve is 0.42 m 1 at point (7.03,4.05) and the corresponding R m c r is 2.38 m, which is greater than R t h . This signifies that the improved trajectory by path smoothing meets the requirements of vehicle kinematic constraints and the vehicle can realize obstacle avoidance along the path.

4.1.4. Comparison of Obstacle Avoidance Effect for the Case of an Obstacle Located on the Right of the Operating Path

To testify the effectiveness for the cases of Figure 5c,f, the position of the obstacle is set as (6.2,4.0) and thus the lateral distance of the vehicle and the obstacle satisfies the Equation (33). The angle α between the long axis of the obstacle and the X-axis is set as 0.44 π . According to the analysis of Figure 5, it is necessary to set virtual goal points so that the vehicle can directly avoid obstacles under this circumstance. The simulation results for this case are presented in Figure 14 and Figure 15.
It can be seen from Figure 5c,f that the left of the vehicle is the zone that has been planted. To prevent the seedlings that have been transplanted from damage during obstacle avoidance of the rice transplanter, it fails to meet agronomic requirements if the vehicle travels across the planted zone during obstacle avoidance. It can be seen that the planned obstacle avoidance paths as shown in Figure 14a and Figure 15a are unreasonable. Moreover, obvious oscillation can be found in the paths. To guide the vehicle to avoid obstacles in the right area of the obstacle, the virtual goal points are adopted for path planning. Figure 14b and Figure 15b show that the planned obstacle avoidance trajectory is located to the right of the obstacle. Moreover, for the planned obstacle avoidance trajectory as shown in Figure 14b, an abrupt change in path curvature occurs at the point (6.58,1.93) and the corresponding R m c r is 0.09 m, which is less than R t h . This implies that the planned path is inappropriate for obstacle avoidance. The same situation occurs with the obstacle avoidance path shown in Figure 15b. The maximum curvature of the planned obstacle avoidance path is 16.18 m 1 at point (5.58,1.02) and the corresponding minimum curvature radius is 0.06 m, which is less than R t h .
To make the planned path smoother and meet the requirements of vehicle kinematics constraints, the third-order B-spline curve is used for smoothing the previously planned path. The improved trajectories are shown in Figure 14b and Figure 15b in red. The curvature of the optimized obstacle avoidance path, as shown in Figure 14b, reaches the maximum value 0.76 m 1 at point (8.06,3.85), and thus the corresponding R m c r is 1.32 m. Likewise, the curvature of the optimized obstacle avoidance path as shown in Figure 15b arrives at the maximum value 0.55 m 1 at point (8.44,4.65), and thus the corresponding R m c r is 1.82 m. Since R m c r >   R t h , the requirements of vehicle kinematic constraints can be satisfied and thus the obstacle avoidance trajectory can be used to avoid obstacles.
A robust collision-free path planning method based on deep reinforcement learning was developed for the guava-harvesting robot [15], which did not consider the constraints during the obstacle avoidance process. In the practical operating process, the rice transplanter is prohibited from traversing across the planted zones to avoid destroying the seedlings, and the harvester is forbidden from moving into the unharvested area to prevent the unharvested crop from being crushed. To meet the agronomic requirements of avoiding traversing across the planted zones, the obstacle avoidance paths in Figure 14a and Figure 15a are not improper. Therefore, the obstacle avoidance paths in Figure 14b and Figure 15b conform to the practical operating requirement as planned. This implies that the obstacle avoidance algorithm in this study has a strong adaptive ability to constraints compared to the collision-free path planning method in Ref. [15].

4.2. Evaluation and Selection of Optimal Path

To validate the effectiveness of the proposed adaptive adjusting strategies of virtual target points, the obstacle avoidance paths for circular and elliptic obstacles under different virtual goal points are presented as shown in Figure 16 and Figure 17. Figure 16b shows that the maximum curvature of the path appears at the same position as the ordinate of the obstacle. The curvatures of six paths are less than 0.66 m 1 and the corresponding R m c r is greater than 1.52 m. This implies that each obstacle avoidance path meets the requirements of vehicle kinematical constraint because R m c r > R t h . Moreover, all paths are smoothed using third-order B-spline curve and thus the continuity of the curvature of the path is ensured. In Figure 16d, the maximum curvature of all paths is less than 0.88 m 1 and R m c r is greater than 1.14 m. Similarly, the curvatures for all paths are continuous and meet the kinematic constraints of the vehicle. This indicates that the proposed adaptive adjusting strategies of virtual target points is effective despite the relative position of the vehicle and the obstacle is different.
To check the adaptive ability to the obstacle shape of the proposed adaptive adjusting strategies of virtual target points, compared with paths around circular obstacles in Figure 16, the obstacle avoidance paths around elliptic obstacles are also presented in Figure 17.
It can be seen from Figure 17 that path 5 has the largest curvature. For the paths in Figure 17b, the maximum curvature of all paths is less than 0.63 m 1 and R m c r is greater than 1.59 m, while the maximum curvature of all paths in Figure 17d is less than 0.73 m 1 and R m c r is greater than 1.37 m. This means that the paths in Figure 17 meet the kinematic constraints of the vehicle and the vehicle can avoid obstacles along each path. By the above analysis, it can be found the proposed adaptive adjusting strategies of virtual target points has a strong adaptive capability to avoid obstacles with different shapes.
Moreover, Figure 16 and Figure 17 show that the closer the obstacle avoidance starting point is to the obstacle, the larger the curvature of the path and the shorter the path length. To select the optimal path, the tradeoff between the path length and the path curvature is necessary. The evaluation index Q i as shown in Equation (31) was used to determine the optimal obstacle avoidance path. By setting ω 1 = 0.4 and ω 2 = 0.6 , the evaluation results for paths in Figure 17a,c are shown in Table 2 and Table 3, respectively. Selecting the path with the maximum Q i value as the optimal path, the optimal paths in Figure 17a,c are the fourth and the third paths, respectively.
It can be seen from Table 2 that the curvature index becomes smaller gradually from path 0 to path 5 while length index is gradually larger. The path 4 with the maximum Q i   is selected as the optimal path.
In the same way, the path 3 with the maximum Q i is selected as the optimal path.

5. Field Experiments

5.1. Field Experiments

A 100 m × 30 m rectangular field was selected for the experiment. The power tower that can be seen as obstacle was in the field. The unevenness of paddy soil was less than 5 cm. The rice transplanter traveled along the planned global path at the speed of 0.8 m/s and the obstacle avoidance path at the speed about 0.4–0.5 m/s. Since an obstacle with a fixed position such as a power tower or power pole were not found in the test field, the obstacle was replaced by a 1.0 m × 0.5 m garbage can. Thus, the three different relative azimuths between the obstacle and the vehicle were obtained by altering the position of the garbage can. That is, the obstacle was located on the left/right side of the operating path and in the operating path, respectively. A pure pursuit control algorithm was used to guide the rice transplanter along the planned paths.
To validate the effectiveness and accuracy, two kinds of obstacle cases were set. One case was that the obstacle was located on the left operating path, and it is unnecessary to set the virtual goal point; the other is that the obstacle was situated in the operating path. To guide the rice transplanter obstacle avoidance in the unplanted areas, it was necessary to set the virtual goal point.

5.2. Field Experiments for the Obstacle Located on the Left Operating Path

The obstacle coordinate 0.1,9.5 , the length (1.0 m), and width (0.5 m) were obtained using the LIDAR. The angle between the long axis of the obstacle and X-axis is 90°. The practical obstacle avoidance process is as shown in Figure 18. After starting the control system, the transplanter ran along the global path SE from the start point S (1.1,2.0) of the operation path. The lateral distance d x between the obstacle and the start point S (1.1,2.0) of the operation path was calculated according to Equation (18). The lateral distance between the vehicle and the obstacle satisfies the Equation (33). According to the above analysis, it is unnecessary to set virtual goal points and the vehicle can directly avoid the obstacle under this circumstance.
It can be seen from Figure 18a that the rice transplanter ran along the global operating path (SP) and switched the obstacle avoidance path when arriving at the P point. Then, the rice transplanter traveled along the obstacle avoidance path (PT) until reaching the end point (T) of the obstacle path. Afterwards, the vehicle resumed to switch back to global path and continue to travel along the path until arriving at the E point. The practical obstacle avoidance path coincided well with the planned obstacle avoidance path. However, the small deviation between the practical obstacle avoidance path and the planned obstacle avoidance path was still observed at the beginning and end segments of the obstacle avoidance. The reason is probably caused by the vehicle slippage, the delay of the actuator, and deficiency for adaptive adjustment ability of the control parameters. Figure 18b indicates that the curvature of the obstacle avoidance path was ranging from 0 to 0.278 m 1 . The maximum curvature 0.278 m 1 appeared at the path point (1.73,8.49) and the corresponding R m c r is greater than 3.59 m. This implied that the obstacle avoidance path met the kinematic constraints of the vehicle, and the vehicle can avoid the obstacle along the path.

5.3. Field Experiments for the Obstacle Located in the Operating Path

Similarly, the obstacle coordinate 0.55,7.6 , the length (1.0 m), and width (0.5 m) were obtained using the LIDAR. The angle between the long axis of the obstacle and X-axis is 80°. Figure 19 demonstrates the practical obstacle avoidance process and results.
After starting the control system, the transplanter ran along the global path SE from the start point S (1.1,2.0) of the operation path. The lateral distance d x between the obstacle and the start point S (1.1,2.0) of the operation path is calculated according to Equation (18). The lateral distance between the vehicle and the obstacle satisfies the Equation (33). According to above analysis, it is necessary to set virtual goal points so that the vehicle can avoid the obstacle under this circumstance. The optimum obstacle avoidance path was acquired by altering the virtual goal point based on the proposed evaluation and selection method of the optimal path in Section 4.2. The path in blue in Figure 19a was adopted as the planned obstacle avoidance path. Figure 19b showed that a good agreement was achieved between the practical obstacle avoidance path and the planned obstacle avoidance path. The curvature of the planned obstacle avoidance path, which is the path 3 in Figure 19c, ranged from 0 to 0.295 m 1 . The maximum curvature 0.295 m 1 and the corresponding R m c r is greater than 3.39 m. This implies that the obstacle avoidance path met the requirements of vehicle kinematic constraint because R m c r > R t h .
Moreover, Figure 19d presents the variation in the distance from the rice transplanter to the obstacle contour. During the obstacle avoidance process, the minimum distance between the rice transplanter and the obstacle contour is 0.85 m. This means that the rice transplanter can realize the safe and collision-free obstacle avoidance, which implies the effectiveness and accuracy of the proposed improved collision avoidance algorithm.

6. Conclusions

In this study, we focused on the actual operation conditions and conducted research of the dynamic obstacle avoidance algorithm based on improved APF, and performed simulation, experiments, and analyses to validate the feasibility and effectiveness of the proposed method. By the above research work and experiments, the following conclusions can be drawn:
(1) On the base of comprehensive considerations of the local minimum and goal inaccessibility of the traditional APF, as well as the computation load, an improved collision avoidance algorithm for an autonomous rice transplanter based on virtual goal point is proposed. Our proposed method has good real-time performance and robustness.
(2) The obstacles are classified into circular or elliptic obstacles according to the difference between the length and width of an obstacle as well as the angle between the vehicle forward direction and length direction of the obstacle. The improved repulsive fields for circular and elliptic models are established. In this way, the obstacle avoidance area can be reduced.
(3) The adaptive adjusting strategy for virtual goal points was presented, and the path evaluation rule is developed based on the curvature and length of the obstacle avoidance paths. In this manner, the planned dynamic obstacle avoidance path has a continuous and smooth curvature. Thus, it can meet the agronomy requirements and kinematics constraints of the rice transplanter. Moreover, the path length is the shortest.
Some aspects in this study can still be improved. For example, the study was restricted to the straight working state of the vehicle. The obstacle avoidance of headland turning was not considered. The proposed obstacle avoidance algorithm was limited to dynamic obstacle avoidance of stationary obstacles and the obstacle avoidance for the moving obstacles such as humans and moving agricultural machinery were not covered. In the future, we will dedicate research to the study of obstacle avoidance during headland turning and an obstacle avoidance algorithm for moving obstacles to improve the adaptability of this study.

Author Contributions

Conceptualization, J.L. and M.Z.; methodology, D.G.; software, M.Z.; validation, J.L.; formal analysis, M.Z.; investigation, J.L.; resources, J.L.; data curation, D.G.; writing—original draft preparation, D.G.; writing—review and editing, M.L.; visualization, M.L.; supervision, J.L.; project administration, J.L. All authors have read and agreed to the published version of the manuscript.

Funding

This research was funded by the Key Research and Development Program of Zhenjiang city (NY2022008), and the Key Research and Development Program of Jiangsu Province (BE2018324).

Data Availability Statement

No new data were created or analyzed in this study. Data sharing is not applicable to this article.

Conflicts of Interest

The authors declare no conflicts of interest.

References

  1. Zhou, J.; He, Y.Q. Research progress on navigation path planning of agricultural machinery. Nongye Jixie Xuebao Trans. Chin. Soc. Agric. Mach. 2021, 52, 1–14. [Google Scholar]
  2. Zhang, T.; Zhu, Y.; Song, J.Y. Real-time motion planning for mobile robots by means of artificial potential field method in unknown environment. Ind. Robot 2010, 37, 384–400. [Google Scholar] [CrossRef]
  3. Wang, S.M.; Zhao, T.T.; Li, W.J. Mobile robot path planning based on improved artificial potential field method. In Proceedings of the 2018 IEEE International Conference of Intelligent Robotic and Control Engineering, IRCE 2018, Lanzhou, China, 24–27 August 2018. [Google Scholar]
  4. Zavlangas, P.G.; Tzafestas, S.G. Motion control for mobile robot obstacle avoidance and navigation: A fuzzy logic-based approach. Syst. Anal. Modell. Simul. 2003, 43, 1625–1637. [Google Scholar] [CrossRef]
  5. Mashhadi, B.; Vesal, M.A.; Amani, H. Obstacle avoidance for an autonomous vehicle using force field method. Int. J. Automot. Eng. 2017, 7, 2468–2479. [Google Scholar]
  6. Molinos, E.J.; Llamazares, A.; Ocana, M. Dynamic window-based approaches for avoiding obstacles in moving. Robot. Auton. Syst. 2019, 118, 112–130. [Google Scholar] [CrossRef]
  7. Liu, C.; Zhao, X.; Du, Y. Research on static path planning method of small obstacles for automatic navigation of agricultural machinery. IFAC-PapersOnLine 2018, 51, 673–677. [Google Scholar] [CrossRef]
  8. Aguinaga, I.; Borro, D.; Matey, L. Parallel RRT-based path planning for selective disassembly planning. Int. J. Adv. Manuf. Technol. 2008, 36, 1221–1233. [Google Scholar] [CrossRef]
  9. Cao, X.M.; Zou, X.J.; Jia, C.Y.; Chen, M.Y.; Zeng, Z.Q. RRT-based path planning for an intelligent litchi-picking manipulator. Comput. Electron. Agric. 2019, 156, 105–118. [Google Scholar] [CrossRef]
  10. Li, Y.; Lida, M.; Suyama, T.; Suguri, M.; Masuda, R. Implementation of deep-learning algorithm for obstacle detection and collision avoidance for robotic harvester. Comput. Electron. Agric. 2021, 174, 105499. [Google Scholar] [CrossRef]
  11. Zhang, H.M.; Li, M.L. Rapid path planning algorithm for mobile robot in dynamic environment. Adv. Mech. Eng. 2017, 9, 1–12. [Google Scholar] [CrossRef]
  12. Henten, V.E.J.; Hemming, J.; Tuijl, V.B.A.J.; Kornet, J.G.; Meuleman, J.; Bontsema, J. An autonomous robot for harvesting cucumbers in greenhouses. Auton. Robot. 2002, 13, 241–258. [Google Scholar] [CrossRef]
  13. Van Henten, E.J.; Hemming, J.; Van Tuijl, B.A.J.; Kornet, J.G.; Bontsema, J. Collision-free motion planning for a cucumber picking robot. Biosyst. Eng. 2003, 86, 135–144. [Google Scholar] [CrossRef]
  14. Guo, J.H.; Luo, Y.G.; Li, K.Q. Adaptive coordinated collision avoidance control of autonomous ground vehicles. Proc. Inst. Mech. Eng. Part I J. Syst. Control. Eng. 2018, 232, 1120–1133. [Google Scholar] [CrossRef]
  15. Lin, G.C.; Zhu, L.X.; Li, J.H.; Zou, X.J.; Tang, Y.C. Collision-free path planning for a guava-harvesting robot based on recurrent deep reinforcement learning. Comput. Electron. Agric. 2021, 188, 106350. [Google Scholar] [CrossRef]
  16. Hedman, M.; Mercorelli, P. FFTSMC with Optimal Reference Trajectory Generated by MPC in Robust Robotino Motion Planning with Saturating Inputs. In Proceedings of the 2021 American Control Conference (ACC), New Orleans, LA, USA, 25 May 2021; pp. 1470–1477. [Google Scholar]
  17. De Simone, M.C.; Rivera, Z.B.; Guida, D. Obstacle avoidance system for unmanned ground vehicles by using ultrasonic sensors. Machines 2018, 6, 18. [Google Scholar] [CrossRef]
  18. Sfeir, J.; Saad, M.; Saliah-Hassane, H. An improved artificial potential field approach to real-time mobile robot path planning in an unknown environment. In Proceedings of the 2011 IEEE International Symposium on Robotic and Sensors Environments, Montreal, QC, Canada, 17–18 September 2011. [Google Scholar]
  19. Daily, R.; Bevly, D.M. Harmonic potential field path planning for high-speed vehicles. In Proceedings of the 2008 American Control Conference, Seattle, WA, USA, 11–13 June 2008. [Google Scholar]
  20. Rostami, S.M.H.; Sangaiah, A.K.; Wang, J.; Liu, X.Z. Obstacle avoidance of mobile robots using modified artificial potential field algorithm. EURASIP J. Wirel. Commun. Netw. 2019, 2019, 70. [Google Scholar] [CrossRef]
  21. Inoue, K.; Kaizu, Y.; Igarashi, S.; Imou, K. The development of autonomous navigation and obstacle avoidance for a robotic mower using machine vision technique. IFAC-PapersOnLine 2019, 52, 173–177. [Google Scholar] [CrossRef]
  22. Qiu, Z.J.; Zhao, N.; Zhou, L.; Wang, M.C.; Yang, L.L.; Fang, H.; He, Y.; Liu, Y.F. Vision-based moving obstacle detection and tracking in paddy field using improved Yolov3 and deep SORT. Sensors 2020, 20, 4082. [Google Scholar] [CrossRef] [PubMed]
  23. Xu, H.Z.; Li, S.C.; Ji, Y.H.; Cao, R.Y.; Zhang, M. Dynamic obstacle detection based on panoramic vision in the moving state of agricultural machineries. Comput. Electron. Agric. 2021, 184, 106104. [Google Scholar] [CrossRef]
  24. Lv, J.L.; Qu, C.X.; Du, S.F.; Zhao, X.Y.; Yin, P.; Zhao, N.; Qu, S.G. Research on obstacle avoidance algorithm for unmanned ground vehicle based on multi-sensor information fusion. Math. Biosci. Eng. 2021, 18, 1022–1039. [Google Scholar] [CrossRef] [PubMed]
  25. Jiang, L.T.; Chi, R.J.; Xiong, Z.X.; Ma, Y.Q.; Ban, C.; Zhu, X.L. Obstacle winding strategy of rice transplanter based on artificial potential field method after optimization. Nongye Jixie Xuebao Trans. Chin. Soc. Agric. Mach. 2022, 53 (Suppl. S1), 20–27. (In Chinese) [Google Scholar]
  26. Howie, C.; Kevin, L.; Seth, H.; George, K.; Wolfram, B.; Lydia, K.; Sebastian, T. Principles of Robot Motion: Theory, Algorithms, and Implementations; MIT Press (MIT Series on Intelligent Robotics and Autonomous Agents): Cambridge, MA, USA, 2005. [Google Scholar]
  27. Li, J.Y.; Shang, Z.J.; Li, R.F.; Cui, B.B. Adaptive sliding mode path tracking control of unmanned rice transplanter. Agriculture 2022, 12, 1225. [Google Scholar] [CrossRef]
Figure 1. Flow chart of determining the obstacle type.
Figure 1. Flow chart of determining the obstacle type.
Agriengineering 06 00041 g001
Figure 2. Development of the elliptic obstacle model.
Figure 2. Development of the elliptic obstacle model.
Agriengineering 06 00041 g002
Figure 3. Schematic diagram of the repulsive force field of a circular obstacle.
Figure 3. Schematic diagram of the repulsive force field of a circular obstacle.
Agriengineering 06 00041 g003
Figure 4. Comparison of the improved attractive force field and the traditional attractive force field.
Figure 4. Comparison of the improved attractive force field and the traditional attractive force field.
Agriengineering 06 00041 g004
Figure 5. Diagram of relative azimuth between obstacle and vehicle. (a) Elliptic obstacle located on the left of the operating path; (b) elliptic obstacle located in the operating path; (c) elliptic obstacle located on the right of the operating path; (d) circular obstacle located on the left of the operating path; (e) circular obstacle located in the operating path; and (f) circular obstacle located on the right of the operating path.
Figure 5. Diagram of relative azimuth between obstacle and vehicle. (a) Elliptic obstacle located on the left of the operating path; (b) elliptic obstacle located in the operating path; (c) elliptic obstacle located on the right of the operating path; (d) circular obstacle located on the left of the operating path; (e) circular obstacle located in the operating path; and (f) circular obstacle located on the right of the operating path.
Agriengineering 06 00041 g005
Figure 6. Schematic diagram of setting and adjusting for virtual target points. (a) Elliptic obstacle; (b) circular obstacle.
Figure 6. Schematic diagram of setting and adjusting for virtual target points. (a) Elliptic obstacle; (b) circular obstacle.
Agriengineering 06 00041 g006
Figure 7. Obstacle avoidance path comparison before and after third-order B-spline curve path smoothing. Black dot: trajectory before using third-order B-spline curve path smoothing. Blue line: trajectory after using third-order B-spline curve path smoothing.
Figure 7. Obstacle avoidance path comparison before and after third-order B-spline curve path smoothing. Black dot: trajectory before using third-order B-spline curve path smoothing. Blue line: trajectory after using third-order B-spline curve path smoothing.
Agriengineering 06 00041 g007
Figure 8. Adopted experimental device in the field tests.
Figure 8. Adopted experimental device in the field tests.
Agriengineering 06 00041 g008
Figure 9. Flow chart of the improved obstacle avoidance algorithm.
Figure 9. Flow chart of the improved obstacle avoidance algorithm.
Agriengineering 06 00041 g009
Figure 10. Comparison of obstacle avoidance path under the action of the elliptic and circular repulsive force field. (a) Circular repulsive force field; (b) elliptic repulsive force field.
Figure 10. Comparison of obstacle avoidance path under the action of the elliptic and circular repulsive force field. (a) Circular repulsive force field; (b) elliptic repulsive force field.
Agriengineering 06 00041 g010
Figure 11. Comparison of obstacle avoidance path for two obstacle models with the different shapes when the obstacle is situated at the left of the working path. (a) Elliptic obstacle; (b) circular obstacle.
Figure 11. Comparison of obstacle avoidance path for two obstacle models with the different shapes when the obstacle is situated at the left of the working path. (a) Elliptic obstacle; (b) circular obstacle.
Agriengineering 06 00041 g011
Figure 12. Comparison of obstacle avoidance paths for whether to set a virtual goal point when the elliptic obstacle is located in the operating path. (a) Not setting virtual goal point; (b) setting virtual goal point.
Figure 12. Comparison of obstacle avoidance paths for whether to set a virtual goal point when the elliptic obstacle is located in the operating path. (a) Not setting virtual goal point; (b) setting virtual goal point.
Agriengineering 06 00041 g012
Figure 13. Comparison of obstacle avoidance paths for whether to set a virtual goal point when the circular obstacle is located in the operating path. (a) Not setting virtual goal point; (b) setting virtual goal point.
Figure 13. Comparison of obstacle avoidance paths for whether to set a virtual goal point when the circular obstacle is located in the operating path. (a) Not setting virtual goal point; (b) setting virtual goal point.
Agriengineering 06 00041 g013
Figure 14. Comparison of obstacle avoidance paths for whether to set a virtual goal point when the elliptic obstacle is located on the right of the operating path. (a) Not setting virtual goal point; (b) setting virtual goal point.
Figure 14. Comparison of obstacle avoidance paths for whether to set a virtual goal point when the elliptic obstacle is located on the right of the operating path. (a) Not setting virtual goal point; (b) setting virtual goal point.
Agriengineering 06 00041 g014
Figure 15. Comparison of obstacle avoidance paths for whether to set a virtual goal point when the circular obstacle is located on the right of the operating path. (a) Not setting virtual goal point; (b) setting virtual goal point.
Figure 15. Comparison of obstacle avoidance paths for whether to set a virtual goal point when the circular obstacle is located on the right of the operating path. (a) Not setting virtual goal point; (b) setting virtual goal point.
Agriengineering 06 00041 g015
Figure 16. Comparison of obstacle avoidance paths for circular obstacles under different virtual goal points. (a) Obstacle avoidance paths at six different virtual goal points when the obstacle coordinates are X 0 = 5.4,8.0 ; (b) variation of path curvature in (a); (c) obstacle avoidance paths at six different virtual goal points when the obstacle coordinates are X 0 = 6.4,8.0 ; and (d) variation of path curvature in (c).
Figure 16. Comparison of obstacle avoidance paths for circular obstacles under different virtual goal points. (a) Obstacle avoidance paths at six different virtual goal points when the obstacle coordinates are X 0 = 5.4,8.0 ; (b) variation of path curvature in (a); (c) obstacle avoidance paths at six different virtual goal points when the obstacle coordinates are X 0 = 6.4,8.0 ; and (d) variation of path curvature in (c).
Agriengineering 06 00041 g016
Figure 17. Comparison of obstacle avoidance paths for elliptic obstacles under different virtual goal points. (a) Obstacle avoidance paths at six different virtual goal points when the obstacle coordinates are X 0 = 3.3,5.6 ; (b) variation of path curvature in (a); (c) obstacle avoidance paths at six different virtual goal points when the obstacle coordinates are X 0 = 4.3,5.6 ; and (d) variation of path curvature in (c).
Figure 17. Comparison of obstacle avoidance paths for elliptic obstacles under different virtual goal points. (a) Obstacle avoidance paths at six different virtual goal points when the obstacle coordinates are X 0 = 3.3,5.6 ; (b) variation of path curvature in (a); (c) obstacle avoidance paths at six different virtual goal points when the obstacle coordinates are X 0 = 4.3,5.6 ; and (d) variation of path curvature in (c).
Agriengineering 06 00041 g017
Figure 18. Obstacle avoidance results when the obstacle is located on the left operating path. (a) Practical obstacle avoidance path; (b) curvature of the practical obstacle avoidance path.
Figure 18. Obstacle avoidance results when the obstacle is located on the left operating path. (a) Practical obstacle avoidance path; (b) curvature of the practical obstacle avoidance path.
Agriengineering 06 00041 g018
Figure 19. Obstacle avoidance results when the obstacle is located in the operating path. (a) Planned obstacle paths for different virtual goal points; (b) practical obstacle avoidance path; (c) curvature of the practical obstacle avoidance path; and (d) distance from the rice transplanter to the outer contour of the obstacle.
Figure 19. Obstacle avoidance results when the obstacle is located in the operating path. (a) Planned obstacle paths for different virtual goal points; (b) practical obstacle avoidance path; (c) curvature of the practical obstacle avoidance path; and (d) distance from the rice transplanter to the outer contour of the obstacle.
Agriengineering 06 00041 g019
Table 1. Simulation parameters.
Table 1. Simulation parameters.
ParameterValueUnit
d t h 2 W 0 + 3 W 1 8 m
k a t t 3.0/
k E r e p 2.0/
k C r e p 2.0/
s t e p 0.25m
D 0 1.0m
L t h 0.3m
Coordinate of starting point(5.4,0.6)m
Coordinate of goal point(5.4,7.0)m
L 1 3.14m
W 1 2.20m
L 0 1.0 m
W 0 (Elliptic obstacle)0.5 m
W 0 (Circular obstacle)0.8m
δ m a x 45°
R t h 1.05m
Table 2. Evaluation results for the planned obstacle avoidance paths in Figure 17a.
Table 2. Evaluation results for the planned obstacle avoidance paths in Figure 17a.
Path Number012345
Curvature index1.000.9260.8360.6900.4290.0
Length index0.00.2410.4060.6180.8201.00
Q i value0.400.5150.5780.6460.6630.60
Table 3. Evaluation for the planned obstacle avoidance paths in Figure 17c.
Table 3. Evaluation for the planned obstacle avoidance paths in Figure 17c.
Path Number012345
Curvature index1.000.9260.8160.6460.3760.0
Length index0.00.2000.3940.5970.7591.00
Q i value0.400.4900.5640.6160.6050.60
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Share and Cite

MDPI and ACS Style

Li, J.; Zhang, M.; Li, M.; Ge, D. Improved Collision Avoidance Algorithm of Autonomous Rice Transplanter Based on Virtual Goal Point. AgriEngineering 2024, 6, 698-723. https://0-doi-org.brum.beds.ac.uk/10.3390/agriengineering6010041

AMA Style

Li J, Zhang M, Li M, Ge D. Improved Collision Avoidance Algorithm of Autonomous Rice Transplanter Based on Virtual Goal Point. AgriEngineering. 2024; 6(1):698-723. https://0-doi-org.brum.beds.ac.uk/10.3390/agriengineering6010041

Chicago/Turabian Style

Li, Jinyang, Miao Zhang, Meiqing Li, and Deqiang Ge. 2024. "Improved Collision Avoidance Algorithm of Autonomous Rice Transplanter Based on Virtual Goal Point" AgriEngineering 6, no. 1: 698-723. https://0-doi-org.brum.beds.ac.uk/10.3390/agriengineering6010041

Article Metrics

Back to TopTop