Next Article in Journal
Systemic Effects of Nitrate on Nitrogen Fixation and Sucrose Catabolism in Soybean (Glycine max (L.) Merr.) Nodules
Previous Article in Journal
A Lightweight Algorithm for Detection and Grading ofOlive Ripeness Based on Improved YOLOv11n
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Research on 3D Obstacle Avoidance Path Planning for Apple Picking Robotic Arm

1
College of Mechanical and Electronic Engineering, Nanjing Forestry University, Nanjing 210037, China
2
Co-Innovation Center of Efficient Processing and Utilization of Forest Resources, Nanjing Forestry University, Nanjing 210037, China
3
Institute of Agricultural Facilities and Equipment, Jiangsu Academy of Agricultural Sciences, Nanjing 210014, China
*
Author to whom correspondence should be addressed.
Agronomy 2025, 15(5), 1031; https://doi.org/10.3390/agronomy15051031
Submission received: 29 March 2025 / Revised: 17 April 2025 / Accepted: 21 April 2025 / Published: 25 April 2025
(This article belongs to the Section Precision and Digital Agriculture)

Abstract

:
To address the challenges of obstacle avoidance and low efficiency by robotic arms during apple picking, this paper proposes an improved informed-RRT* motion planning algorithm to improve path planning performance. By integrating the artificial potential field method, the unique location points within the planning space are identified. Segmenting the path planning further accelerates the path searching efficiency. The algorithm includes target bias and cosine offset strategies, along with bidirectional planning to improve planning efficiency, enhancing the purposefulness of informed-RRT* sampling. Spatially expanding sampling by dynamic step size enhances the robustness of path indexing in complex obstacle environments. The algorithm is compared with RRT* and in-formation-RRT* in several scenarios. The experimental results show that compared to RRT* and IRRT*, the average path cost of the optimization algorithm is reduced by 31.565 mm and 14.935 mm and the average search time is reduced by 7.18 s and 4.33 s. In the complex two-dimensional simulation experiment, compared to RRT* and IRRT*, the average path cost of the optimization algorithm is reduced by 362.4 mm and 343.5 mm and the average search time is reduced by 5.49 s and 1.54 s. In the 3D simulation, compared to RRT* and IRRT*, the average path cost is reduced by 1110.17 mm and 469.97 mm and the average search time is reduced by 37.82 s and 11.26 s. The optimization algorithm effectively reduces the total length of the picking path and the path planning time. The research results provide a reference for apple picking robots to perform collision-free picking tasks.

1. Introduction

Apples are among the most widely cultivated fruits in the world [1]. In recent years, the apple industry in China has expanded significantly, resulting in a continuous increase in orchard area. However, traditional apple-picking work relies heavily on manual labor, leading to increased labor costs. With the development of science and technology, the development of apple-picking robots has become an important research direction to improve the efficiency of apple harvesting. Mechanizing apple picking significantly reduces labor requirements and promotes industry growth [2]. It also solves the problems of labor shortage and resource inefficiency [3]. Typically, apple-picking robots first move to a suitable picking position, use vision systems to identify apple positions, and then the robotic arm harvests the fruit based on the visual information. In the natural environment, apple growth is random and often obstructed by branches and leaves, making the motion planning of the picking robots more complicated [4]. Therefore, effective robotic arm path planning can directly improve picking success and reduce harvesting time.
Existing motion planning algorithms for robotic arms are classified into four categories: traditional planning algorithms, biological intelligence algorithms, deep reinforcement learning algorithms, and probabilistic sampling algorithms [5]. Traditional planning algorithms include A* and Dijkstra. The traditional planning algorithm is simple and easy [6]. However, when dealing with large-scale maps and dynamic environments, the computational load will be larger and the real-time performance will be affected [7]. Biological intelligence algorithms include the ant colony algorithm [8] and particle swarm algorithm [9]. Biological intelligence algorithms can show strong robustness in the face of complex problems but the calculation cost is high and the precision is low. Deep reinforcement learning algorithms [10,11] are mainly divided into value-function-based methods and strategy-gradient-based methods, etc. Deep reinforcement learning algorithms can solve path planning problems in complex environments but the sample efficiency is low and the reward function design is difficult. Probabilistic sampling algorithms can avoid constructing an accurate configuration planning space, effectively reducing planning time and thus becoming the mainstream in robotic path planning. Rapidly exploring random tree (RRT) is a typical probabilistic sampling search algorithm proposed by Lavalle [12]. The algorithm uniformly samples the whole environment space. Due to its randomness, broad search range, and extensive coverage, RRT performs effectively in large-scale environments without requiring complex parameter adjustments. However, in complex environments, RRT suffers from inefficiency, underutilized sampling points, and does not guarantee an optimal solution [13,14,15].
Many researchers have investigated the limitations of RRT, particularly its low efficiency and poor-quality paths. Notable improvement variants based on the RRT mainly include RRT-CONNECT and RRT* [16]. RRT-CONNECT generates node trees simultaneously at the starting and target points, and the node trees are explored independently until they are connected to create paths. Although RRT-CONNECT improves search efficiency, it still has shortcomings such as excessive sampling ranges, slow convergence, and paths that are overly complex and difficult to optimize. To address these issues, some scholars used the greedy algorithm, which significantly shortens the convergence time and improves the quality of the path [17]. RRT* adds the optimization of nodes based on RRT, which mainly carries out the reselection of the parent node and the rewiring operation. The optimal parent and child nodes are selected using the cost function. Finally, the path is continuously optimized by iteratively calculating the path cost for each node in this node tree. However, RRT* still exhibits slow convergence and low overall efficiency. To address these problems, Cao et al. introduced gravitational vectors to the basic RRT [18]. This allows the RRT to have a certain direction in the search process, which can help find the path faster. Finally, the obtained paths are smoothed. Experimental comparisons show that the improved algorithm obtains higher quality paths and faster path search speed. Chen et al. made an improvement on the basis of RRT-CONNECT [19]. Target bias and adaptive step size strategy are introduced to speed up the path search. A two-way pruning optimization strategy with a three-times nonuniform B-spline interpolation method is used to smooth the generated paths. The simulation and comparison test results show that the improved algorithm reduces the path planning time and path distance by 55% and 60%, respectively. Gammel et al. added elliptic subset constraints based on RRT* and proposed the asymptotically optimal informed-RRT* algorithm, which effectively improves the quality of indexed paths [20]. Wang et al. proposed a picking motion planning algorithm (PGI-RRT*) based on prepicking guidance points [21]. PGI-RRT* is based on the informed-RRT* algorithm, which selects the third point between the initial and target points as the prepicking guidance point. Four random trees are generated simultaneously among the initial point, the target point, and the bootstrap point for fast path acquisition. In the PGI-RRT* algorithm, P probability sampling is used instead of random sampling. This reduces the randomness of sampling and generates new nodes in dynamic steps. It improves the speed and flexibility of the PGI-RRT* algorithm to explore the unknown space as well as the convergence speed of the algorithm. Simulation test results show that the PGI-RRT* algorithm reduces initial path-finding time by 75% to 86% and improves the success rate by 18% to 32% compared to informed-RRT*.
As the application range for robotic arm path planning expands and operating environments grow more complex, no single algorithm adequately meets all conditions. Although some scholars have improved the single algorithm, the adaptability is poor when facing a changing and complex environment in the forest. The method of algorithm fusion is simple, effective, and targeted. To improve the efficiency and quality of robotic arm picking path planning in complex apple orchard environments, this paper proposes an adaptive subnode tree RRT* robotic arm path planning algorithm. An artificial potential field is introduced into the RRT* algorithm. The artificial potential field method is a path planning technique based on a force field model, which generates an attractive force to attract a robot by setting a goal to generate an attractive force and a repulsive force from an obstacle to avoid the robot colliding with the obstacle. This method strategically determines the positions of new nodes and the direction of tree expansion to accelerate convergence and reduce the path cost. It can be varied according to the environment while expanding the step size. The generated path can be optimized by pruning the path with a three-times B-spline interpolation function to produce relatively smooth curves. Finally, the algorithm is substituted to control the 6-axis UR5 robotic arm for apple picking with obstacles.

