
Citation: Xuewu Wang, Bin Tang, Xin Zhou, Xingsheng Gu. Double-robot obstacle avoidance path optimization for welding process[J]. Mathematical Biosciences and Engineering, 2019, 16(5): 5697-5708. doi: 10.3934/mbe.2019284
[1] | Zhen Yang, Junli Li, Liwei Yang, Qian Wang, Ping Li, Guofeng Xia . Path planning and collision avoidance methods for distributed multi-robot systems in complex dynamic environments. Mathematical Biosciences and Engineering, 2023, 20(1): 145-178. doi: 10.3934/mbe.2023008 |
[2] | Yuzhuo Shi, Huijie Zhang, Zhisheng Li, Kun Hao, Yonglei Liu, Lu Zhao . Path planning for mobile robots in complex environments based on improved ant colony algorithm. Mathematical Biosciences and Engineering, 2023, 20(9): 15568-15602. doi: 10.3934/mbe.2023695 |
[3] | Baoye Song, Shumin Tang, Yao Li . A new path planning strategy integrating improved ACO and DWA algorithms for mobile robots in dynamic environments. Mathematical Biosciences and Engineering, 2024, 21(2): 2189-2211. doi: 10.3934/mbe.2024096 |
[4] | Liwei Yang, Lixia Fu, Ping Li, Jianlin Mao, Ning Guo, Linghao Du . LF-ACO: an effective formation path planning for multi-mobile robot. Mathematical Biosciences and Engineering, 2022, 19(1): 225-252. doi: 10.3934/mbe.2022012 |
[5] | Chikun Gong, Yuhang Yang, Lipeng Yuan, Jiaxin Wang . An improved ant colony algorithm for integrating global path planning and local obstacle avoidance for mobile robot in dynamic environment. Mathematical Biosciences and Engineering, 2022, 19(12): 12405-12426. doi: 10.3934/mbe.2022579 |
[6] | Ping Li, Liwei Yang . Conflict-free and energy-efficient path planning for multi-robots based on priority free ant colony optimization. Mathematical Biosciences and Engineering, 2023, 20(2): 3528-3565. doi: 10.3934/mbe.2023165 |
[7] | Wenyang Gan, Lixia Su, Zhenzhong Chu . A PSO-enhanced Gauss pseudospectral method to solve trajectory planning for autonomous underwater vehicles. Mathematical Biosciences and Engineering, 2023, 20(7): 11713-11731. doi: 10.3934/mbe.2023521 |
[8] | Jiliang Lv, Chenxi Qu, Shaofeng Du, Xinyu Zhao, Peng Yin, Ning Zhao, Shengguan Qu . Research on obstacle avoidance algorithm for unmanned ground vehicle based on multi-sensor information fusion. Mathematical Biosciences and Engineering, 2021, 18(2): 1022-1039. doi: 10.3934/mbe.2021055 |
[9] | Xue Li, Lei Wang . Application of improved ant colony optimization in mobile robot trajectory planning. Mathematical Biosciences and Engineering, 2020, 17(6): 6756-6774. doi: 10.3934/mbe.2020352 |
[10] | Zhenao Yu, Peng Duan, Leilei Meng, Yuyan Han, Fan Ye . Multi-objective path planning for mobile robot with an improved artificial bee colony algorithm. Mathematical Biosciences and Engineering, 2023, 20(2): 2501-2529. doi: 10.3934/mbe.2023117 |
In recent years, welding robots are widely used in research and industrial production [1]. Sometimes, a single robot system can't quickly complete some complex tasks such as car body welding. Hence, double-robot welding systems are developed for efficiency improvement. Some research works were done to study robot path planning and obstacle avoidance. All the welding joints are divided into two groups by using the elite particle swarm algorithm, and the double-robot path planning is treated as the welding path planning of the two individual robots [2]. The virtual point is introduced to convert the multi-traveling salesman problem into a single traveling salesman problem. And the shortest welding time is set as the optimization purpose [3]. Both methods determine the obstacle avoidance path of the two robots by the separation of the welding joints before the path planning of the dual robots. Besides, task sequencing and path planning for remote laser welding was studied based on TSP and meta-heuristic algorithm [4], and genetic algorithm was used to minimize the cycle time of the robotic spot welding operations [5]. For industrial welding robot task planning, manual planning is still widely used. It is time-consuming when there are large-scale weld joints. Hence, it is necessary to use automatic and efficient path optimization method.
As a widely used intelligent optimization algorithm, PSO [6] is used to solve path planning problem due to its simple structure, fast convergence speed and easy implementation. At the same time, many improvements were conducted for the PSO algorithm to solve the premature problem of PSO algorithm and accelerate the convergence rate of the algorithm. Algorithm improvements were studied on parameters [7], the position and velocity of PSO [8], local search PSO algorithm [9], fusion of different intelligent optimization algorithms [10], and updating strategy [11]. Improved PSO algorithm shows its advantages, such as fast convergence and global optimization. Therefore, an improved particle swarm optimization algorithm based on grouping and competition strategy is proposed to realize the welding robot path optimization.
In this paper, the welding time is set as the optimization objective first, and the collision test is realized based on welding gun pose consideration. Then, path optimization for two robots is conducted. Following above introduction, welding robot path optimization problem description is introduced in Section 2. Section 3 describes robots obstacle avoidance based on three-dimensional grid method modeling, and section 4 presents obstacle avoidance for robot joints. The dual-robot path optimization is given in Section 5 followed by conclusion.
A part of the white car is selected as work piece in this paper. The shape of the work piece and position of the welding joints are shown in Figure 1. The robot used here is ABB R2400 and the welding gun is GTAW10.
The time-optimal path planning for the dual-welding robot requires that the welding gun walks through all the welding joints and the welding time is the shortest. Suppose the number of the welding joints is M, number of the welding joints and transition points are N, and the order of the welding joints is π(i), (i = 1, 2, …, n). Then, the time optimal path planning problem can be regarded as a constraint TSP problem.
MinT=∑N−1i=1Lπ(i),π(i+1)/v | (1) |
where ∑N−1i=1Lπ(i),π(i+1) is the sum of the distances between all welding joints. If the pose of welding gun need to be changed or there is obstacle between some welding joints, ∑N−1i=1Lπ(i),π(i+1) includes the distance between the welding joint and the intermediate joint where the welding gun changes its pose or conduct obstacle avoidance, v is the welding speed which is set as 2m/s. The methods to define obstacles will be presented in Section3 and Section 4.
For double robot system, some other criteria should be considered in addition to the shortest time. First, the difference between the welding times for the two robots should be as small as possible to make sure the two welding robots finish the welding work at the same time nearly.
|T1−T2|<Tc | (2) |
Second, the paths need be monitored in real-time to make sure that the two welding guns will not influence each other. Hence, a safe distance between the two welding guns should be defined. The two welding guns will not influence each other as long as they keep a distance bigger than the safe distance. When the distance is smaller than the safe distance, the welding robot with a shorter welding distance will wait for a while to make sure the distance between the two welding guns is larger than the safe distance.
D(R1,R2)−dsafe≥0 | (3) |
Where R1,R2, represent robot1, robot2 respectively, and dsafe represents safe distance to avoid collision. Besides, the distance between the welding gun and the workpiece should be also larger than the safe distance.
D(R,W)−dsafe≥0 | (4) |
Where W denotes workpiece. Then, the two welding robots global path planning problem can be described as:
MinT1=∑N−1i=kLπ(i),π(i+1)/v,T2=∑N−1i=k+1Lπ(i),π(i+1)/v | (5) |
Subject to the constrains (2)–(4)
Based on the optimization problem description, the flow chart of dual-robot trajectory planning is presented in Figure 2. The two-robot path optimization is carried out to obtain the welding path using particle swarm optimization based on work piece modeling, local obstacle avoidance, and obstacle avoidance for robot joints. Local obstacle avoidance will be studied to obtain collision free path between the robot gun and the work piece in Section 3. Collision free path for the robot joints with work piece and fixture is studied in Section 4.
The first step to solve the robot path planning problem is robot working environment modeling. As the grid method is simple, the generated path is more intuitive and easier to judge the local environment, the three-dimensional grid method is selected in this paper for environmental modeling. After the work piece is simplified to a combination of multiple triangles, the grid matrix is established. Considering the searching time and path searching accuracy, this paper divides the whole space into cubes with a side length of 5 mm. The center of each cube is used as the starting point of the search path, and the center points are projected to the plane. If the projection point is outside the triangle which means that the triangle is not an obstacle to the point. If the projection point is inside the triangle and the length of the perpendicular is less than 6 mm that means the triangle is the obstacle of the point. As a result, the free grid and obstacle grid can be obtained. If there is an obstacle in the center point, it means that the point is an obstacle, otherwise it means that the point is a free point. Based on the established environment model, the obstacle between the robot end and the work piece will de identified in section 3.2.
Obstacle avoidance is very important for robot safety operation. Ant colony algorithm is applied to realize local obstacle avoidance path planning in this paper. Local search starts from initial solution, and begin to search the vicinity field. If particle can find a better solution, then replace the initial solution.
The parameters of ACO are initialized as follows. Based on the empirical value, the weight of the pheromone α is set as 1, the weight of heuristic pheromone β is set as 11, the evaporation coefficient of pheromone ρ is set as 0.9, and the pheromone quality coefficient Q is set as 5. The iteration number N is set as 50, and the population quantity M is set as 50. Initialize the coordinates of the starting point and the terminal point. Initialize the pheromone matrix, and the pheromones for all points are set as 0.5. Iterator is defined as n. The number of ant is k.
Then, the probability of each node is calculated. The step length unit for adjacent node is set as 1, the maximum number of nodes which can be selected is set as 6. When the adjacent node is obstacle, it can't be chose. Then, the number of optional nodes is less than 6. The ant will move to the next node according to the roulette method, and the selected node is added to the taboo table. If the ant arrives at the end point or the optional node number is 0, the path is cleared from the taboo table. And the next node direction is selected again until all directions are taken. If the optional node number is 0, then this path won't be recorded in the taboo table. When the ant reaches the end point, the path length L is calculated until the iteration ends. The final obtained shortest path is selected as the welding robot obstacle avoidance path.
The local obstacle avoidance path of the two robots can be obtained by the local searching algorithm. However, the path obtained by ant colony algorithm is not a straight line, it can't meet requirement of the shortest welding path. To achieve the shortest and collision free welding path, second optimization is conducted. Principles of the second optimization are presented as follows. Some nodes are canceled and the left nodes are connected to obtain a shorter path. In the process, collision detect is always conducted to promise a collision free path.
Based on the above work, the path is collision free for the robot end and the work piece. However, in the actual industrial production process, it is not enough. The trajectory of the robot is based on all joints movement, and it is necessary to promise collision free path for the robot joints and work piece.
To meet the actual obstacle avoidance requirements, the obstacle avoidance trajectory for robot joints is studied using geometric collision detection. According to the welding path in this paper, there is no collision between the two robots. Hence, the collision detection in this paper focuses on the detection between the robot joints and the work piece. Collision detection here includes rough detection, accurate detection and path selection after collision.
The Bounding box technology and Spatial division method [12] are considered in this paper, whereafter the spatial division was chose to realize rough detection, and the work piece area division is shown in Figure 3.
In Figure 3, the work piece is divided into five regions. The distance between the center axis of each joint of the robot and the plane of the different area of the work piece is calculated, and the area with the shortest distance is selected as collision area in the rough detection phase, which is most likely to collide with the robot.
After bounding box [13], artificial Field [14], and geometric methods are analyzed, geometric method is selected to realize accurate collision detection.
According to the results of rough detection, it can be seen that the area most likely collide is the edge of each plane, which is also the key composition of the model. In geometric accurate detection, the distance between each joint of the robot and the edge line where the collision area may occur is calculated using the simplified robot model. In welding process, the robots are placed on the both sides of the work piece. Hence, in the accurate collision detection process, the distance between the robot model and work piece edge is calculated. And there are two situations for the calculation, which are the shortest distance from the center of the ball to the edge of the work piece and the shortest distance from the axis line of the cylinder to the edge of the work piece.
When the geometry is the ball or hemisphere, the shortest distance is the distance from the center to the edge line, as shown in Figure 4. M0(x0,y0,z0),M1(x1,y1,z1) are the coordinates of two endpoints of the segment, O(x,y,z) is the coordinates of center of the circle. When the geometry is a cylinder, the shortest distance is the distance from the axis line to the edge line, it is shown in Figure 5.
After the collision is detected between the robot and the work piece in the welding process, some obstacle avoidance strategy needs to be applied to avoid the collision and promise the following weld joints welding procedure. In this case, Geometric method [15] is applied in this paper to avoid collision, and the middle point is found to realize obstacle avoidance.
Geometric method is a mathematical method of calculating the distance from a robot to a work piece. Based on the simplified robot model, the distance between the joints of the robot and the work piece is calculated to avoid collision.
Because the traditional PSO algorithm is slow to converge and easy to fall into local optimum, a group competition particle swarm optimization (GC-PSO) algorithm is proposed in this paper. The algorithm divides the particle into two parts according to the fitness value of each particle. Particles with fitness value in the top 20% of the total fitness value are regarded as leading particles, and the remaining particles are set as the following particles. After all particles are divided into two parts, all the particles are grouped randomly, each group consists of a leading particle and some following particles where the following particles are randomly assigned to the leading particles and the number of following particles in each group is not unique. When iteration number satisfies G=10, the fitness value of the particle will be reordered. Then, the leading particle and following particle are defined according to the fitness value. And all the particles are grouped randomly again.
The group competition PSO algorithm adopts different speed updating strategy for different particles. In order to avoid the particle falling into local optimum, the group competition PSO algorithm introduces the intra-group competition and inter-group competition in the speed update formula.
The velocity update formulas for leading particles is described as follows:
vt+1i=ω∗vti+vti∗Randn(0,σ2) | (6) |
σ2={1,iffi<fke−fi+fk|fi+ε|,otherwise,k∈[1,Nl],k≠i | (7) |
The location update formula for leading particles is described as follows:
xk+1i=xki+vk+1i | (8) |
where Randn (0,σ2) is a Gaussian distribution function with mean 0 and variance σ2. The parameter Randn (0,σ2) expands the searching range of particle and avoids particle falling into local optimization. ε is an infinitely small number which promise the denominator is not zero. k denotes the subscript number of the other leading particles which will increasing the competition between the particles. This strategy can make particle with the poor fitness move closer to the particle with better fitness. f is the corresponding fitness value of each particle. Nl is number of leading particles.
Speed update formulas for following particle are given as follows:
vt+1i=ω∗vti+s1∗Rand∗(vtj1−vti)+s2∗Rand∗(vtj2−vti) | (9) |
s1=efi−fj1|fi|+ε,s2=e(fj2−fi) | (10) |
Location update formula for following particle is given as follows:
xk+1i=xki+vk+1i | (11) |
The velocity update formula of the following particle contains two parameters s1 and s2. s1 is the intra-group competition coefficient, j1 is the subscript number of leading particles in the group. Following particle competes with the leading particle with probability s1. s2 is the inter-group competition coefficient, j2 is the number of the leading particles in the other group. The following particles in this group compete with the leading particles in other groups with the probability s2. ε is an infinitely small number which promise the denominator is not zero. f denotes the fitness value of the particle.
Although the GC-PSO shows the ability of fast convergence and optimization, it can only solve the continuous problem. To solve the problem of dual-robot path planning, the GC-PSO algorithm needs to be discretized.
In the discrete particle swarm optimization algorithm, each particle represents a feasible solution, and the population is a set of feasible solutions. Same to continuous PSO algorithm, xi in discrete particle swarm algorithm also represents the ith sorting result, vi represents the velocity of ith particle, pbest, and represents the best individual, gbest represent the best population sort. Among them, vi is a set of directions the particle can search, xi, pbest, gbest are the results of optimization. Then (6), (8), (9) and (11) are updated as follows. Velocity and position update equation for leading particle are presented as:
vt+1i=ω∗vti+vti∗Randn(0,σ2) | (12) |
xt+1i=xti⊕vt+1i | (13) |
Velocity and position update equation for following particle are presented as:
vt+1i=ω∗vti+s1∗Rand∗(vtj1−vti)+s2∗Rand∗(vtj2−vti) | (14) |
xt+1i=xti⊕vt+1i | (15) |
Where the operators +, -, and ⊕ also have new definitions. The definitions include the rule of particle crossover and combination with individual and global, which is important to transfer continuous algorithm to the discrete algorithm. Subtraction operator (−) represents the difference set of individual optimal position and the current position. For multiply operator ⊕, take xti⊕vt+1i as example, vt+1i is a set of particle exchange order, and ⊕ operation refers to conduction exchange order vt+1i for vti. Addition operator (+) represents the union of two edge sets. The above discretization method inherits the characteristics of continuous GC-PSO. The updating process of GC-PSO is the process moving to the global optimal solution.
Convergence rate and accuracy between standard PSO, GA, GAPSO and GC-PSO algorithm are compared based on four traveling salesman problems. Four algorithms run independently 30 times for each test function, the population size is set as 100, and the maximum number of iterations for each run is set as 500. ω decreases exponentially from 0.9 to 0.4 with the iteration increase.
The average convergence curves of the four algorithms are shown in Figure 6. It can be concluded that GC-PSO still shows excellent convergence speed and convergence accuracy with the same parameters and discrete method. GC-PSO algorithm uses the intra-group and inter-group competitions in the speed update formula to make each particle move toward the global optimal particle. The group division strategy ensures that the algorithm will not fall into the local optimum. The simulation results show that the GC-PSO algorithm is still feasible and efficient after discretization.
In this paper, it is assumed that the welding speed of the robot is 2 m/s, and the welding time of each weld joint is 0.5 s. In order to meet the requirement of the shortest welding time, welding joints are divided considering the welding pose. This principle can reduce the welding pose change in welding process. The welding gun reverses when it arrives at the transition point, and the reversing time is set as 2 s to facilitate the calculation.
Based on the above-mentioned environmental modeling, the obstacle avoidance strategy between robot and work piece, the GC-PSO algorithm is used to optimize the robot welding time, and realizes the time optimal obstacle avoidance path planning. After parameters initialization, the positions of two robots are placed on opposite sides of the work piece, and the coordinates for the weld joints are determined. Then, the weld joints are divided for two robots according to the same welding time principle. Besides, models for work piece and robot working space are established according to the grid method. And the local path planning is realized using the ant colony algorithm, which promise collision free path for the robot and work piece. At last, global path optimization is conducted based on the particle swarm optimization algorithm.
The path planning results with obstacle avoidance for the dual-robot is shown in Figure 7. The welding path length for two robots are 87.961 mm and 109.29004 mm respectively, and obstacle avoidance path length for two robots are 21.23 mm and 57.5621 mm. The final optimal welding time is 123.259072 s. The global path planning of the dual robot path order: 19–20–21–22–23–25–27–28–26–24–31–30–29 and 1–2–3–4–5–8–7–6–9–10–11–12–13–16–15–17– 14–18.
The actual workpiece is used in this paper, and the welding path optimization studied in this paper is similar to practical welding situations. Hence, the obtained welding path can help welding engineering by shortening the teaching time based on the optimization strategy. And, the optimization strategy can be used to improve the path planning ability for offline programming (OLP) after the optimization strategy is integrated with OLP software.
From Figure 8, it can be seen that there are several optimization objectives and influence facotrs need to be studied in the welding robot path optimization. Hence, some works are necessary to be considered for better optimization results. The future work will focus on the real welding robot system optimization to test the effectiveness of the proposed strategy in practical industrial application. Firstly, the model for the workpiece and the fixture should be more complex and accurate. Secondly, cooperation between the two robots can be studied to obtain better optimization results [16,17]. Thirdly, the optimization results will be tested using some offline programing software. At last, calibration will be studied to realize path optimization for real welding robot system.
Traditional teaching method for industrial robot is time-consuming and has difficulties in batch production. The proposed strategy could improve the efficiency in welding process. The environmental modeling and local obstacle avoidance was introduced firstly. Then, two-level collision detection and geometrical collision avoidance, obstacle avoidance of robot joints was studied based on the previous robot modeling. Finally, welding robot path optimization procedure was realized using improved PSO algorithm. Simulation results show high efficiency and precision of the path planning strategy, and it is suitable for welding robot path planning.
This study was funded by National Natural Science Foundation of China (Grant Number 61773165, 51775416, 61573144).
All authors declare that they have no conflict of interest.
[1] | L. J. Zhang, J. Ning, X. J. Zhang, et al., Single pass hybrid laser–mig welding of 4-mm thick copper without preheating, Mater. Design, 74 (2015), 1–18. |
[2] | X. W. Wang, Y. P. Shi, D. Y. Ding, et al., Double global optimum genetic algorithm–particle swarm optimization based welding robot path planning, Eng. Optimiz., 48 (2016), 299–316. |
[3] | Z. T. Wang, Z. L. Feng, G. Y. Ye, et al., Path planning of double robot based on artificial bee colony algorithm, Trans. China Weld. Inst., 2 (2015), 97–100. |
[4] | A. Kovács, Integrated task sequencing and path planning for robotic remote laser welding, Int. J. Prod. Res., 4 (2016), 1210–1224. |
[5] | M. Givehchi, A. H. C. Ng and L. Wang, Spot-welding sequence planning and optimization using a hybrid rule-based approach and genetic algorithm, Robot. Comput. Integr. Manuf., 4 (2011), 714–722. |
[6] | J. Kennedy and R. C. Eberhart, Particle swarm optimization, Process of IEEE International Conference on Neural Networks, Perth, Australia: IEEE Service Center, (1995), 1942–1948. |
[7] | M. J. Amoshahy, M. Shamsi and M. H. Sedaaghi, A novel flexible inertia weight particle swarm optimization algorithm, PLoS One, 38 (2016), 281–295. |
[8] | B. Najeh, Improved accelerated PSO algorithm for mechanical engineering optimization problems, Appl. Soft. Comput., 40 (2016), 455–467. |
[9] | Y. Ye, C. B. Yin, Y. Gong, et al., Position control of nonlinear hydraulic system using an improved PSO based PID controller, Mech. Syst. Signal Proc., 83 (2017), 241–259. |
[10] | A. Benvidi, S. Abbasi, S. Gharaghani, et al., Spectrophotometric determination of synthetic colorants using PSO–GA-ANN, Food Chem., 220 (2017), 377–384. |
[11] | D. Q. Wu and J. G. Zheng, Parallel particle swarm optimization algorithm based on hybrid strategy adaptive learning. J. Control Decis., 28 (2013), 1087–1093. |
[12] | X. Y. Qu, L. Ma and C. Z. Yao, Research of collision detection algorithm based on hybrid bounding box for complex environment. IEEE ICICM, (2017), 248–252. |
[13] | Y. F. Zhu and J. Meng, Efficient Approach Based on Hybrid Bounding Volume Hierarchy for Real-time Collision Detection, J. Syst. Simulat., 19 (2008), 5099–5104. |
[14] | Y. J. Yan and Y. Zhang, Collision avoidance planning in multi-robot based on improved artificial potential field and rules. Proceedings of the 2008 IEEE ROBIO, Bangkok, Thailand, (2009), 1026–1031. |
[15] | X. W. Wang, Y. X. Yan and X. S. Gu, Spot welding robot path planning using intelligent algorithm. J. Manuf. Process., 42 (2019), 1–10. |
[16] | N. Kousi, G. Michalos, S. Aivaliotis, et al., An outlook on future assembly systems introducing robotic mobile dual arm workers. Procedia CIRP, 72 (2018), 33–38. |
[17] | S. Makris, P. Tsarouchi, A. S. Matthaiakis, et al., Dual arm robot in cooperation with humans for flexible assembly. CIRP Ann. Manuf. Tech., 66 (2017), 13–16. |
1. | Xuewu Wang, Xin Zhou, Zelong Xia, Xingsheng Gu, A survey of welding robot intelligent path optimization, 2021, 63, 15266125, 14, 10.1016/j.jmapro.2020.04.085 | |
2. | Yan Gao, Yiwan Zhang, Wei-Chiang Hong, Path Optimization of Welding Robot Based on Ant Colony and Genetic Algorithm, 2022, 2022, 1687-0042, 1, 10.1155/2022/3608899 | |
3. | Gaoping Xu, Zhuo Meng, Shuo Li, Yize Sun, Collision-free trajectory planning for multi-robot simultaneous motion in preforms weaving, 2022, 40, 0263-5747, 4218, 10.1017/S026357472200087X | |
4. | Xiaojiao Chen, Ling Chen, Lantian Fu, Chengliang Wang, Algorithm Selection and Application for Robot Path Planning Problems, 2024, 2722, 1742-6588, 012008, 10.1088/1742-6596/2722/1/012008 | |
5. | Sining Cheng, Huiyan Qu, Yang Gao, Real-Time Collision Detection Optimization Algorithm Based on Snake Model in the Field of Big Data, 2023, 2023, 1875-905X, 1, 10.1155/2023/4960900 |