Next Article in Journal
Using Genetic Programming to Identify Characteristics of Brazilian Regions in Relation to Rural Credit Allocation
Previous Article in Journal
Macro and Microelements in Leaves of ‘Meredith’ Peach Cultivar Supplied with Biochar, Organic and Beneficial Biofertilizer Combinations
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Research on Tractor Optimal Obstacle Avoidance Path Planning for Improving Navigation Accuracy and Avoiding Land Waste

1
School of Mechanical Engineering, Tianjin University, Tianjin 300350, China
2
State Key Laboratory of Intelligent Agricultural Power Equipment, Luoyang 471039, China
3
Luoyang Tractor Research Institute Co., Ltd., Luoyang 471039, China
*
Author to whom correspondence should be addressed.
Agriculture 2023, 13(5), 934; https://doi.org/10.3390/agriculture13050934
Submission received: 8 March 2023 / Revised: 18 April 2023 / Accepted: 21 April 2023 / Published: 24 April 2023
(This article belongs to the Section Agricultural Technology)

Abstract

:
Obstacle avoidance operations of tractors can cause parts of land to be unavailable for planting crops, which represents a reduction in land utilization. However, land utilization is significant to the increase in agricultural productivity. Traditional obstacle avoidance path planning methods mostly focus on automatic tractor navigation with small errors, ignoring the decrease in land utilization due to obstacle avoidance operations. To address the problem, this paper proposed an obstacle avoidance path planning method based on the Genetic Algorithm (GA) and Bezier curve. In this paper, a third-order Bezier curve was used to plot the obstacle avoidance path, and the range of control points for the third-order Bezier curve was determined according to the global path and the location of the obstacle. To target the navigation error and land utilization problems, GA was used to search for the optimal point from the selection range of the control point under multiple constraints for automatic tractor navigation such as the obstacle collision avoidance, the minimum turning radius, and the maximum turning angle. Finally, the optimal obstacle avoidance path was determined based on the selected control points to minimize the navigation error and maximize land utilization. The algorithm proposed in this paper was compared with existing methods and the results showed that it has generally favorable performance on obstacle avoidance path planning.

1. Introduction

Tractor automatic navigation technology is widely used in many agricultural production processes such as planting and plant protection. It is necessary to plan an obstacle avoidance path for the tractor to achieve obstacle avoidance and then return to the global path again when there are obstacles in the field. So, Obstacle Avoidance Path Planning is an important research area for Tractor Automatic Guidance Systems, and a key technology that must be solved for intelligent agriculture.
There are many theories and methods that have been proposed to plan the optimal Obstacle Avoidance Path. For example, geometric curves such as the Bezier curve [1,2] and B-spline curve [3,4] have been frequently applied to plot the obstacle avoidance path. Xi et al. proposed a third-order Bezier curve optimization method to form a continuous smooth obstacle avoidance path, and the results showed favorable tracking performance of the curve path [5]. An improved cubic B-spline optimization method for obstacle avoidance in the motion of the manipulator was proposed by Wan et al. [6]. The main idea of existing methods above is to smoothly connect intermediate path points using the cubic B-spline method.
Moreover, algorithms such as the Ant Colony Algorithm [7,8], Particle Group Algorithm [9,10], A* Algorithm [11,12], and Genetic Algorithm [13,14] are widely applied in obstacle avoidance path planning and have also been applied in different industry fields. In the ocean current environment, for instance, Ajeil et al. proposed an obstacle avoidance path planning method for an unmanned submarine based on an improved firework-ant colony algorithm [15]. At the same time, an obstacle avoidance path planning scheme for UAVs was proposed to improve the safety level of UAVs. In this paper, the path was optimized with consideration of objective functions including the minimum trajectory length, elapsed time energy consumption, and obstacle collision avoidance constrains [16]. In order to solve the problem of obstacle avoidance path planning for mobile robots, F et al. proposed a modified genetic algorithm to plan the obstacle avoidance path based on the Bezier curve [17]. With the distance between the starting point and the end point as the optimization objective, the obstacle avoidance path was planned based on the Bezier curve by determining the control points. In the field of agricultural machinery, Inoue et al. proposed a method using machine vision to detect obstacles and then plan a feasible obstacle avoidance path [18]. In summary, existing algorithms take the navigation error as the path planning objective and the land utilization is not considered.
To address this problem, this paper proposes an avoidance path planning method based on the Genetic Algorithm (GA) and Bezier curve. In this paper, the Bezier curve is used to plot the obstacle avoidance path, and the control points that determine the geometry of the third-order Bezier curve have a selection range based on the global path and locations of obstacles. The algorithm proposed in this paper consists of 3 steps as follows: (1) The kinematics model of the tractor was established to simulate automatic navigation of the tractor. (2) The selection range of control points was obtained through data of the global path and obstacle. (3) With the goal of a small error in tractor automatic navigation and high land utilization, the optimal control point was searched from the control point selection range using GA to obtain an obstacle avoidance path that satisfies multiple constraints such as anti-collision, minimum turning radius, and kinematic constraints.

2. Materials and Methods

2.1. Obstacle Avoidance Path Model

2.1.1. Bezier Curve