2. Materials and Methods

2.1. Description of Apple-Picking Robotic Arm Motion Planning

Configuration space, commonly referred to as C-space, is an essential concept in robotic arm motion planning [22]. The C-space consists of all possible configurations, each defined by a combination of all joint angles. The dimension of the joint space is equal to the degrees of freedom of the robotic arm, and points in the configuration space can be described by q = {q1, q2 …, qn} ∈ Rn. The portion of the joint space that does not collide with environmental obstacles is known as the free joint space Cfree. Thus, the motion planning problem for a robotic arm can be described as follows: given an initial position state Xstart and the end position state Xgoal. The final finding time T is associated with a set of control variables u: [0, T] → U. This can be performed for all t ∈ [0, T] and fulfill q(x(t)) ∈ Cfree. In a given environment, the start and end positions are specified and the trajectory connecting the start and end points and satisfying certain constraints is computed in a specified time.

2.1.1. From End-Path Collision-Free to Robotic Arm Motion Collision-Free

Ensuring collision-free movement from the end effector path to full robotic arm motion is crucial to achieve obstacle avoidance picking of the robotic arm of the picking robot. Firstly, the motion model of the robotic arm is established by the D-H method. Secondly, the obstacles in the orchard are simplified based on their geometrical shapes to construct a reasonable obstacle collision detection model. Thirdly, the improved algorithm and the enclosing box method are used for fast collision detection to obtain the end collision-free path in the complex environment. Finally, the collision-free movement of the robotic arm is based on the end collision-free path, which is interpolated by a B-spline curve to obtain a smooth and continuous collision-free path curve of the robotic arm motion.

2.1.2. Kinematic Model of the Apple-Picking Robot Arm

Figure 1 illustrates a 3D model of the UR5 robot arm, which consists entirely of rotary joints. Joint six is coupled with an end effector for grasping apples. Apples grow in a variety of directions. Low-degree-of-freedom robotic arms may not be able to avoid branches and leaves. The UR5 robot arm is a six-degree-of-freedom robot arm. It works together through joint motion and end Cartesian space motion. Then, using inverse kinematics to calculate the angle, it can reach any attitude. In addition, the UR5 robot arm loads 5 kg, which matches the weight of the apple. The UR5 robot arm is a lightweight robot arm for easy mobile deployment.
The DH parameter method of the robot mechanism was used to establish the coordinate relationship between the mutual axes [23]. The relevant data are shown in Table 1. The coordinate system is illustrated in Figure 2. The equation of positive motion is shown in Equation (1). The inverse motion equation is shown in Equation (2).
T 6 0 = T 1 0 · T 2 1 · T 3 2 · T 4 3 · T 5 4 · T 6 5 = n x o x a x p x n y a 22 a 23 p y n z a 32 a 33 p z 0 0 0 1
n x o x a x p x n y a 22 a 23 p y n z a 32 a 33 p z 0 0 0 1 = T 1 0 ( J 1 ) · T 2 1 ( J 2 ) · T 3 2 ( J 3 ) · T 4 3 ( J 4 ) · T 5 4 ( J 5 ) · T 6 5 ( J 6 ) = T 6 0 ( J )

2.1.3. Robotic Arm and Branch Collision Detection

