Next Article in Journal
Classifying Malicious Documents on the Basis of Plain-Text Features: Problem, Solution, and Experiences
Previous Article in Journal
The Impact of Rising Reservoir Water Level on the Gravity Field and Seismic Activity in the Reservoir Area: Evidence from the Impoundment of the Three Gorges Reservoir (China)
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Obstacle Avoidance Path Planning for the Dual-Arm Robot Based on an Improved RRT Algorithm

1
University of Chinese Academy of Sciences, Beijing 100049, China
2
Key Lab of Space Utilization, Technology and Engineering Center of Space Utilization, Chinese Academy of Sciences, Beijing 100094, China
*
Author to whom correspondence should be addressed.
Submission received: 23 February 2022 / Revised: 13 April 2022 / Accepted: 17 April 2022 / Published: 18 April 2022
(This article belongs to the Topic Industrial Robotics)

Abstract

:
In the future of automated production processes, the manipulator must be more efficient to complete certain tasks. Compared to single-arm robots, dual-arm robots have a larger workspace and stronger load capacity. Coordinated motion planning of multi-arm robots is a problem that must be solved in the process of robot development. This paper proposes an obstacle avoidance path planning method for the dual-arm robot based on the goal probability bias and cost function in a rapidly-exploring random tree algorithm (GA_RRT). The random tree grows to the goal point with a certain probability. At the same time, the cost function is calculated when the random state is generated. The point with the lowest cost is selected as the child node. This reduces the randomness and blindness of the RRT algorithm in the expansion process. The detection algorithm of the bounding sphere is used in the process of collision detection of two arms. The main arm conducts obstacle avoidance path planning for static obstacles. The slave arm not only considers static obstacles, but also takes on the role of the main arm at each moment as a dynamic obstacle for path planning. Finally, MATLAB is used for algorithm simulation, which proves the effectiveness of the algorithm for obstacle avoidance path planning problems for the dual-arm robot.

1. Introduction

With the development of science and industrial automation, robot technology has been greatly developed in recent decades, and gradually applied in military, aerospace, industry, medical, service, and other fields [1,2]. Single-arm industrial robots have achieved notable development and application in China, widely replacing manual casting, welding, palletizing, and other operations [3,4]. However, many complex operational tasks require collaboration between the robotic arms. The dual-arm robot has a larger working space, stronger load capacity, and obvious advantages in heavy lifting and assembly scenarios. However, unlike a simple combination of two single-arm robots, a dual-arm robot has some overlap in its workspace. The path planning of two arms should not only consider static obstacles in space, but also consider the interference between the two arms. In the field of dual-arm robotics, how to realize obstacle avoidance motion planning is always a hot issue [5,6].
In the field of robot path planning, many path planning algorithms have been formed. The traditional methods mainly include the artificial potential field algorithm [7,8,9], the A* algorithm [10,11], and the RRT algorithm [12,13], etc. The methods based on computational networks mainly include neural network algorithms [14,15] and bioinspired planning algorithms [16,17]. Bioinspired planning algorithms mainly include the genetic algorithm, ant colony optimization (ACO), and so on. The genetic algorithm is an intelligent bionic algorithm based on natural selection and genetic mechanisms [18]. The ACO is an intelligent optimization search model established with reference to the foraging method of ant populations [19,20]. However, in the joint space of a manipulator with high degrees of freedom, each movement of the arms will generate a high computational workload. Algorithms based on computational networks have problems such as excessive computational load and insufficient real-time performance in the field of dual-arm robot path planning.
Among the traditional path planning algorithms, the artificial potential field method has the characteristics of simple implementation and good real-time performance, and has been widely used. Nonetheless, once the resultant force is zero, that is, at the local potential energy minimum point, the algorithm will fall into a deadlock state and stop searching [21]. In addition, the artificial potential field algorithm needs the sampling information of the entire workspace to avoid local minima, which affects the dynamic obstacle avoidance of the dual-arm robot.
The A* algorithm is a method for solving the shortest path in a known static road network. This method is a search algorithm obtained by adding a heuristic function to the Dijkstra algorithm [22]. It evaluates the nodes and guides the search process based on the evaluation value. Latombe et al. applied a PRM (probabilistic road map) to multi-robot path planning, but the increase in degrees of freedom and obstacles reduced the speed of the method [23].
In the field of multi-axis robot planning, due to the constraints of complex environments, most search methods are based on random sampling. Among the path planning methods used in the past few decades, the RRT algorithm, based on random search strategy, is suitable for path planning in high-dimensional space, and has been widely used in the path planning of robots [24,25,26]. The algorithm avoids modeling the entire space by detecting collisions at sample points in the state space. Therefore, it can effectively solve path planning problems with complex constraints in high-dimensional space, and has the advantages of probabilistic completeness and perfect scalability.
RRT is a fast search algorithm proposed by LaValle [27]. However, it is a random search algorithm, and the search path may not be in the direction of the target, therefore the convergence speed is relatively slow. In order to improve the target orientation of the RRT algorithm, Chris Urmson et al. [28] proposed a P probability RRT algorithm based on goal bias strategy. Li et al. [29] proposed a variable step size trunk fast exploration random tree (VT-RRT) algorithm. By transforming the search space of random nodes in the RRT algorithm and adaptively adjusting the step size according to the target position, the search efficiency is effectively improved, and the path planning time is reduced. Jiang Hong et al. [30] proposed a new node expansion method that is biased towards the target point. The method combines the target point gravity, obstacle repulsion, and random point gravity, and adds an adaptive function related to the obstacle distance. A pruning optimization method is proposed to optimize the path length. Lei Shao et al. [31] used an ant colony algorithm to optimize RRT. Experiments show that the combination of an ant colony algorithm and RRT algorithm effectively reduces the number of nodes and the average computing time. Kun Wei [32] proposed a dynamic path planning method for robot autonomous obstacle avoidance based on an improved RRT algorithm, namely smooth RRT (S-RRT). This method takes the directional node as the goal, which greatly improves the sampling speed and efficiency of RRT.
In the field of path planning for dual-arm robots, Andreas [33] proposed a dual-arm path planning method based on closed-chain kinematics to meet the motion constraints of the manipulator. Kim [34] proposed a dimension reduction RRT method, which reduced the dimension of high-dimensional path planning space according to the task requirements of the dual-arm robot. To ensure that the RRT algorithm has higher efficiency, Li yang [35] proposed a cooperative path planning method for a dual-arm robot based on gravity adaptive step length RRT. The simulation results show that the gravity adaptive step size RRT method can effectively constrain the step size in the workspace to ensure the effectiveness of the collision detection algorithm.
In this paper, the GA_RRT path planning algorithm is proposed based on the traditional RRT algorithm by introducing the goal probability bias strategy and A* cost function. In addition, two manipulators use the bounding sphere collision detection method. The main arm considers static obstacles, and the slave arm considers static obstacles and dynamic main arm obstacles. Finally, MATLAB software is used to simulate the obstacle avoidance path planning for the dual-arm robot. It is finally proved that the algorithm is effective and superior for the path planning of dual-arm robot.