The third-order Bezier curve is widely used in many fields, such as the path planning of mobile robots and structural modeling. The schematic diagram of the third-order Bezier curve is shown in Figure 1 and is defined as follows:
x   y = t 3   t 2   t   1 G P , t 0,1
where t indicates the normalized time variable; (p0,x, p0,y), (p1,x, p1,y), (p2,x, p2,y), and (p3,x, p3,y) are coordinates of control points P0, P1, P2, and P3, respectively.
G = 1 3 3 1 3 6 3 0 3 3 0 0 1 0 0 0 , P = p 0 , x p 0 , y p 1 , x p 1 , y p 2 , x p 2 , y p 3 , x p 3 , y
The first derivative and second derivative of the third-order Bezier curve are expressed as in Equation (2).
x ˙   y ˙ = 3 t 2   2 t   1   0 G P x ¨   y ¨ = 6 t   2   0   0 G P
where x ˙ , y ˙ , x ¨ , and y ¨ are the components of first and second derivatives of the point (x(t),y(t)) for the X and Y coordinates, respectively.
The curvature of the third-order Bezier curve is expressed as follows:
k t = x ˙ y ¨ x ¨ y ˙ ( x ˙ 2 + y ˙ 2 ) 3 2
where k(t) represents the radius of curvature.

2.1.2. Obstacle Avoidance Path Model

The obstacle avoidance path was planned in the world standard latitude and longitude coordinate system (WGS84 coordinate system), and the navigation path L is a sequence of path discrete points {k0, k1, k2, …, ki…}, where ki = (loni,lati). As shown in Figure 2, the obstacle avoidance path contains two third-order Bezier curves. The shapes of third-order Bezier curves are determined based on the coordinates of control points, and the first curve is connected to the second curve through P1,3 = P2,0. Therefore, the problem of obstacle avoidance path planning is transformed into the acquisition of coordinates of optimized control points [19].
The control point coordinates of the obstacle avoidance path have the limitation of selection range. Therefore, the optimal obstacle avoidance path is obtained by searching the range of the limit control point coordinates according to the optimal control point.
First, a kinematic model is established to simulate autonomous navigation of the tractor. Secondly, with the goal of minimizing the error of tractor automatic navigation and maximizing land utilization rate, the obstacle avoidance path is generated by searching for optimal control points, which meets the multi-constraint conditions such as the minimum turning radius, the collision avoidance, and the maximum wheel angle. Then, with the goal of small automatic tractor navigation error and less wasted land in the obstacle avoidance path, the optimal control point is searched to obtain the obstacle avoidance path that satisfies multiple constraints such as anti-collision, minimum turning radius, and kinematic constraints.

2.2. Tractor Kinematic Model

As shown in Figure 3, the tractor is simplified to a bicycle model [20,21]. The bicycle model is subjected to the following assumptions:
  • The tractor is a rigid body.
  • The tractor is front-wheel-steered and the left and right wheels are steered at the same angle.
  • The roll and pitch movements are ignored.
  • The lateral sliding is ignored.
The two-wheeled bicycle model has the rear wheels fixed to the body of the tractor and the front wheels can be turned around a horizontal axis to steer the tractor. In this paper, using the center of the rear axis as the reference point, we have the following equation:
v = v B R = R 2
v is the velocity of the tractor’s rear wheels in the x-axis direction and R is the tractor’s steering radius.
The tractor’s poses are represented by the coordinate system {V} shown in Figure 3, with the x-axis being the forward direction of the tractor and the origin of the coordinates at the center of the rear wheels. The tractor ‘s locus is given by the generalized coordinates q = (x,y,θ)∈S, S SE(2) (S is the conformal space of the tractor). The velocity of the cart is defined on the basis of its velocity v in the x-direction and 0 in the y-direction, as the wheels cannot move sideways. In the cart coordinate system, this is expressed as
v x ˙ = v , v y ˙ = 0
The dotted line in the diagram indicates that the wheel cannot move in this direction, and at the intersection of the dotted lines is the instantaneous center of rotation, a reference point on the tractor will move along an arc trajectory with the angular velocity shown in Equation (4).
θ ˙ = v R 1
At the center of the rear wheel, the speed is expressed as Equation (5):
v = x ˙ B c o s θ + y ˙ B s i n θ
Kinematic constraints of front and rear axles (no lateral sideslip):
x ˙ A sin γ + θ y ˙ A cos γ + θ = 0 x ˙ B sin θ y ˙ B cos θ = 0
From Equations (5) and (6), we have:
x ˙ B = vcos θ y ˙ B = vsin θ
Equation (8) can be obtained from the front and rear wheel geometry:
x A = x B + Lcos θ y A = y B + Lsin θ
Substituting Equations (7) and (8) into Equation (6), the angular velocity of the transverse pendulum can be obtained as:
ω = v L t a n γ
The steering radius R and the front wheel deflection angle γ can be obtained from w and v tractor speed:
R = v / ω γ = arctan ( L / R )
In addition, the following equations can be derived according to Figure 3:
x ˙ = vcos θ y ˙ = vsin θ θ ˙ = v L tan γ
where (xB,yB) represents the coordinate of point B; x ˙ B and y ˙ B are the components of the first derivatives of point B for the X and Y coordinates, respectively.
Figure 4 illustrates the tractor path tracking model. With the goal of minimizing the heading angle of the tractor, preview point C can be determined by searching for the points in the planned path, and the preview point satisfies the requirement that the distance to point Cs is less than d1. The tractor reaches preview point C by the desired path.
Based on Figure 4, the following results can be calculated:
L d sin 2 α = R cos α
The kinematic model of automatic tractor navigation can be obtained by combining Equations (12) and (13):
θ = arctan 2 L sin α L d