Modern apple orchards increasingly utilize a combination of dwarfing rootstocks [24] and superior varieties. This approach is characterized by short trees and early fruiting. It is convenient for intensive management and can significantly save labor costs. It improves orchard management efficiency and facilitates the implementation of mechanization. Modern orchards have a semistructured environment, with trees of the same type planted in evenly spaced rows [25]. Typically, the plant spacing is 1–2.5 m and the row spacing is 3–4.5 m. The picking robot travels in this space. The picking robot drives the robotic arm to complete the picking. In the study of the apple robotic arm picking path planning problem, in order to avoid the movement of the robotic arm and collision with fruit tree branches, the robotic arm and fruit tree branches need to undergo collision detection [26]. The collision detection function returns the collision between the robotic arm and the obstacle to the path planning process. This enables collision-free path planning.
Apple trees consist primarily of twigs, branches, fruits, and leaves. During robotic picking, the leaves and branches near the apples to be picked are small obstacles to the picking process. The main obstacles that are recognized and segmented as obstacles are branches, trunks, and unripe fruits. As a result, collision detection mainly focuses on the robotic arm with the apple trunk and branches. This link is time-consuming and computationally intensive, while the computational efficiency is usually low.
To improve the efficiency of collision detection, the enveloping box method can be employed to simulate the complex environment of apple trees with intertwined branches. The box-around method is a more appropriate choice. Simple regular geometry is used to enclose complex-shaped objects, which approximates the actual geometric features of the complex objects. The encircled model is then subjected to collision detection with a robotic arm. This detection method allows for fast collision detection. It can cover the enclosed objects closely and facilitate the calculation.
A collision-free path is generated through point-by-point detection, and the point will be discarded if a collision is detected. In this process, the obstacles are reduced to geometric models and the trunks and branches are reduced to cylinders of different sizes. The manipulator consists of six connecting rods to construct six cylindrical models. Therefore, in one position, collision detection will be performed six times between the robot arm and the obstacle to detect if a collision occurs. Any link of the robot arm colliding with an obstacle is considered a collision between the robot and the obstacle. Nodes causing collisions are discarded. The flow chart is shown in Figure 3. The schematic diagram is shown in Figure 4. This paper takes the six-axis UR5 robot arm as the object of study. It simplifies the link to a cylinder according to the inherent geometrical characteristics of the manipulator. Consequently, the collision detection problem between the manipulator and the obstacle is transformed into the collision detection problem between the cylinder and the sphere, the cylinder and the cylinder.

2.2. Informed-RRT* Algorithm

RRT* enhances parent node selection in the RRT algorithm through parent node reselection and rewiring based on a cost function. In each iteration, nodes in the expanded tree are recalculated to continuously optimize the path. With sufficient run time, RRT* converges toward the optimal solution, yielding shorter and smoother paths. Thus, the efficiency of the apple-picking robotic arm will be improved.
The detailed procedure for node selection in RRT* is shown in Figure 5 and Figure 6. When the newly generated node is the center of the circle, the parent node is selected again. All existing nodes within a specified radius are evaluated to determine the optimal parent node. The principle of reselection is to connect all the new nodes and get the node with the smallest path cost when backtracking to the initial position. In addition to reselecting the parent node, the rewiring strategy is a reselection of the child nodes. Acquiring all the path nodes within a given radius of the new node, so that the newly generated path node acts as the parent node and the rest of the nodes are children. In principle, the selected node generates the path with the new node at the least cost. RRT* optimizes the path by means of parent node reselection and rewiring methods. As the algorithm iteratively progresses, the paths gradually approach optimality. But the RRT* algorithm increases the path indexing time to some extent, making the picking efficiency of the robotic arm inefficient during apple picking.
Informed-RRT* obtains the initial elliptic sampling range based on RRT*, as shown in Figure 7. The path line length is the short axis of the ellipse and the path cost is the long axis of the ellipse. In this way, the search space can be reduced, the search scope can be accelerated, and the optimal path can be obtained in the iteration. Nevertheless, the algorithm still has many problems, as shown in Figure 8. The node search strategy of informed-RRT* remains global and somewhat random, leading to inefficient convergence. During planning, the path cost obtained for the first time is more dependent on RRT* and the planning efficiency is low [27]. Moreover, the path is not smooth.

2.3. Algorithm Improvement

To overcome these limitations, this paper proposes an improved informed-RRT* algorithm. The algorithm flow chart is shown in Figure 9. When paths are indexed, multisegment planning is performed and probabilistic bias strategies are added. The node tree grows in dynamic steps as it expands, which reduces the randomness of path planning. Then, the inflection points are optimized by B-spline interpolation to obtain a smooth path. Smooth paths can improve picking efficiency.

2.3.1. Environmental A Priori Sampling

The sampling strategy of informed-RRT* is to limit the sampling area using the initial path cost of RRT* as an a priori condition. But this slows down convergence and requires a lot of path optimization iterations. Additionally, searching directly between start and goal points leads to redundant sampling, which reduces the planning efficiency. This leads to inefficient movement of the robotic arm, which is prone to jitter when picking apples. To improve the sampling efficiency, this paper proposes a priori. Subpath points in the environment that are far from the obstacles are identified and then selected by the repulsive field [28]. The repulsive force function is defined by the following equation and the calculation of the repulsive force is illustrated in Figure 10.
U r e p = 1 2 η 1 D q 1 Q 2 D ( q ) Q 0 D ( q ) > Q
The gradient repulsion is shown in Equation (4).
U r e p = η 1 Q 1 D q 1 D 2 q D q D ( q ) Q 0 D ( q ) > Q
Note: η is the repulsive gain coefficient. D(q) is the distance between the sampling point and the obstacle. Q is the radius of the obstacle.
The required subpath nodes are determined in a straight line between the start and end points by using the environment parameters. Probabilistic bias is applied to the obtained subpath nodes to increase the speed of path convergence. To simplify the calculation, this paper uses a sphere to simulate the complex environment faced by the apple-picking robotic arm during picking. For the same position sphere, the superposition of fields is used for the calculation.
To further improve the sampling efficiency, superimposed field sampling is calculated by selecting n points on a straight line between the start and end points. The m of these points is selected as subpaths used for sampling. In this paper, n is taken as 100 and m is taken as 3. The point sampling function is as follows:
X = X s t a r t + X g o a l X s t a r t X g o a l X s t a r t θ D
Note: X 2 denotes the 2-parameter of X. D is the distance from the starting point to the end point. θ is a random number generated in 0 to 1. The m points in n with smaller potentials are selected as the new substart and subterminal nodes.