2. Model Building

In this paper, the robot platform composed of two UR5 robotic arms is taken as an example. It mainly includes one base and two 6-DOF manipulators. According to the DH modeling method, we construct the dual-arm robot model, as shown in Figure 1. The joint diagram of the main manipulator is shown in Figure 2. Using the parameters of the robotic arm and DH method, we obtain the DH parameters in Table 1. The joint diagram of the slave manipulator, and the joint diagram of the main manipulator, are mirror-symmetric with the robot body. For example, the DH parameters α and θ of the master manipulator are opposite to those of the slave manipulator.
The homogeneous coordinate transformation matrix of a six-axis manipulator with this parameter is shown in Equation (1).
T i i 1 = [ cos ( θ i ) sin ( θ i ) cos ( α i ) sin ( θ i ) sin ( α i ) α i cos ( θ i ) sin ( θ i ) cos ( θ i ) cos ( θ i ) sin ( α i ) α i sin ( θ i ) 0 sin ( α i ) cos ( α i ) d i 0 0 0 1 ]
The transformation matrix of all adjacent coordinate systems can be obtained by substituting DH parameters. The transformation matrix relative to the base coordinate system is shown in Equation (2).
T = T 1 0 T 2 1 T 3 2 T 4 3 T 5 4 T 6 5
Finally, the dual-arm manipulator needs to be unified into the base coordinate system using Equation (3).
S = S 0 T

3. Algorithm Improvement

3.1. Basic RRT

RRT constructs a random tree through random sampling. In the space with obstacles, the algorithm starts to explore from the initial node, X i n i t . This process is shown in Figure 3. Firstly, the random point, X r a n d , is generated. In all the added path nodes of the tree [ X i n i t ,   X 1 ,   X 2 ,   X 3 ,   X n e a r e s t ], the node X n e a r e s t , which is nearest to X r a n d , is selected. Taking X n e a r e s t as the root node, a fixed step R is added to the direction of X r a n d to obtain X n e w . The collision detection algorithm is used to detect whether the path between X n e a r e s t and X r a n d is feasible. If there is no collision, X n e w is added to the random tree, T. Alternatively, if there is a collision, X r a n d will be regenerated. Repeat the whole process until the distance between the latest node and X g o a l is less than the step value, and there are no obstacles between them; at this point it is considered that the algorithm has converged. When the planning algorithm converges, we start from X g o a l and trace back along its parent node to find an effective path between the start point and the end point.
The process of the RRT algorithm is shown in Algorithm 1.
Algorithm 1: RRT algorithm
1:  T = init Tree(); // Initialize the random tree
2:  R = init R(); // Initialize the step size
3:  T[0] = Node( X i n i t );
4:  for i = 1 to N:
5:       X r a n d = Random sampling(); // Random sampling
6:       X n e a r e s t = min the distance ( X r a n d ) N o d e t r e e ) ;   // Find the nearest node
7:       X n e w = extend ( X n e a r e s t , X r a n d , R); // Expand towards random points
8:      if not obstacle( X n e a r e s t , X n e w ):
9:         T[i] = add Node( X n e w ); // Add a new node to the tree
10:     end if
11:  end for
12:  return T

3.2. Path Planning of Dual-Arm Based on GA_RRT