2.3. Selection Range of Control Points

2.3.1. Key Point Coordinates

In order to improve the efficiency of path planning, obstacles with irregular contours are fitted with semicircles. As shown in Figure 5a, the global path is used as the dividing line, and the field can be divided into two areas: planted and unplanted. Next, we need to fit the contour of the obstacle in the working area with a semicircle to obtain the intersection points (Ps and Pe) of the semicircle and the global path, as well as the coordinates of the vertex Pv of the semicircle that envelops the obstacle [22].
The obstacle avoidance path is calculated based on Equation (1), and it must be achieved in the rectangular coordinate system. Therefore, the WGS84 coordinate system is converted to a rectangular coordinate system by using Equation (14) in this paper, and then we can obtain the key points Ps = (xs,ys), Pe = (xe,ye), and Pv = (xv,yv) in the rectangular coordinate system.
x p y p = A cos ( l a t ) cos ( l o n ) A cos ( l a t ) sin ( l o n )
where (lon,lat) is the coordinate of point P in the WGS84 coordinate series, (xp,yp) is the coordinate of point P in the rectangular coordinate series, and A is defined as the following equation:
A = a 2 / a 2 cos l o n 2 + b 2 sin l o n 2 1 2
where a is the semi-major axis of the earth ellipsoid and b is the semi-minor axis of the earth ellipsoid.

2.3.2. Control Point Selection Range

The geometric shape of the obstacle avoidance path is determined by control points, and the selection range of control points is shown in Figure 5b. The maximum distance between the tractor and global path is introduced by changing the coordinate of control point P1,3, and we set the control point P1,3 = Py = (xy,yy) to obtain the minimum value.
From the properties of the third-order Bezier curve, it is known that the relationship between the positions of control points satisfies the following equation:
v 0 v 0 / / v 3 v 3 / / v 6 v 6 / / p 1,0 p 1,1 / / p 1,2 p 1,3 / / p 1,3 p 2,1 / / p 2,2 p 2,3
where v0 is the speed vector when the tractor is in the control point P1,0, v3 is the speed vector when the tractor is in the control point P1,3, and v6 is the speed vector when the tractor is in the control point P2,3.
Based on Equation (16), the selection range of control points P1,0, P1,1, P2,2, and P2,3 are all on the global path, and the selection range of control points P1,2 and P2,1 are all on the straight line L1 passing through point P1,3. In addition, the global path is parallel to the straight line L1.
We can determine the coordinate of control point P1,0 according to the straight line P0,sPs with a length of 2r, and the selection range of control point P1,0 shown in Equation (15) can be calculated based on Equation (16):
m i n 2 x s x e , x s x 1,0 m a x 2 x s x e , x s y 1,0 = y e y s x e x s x 1,0 + x e y s x s y e x e x s
Similarly, it can be obtained that the selection range of control points P2,3 is the straight line PeP6,e with a length of 2r:
m i n 2 x e x s , x e x 2,3 m a x 2 x e x s , x e y 2,3 = y e y s x e x s x 2,3 + x e y s x s y e x e x s
where (x2,3, y2,3) represents the coordinate of control point P2,3, (xs,ys) is the coordinate of key point Ps, and (xe,ye) is the coordinate of key point Pe.
The selection range of control point P1,1 is the straight line P0,sP1,e with a length of 3r:
m i n 2 x s x e , x s + x e 2 x 1,1 m a x 2 x s x e , x s + x e 2 y 1,1 = y e y s x e x s x 1,1 + x e y s x s y e x e x s
where (x1,1, y1,1) is the coordinate of control point P1,1, (xs,ys) represents the coordinate of key point Ps, and (xe,ye) is the coordinate of key point Pe.
The selection range of control point P1,2 is the straight line P2,s Pv with a length of 3r:
m i n x v + x s x e , x v x 1,2 m a x x v + x s x e , x v y 1,2 = y e y s x e x s x 1,2 + x e y v x s y v x s y e + x v y v x e x s
where (x1,2, y1,2) is the coordinate of control point P1,2, (xv, yv) is the coordinate of key point Pv, (xs,ys) is the coordinate of key point Ps, and (xe,ye) is the coordinate of key point Pe.
The selection range of control point P2,1 is the straight line PvP4,e with a length of 3r:
m i n x v x s + x e , x v x 2,1 m a x x v x s + x e , x v y 2,1 = y e y s x e x s x 2,1 + x e y v x s y v x s y e + x v y v x e x s
where (x2,1, y2,1) is the coordinate of control point P2,1, (xv, yv) is the coordinate of control point Pv, (xs,ys) is the coordinate of key point Ps, and (xe,ye) is the coordinate of key point Pe.
The selection range of control point P2,2 is the straight line P1,eP6,e with a length of 3r:
m i n 2 x e x s , x s + x e 2 x 2,2 m a x 2 x e x s , x s + x e 2 y 2,2 = y e y s x e x s x 2,2 + x e y s x s y e x e x s
where (x2,2, y2,2) is the coordinate of control point P2,2, (xs,ys) is the coordinate of key point Ps, and (xe,ye) is the coordinate of key point Pe.
The selection range of all control points is shown in Equation (23):
m i n 2 x s x e , x s x 1,0 m a x 2 x s x e , x s m i n 2 x s x e , x s + x e 2 x 1,1 m a x 2 x s x e , x s + x e 2 m i n x v + x s x e , x v x 1,2 m a x x v + x s x e , x v m i n x v x s + x e , x v x 2,1 m a x x v x s + x e , x v m i n 2 x e x s , x s + x e 2 x 2,2 m a x 2 x e x s , x s + x e 2 m i n 2 x e x s , x e x 2,3 m a x 2 x e x s , x e y 1,0 y 62,3 y 1,1 y 52,2 y 1,2 y 42,1 = 1 x e x s y e y s T 1 + T 2 T 3 x 1,3 y 1,3 = x v y v
where T1, T2, and T3 are defined as follows:
T 1 = x 1,0 x 62,3 x 1,1 x 52,2 x 1,2 x 42,1 , T 2 = y s y s y v y e y e y e 0 0 y v 0 0 y v , T 3 = x e x s x v x s x e x s x v x s