2.3.2. Target Offset Sampling

Establishing an initial path cost threshold and incorporating a probability bias function during the initial RRT* search. It can further reduce the computation time and improve the planning efficiency. The probabilistic bias sampling function is shown in the following equation and the cosine bias is shown in Figure 11 [29].
X r a n d = X g o a l r p I n f o r m e d S a m p l e r > p
Xgoal is the target node of the subpath at the time of sampling. p is the probability bias parameter, which takes the value of 0.8 to improve the speed of convergence and increase the randomness of sampling. r is a random number. When the random number is less than 0.8, Xrand is a subtarget node. When the random number is greater than 0.8, elliptical geometry sampling is used.
In accordance with the gravity offset principle, the indexing ability of the algorithm is further enhanced. When the target node is not a subtarget node, increase the vector that indexes toward the target position.

2.3.3. Two-Way Planning

Bidirectional search is a commonly used improvement strategy. The basic idea of bidirectional simultaneous search is to start the wide search from the start and end points on the state graph at the same time, which can significantly improve the success rate and convergence speed of motion planning algorithms [30]. As shown in Figure 12, the algorithm in this paper uses the child nodes as intermediate points and incorporates a bidirectional search strategy. Parallel indexing of multiple random trees is achieved. Multiple random trees are located between the initial point and the subgoal node and between the subgoal bootstrap point and the total end point, so that the subgoal node serves as the initial point of the tree at the same time. This improves the indexing speed and efficiency. This also improves obstacle avoidance and picking ability of the apple-picking robotic arm during the picking process.

2.3.4. Dynamic Step Size Strategy

The informed-RRT* algorithm uses a fixed step size approach in the path planning expansion process. This method will cause the turning point of the path to be too inflexible during the path query, resulting in a turning angle that is too large. It is difficult to achieve a smooth over-path, resulting in poor quality of the planned path. To address this issue, this paper performs dynamic step-size adjustment during the indexing process for each subpath under the above total path splitting. This balances the speed and quality of path planning. Larger step sizes can speed up exploration. However, it can create redundant points and inflection points, which can lead to a decrease in the quality of the path. A smaller step size improves the quality of the path. However, it can lead to slower planning. When the generated new node is close to an obstacle, a smaller step size can make the overall path smoother. Increasing the step size improves the efficiency of path exploration when the nodes are far from the obstacles. This is the basic idea of the dynamic step size proposed in this paper. This allows the apple-picking robotic arm to plan the picking path faster. It improves the efficiency of apple picking.
The specific dynamic step size adjustment function is defined in Equation (7). λ is the step size adjustment factor. Increasing the step size adjustment coefficient can enhance the global search ability and escape the local optimal but the convergence speed decreases and the precision is low. The reduction in the step size adjustment coefficient can improve local development and enhance stability but it may fall into local optimization and lead to low search efficiency. The random tree explores the target with a ϕ-valued initial step. When unfolding a new node, if the node link does not collide with an obstacle or connect to another random tree, the node tree will increase in step size at the next time with the generated new node Xnew stacked sequentially. The larger the step size, the faster the algorithm converges. When the environment is complex, the local path of the manipulator becomes longer and the likelihood of collision with the environment is raised. Therefore, after colliding with the obstacle, the step size becomes the original step size, the adjustment factor changes from positive to negative, and the step coefficients decrease sequentially until they leave the obstacle at a longer distance.
X n e w = λ X n e a r e s t X r a n d X n e a r e s t X r a n d + X n e a r e s t
Note: λ is the step size adjustment coefficient and the determination formula is shown in Formula (8). It is dynamically adjusted by the obstacle density ρ in the region and the determination formula is shown in Equation (9).
λ = L 1 ( 1 ρ ) + L 2 ρ
Note: L1 is the maximum step size. L2 is the minimum step size. L1 > L2.
ρ = A π R 2
Note: A is the total area occupied by the obstacle. It is a circular area centered on Xnearest with R as the radius.

2.3.5. Path Smoothing

The informed-RRT* algorithm plans the path obtained by connecting a number of nodes. The generated path is a folded segment and will have many redundant points and inflection points. Redundant points reduce the quality of path planning and increase the movement time of the robotic arm. Inflection points can cause robotic arm jitter during movement. This problem reduces the stability and accuracy of the robotic arm. To address this issue, path optimization is required. The Bessel function method and spline interpolation are common methods for smoothing paths. In this paper, the B-spline interpolation function is introduced to optimize the path [31]. The third-order interpolation function is chosen. The optimization curve is shown in Figure 13 and the interpolation function is shown in Equation (10).
P ( u ) = Σ i = 0 n P i B i , k ( u ) , [ u k 1 , u n + 1 ]
Note: Pi is the control point of the given curve. Bi,k(u) denotes the k to order B-spline basis function. k is 3 in this paper.
Figure 13. Optimization of function interpolation. Note: the blue line is the initial path before smoothing and the green line is the smooth path after smoothing.
Figure 13. Optimization of function interpolation. Note: the blue line is the initial path before smoothing and the green line is the smooth path after smoothing.
Agronomy 15 01031 g013

3. Results and Discussion

The simulation experiments are carried out on the MATLAB R2022B platform to verify the reliability and superiority of the proposed algorithms in this paper. The improved algorithms, RRT* and IRRT*, are simulated and experimented in 2D and 3D scenes, respectively. The simulation hardware environment is an i3-10100FCPU. The main frequency is 3.60 GHz. The graphics card is a GTX 1650 (NVIDIA, Santa Clara, CA, USA). The video memory is 4 GB. The memory is 16 GB. The memory is 500 GB. The operating system is Windows 10 Professional.