The disadvantage of the traditional RRT algorithm is that it is a random exploration of the whole space, and does not consider the path cost. This paper provides some knowledge of goal probability bias and path cost.
Some principles of the goal probability bias and A* cost function are mainly introduced in this section. Due to the computational complexity of collision detection for dual-arm robots, collision detection is mainly performed using the method of the bounding sphere.

3.2.1. The Goal Probability Bias

The traditional RRT algorithm is a random search of space, which ensures the effectiveness of the RRT algorithm. However, excessive blind search reduces the convergence speed and consumes a large amount of computation power. Therefore, we adopt a goal probability bias strategy. This method sets a parameter, P a , in sampling judgment. Before each extension, a random value, P r a n d , (between point 0, 1) is randomly generated. When 0 < P r a n d < P a , the random tree grows toward the target point, making the random tree expansion more objective. When P a < P r a n d < 1, X r a n d points are generated randomly.
For the dual-arm manipulator environment, when the goal point is taken as a random point with probability P a , we need to read the real-time position of the manipulator, and detect whether there are static obstacles and dynamic obstacles of the manipulator under the path. When there are obstacles, the cost of expansion is infinite. We abandon the random point and restart the random process.

3.2.2. A* Cost Function

Although the probability-biased RRT algorithm greatly shortens the search time, there are still many redundant random points. Therefore, this paper combines the goal probability bias RRT algorithm with the A* search algorithm. The cost function was used to search for the best sampling point, so as to reduce the level of redundant computing and optimize the path. We consider the forward and backward cost of the current node in the RRT algorithm. The distance from the initial point, X i n i t , to the selected node is called forward cost, which can also be called heuristic function H(i). The distance between X s e l e c t and X g o a l is called backward cost B(i). The cost function of the current node is represented by F(i), shown in Equation (4).
{ F ( i ) = H ( i ) + B ( i ) B ( i ) = X g o a l X r a n d ( i ) H ( i ) = X r a n d X i n i t ( i )
After calculating the random node, select the random point with the smallest cost function to join the random tree list. Repeat the calculation process until extended to the target node.
We need to add two additional data groups. One is the optional random point data group, and the other is the cost function data group corresponding to the optional random point. Each time we expand the random tree, multiple random points, X r a n d , are generated and put into the optional random point group. Next, the cost function is calculated for the optional random point group. According to the cost function data group, the minimum cost node is taken.

3.2.3. Collision Detection of Dual-Arm Robots

In order to simplify the calculation of the 6-DOF manipulator, the method of the bounding sphere is used for obstacle avoidance detection. It is the smallest sphere that surrounds three-dimensional objects. In order to reduce the complex calculation of collision detection during the movement of the arms, this method is selected in this paper. Its advantages are convenient calculation, simple structure, and it is not affected by spin. This algorithm has better security while generating partial redundant spaces. When considering whether there is a collision between the manipulator and the obstacle, or a collision between the main manipulator and the slave manipulator, it is only necessary to consider the distance and radius of the object center.
The base point of the main manipulator is denoted as O 10 , and the center points of the six joints are denoted as { O 11 ,   O 12 ,   O 13 ,   O 14 ,   O 15 ,   O 16 }. Then, the center points of the connecting rod are denoted as { A 1 ,   A 2 ,   A 3 ,   A 4 ,   A 5 ,   A 6 }. These values are determined by the parameters of the manipulator body. Taking the joint bounding sphere as an example, the joint bounding sphere can be expressed as:
R = { ( x , y , z ) | ( x o i j x ) 2 + ( y o i j y ) 2 + ( z o i j z ) 2 < r 2 }
The radius of the joint bounding sphere for the main manipulator is set as { R 11 ,   R 12 ,   R 13 ,   R 14 ,   R 15 ,   R 16 }, and the bounding sphere radius of the connecting rod is set as { R a 1 ,   R a 2 ,   R a 3 ,   R a 4 ,   R a 5 ,   R a 6 }. The slave arm parameters are represented by O 2 i , B i , R 2 i , R b i . The radius can be calculated using Equation (6)
R i j = 1 2 ( x i j max x i j min ) 2 + ( y i j max y i j min ) 2 + ( z i j max z i j min ) 2
where x i j m a x , x i j m i n ,   y i j m a x , y i j m i n , z i j m a x , z i j m a x , respectively, represent the maximum and minimum values of the object projected on the XYZ coordinate axes. Bounding sphere model of the dual-arm robot is shown in Figure 4.
The conditions for collision detection of an enclosing ball are shown in Equations (5)–(7).
1.
No collision between each connecting rod and the joint in the main manipulator:
{ O 1 l O 1 j < ( R 1 l + R 1 j ) O 1 i A j < ( R 1 i + R a j ) , i j , i = 1 , 2 , , 6 , j = 1 , 2 , , 6
2.
No collision between each connecting rod and the joint in the slave manipulator:
{ O 2 i O 2 j < ( R 2 i + R 2 j ) O 2 i B j < ( R 2 i + R b j ) , i j , i = 1 , 2 , , 6 , j = 1 , 2 , , 6
3.
No collision between the links of the main manipulator and the links of the slave manipulator:
{ O 1 i O 2 j < ( R 1 i + R 2 j ) O 1 i B j < ( R 1 i + R b j ) A i O 2 j < ( R a i + R 2 j ) A i B j < ( R a i + R b j ) , i = 1 , 2 , , 6 , j = 1 , 2 , , 6
The static obstacle collision detection in the environment mainly calculates the distance, D, from the center of the manipulator to the center of the obstacle ball. The collision is judged by comparing the distance, D, with the sum of the radius of the enclosing ball.

3.2.4. Overall Process of GA_RRT

The GA_RRT algorithm combines the probabilistic bias method and A* algorithm with RRT. The process of the algorithm is shown in Algorithm 2.
Algorithm 2: GA_RRT algorithm
1: T = init Tree(); // Initialize the random tree
2:  R = init R(); // Initialize the step size
3:  T[0] = Node( X i n i t );
4:  for i = 1 to N:
5:      for j = 1 to M: // M random states are generated, recommended value 4
6:           if P r a n d < P a :
7:                 X d i r e c t i o n = X g o a l ;// Select random points as target points
8:           else:
9:             X d i r e c t i o n = Random sampling(); // Random sampling
10:            X n e a r e s t = min the distance X d i r e c t i o n , N o d e t r e e ) ;
10:            X s e l e c t = extend ( X n e a r e s t , X d i r e c t i o n , R); // Expand
11:            X p a t h (j) = add X s e l e c t // Add random states to cost function group
12:     end for
13:     F(j) = the distance( X p a t h (j), X i n i t ) + the distance( X p a t h (j), X g o a l ); // cost function
14:      X n e w = min F(j); // The minimum cost node is taken in tree
15:  if not obstacle( X n e a r e s t , X n e w ):
16:     T[i] = add Node( X n e w ); // Add new nodes
17:  end if
18:  end for
19:  return T
The overall flow of GA_RRT algorithm is shown in Figure 5. First, the main flow of the algorithm is used to perform random sampling. Then, the target point is expanded as a direction point with a probability of P a , and a random point is generated with a probability of 1 −     P a for expansion. After randomly generating multiple random points for expansion, the algorithm calculates the A* cost function and selects the node with the smallest cost function for the next collision detection. If it passes the detection, the node is added to the random tree. Loop this process until you are near the target point.

4. Simulation

4.1. Obstacle Avoidance Path Planning for Static Plane

In order to analyze the effectiveness of the GA_RRT algorithm for the path planning problem, this paper compares with the traditional RRT algorithm and the RRT algorithm based on goal bias probability (G_RRT) in two different scenarios. The hardware platform is Intel(R) Core (TM) i7-10700f CPU with 16GB of memory. The simulation experiment is built using MATLAB software.
The simulation mainly adopts two common methods to verify the validity of the path planning algorithm. Scenario A is shown in Figure 6, the initial point is 1, 1 and the target point is 750,750. As can be seen in Figure 6a, the RRT algorithm explores the entire space, while the G_RRT algorithm explores the target point with a probability of 0.5, presented in Figure 6b. This greatly reduces the number of nodes for spatial search. The GA_RRT algorithm performs node pruning by calculating the cost function while exploring the goal point. This further effectively reduces the number of tree node branches and speeds up the search efficiency.
In the experiment, since the paths generated by the RRT algorithm have high randomness, the number of nodes and time of each path may be quite different. Therefore, this paper conducts ten experiments for each algorithm, and takes the average value as the final data. The path data for Scenario A are shown in Table 2.
It is calculated that the average number of nodes explored by the G_RRT algorithm is 58.9% less than that of the RRT algorithm. The GA_RRT algorithm is further reduced by 51.3% on the basis of the G_RRT algorithm. Due to the addition of the cost function, the path length is also optimized. Compared with the RRT algorithm, the GA_RRT path length is optimized by 10.7%. Due to the reduction in node redundancy, the time cost of the GA_RRT algorithm is reduced by 59.5% in this scenario. Compared to the G_RRT algorithm, it is reduced by 24.8%.
In scenario B, the target point is directly occluded, as shown in Figure 7. The initial point is 400,400 and the target point is 750,750.
The average experimental data for Scenario B is shown in Table 3.
In scenario B, the starting point and the target point are directly blocked. Theoretically, there is no significant difference among the three algorithms in the U-shaped obstacle space. However, outside the obstacle space, the GA_RRT algorithm should have better performance. By comparing the data in Table 3, we can draw similar conclusions.
The total number of nodes explored by G_RRT is 62.9% lower than that of the RRT algorithm. The GA_RRT algorithm is further reduced by 41.8% on the basis of the G_RRT algorithm. Compared to the RRT algorithm, the GA_RRT path length is optimized by 32.8%, and the time cost is reduced by 72.5%.

4.2. Obstacle Avoidance Path Planning for Dynamic Dual-Arm Robots

Through the above path planning simulations in conventional scenarios, the effectiveness of the GA_RRT algorithm in path searching and reducing redundancy is successfully verified. Finally, in order to verify the effectiveness of the algorithm for the obstacle avoidance path planning of the dual-arm robot, this paper establishes a three-dimensional obstacle environment through the robot simulation toolbox.
The starting joint angle and target joint angle of the main arm are set to 45, −15, −15, 0, 0, 0 and 5, 45, 5, 15, −5, 0. The starting joint angle and target joint angle of the slave arm are set to 35, 30, 20, 0, 0, 0 and 0, −45, 30, −30, −15, 0, respectively. Due to the bounding sphere collision detection model, the obstacles will eventually be equivalent to a sphere. Therefore, this paper sets five spherical static obstacles of different sizes in the environment. The center and radius of each obstacle are shown in Equation (10).
O s p h e r e 0 = [ 0.55 0.25 0.15 0.5 0.3 0.5 0.45 0.2 0.15 0.3 0.3 0.15 0.4 0.25 0.15 ] ;   R = [ 0.05 0.04 0.03 0.05 0.06 ]
The obstacle is placed on the path of the dual-arm robot moving towards the target point. The initial scene is shown in Figure 8a.
As shown in Figure 8b,c, if the robot arm does not plan the obstacle avoidance path, the slave robot arm will collide with the static obstacle and the master arm link during the movement. The final state of the dual-arm robot reaching the target point is shown in Figure 8d.
Keeping the surrounding environment of robot arm unchanged, the obstacle avoidance path planning algorithm of the dual-arm robot based on GA_RRT is added into the simulation.
Figure 9a shows the exploration process of the main arm joint angle. In order to visualize the six-dimensional exploration process, it is divided into the exploration process of the first three joints and the exploration process of the last three joints.
The angle exploration process is shown in Figure 9. The final result of the exploration is shown in Figure 10. From Figure 10, we can clearly observe the change process of the joint angle. The starting joint angle and target joint angle of the main arm are 45, −15, −15, 0, 0, 0 and 5, 45, 5, 15, −5, 0, respectively.
Similarly, Figure 11 shows the path exploration process for the slave arm. The starting joint angle and target joint angle of the slave arm are 35, 30, 20, 0, 0, 0 and 0, −45, 30, −30, −15, 0, respectively. We can draw similar conclusions from the search results in Figure 12.
The simulation realizes the search process and results of a total of 12 joint angles of the main arms and slave arms. It can be seen from the search process that the joint angle search starts from the green starting point. At the beginning, because of the obstacles, the random points directly extended to the target point were not able to pass the obstacle detection. The algorithm explores the joint angle to avoid obstacles. After avoiding obstacles, all random nodes extended to the target point are quickly selected by the cost function, and the search efficiency is greatly improved.
To analyze the effectiveness of the GA_RRT algorithm for obstacle avoidance, the visualization results are presented in Figure 13 and Figure 14.
For static obstacles in the environment, as shown in Figure 13, the trajectory of the main arm is far away from the static obstacles. This can also be seen in Figure 14a. For the slave arm, the arm successfully avoids static obstacles, compared to Figure 8b. In addition, through the comparison of Figure 14a and Figure 8c, it can be seen that the slave arm realizes the static obstacle avoidance and completes the dynamic obstacle avoidance of the main arm.
After ten groups of angle planning experiments, the average planning time of the robotic arms is 2.04 s. Due to the complexity of transplanting different algorithms into the simulation of dual-arm robots, we here present a comparison by referencing the experimental data of algorithms that are similar [32]. The comparison results are shown in Table 4.
Compared to the traditional RRT algorithm, the search time of the GA_RRT algorithm is reduced by about 70% for the obstacle avoidance path planning of the dual-arm robot. Although the simulation environment is different, it can be seen that the algorithm is effective at accelerating the search efficiency.
Finally, in order to fully verify the effectiveness of the algorithm for dual-arm obstacle avoidance path planning, this paper changes the position and radius of the obstacle sphere, and records the experimental results of the GA_RRT algorithm several times. The center and radius of each obstacle in scenarios 1 and 2 are shown in Equations (11) and (12).
O s p h e r e 1 = [ 0.55 0.2 0.15 0.45 0.2 0.15 0.35 0.2 0.15 0.35 0.2 0.15 0.35 0.2 0.15 ] ;   R = [ 0 . 05 , 0 . 05 , 0 . 05 , 0 . 05 , 0 . 05 ]
O s p h e r e 2 = [ 0.55 0.2 0.15 0.45 0.2 0.15 0.3 0.3 0.15 0.4 0.25 0.15 0.5 0.3 0.05 ] ;   R = [ 0 . 08 , 0 . 1 , 0 . 06 , 0 . 06 , 0 . 06 ]
The path planning algorithm is tested ten times in each scenario, and the final average values of the tests are shown in Table 5.
From the analysis of successful times, we can find that the algorithm realizes obstacle avoidance path planning for the dual-arm robot in various scenarios. Compared with the slave arm, the master arm only considers spherical obstacles, and its path planning will be faster. This can also be seen from the experimental data. The slave arm needs to detect the motion state of the main arm for dynamic obstacle avoidance. In each scenario of ten tests, path planning time will be different. However, the final average in various scenarios is about 2s. This fully demonstrates that the algorithm is effective, and its average efficiency is reliable in the obstacle avoidance scenario of the dual-arm robot.

5. Conclusions

Based on the traditional RRT algorithm, this paper introduces the goal probability bias and A* cost function algorithm. The search time and efficiency of the RRT algorithm is greatly optimized. In addition, the generated paths are also locally optimized. The effectiveness of the GA_RRT algorithm is first verified by the simulation of planar obstacle avoidance path planning. Furthermore, the algorithm is applied to obstacle avoidance path planning simulation of a dual-arm robot. In the process of obstacle avoidance, not only static obstacles are considered, but also the influence of dynamic manipulator obstacles in real time. Finally, the simulation results show that the algorithm can realize the cooperative obstacle avoidance path planning of a dual-arm robot. In terms of search efficiency, it is also superior to the traditional RRT algorithm.
As a future research task, the experimental verification process will first need to be improved. In addition, the adaptive step size will be further used to improve the search efficiency of the algorithm. The visual method is also considered to detect the dynamic obstacles in the environment, so as to realize the dual-arm path planning in unstructured environments.

Author Contributions

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

Funding

This research was funded by China’s manned space program.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

Not applicable.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Bohren, J.; Rusu, R.B.; Jones, E.G.; Marder-Eppstein, E.; Pantofaru, C.; Wise, M.; Mösenlechner, L.; Meeussen, W.; Holzer, S. Towards autonomous robotic butlers: Lessons learned with the PR2. In Proceedings of the 2011 IEEE International Conference on Robotics and Automation, Shanghai, China, 9–13 May 2011; pp. 5568–5575. [Google Scholar]
  2. Matthias, B.; Kock, S.; Jerregard, H.; Kallman, M.; Lundberg, I.; Mellander, R. Safety of collaborative industrial robots: Certification possibilities for a collaborative assembly robot concept. In Proceedings of the 2011 IEEE International Symposium on Assembly and Manufacturing (ISAM), Tampere, Finland, 25–27 May 2011; pp. 1–6. [Google Scholar]
  3. Connolly, C. Motoman markets co-operative and humanoid industrial robots. Ind. Robot: Int. J. 2009, 36, 417–420. [Google Scholar] [CrossRef]
  4. Fuchs, M.; Borst, C.; Giordano, P.R.; Baumann, A.; Kraemer, E.; Langwald, J.; Gruber, R.; Seitz, N.; Plank, G.; Kunze, K.; et al. Rollin’Justin-Design considerations and realization of a mobile platform for a humanoid upper body. In Proceedings of the 2009 IEEE International Conference on Robotics and Automation, Kobe, Japan, 12–17 May 2009; pp. 4131–4137. [Google Scholar]
  5. Wang, M. Research on Collaborative Motion Planning and Control Methods of Dual-Arm Robots for Rescue Tasks; University of Science and Technology of China: Hefei, China, 2015. [Google Scholar]
  6. Peng, Y.C.; Carabis, D.S.; Wen, J.T. Collaborative manipulation with multiple dual arm robots under human guidance. Int. J. Intell. Robot. Appl. 2018, 2, 252–266. [Google Scholar] [CrossRef]
  7. Khatib, O. Real-time obstacle avoidance for manipulators and mobile robots. In Autonomous Robot Vehicles; Springer: New York, NY, USA, 1986; pp. 396–404. [Google Scholar]
  8. Abhishek, T.S.; Schilberg, D.; Doss, A.S.A. Obstacle Avoidance Algorithms: A Review. In Proceedings of the International Conference on Robotics, Intelligent Automation and Control Technologies (RIACT 2020), Chennai, India, 2–3 October 2020; Volume 1012, p. 012052. [Google Scholar]
  9. Palmieri, G.; Scoccia, C.; Palpacelli, M.C.; Callegari, M. Motion planning and control of redundant manipulators for dynamical obstacle avoidance. Machines 2021, 9, 121. [Google Scholar] [CrossRef]
  10. Duchoň, F.; Babinec, A.; Kajan, M.; Beňo, P.; Florek, M.; Fico, T.; Jurišica, L. Path planning with modified a star algorithm for a mobile robot. Procedia Eng. 2014, 96, 59–69. [Google Scholar] [CrossRef] [Green Version]
  11. Guruji, A.K.; Agarwal, H.; Parsediya, D.K. Time-efficient A* algorithm for robot path planning. Procedia Technol. 2016, 23, 144–149. [Google Scholar] [CrossRef] [Green Version]
  12. Han, B.; Luo, X.; Luo, Q.; Zhao, Y.; Lin, B. Research on Obstacle Avoidance Motion Planning Technology of 6-DOF Manipulator. International Conference on Geometry and Graphics; Springer: Berlin/Heidelberg, Germany, 2021; pp. 604–614. [Google Scholar]
  13. Wang, J.; Liu, S.; Zhang, B.; Yu, C. Manipulation Planning with Soft Constraints by Randomized Exploration of the Composite Configuration Space. Int. J. Control. Autom. Syst. 2021, 19, 1340–1351. [Google Scholar] [CrossRef]
  14. Glasius, R.; Komoda, A.; Gielen, S.C.A.M. Neural network dynamics for path planning and obstacle avoidance. Neural Netw. 1995, 8, 125–133. [Google Scholar] [CrossRef]
  15. Sung, I.; Choi, B.; Nielsen, P. On the training of a neural network for online path planning with offline path planning algorithms. Int. J. Inf. Manag. 2021, 57, 102142. [Google Scholar] [CrossRef]
  16. Gerke, M. Genetic path planning for mobile robots. In Proceedings of the American Control Conference, San Diego, CA, USA, 2–4 June 1999; pp. 596–601. [Google Scholar]
  17. Kang, H.B. Mechanical Dual-Arms: Collision-Free Path Planning of Robot Based on Improved Ant Colony Algorithms; Northeastern University: Shenyang, China, 2010. [Google Scholar]
  18. Tuncer, A.; Yildirim, M. Dynamic path planning of mobile robots with improved genetic algorithm. Comput. Electr. Eng. 2012, 38, 1564–1572. [Google Scholar] [CrossRef]
  19. Dorigo, M.; Maniezzo, V.; Colorni, A. Ant system: Optimization by a colony of cooperating agents. IEEE Trans. Syst. Man Cybern. Part B (Cybern.) 1996, 26, 29–41. [Google Scholar] [CrossRef] [PubMed] [Green Version]
  20. Silvia, M.; Irene, L. An ant colony system for responsive dynamic vehicle routing. Eur. J. Oper. Res. 2015, 245, 704–718. [Google Scholar]
  21. Zong, C.; Lu, L.; Lei, X.; Zhao, P. A path planning approach for multi-dof spatial manipulator via A* algorithm. J. Hefei Univ. Technol. (Nat. Sci.) 2017, 40, 164–168. [Google Scholar]
  22. Dijkstra, E.W. A note on two problems in connexion with graphs. Numer. Math. 1959, 1, 269–271. [Google Scholar] [CrossRef] [Green Version]
  23. Sanchez, G.; Latombe, J.C. Using a PRM planner to compare centralized and decoupled planning for multi-robot systems. In Proceedings of the IEEE International Conference on Robotics and Automation, Washington, DC, USA, 11–15 May 2002; pp. 2112–2119. [Google Scholar]
  24. Karaman, S.; Frazzoli, E. Sampling-based algorithms for optimal motion planning. Int. J. Robot. Res. 2011, 30, 846–894. [Google Scholar] [CrossRef]
  25. Jaillet, L.; Cortés, J.; Siméon, T. ‘Sampling-based path planning on configuration-space costmaps. IEEE Trans. Robot. 2010, 26, 635–646. [Google Scholar] [CrossRef] [Green Version]
  26. Pepy, R.; Lambert, A. Safe path planning in an uncertain-configuration space using RRT. In Proceedings of the 2006 IEEE/RSJ International Conference on Intelligent Robots and Systems, Beijing, China, 9–15 October 2006; pp. 5376–5381. [Google Scholar]
  27. LaValle, S.M.; Kuffner, J.J.; James, J. Randomized Kino-dynamic Planning. Int. J. Robot. Res. 1999, 15, 378–400. [Google Scholar]
  28. Urmson, C.; Simmons, R. Approaches for heuristically biasing RRT growth. In Proceedings of the 2003 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS 2003) (Cat. No. 03CH37453), Las Vegas, NV, USA, 27–31 October 2003; Volume 2, pp. 1178–1183. [Google Scholar]
  29. Li, Z.; Ma, H.; Zhang, X.; Fei, Q. Path planning of the dual-arm robot based on VT-RRT algorithm. In Proceedings of the 2019 Chinese Control Conference (CCC), Guangzhou, China, 27–30 July 2019; pp. 4359–4364. [Google Scholar]
  30. Jiang, H.; Jiang, X. An improved path planning algorithm based on RRT. J. Chongqing Univ. Technol. (Nat. Sci.) 2021, 35, 10–16. [Google Scholar]
  31. Shao, L.; Liu, H.; Chen, C.; Du, D.; Li, J.; Liu, H. Path Planning for Mobile Robots Based on Improved RRT Algorithm. In Proceedings of the 2020 IEEE International Conference on Mechatronics and Automation (ICMA), Beijing, China, 13–16 October 2020; pp. 1240–1244. [Google Scholar]
  32. Wei, K.; Ren, B. A method on dynamic path planning for robotic manipulator autonomous obstacle avoidance based on an improved RRT algorithm. Sensors 2018, 18, 571. [Google Scholar] [CrossRef] [PubMed] [Green Version]
  33. Andreas, V.; Knut, G. An optimization-based approach to dual-arm motion planning with closed kinematics. In Proceedings of the IEEE/RSJ International Conference on Intelligent Robots and Systems, Madrid, Spain, 1–5 October 2018; pp. 8346–8351. [Google Scholar]
  34. Kim, D.H.; Lim, S.J.; Lee, D.H.; Lee, J.; Han, C. A RRT-based motion planning of dual-arm robot for (Dis)assembly tasks. In Proceedings of the IEEE Conference on Intelligence and Safety for Robotics, Seoul, Korea, 24–26 October 2013. 6p. [Google Scholar]
  35. Li, Y.; Xu, D. Cooperative path planning of dual-arm robot based on gravitational adaptive step RRT. Robot 2020, 42, 606–616. [Google Scholar]
Figure 1. The model of the dual-arm robot.
Figure 1. The model of the dual-arm robot.
Applsci 12 04087 g001
Figure 2. Coordinate system of the main manipulator joint.
Figure 2. Coordinate system of the main manipulator joint.
Applsci 12 04087 g002
Figure 3. RRT algorithm random tree expansion process.
Figure 3. RRT algorithm random tree expansion process.
Applsci 12 04087 g003
Figure 4. Bounding sphere model of the dual-arm robot.
Figure 4. Bounding sphere model of the dual-arm robot.
Applsci 12 04087 g004
Figure 5. GA_RRT algorithm flow.
Figure 5. GA_RRT algorithm flow.
Applsci 12 04087 g005
Figure 6. The obstacle avoidance path planning result of scenario A (a) RRT; (b) G_RRT; (c) GA_RRT.
Figure 6. The obstacle avoidance path planning result of scenario A (a) RRT; (b) G_RRT; (c) GA_RRT.
Applsci 12 04087 g006
Figure 7. The obstacle avoidance path planning result of scenario B: (a) RRT; (b) G_RRT; (c) GA_RRT.
Figure 7. The obstacle avoidance path planning result of scenario B: (a) RRT; (b) G_RRT; (c) GA_RRT.
Applsci 12 04087 g007
Figure 8. Motion state decomposition without obstacle avoidance path planning: (a) initial state; (b) motion state 1, collide with the environment; (c) motion state 2, self-collision; (d) side view of final state.
Figure 8. Motion state decomposition without obstacle avoidance path planning: (a) initial state; (b) motion state 1, collide with the environment; (c) motion state 2, self-collision; (d) side view of final state.
Applsci 12 04087 g008
Figure 9. Exploration process of the main arm joint angle: (a) the first three joint angles of the main arm; (b) the posterior three joint angles of the main arm.
Figure 9. Exploration process of the main arm joint angle: (a) the first three joint angles of the main arm; (b) the posterior three joint angles of the main arm.
Applsci 12 04087 g009
Figure 10. The final result of the path planning for the main arm.
Figure 10. The final result of the path planning for the main arm.
Applsci 12 04087 g010
Figure 11. Exploration process of the salve arm: (a) the first three joint angles of the slave arm; (b) the posterior three joint angles of the slave arm.
Figure 11. Exploration process of the salve arm: (a) the first three joint angles of the slave arm; (b) the posterior three joint angles of the slave arm.
Applsci 12 04087 g011
Figure 12. The final result of the path planning for the slave arm.
Figure 12. The final result of the path planning for the slave arm.
Applsci 12 04087 g012
Figure 13. Static obstacle avoidance.
Figure 13. Static obstacle avoidance.
Applsci 12 04087 g013
Figure 14. GA_RRT obstacle avoidance trajectory: (a) self-collision avoidance; (b) side view of final state.
Figure 14. GA_RRT obstacle avoidance trajectory: (a) self-collision avoidance; (b) side view of final state.
Applsci 12 04087 g014
Table 1. DH parameters of the main robot arm.
Table 1. DH parameters of the main robot arm.
Joint Numberαa θd
1900 θ 1 89.2
20−425 θ 2 0
30−392 θ 3 0
4900 θ 4 109.3
5−900 θ 5 94.75
600 θ 6 82.5
Table 2. The average experimental data for Scenario A.
Table 2. The average experimental data for Scenario A.
RRTG_RRTGA_RRT
Total number of nodes25610549
Path length153913601373
Average time/s8.354.53.38
Table 3. The average experimental data for Scenario B.
Table 3. The average experimental data for Scenario B.
RRTG_RRTGA_RRT
Total number of nodes34812975
Path length683.53465.42459.3
Average time/s13.15.53.6
Table 4. Calculation time.
Table 4. Calculation time.
RRTBi-RRTS-RRTGA_RRT
Average Planning Time/s9.865.232.422.04
Table 5. Simulation results in different obstacle environments.
Table 5. Simulation results in different obstacle environments.
Robotic ArmPath LengthAverage Planning Time/sSuccessful Times
Scenario 0The main arm142.51.7310
The slave arm195.22.359
Scenario 1The main arm154.01.8710
The slave arm234.32.9010
Scenario 2The main arm153.91.6710
The slave arm163.82.2310
Publisher’s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

Shi, W.; Wang, K.; Zhao, C.; Tian, M. Obstacle Avoidance Path Planning for the Dual-Arm Robot Based on an Improved RRT Algorithm. Appl. Sci. 2022, 12, 4087. https://0-doi-org.brum.beds.ac.uk/10.3390/app12084087

AMA Style

Shi W, Wang K, Zhao C, Tian M. Obstacle Avoidance Path Planning for the Dual-Arm Robot Based on an Improved RRT Algorithm. Applied Sciences. 2022; 12(8):4087. https://0-doi-org.brum.beds.ac.uk/10.3390/app12084087

Chicago/Turabian Style

Shi, Wubin, Ke Wang, Chong Zhao, and Mengqi Tian. 2022. "Obstacle Avoidance Path Planning for the Dual-Arm Robot Based on an Improved RRT Algorithm" Applied Sciences 12, no. 8: 4087. https://0-doi-org.brum.beds.ac.uk/10.3390/app12084087

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