2.4. Constraint Functions

2.4.1. Geometric Constraints

The obstacle avoidance path has the following two geometric constraints. On the one hand, it is required that the curvature radius of the obstacle avoidance path should not be less than the minimum turning radius:
k t = x ˙ y ¨ x ¨ y ˙ ( x ˙ 2 + y ˙ 2 ) 3 2 1 R m i n
where Rmin is the minimum turning radius of the tractor.
On the other hand, the obstacle avoidance path should satisfy the anti-collision constraint described in Equation (25):
( x t x s + x e 2 ) 2 + ( y t y s + y e 2 ) 2 1 2 x s x e 2 + y s y e 2
where (xt, yt) is any point of the obstacle avoidance path.

2.4.2. Tractor Kinematic Constraint

Due to the limitation of the mechanical structure, the turning angle of the tractor has a certain range. Therefore, it is required that the turning angle should not exceed the maximum turning angle.
θ = arctan 2 L sin α L d < θ m a x
where L is the tractor wheelbase, Ld is the distance between the tractor rear axle and preview point, α is the heading angle when the tractor arrives at the preview point, and θmax is the maximum turning angle of tractor.
In addition, all constraints are shown in Equation (27):
k = x ˙ y ¨ x ¨ y ˙ ( x ˙ 2 + y ˙ 2 ) 3 2 1 R m i n θ = arctan 2 L sin α l d < θ m a x ( x t x s + x e 2 ) 2 + ( y t y s + y e 2 ) 2 1 2 x s x e 2 + y s y e 2

2.5. Objective Function

The objective function needs to minimize the error of tractor automatic navigation and maximize the land utilization. Therefore, m is designed as follows:
m = w 1 d m a x + w 2 4 s π x s x e 2 + y s y e 2 w 1 + w 2 = 1 , ( 0 < w 1 < 1 , 0 < w 2 < 1 )
where m is the objective function value, (xs,ys) is the coordinate of key point Ps, (xe,ye) is the coordinate of key point Pe, and dmax and s’ are defined as Equations (29) and (30), respectively.
d m a x = m a x d 0 , d 1 , , d i ,
where d’i is the error value of the ith tractor path tracking simulation and d’i is the maximum error value in this tractor path tracking simulation.
s = S w 1 + S w 2 = w x s x 0 2 + y s y 0 2 + x e x 6 2 + y e y 6 2
where SW1 is the area of area W1 as in Figure 6, SW2 is the area of area W2 as shown in Figure 6, s’ is the total area of wasteful land, (xs,ys) represents the coordinate of key point Ps, (xe,ye) is the coordinate of key point Pe, (x1,0,y1,0) is the coordinate of control point P1,0, and (x2,3,y2,3) is the coordinate of control point P2,3.

2.6. Search Strategy of Optimal Control Points

In this paper, GA is used to search for the optimum control points, and the search strategy of optimal control points consists of two processes [23]. First, the individual and population are established using Equation (23), and the fitness function is established using Equation (26). Secondly, the kinematic model of the tractor is combined with GA to search for obstacle avoidance paths that meet the constraints of Equation (26).

2.6.1. Individual Establisher

In GA, an individual is expressed by Si = {P1,0,P1,1,P1,2,P1,3,P2,0,P2,1,P2,2,P2,3}∈Ω, where Ω is the search space [24,25]. Each individual consists of discrete units called genes, and genes are the control point coordinate in this paper. The control points and Equation (1) are used to generate the obstacle avoidance path. Then, the obstacle avoidance path of the WGS84 coordinate system is obtained using Equation (31):
l o n l a t = arcsin y x 2 + y 2 × 180 π a r c c o s ( x 2 + y 2 A ) × 180 π
where (lon,lat) is the coordinate of a point in the WGS84 coordinate system, (x,y) is the coordinate of a point in the rectangular coordinate system, and A is defined as follows:
A = a 2 / a 2 cos ( lon ) 2 + b 2 sin ( lon ) 2 1 2
where a is the semi-major axis of the earth ellipsoid and b is the semi-minor axis of the earth ellipsoid.

2.6.2. Fitness Function