3.1. Two-Dimensional Simulation Experiment of Path Planning

3.1.1. Simple Two-Dimensional Scene

Fewer barriers are set up in the case of simple obstacles. The overall size of the map is (100 × 100). The maximum number of iterations of the algorithm is 1200. The bias probability is set to 0.2. As shown in Figure 14, the white parts are obstacle-free areas and the black spheres are obstacles. The red line represents the collision-free path from the start point to the target point. The remaining colored points are sampling points in space for the algorithm. The step size of RRT* and IRRT* algorithms is set to 5. The dynamic step factor in the improved algorithm is 0.8. The following is an experimental comparison of the three algorithms.
As can be seen from Table 2 and Figure 14, there is a large amount of useless planning in the global sampling of RRT*. This leads to long indexing times and inefficient planning. Excessively angular inflection points occur when generating paths. This gives poor path quality. The informed-RRT* algorithm samples both sides of the line connecting the initial and target points. A small number of unnecessary indexes are reduced and the path cost is reduced. However, there are still problems of a long indexing time and excessive path turning angle. The improved algorithm not only reduces the road cost and search time but also generates smoother paths. In summary, the experiments show that the algorithm has better indexing efficiency and indexing path quality.

3.1.2. Complex Two-Dimensional Scenes

In this experiment, more obstacles were placed in the complex scene than in the simple scene. And the radii of the obstacles were different. The total number of iterations for the experiment was set to 2000. The overall size of the map was (100 × 100). The starting point was (0, 100). The target position was (100, 0). After 100 repetitions of the experiment, the comparison of the three algorithms is shown in Figure 15 and the test data are shown in Table 3.
Obstacles are not the same size. They are more densely distributed in complex environments. From the experimental data, it can be seen that the IRRT* algorithm has a faster indexing speed and better path quality than RRT* in complex environments. Because the IRRT* algorithm adds an ellipsoidal sampling range to the RRT* algorithm. Ellipsoidal sampling reduces useless indexing and increases the purposefulness of indexing. As can be seen from the figure, the improved algorithm is more computationally efficient. Because the improved algorithm explores toward the goal point with a certain probability at the time of indexing, the division of subgoal points and subendpoints reduces the difficulty of global indexing. The improved algorithm plans higher-quality paths. It effectively proves its effectiveness and superiority.

3.2. Three-Dimensional Simulation Experiment of Path Planning

Unlike the 2D simulation, the robotic arm path planning is performed in the joint space. In the robotic arm, the rotation angle (θ1, θ2, θ3, θ4, θ5, θ6) of each axis is the sampling point. Since the position information of the picking point obtained from the depth camera is Cartesian spatial coordinates, the endpoint attitude joint angles are not directly acquired. Therefore, before planning, an inverse kinematics solution has to be performed to convert the coordinates into robotic arm joint angles. It is able to map the target position and attitude information into the rotation angles of each joint of the robotic arm [32]. Inverse kinematics solving is a key step in robotic arm motion planning.
Spherical obstacles are arranged in 3D space to verify the effectiveness of the algorithm in 3D space. Yellow and blue spheres represent obstacles. They have different radius sizes. The overall plan space size is (1000 × 1000 × 1000). The starting point is (0, 0, 0). The endpoint location is (1000, 1000, 1000). The red-line segments in the figure are collision-free paths. Each group performs 100 tests. The results are shown in Figure 16 and the test data are shown in Table 4. The red line segments in the figure are collision-free paths.
Figure 16 shows that RRT* and IRRT* sample over the entire space. A larger initial sampling range will take longer in convergence of the algorithm. Improved algorithm divides path points. It indexes subpaths. Sampling is more efficient. The improved algorithm can guide the node tree to index shorter paths while avoiding obstacles on the subpaths. The improved algorithm can generate smoother planning paths with higher path quality. It effectively proves the effectiveness and superiority of the improved algorithm.

3.3. Robot Arm Simulation

A six-axis robotic arm model was established through MATLAB. The improved algorithm in this paper is applied to robotic arm motion planning experiments to further verify the effectiveness of the algorithm in complex environments. In the diagram, the yellow sphere represents the apple. The rest of the spheres and rectangles represent obstacles.
As can be seen from Figure 17, the path of the improved algorithm in this paper is smoother. It can effectively avoid obstacles to complete the path planning of the robotic arm. From the test data in Table 5, it can be seen that the improved algorithm in this paper has shorter search path cost and shorter search duration. These data demonstrate the superiority of the improved algorithm in this paper.
In summary, this experiment verifies the robustness of the algorithm by increasing the number and density of obstacles in the simulation environment. Although the obstacles (branches, trunks, etc.) in the actual orchard have a complex morphology, their spatial distribution is relatively sparse. This provides more feasible paths for the motion planning of the robotic arm. Therefore, the performance of the improved algorithm in real applications should be better than the simulation environment in this paper. It is not only more efficient in path searching but also better able to adapt to dynamic changes in the orchard environment.

4. Conclusions