The fitness function is established according to the objective function shown in Equation (25) and constraint functions shown in Equation (33).
f = X m = X d m a x + 4 s π x s x e 2 + y s y e 2
where f is the fitness function value and X is defined as follows:
x = 1   i f   o b s t a c l e   a v o i d a n c e   p a t h   s a t i s f y   t h e   E q u a t i o n   ( 24 ) 0   e l s e

3. Results and Discussion

3.1. Experimental Settings

To evaluate the algorithm proposed in this paper, we designed an experiment with the parameters in Table 1. First, we set up a semicircle with a radius of 3 m to envelop the obstacle in the field. Then, the key point coordinates and radius of the semicircle were input into GA to calculate the optimum obstacle avoidance path. In addition, the population size was set to 80, the mutation probability was 0.7, and the crossover probability was 0.64. The number of iterations affected the result and computation time. Therefore, iterations will be terminated when the average fitness of the population exceeds 10 times at a constant value. Finally, the tractor automatic navigation error and wasted land area were obtained. The results obtained by the algorithm in references and this paper are compared.
This paper used the modified Dongfanghong LF1104-C tractor with the automatic navigation function as the experimental platform, as shown in Figure 7. Dongfanghong has remote control and positioning and navigation functions. It is equipped with an automatic steering system, tractor control system, radar and visual measurement system, remote video transmission system, monitoring system, remote control system, and other information and control systems [26]. The specific parameters of the tractor are shown in Table 2.
At the same time, an industrial computer with a Windows 10 operating system and a corn planter with a width of 2.4 m were installed on the tractor. The software of the whole experimental system was developed based on Python, the hardware was controlled by a single chip microcomputer, and the CAN bus was used for data transmission between software and hardware [27]. The experiment was conducted at the Anhui Agricultural University Wanbei comprehensive experimental station, where the field was flat enough for us to set-up artificial obstacles.
The obstacle in Figure 8a is not within the operating range of the agricultural machine, which remains in normal operating condition. In Figure 8b, the LIDAR device on the agricultural machine detects the presence of obstacles in the current operation line and starts the obstacle avoidance operation of the current operation line, the obstacle avoidance operation is shown in Figure 8c to Figure 8i. When the farm machine bypasses the obstacle, the end point of the third-order Bessel curve will cause the farm machine to return to the original operation row, as in Figure 8i, and the farm machine will continue to drive along the original planning path, as in Figure 8j.

3.2. Obstacle Avoidance Path Planning

The coordinates of key points collected through BeiDou positioning equipment are shown in Table 3. The results of the average population fitness value are shown in Figure 9. It can be noticed from the figure that the highest average population fitness value of the experiment was 4.09597 at the 20th iteration. In the experiment, the iterations were terminated when we reached the point that increasing the number of iterations by more than 10 no longer affected the result. In our result, the point was 20. Therefore, we obtained the optimal solution when the number of iterations was 30.
The algorithm of obstacle avoidance path planning with the objective of curvature continuity proposed by Xi et al. is a popular method in recent years [5]. Lee et al. proposed a novel obstacle avoidance algorithm for mobile robots based on finite memory filtering (FMF) [28]. So, we chose these to compare the performance of the algorithm proposed in this paper. The results of the obstacle avoidance path are shown in Figure 10. There are four obstacle avoidance paths in Figure 10; one path is the obstacle avoidance path planned by the algorithm in this paper (TA). The other three comparison algorithms are the obstacle avoidance path planned by the algorithm of Xi et al. (PR), the obstacle avoidance path planned by the algorithm of Lee (DWA), and the artificial potential field method (APF).
The smoothness of the obstacle avoidance path affects the path tracking accuracy. The smoother the path, the smaller the curvature, and the smaller the curvature, the higher the tractor path tracking accuracy. The results of the comparison between TA and PR in terms of maximum curvature, average curvature, and wasted land area are presented in Table 4. As shown in Table 4, the curvature value of TA was much smaller than those of the other three algorithms, and the land wasted area of TA was also much smaller than those of PR and DWA. Although the land wasted area was smaller for APF, the curvature value for APF was too large and more demanding for the steering operation of the farm machinery. Therefore, TA was more advantageous than the other three algorithms.

3.3. Field Experiment

We conducted a field experiment to verify the performance of the algorithm in this paper. In the experiment, the initial position of the tractor was set to deviate from the obstacle avoidance path by 0.01 m, and the initial wheel angle and speed of the tractor were 0° and 2 m/s, respectively. The results are shown in Figure 11 and Figure 12.
The path tracking results for TA and PR are shown in Figure 11. The navigation errors are illustrated in Figure 12. From Figure 12a, it can be observed that the maximum navigation error and the average navigation error of TA were 0.144 m and 0.048 m, respectively. The maximum navigation error and the average navigation error of PR were 0.215 m and 0.082 m, respectively. The maximum navigation error and the average navigation error of TA were 33% and 41.5% lower than those of PR, respectively. The navigation errors obtained from the statistical experiments and the final results are shown in Figure 12b.
From Figure 12b, it can be observed that more than 50% of TA navigation errors were less than 0.05 m, while only 35.4% of PR errors were less than 0.05 m. TA errors were less than 0.15 m, while 14.9% of PR errors were larger than 0.15 m. In short, compared with the current mainstream obstacle avoidance path planning algorithms, the algorithm proposed in this paper plans a smoother obstacle avoidance path and can further improve the tractor path tracking accuracy.