This paper proposes an improved informed-RRT* path planning algorithm for robotic arms in complex environments. The main improvements over the original informed-RRT* algorithm are as follows:
(1)
In global planning, multiple subpath points are obtained using an artificial potential field and multiple subsegments are divided, which enhances the path indexing purposefulness. This method reduces the difficulty of path exploration and improves the path planning efficiency of the apple-picking robotic arm.
(2)
Traditional sampling methods use fully random sampling, resulting in inefficient planning. The purposefulness of the indexing is improved by using a bidirectional exploration method and making the target node as a parent node with a certain probability.
(3)
Exploring paths with a dynamic step size. The exploration speed can be accelerated when there are fewer obstacles and the path is smoother when there are more obstacles. Dynamic step size can not only avoid obstacles effectively but also improve the path planning quality of the picking robot arm.
Simulations were conducted comparing the improved algorithm with RRT* and informed-RRT* (IRRT*) across multiple scenarios. The experimental results show that compared to RRT* and IRRT*, the average path cost of the optimized algorithm is reduced by 31.565 mm and 14.935 mm and the average search time is reduced by 7.18 s and 4.33 s, respectively. In the complex two-dimensional simulation experiment, the average path cost of the optimization algorithm is reduced by 362.4 mm and 343.5 mm and the average search time is reduced by 5.49 s and 1.54 s, respectively, compared to RRT* and IRRT*. In 3D simulation, compared to RRT* and IRRT*, the average path cost is reduced by 1110.17 mm and 469.97 mm and the average search time is reduced by 37.82 s and 11.26 s, respectively. The effectiveness and superiority of the improved algorithm are proved effectively.
In this paper, only two-dimensional and three-dimensional simulation experiments of MATLAB were carried out for the improved algorithm, and it was not applied to the actual apple picking scene. Future direction: The algorithm in this paper will first carry out an apple-picking experiment in the laboratory. Then, apple-picking experiments will be carried out under different actual apple distribution scenarios, including sparse distribution environment, dense distribution environment, and mixed distribution environment.

Author Contributions

Conceptualization, X.C. and Q.C.; Methodology, X.C., C.L., Z.G., C.Y., X.W. and Q.C.; Software, C.L., Q.C. and X.L.; Validation, X.C., C.L., C.Y. and X.W.; Resources, Q.C.; Data curation, X.C. and Z.G.; Writing—original draft, X.C., C.L., Z.G., X.W., Q.C. and X.L.; Writing—review and editing, X.C., C.L., Z.G., C.Y., Q.C., X.W. and X.L.; Visualization, X.C.; Project administration, Q.C.; Funding acquisition, Q.C. All authors have read and agreed to the published version of the manuscript.

Funding

This research is funded by the Practical Innovation Training Program for College Students, Nanjing Forestry University (202410298123Y) and the Jiangsu Province Agricultural Machinery R&D and Manufacturing Integration Project (JSYTH01).

Data Availability Statement

Data are contained within the article.

Conflicts of Interest

The authors declare no conflicts of interest.

References

  1. Li, Q.; Zhang, F. Progress of research on nutrient composition and application value of apple. J. Zhejiang Agric. Sci. 2017, 58, 132–134. [Google Scholar]
  2. Chen, Q.; Yin, C.; Guo, Z.; Wang, J.; Zhou, H.; Jiang, X. Current status and future development of the key technologies for apple picking robots. Trans. Chin. Soc. Agric. Eng. 2023, 39, 1–15. [Google Scholar]
  3. Sathesh, S.; Maheswaran, S.; Rega, P.; Sowmitha, K.; Shivabalan, S.R.; Sukhundhan, V.S. Design of Delta Arm for Multi-Purpose Agribot. In Proceedings of the 2024 10th International Conference on Advanced Computing and Communication Systems (ICACCS), Coimbatore, India, 14–15 March 2024. [Google Scholar]
  4. Cao, X. Research on Motion Planning of Fruit Picking Robot. Ph.D. Thesis, South China Agricultural University, Guangzhou, China, 2022. [Google Scholar]
  5. Yang, X.; Zhou, W.; Li, Y.; Qi, X.; Zhang, Q. A review on the current research status of path planning algorithms for picking robotic arm. J. Chin. Agric. Mech. 2023, 4, 161–169. [Google Scholar]
  6. Kang, M.; Chen, Q.; Fan, Z.; Yu, C.; Wang, Y.; Yu, X. A RRT based path planning scheme for multi-DOF robots in unstructured environments. Comput. Electron. Agr. 2024, 218, 108707. [Google Scholar] [CrossRef]
  7. Huang, A.; Yu, C.; Feng, J.; Tong, X.; Yorozu, A.; Ohya, A.; Hu, Y. A motion planning method for winter jujube harvesting robotic arm based on optimized Informed-RRT* algorithm. Smart Agric. Technol. 2025, 10, 100732. [Google Scholar] [CrossRef]
  8. Blum, C. Ant colony optimization: A bibliometric review. Phys. Life Rev. 2024, 51, 87–95. [Google Scholar] [CrossRef]
  9. Fang, W.; Sun, J.; Ding, Y.; Wu, X.; Xu, W. A review of quantum-behaved particle swarm optimization. IETE Tech. Rev. 2010, 27, 336–348. [Google Scholar] [CrossRef]
  10. Han, D.; Mulyana, B.; Stankovic, V.; Cheng, S. A survey on deep reinforcement learning algorithms for robotic manipulatio. Sensors 2023, 23, 3762. [Google Scholar] [CrossRef]
  11. Sun, H.; Zhang, W.; Yu, R.; Zhang, Y. Motion planning for mobile robots—Focusing on deep reinforcement learning: A systematic review. IEEE Access 2021, 9, 69061–69081. [Google Scholar] [CrossRef]
  12. LaValle, S. Rapidly-exploring random trees: A new tool for path planning. In Proceedings of the 1998 IEEE International Conference on Robotics and Automation (ICRA), Leuven, Belgium, 16–20 May 1998. [Google Scholar]
  13. Liu, T.; Zhang, D.; Zheng, Y.; Cheng, Y.; Qiu, J.; Qi, L. Pineapple harvester navigation path planning based on improved RRT* algorith. Trans. Chin. Soc. Agric. Eng. 2022, 38, 20–28. [Google Scholar]
  14. Chu, D.; Liu, H.; Gao, B.; Wang, J.; Yin, G. Research Review on Predictive Cruise Control of Vehicle Queue. J. Mech. Eng. 2019, 60, 218–246. [Google Scholar]
  15. Xu, K.; Su, R. Path planning of nanorobot: A review. Microsyst. Technol. 2022, 28, 2393–2401. [Google Scholar] [CrossRef]
  16. Karaman, S.; Frazzoli, E. Optimal kinodynamic motion planning using incremental sam-pling-based methods. In Proceedings of the 49th IEEE Conference on Decision and Control (CDC), Atlanta, GA, USA, 15–17 December 2010. [Google Scholar]
  17. Zhang, L.; Shi, X.; Yi, Y.; Tang, L.; Peng, J.; Zou, J. Mobile Robot Path Planning Algorithm Based on RRT Connect. Electronics 2023, 12, 2456. [Google Scholar] [CrossRef]
  18. Cao, X.; Zou, X.; Jia, C.; Chen, M.; Zeng, Z. RRT-based path planning for an intelligent litchi-picking manipulator. Comput. Electron. Agr. 2019, 156, 105–118. [Google Scholar] [CrossRef]
  19. Chen, Y.; Fu, Y.; Zhang, B.; Fu, W.; Shen, C. Path planning of the fruit tree pruning manipulator based on improved RRT-Connect algorithm. Int. J. Agr. Biol. Eng. 2022, 15, 177–188. [Google Scholar] [CrossRef]
  20. Gammel, J.; Srinivasa, S.; Barfoot, T. Informed RRT*:optimal sampling-based path planning focused via direct sampling of an admissible ellipsoidal heuristic. In Proceedings of the 2014 IEEE International Conference on Robotics and Automation (ICRA), Hong Kong, China, 31 May–7 June 2014. [Google Scholar]
  21. Wang, Y.; Liu, D.; Zhao, H.; Li, Y.; Song, W.; Liu, M.; Tian, L.; Yan, H. Rapid citrus harvesting motion planning with pre-harvesting point and quad-tree. Comput. Electron. Agric. 2022, 202, 107348. [Google Scholar] [CrossRef]
  22. Liang, S. Research on Offline and Online Motion Planning Methods for Multi-Degree-of-Freedom Robotic Arm. Master’s Thesis, Zhejiang University, Hangzhou, China, 2023. [Google Scholar]
  23. Denavit, J.; Hartenberg, R. A Kinematic Notation for Lower-Pair Mechanisms. J. Appl. Mech. 1955, 22, 215–221. [Google Scholar] [CrossRef]
  24. Liu, L. Optimization of Sugar-Free Tissue Culture and Rapid Propagation System for Dwarfing Apple Rootstock. Master’s Thesis, Northwest A&F University, Xianyang, China, 2024. [Google Scholar]
  25. Li, Q.; Zhu, H. Performance evaluation of 2D LiDAR SLAM algorithms in simulated orchard environments. Comput. Electron. Agric. 2024, 221, 108994. [Google Scholar] [CrossRef]
  26. Zhou, W. Research on Trajectory Planning of Robotic Arm Based on Particle Swarm Algorith. Master’s Thesis, Nanjing University of Posts and Telecommunications, Nanjing, China, 2023. [Google Scholar]
  27. Gammell, J.; Barfoot, T.; Srinivasa, S. Informed Sampling for Asymptotically Optimal Path Planning. IEEE Trans. Robot. 2018, 34, 966–984. [Google Scholar] [CrossRef]
  28. Khatib, O. Real-Time Obstacle Avoidance System for Manipulators and Mobile Robots. Int. J. Robot. Res. 1986, 5, 90–98. [Google Scholar] [CrossRef]
  29. Wang, H.; Gao, M.; Wang, J.; Fang, L.; Li, H. Multi-scene motion planning for robotic arm based on improved RRT~*-Connect algorithm. Trans. Chin. Soc. Agric. Mach. 2022, 5, 432–440. [Google Scholar]
  30. Wang, J.; Li, B.; Meng, M. Kinematic Constrained Bi-directional RRT with Efficient Branch Pruning for Robot Path Planning. Expert Syst. Appl. 2020, 170, 114541. [Google Scholar] [CrossRef]
  31. Xie, W.; Huang, K.; Wei, S.; Fu, H.; Yang, D. Crack removal of carrot based on the Cartesian robot with a novel path planning method. J. Food Eng. 2025, 388, 112381. [Google Scholar] [CrossRef]
  32. Xiong, J.; Chen, H.; Yao, Z.; Ning, Q. Motion planning method of litchi picking robot arm based on PIB-RRTstar. Trans. Chin. Soc. Agric. Mach. 2024, 55, 82–92. [Google Scholar]