4. Conclusions

In this paper, a new method for the tractor obstacle avoidance path planning is proposed. The third-order Bezier curve is used to plot the obstacle avoidance path. Therefore, in this paper, the optimal obstacle avoidance path is generated by searching for the optimal control points. The key point coordinates of the obstacle avoidance path are determined by the global path and obstacle information, and the control point selection range is determined by the key point coordinates. GA is used to search for the optimal control points from the control point selection range and the optimal obstacle avoidance path satisfying the tractor obstacle avoidance constraint, the minimum turning radius constraint, and the tractor kinematic constraint generated by the optimal control point. The algorithm proposed in this paper is superior to some existing methods in terms of navigation accuracy and wasted land area for the planned path.

Author Contributions

Writing—original draft preparation, H.C.; writing—review and editing, H.X.; validation, L.S.; supervision, T.S. All authors have read and agreed to the published version of the manuscript.

Funding

This research received no external funding.

Institutional Review Board Statement

Not applicable.

Data Availability Statement

Not applicable.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Al-Mayyahi, A.; Aldair, A.A.; Rashid, A.T. Intelligent Control of Mobile Robot Via Waypoints Using Nonlinear Model Predictive Controller and Quadratic Bezier Curves Algorithm. J. Electr. Eng. Technol. 2020, 15, 1857–1870. [Google Scholar] [CrossRef]
  2. Panda, B.K.; Bhanja, U.; Pattnaik, P.K. Obstacle and mobility aware optimal routing for manet. J. Intell. Fuzzy Syst. 2019, 37, 1007–1017. [Google Scholar] [CrossRef]
  3. Zambom, A.Z.; Seguin, B.; Zhao, F. Robot path planning in a dynamic environment with stochastic measurements. J. Glob. Optim. 2019, 73, 389–410. [Google Scholar] [CrossRef]
  4. Ren, H.; Chen, S.; Yang, L.; Zhao, Y. Optimal Path Planning and Speed Control Integration Strategy for UGVs in Static and Dynamic Environments. IEEE Trans. Vehicular Technol. 2020, 69, 10619. [Google Scholar] [CrossRef]
  5. Xiaobo, X.; Yangjie, S.; Xiang, S.; Qi, Z.; Yifu, J.; Junjie, G.; Jianfeng, Z.; Ruihong, Z. Obstacle avoidance path control method for agricultural machinery automatic driving based on optimized Bezier. Trans. Chin. Soc. Agric. Eng. 2019, 35, 82–88. [Google Scholar]
  6. Wan, N.; Xu, D.; Ye, H. Improved cubic B-spline curve method for path optimization of manipulator obstacle avoidanc. In Proceedings of the Chinese Automation Congress (CAC), Xi’an, China, 30 November–2 December 2018. [Google Scholar]
  7. Han, G.; Zhou, Z.; Zhang, T.; Wang, H.; Liu, L.; Peng, Y.; Guizani, M. Ant-Colony-Based Complete-Coverage Path-Planning Algorithm for Underwater Gliders in Ocean Areas with Thermoclines. IEEE Trans. Vehicular Technol. 2020, 69, 8959–8971. [Google Scholar] [CrossRef]
  8. Chen, W.; Sun, J.; Li, W.; Zhao, D. A real-time multi-constraints obstacle avoidance method using LiDAR. J. Intell. Fuzzy Syst. 2020, 39, 119–131. [Google Scholar] [CrossRef]
  9. Wang, X.; Yan, Y.; Gu, X. Spot welding robot path planning using intelligent algorithm. J. Manuf. Process. 2019, 42, 1–10. [Google Scholar] [CrossRef]
  10. Song, B.; Wang, Z.; Zou, L. An improved PSO algorithm for smooth path planning of mobile robots using continuous high-degree Bezier curve. Appl. Soft Comput. 2021, 100, 106960. [Google Scholar] [CrossRef]
  11. Chen, X.; Zhao, M.; Yin, L. Dynamic Path Planning of the UAV Avoiding Static and Moving Obstacles. J. Intell. Robotic Syst. 2020, 99, 909–931. [Google Scholar] [CrossRef]
  12. Zhong, X.; Tian, J.; Hu, H.; Peng, X. Hybrid Path Planning Based on Safe A* Algorithm and Adaptive Window Approach for Mobile Robot in Large-Scale Dynamic Environment. J. Intell. Robotic Syst. 2020, 99, 65–77. [Google Scholar] [CrossRef]
  13. Hao, K.; Zhao, J.; Yu, K.; Li, C.; Wang, C. Path Planning of Mobile Robots Based on a Multi-Population Migration Genetic Algorithm. Sensors 2020, 20, 5873. [Google Scholar] [CrossRef] [PubMed]
  14. Receveur, J.B.; Victor, S.; Melchior, P. Autonomous car decision making and trajectory tracking based on genetic algorithms and fractional potential fields. Intell. Service Robot. 2020, 13, 315–330. [Google Scholar] [CrossRef]
  15. Ajeil, F.H.; Ibraheem, I.K.; Azar, A.T.; Humaidi, A.J. Autonomous navigation and obstacle avoidance of an omnidirectional mobile robot using swarm optimization and sensors deployment. Int. J. Adv. Robot. Syst. 2020, 17, 172988142092949. [Google Scholar] [CrossRef]
  16. Zhang, Z.; Cao, Y.; Ding, M.; Zhuang, L.; Tao, J. Monocular vision based obstacle avoidance trajectory planning for Unmanned Aerial Vehicle. Aerospace Sci. Technol. 2020, 106, 106199. [Google Scholar] [CrossRef]
  17. Elhoseny, M.; Tharwat, A.; Hassanien, A.E. Bezier Curve Based Path Planning in a Dynamic Field using Modified Genetic Algorithm. J. Comput. Sci. 2018, 25, 339–350. [Google Scholar] [CrossRef]
  18. 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-Papers OnLine 2019, 52, 173–177. [Google Scholar] [CrossRef]
  19. Yi, D.; Zhang, Y.; Tsang, H.K. Optimal Bezier Curve Transition for Low-Loss Ultra-compact S bends. Opt. Lett. 2022, 15, 876–879. [Google Scholar] [CrossRef]
  20. Kim, J. Trajectory Generation of a Two-Wheeled Mobile Robot in an Uncertain Environment. IEEE Trans. Ind Electron. 2019, 67, 5586–5594. [Google Scholar] [CrossRef]
  21. Bai, G.; Meng, Y.; Liu, L.; Luo, W.; Gu, Q.; Li, K. Anti-sideslip path tracking of wheeled mobile robots based on fuzzy model predictive control. Electron. Lett. 2020, 56, 490–493. [Google Scholar] [CrossRef]
  22. Chen, Y.; Chen, S.; Ren, H.; Gao, Z.; Liu, Z. Path Tracking and Handling Stability Control Strategy With Collision Avoidance for the Autonomous Vehicle Under Extreme Conditions. IEEE Transactions on Vehicular Technol. 2020, 69, 14602–14617. [Google Scholar] [CrossRef]
  23. Rodrigues, L.L.; Potts, A.S.; Vilcanqui, O.A.; Sguarezi Filho, A.J. Tuning a model predictive controller for Doubly Fed Induction Generator employing a constrained Genetic Algorithm. IET Electric Power Appl. 2019, 13, 812–819. [Google Scholar] [CrossRef]
  24. Gonzalez, J.L.; Jo, P.K.; Abbaspour, R.; Bakir, M.S. Flexible Interconnect Design Using a Mechanically-Focused, Multi-Objective Genetic Algorithm. J. Microelectromech. Syst. 2018, 27, 677–685. [Google Scholar] [CrossRef]
  25. Ali, H.; Gong, D.; Wang, M.; Dai, X. Path Planning of Mobile Robot With Improved Ant Colony Algorithm and MDP to Produce Smooth Trajectory in Grid-Based Environment. Front. Neurorobot. 2020, 14, 44. [Google Scholar] [CrossRef] [PubMed]
  26. Han, X.; Kim, H.J.; Jeon, C.W.; Moon, H.C.; Kim, J.H.; Yi, S.Y. Application of a 3D tractor-driving simulator for slip estimation-based path-tracking control of auto-guided tillage operation. Biosyst. Eng. 2019, 178, 70–85. [Google Scholar] [CrossRef]
  27. Yang, Y.; Zhou, Y.; Yue, X.; Zhang, G.; Wen, X.; Ma, B.; Xu, L.; Chen, L. Real-time detection of crop rows in maize fields based on autonomous extraction of ROI. Expert Syst. Appl. 2023, 213, 118826. [Google Scholar] [CrossRef]
  28. Lee, D.H.; Lee, S.S.; Ahn, C.K.; Shi, P.; Lim, C.C. Finite Distribution Estimation-based Dynamic Window Approach to Reliable Obstacle Avoidance of Mobile Robot. IEEE Trans. Ind. Electron. 2020, 35, 82–88. [Google Scholar] [CrossRef]
Figure 1. Third-order Bezier curve.
Figure 1. Third-order Bezier curve.
Agriculture 13 00934 g001
Figure 2. Obstacle avoidance path model.
Figure 2. Obstacle avoidance path model.
Agriculture 13 00934 g002
Figure 3. Tractor model. Note: The shape of the four-wheeled tractor is shown as a red dashed area and the approximate two-wheeled tractor is shown as a red straight area. γ indicates the steering angle of the steering wheel (front wheel deflection) and the velocity of the rear wheel in the x-axis direction is v. The front and rear wheel axes are shown as black dashed lines, the intersection of which is the instantaneous center of rotation (ICR); the blue dashed lines indicate the steering trajectory; the distances from the front and rear wheels to the instantaneous center are R1 and R2, respectively. L is the length of the tractor or wheel base. A (xA, yA) are the rear axle coordinates, B(xB, yB) are the front axle coordinates, θ is the traverse angle (heading angle) of the tractor, w is the traverse angular velocity of the tractor, vA is the front axle center velocity, and vB is the rear axle center velocity of the tractor.
Figure 3. Tractor model. Note: The shape of the four-wheeled tractor is shown as a red dashed area and the approximate two-wheeled tractor is shown as a red straight area. γ indicates the steering angle of the steering wheel (front wheel deflection) and the velocity of the rear wheel in the x-axis direction is v. The front and rear wheel axes are shown as black dashed lines, the intersection of which is the instantaneous center of rotation (ICR); the blue dashed lines indicate the steering trajectory; the distances from the front and rear wheels to the instantaneous center are R1 and R2, respectively. L is the length of the tractor or wheel base. A (xA, yA) are the rear axle coordinates, B(xB, yB) are the front axle coordinates, θ is the traverse angle (heading angle) of the tractor, w is the traverse angular velocity of the tractor, vA is the front axle center velocity, and vB is the rear axle center velocity of the tractor.
Agriculture 13 00934 g003
Figure 4. Tractor path tracking model. Note: C is a preview point on the planned path. Ld is the distance between the tractor rear axle and preview point C. 2α is the angular deviation of the tractor with respect to the preview point C. CS is the point on the planned path with the least distance from the tractor.
Figure 4. Tractor path tracking model. Note: C is a preview point on the planned path. Ld is the distance between the tractor rear axle and preview point C. 2α is the angular deviation of the tractor with respect to the preview point C. CS is the point on the planned path with the least distance from the tractor.
Agriculture 13 00934 g004
Figure 5. Control point selection range. (a) Key point coordinates, (b) Control point selection range.
Figure 5. Control point selection range. (a) Key point coordinates, (b) Control point selection range.
Agriculture 13 00934 g005
Figure 6. An example of wasteful land.
Figure 6. An example of wasteful land.
Agriculture 13 00934 g006
Figure 7. Dongfanghong LF1104-C.
Figure 7. Dongfanghong LF1104-C.
Agriculture 13 00934 g007
Figure 8. Experimental platform and experimental site.
Figure 8. Experimental platform and experimental site.
Agriculture 13 00934 g008
Figure 9. Result diagram of average population fitness value in GA.
Figure 9. Result diagram of average population fitness value in GA.
Agriculture 13 00934 g009
Figure 10. Obstacle avoidance path planning by different algorithm.
Figure 10. Obstacle avoidance path planning by different algorithm.
Agriculture 13 00934 g010
Figure 11. The result of path tracking.
Figure 11. The result of path tracking.
Agriculture 13 00934 g011
Figure 12. Navigation error of tractor path tracking. (a) Navigation error of tractor path tracking, (b) A navigation error comparison between TA and PR.
Figure 12. Navigation error of tractor path tracking. (a) Navigation error of tractor path tracking, (b) A navigation error comparison between TA and PR.
Agriculture 13 00934 g012
Table 1. Parameters of obstacle avoidance path planning.
Table 1. Parameters of obstacle avoidance path planning.
ParameterValue
d12.5 m
w2.4 m
L2.06 m
Rmin4 m
θmaxπ/6
Note: d1 is the distance from the point on the planned path that is the smallest distance from the tractor to the preview point on the path, w is the width of the job line, L is the tractor wheelbase, Rmin is the minimum turning radius of the tractor, θmax is the maximum turning angle of tractor.
Table 2. Dongfanghong LF1104-C basic parameters.
Table 2. Dongfanghong LF1104-C basic parameters.
ModelLF1104-C
TypeFour-Wheel Drive
PTO Power (Kw)≥67
Maximum Traction (Kn)19.8
Length (Including Suspension)4436
Width (Factory Wheelbase)2250
Height2765
Wheelbase (Mm)2314
Front Wheel (Factory Wheelbase)1748–2000 (1760)
Rear Wheel (Factory Wheelbase)1620–2120 (1632)
Ground Clearance (Mm)440 (Under The Bent Rod Housing)
Front Counterweight (Kg)400
Rear Counterweight (Kg)300
Minimum Operation Mass (Assembly Frame Without Counterweight, With Cab (Kg))4250
Table 3. Longitude and latitude coordinates of key points.
Table 3. Longitude and latitude coordinates of key points.
Key PointsCoordinates
ps(117.07882885798031, 33.69548283272718)
pv(117.0787965, 33.69550988)
pe(117.07882885798195, 33.69553692727986)
Table 4. The data of path curvature and wasted land area with different path planning methods.
Table 4. The data of path curvature and wasted land area with different path planning methods.
PathkmaxkaveSp/m2
TA0.660.1723.14
PR1.710.1236.00
APF4.730.7922.61
DWA1.820.1338.17
Note: kmax is the maximum curvature, kave is the mean curvature, Sp is wasteful land area.
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

Chen, H.; Xie, H.; Sun, L.; Shang, T. Research on Tractor Optimal Obstacle Avoidance Path Planning for Improving Navigation Accuracy and Avoiding Land Waste. Agriculture 2023, 13, 934. https://doi.org/10.3390/agriculture13050934

AMA Style

Chen H, Xie H, Sun L, Shang T. Research on Tractor Optimal Obstacle Avoidance Path Planning for Improving Navigation Accuracy and Avoiding Land Waste. Agriculture. 2023; 13(5):934. https://doi.org/10.3390/agriculture13050934

Chicago/Turabian Style

Chen, Hongtao, Hui Xie, Liming Sun, and Tansu Shang. 2023. "Research on Tractor Optimal Obstacle Avoidance Path Planning for Improving Navigation Accuracy and Avoiding Land Waste" Agriculture 13, no. 5: 934. https://doi.org/10.3390/agriculture13050934

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

Article Metrics

Back to TopTop