Figure 1. Robot arm model.
Figure 1. Robot arm model.
Agronomy 15 01031 g001
Figure 2. Coordinate conversion of the robotic arm.
Figure 2. Coordinate conversion of the robotic arm.
Agronomy 15 01031 g002
Figure 3. Collision detection flow chart. Note: n is the number of detections.
Figure 3. Collision detection flow chart. Note: n is the number of detections.
Agronomy 15 01031 g003
Figure 4. Collision detection between the mechanical arm and the branch. Note: A safety zone is left outside the obstacle to prevent the robot arm from colliding with the obstacle. The minimum distance from the perimeter of the safe zone to the obstacle is greater than the radius of the robot arm.
Figure 4. Collision detection between the mechanical arm and the branch. Note: A safety zone is left outside the obstacle to prevent the robot arm from colliding with the obstacle. The minimum distance from the perimeter of the safe zone to the obstacle is greater than the radius of the robot arm.
Agronomy 15 01031 g004
Figure 5. Reselect the parent node. Note: Node reselection will be carried out within the dotted circle.
Figure 5. Reselect the parent node. Note: Node reselection will be carried out within the dotted circle.
Agronomy 15 01031 g005
Figure 6. Rewiring. Note: Node reselection will be carried out within the dotted circle. The re-selected nodes are connected with red lines.
Figure 6. Rewiring. Note: Node reselection will be carried out within the dotted circle. The re-selected nodes are connected with red lines.
Agronomy 15 01031 g006
Figure 7. Elliptic sampling space.
Figure 7. Elliptic sampling space.
Agronomy 15 01031 g007
Figure 8. Informed-RRT* iteration process. Note: Iter is the number of iterations. Cbest is the cost of the first path found.
Figure 8. Informed-RRT* iteration process. Note: Iter is the number of iterations. Cbest is the cost of the first path found.
Agronomy 15 01031 g008
Figure 9. Flowchart of the algorithm.
Figure 9. Flowchart of the algorithm.
Agronomy 15 01031 g009
Figure 10. Calculation of repulsion force. Note: The green arrow is the repulsive component. The blue arrow is the gravitational component. The black arrow is the extended component. Red is the resultant force. The yellow circle is the newly created node. The blue circle is the initial point. The black circle is the point generated without introducing the repulsive force field. The red circle is the target point.
Figure 10. Calculation of repulsion force. Note: The green arrow is the repulsive component. The blue arrow is the gravitational component. The black arrow is the extended component. Red is the resultant force. The yellow circle is the newly created node. The blue circle is the initial point. The black circle is the point generated without introducing the repulsive force field. The red circle is the target point.
Agronomy 15 01031 g010
Figure 11. Cosine offset.
Figure 11. Cosine offset.
Agronomy 15 01031 g011
Figure 12. Bidirectional planning.
Figure 12. Bidirectional planning.
Agronomy 15 01031 g012
Figure 14. Comparison of path algorithms in simple scenarios. Note: The points of different colors in the figure are the sampling points. The green dot and the red dot are the starting point and the goal point.
Figure 14. Comparison of path algorithms in simple scenarios. Note: The points of different colors in the figure are the sampling points. The green dot and the red dot are the starting point and the goal point.
Agronomy 15 01031 g014
Figure 15. Comparison of path algorithms in complex scenarios. Note: The points of different colors in the figure are the sampling points. The green dot and the red dot are the starting point and the goal point.
Figure 15. Comparison of path algorithms in complex scenarios. Note: The points of different colors in the figure are the sampling points. The green dot and the red dot are the starting point and the goal point.
Agronomy 15 01031 g015
Figure 16. Comparison of path planning algorithms in a three-dimensional environment. Note: The balls of different colors and sizes in the picture are obstacles.
Figure 16. Comparison of path planning algorithms in a three-dimensional environment. Note: The balls of different colors and sizes in the picture are obstacles.
Agronomy 15 01031 g016
Figure 17. Comparison of path planning algorithms for virtual robot arm picking simulation. Note: The green line segment is the generated path.
Figure 17. Comparison of path planning algorithms for virtual robot arm picking simulation. Note: The green line segment is the generated path.
Agronomy 15 01031 g017
Table 1. DH parameter table.
Table 1. DH parameter table.
LinkThetad/mma/mmAlpha/radOffset/mm
1θ1137.501.57080
2θ2040201.5708
3θ3037600
4θ4120.50−1.5708−1.5708
5θ5120.501.57080
6θ688.5000
Note: Theta is the link joint angle, which is the angle between two neighboring links around a common axis. d is the link deflection, which is the distance along the direction of the common axis of the two neighboring links. a is the link length, which is the length of the common perpendicular of the two neighboring joint axes. Alpha is the angle between two neighboring joint axes. Offset is the distance between the origins of two adjacent link coordinate frames.
Table 2. Comparison of algorithm data results in simple scenarios.
Table 2. Comparison of algorithm data results in simple scenarios.
AlgorithmsAverage Path Cost/mmAverage Search Duration/sSuccess Rate/%
RRT*165.5827.2596
IRRT*160.3525.3597
Improved algorithm149.718.3497
Table 3. Comparison of path planning algorithm data results in complex scenarios.
Table 3. Comparison of path planning algorithm data results in complex scenarios.
AlgorithmsAverage Path Cost/mmAverage Search Duration/sSuccess Rate/%
RRT*186.43522.9389
IRRT*169.80520.0891
Improved algorithm154.87015.7595
Table 4. Comparison of path planning algorithms in a 3D environment.
Table 4. Comparison of path planning algorithms in a 3D environment.
AlgorithmsAverage Path Cost/mmAverage Search Duration/sSuccess Rate/%
RRT*2518.8135.9387
IRRT*2499.9131.9890
Improved algorithm2156.4130.4492
Table 5. Comparison of path planning algorithms for virtual robot arm picking simulation.
Table 5. Comparison of path planning algorithms for virtual robot arm picking simulation.
AlgorithmsAverage Path Cost /mmAverage Search Duration/sSuccess Rate/%
RRT*4520.60211.8988
IRRT*3880.40185.3392
Improved algorithm3410.43174.0794
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, X.; Lu, C.; Guo, Z.; Yin, C.; Wu, X.; Lv, X.; Chen, Q. Research on 3D Obstacle Avoidance Path Planning for Apple Picking Robotic Arm. Agronomy 2025, 15, 1031. https://doi.org/10.3390/agronomy15051031

AMA Style

Chen X, Lu C, Guo Z, Yin C, Wu X, Lv X, Chen Q. Research on 3D Obstacle Avoidance Path Planning for Apple Picking Robotic Arm. Agronomy. 2025; 15(5):1031. https://doi.org/10.3390/agronomy15051031

Chicago/Turabian Style

Chen, Xinyan, Chun Lu, Ziliang Guo, Chengkai Yin, Xuanbo Wu, Xiaolan Lv, and Qing Chen. 2025. "Research on 3D Obstacle Avoidance Path Planning for Apple Picking Robotic Arm" Agronomy 15, no. 5: 1031. https://doi.org/10.3390/agronomy15051031

APA Style

Chen, X., Lu, C., Guo, Z., Yin, C., Wu, X., Lv, X., & Chen, Q. (2025). Research on 3D Obstacle Avoidance Path Planning for Apple Picking Robotic Arm. Agronomy, 15(5), 1031. https://doi.org/10.3390/agronomy15051031

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