Minimum time path planning of robotic manipulator in drilling/spot welding tasks

17 Apr.,2023

 

Abstract

In this paper, a minimum time path planning strategy is proposed for multi points manufacturing problems in drilling/spot welding tasks. By optimizing the travelling schedule of the set points and the detailed transfer path between points, the minimum time manufacturing task is realized under fully utilizing the dynamic performance of robotic manipulator. According to the start-stop movement in drilling/spot welding task, the path planning problem can be converted into a traveling salesman problem (TSP) and a series of point to point minimum time transfer path planning problems. Cubic Hermite interpolation polynomial is used to parameterize the transfer path and then the path parameters are optimized to obtain minimum point to point transfer time. A new TSP with minimum time index is constructed by using point-point transfer time as the TSP parameter. The classical genetic algorithm (GA) is applied to obtain the optimal travelling schedule. Several minimum time drilling tasks of a 3-DOF robotic manipulator are used as examples to demonstrate the effectiveness of the proposed approach.

Highlights

  • In this paper, an optimization strategy is proposed for solving minimum time manufacturing path planning in multi points manufacturing tasks.

  • According to the start-stop movement in drilling/spot welding task, the path planning problem is converted into a traveling salesman problem (TSP) and a series of point to point minimum time transfer path planning problems.

  • Cubic Hermite interpolation polynomial is used to parameterize the transfer path and then the path parameters are optimized to obtain minimum point to point transfer time.

  • A new TSP with minimum time index is constructed and then solved by using a classical genetic algorithm (GA).

  • Numerical test is executed to demonstrate the effectiveness of the proposed approach.

1 Introduction

Minimum time motion planning problems for robotic manipulator were widely studied in industrial applications and several efficient solution methods are proposed. Aiming at the minimum time motion planning problem along given path, Bobrow et al. [1] proposed a phase plane analysis approach to obtaining minimum time motion trajectory with confined torque. The similar problems were solved by Zhang et al. [2] with a greedy search algorithm and Zhang et al. [3, 4] with convex optimization approaches. For the more general minimum time point-to-point motion planning problem, the solution becomes complex since the path and the motion along the path need to be optimized simultaneously. Bobrow [5] applied the phase plane analysis approach to calculate minimum motion time along given path, then the point-to-point motion planning problem was solved by searching minimum time path in feasible path space.

Different from the simplex motion planning problems as mentioned above, in manufacturing industry there exists a class of complex tasks called multi-points manufacturing, such as drilling [6, 7], spot welding and assembly [8]. These tasks have many unordered points and hence it is necessary to plan an optimal strategy to traverse all the desired points in an orderly way while satisfying the requirement of minimum distance, minimum time or minimum energy, etc.

It is shown that the studied drilling/ spot welding tasks can be described by a performance limited traveling salesman problem (TSP) [9–11]: the manipulator effector acts as the salesman, it starts from one machining point and passes through each point just by once meanwhile it must be full stopped to finish the machining task. Since its high computational complexity, the solution of TSP is always an open problem. Currently, the feasible solutions of TSP can be classified by enumeration method, dynamic programming, branch and bound method, or intelligent optimization method (such as genetic algorithm (GA) [12], simulated annealing (SA), Particle Swarm Optimization (PSO), etc).

In order to simplify the problem, the common path planning strategies for multi points manufacturing assume the transfer path between any two points is straight line, and the problem can be described as a TSP with minimum distance index [11]. However according to Bobrow [8] and Dubowsky and Blubaugh [9], it is shown that due to the nonlinear expressions of the manipulator kinodynamics and gravitational torques, it is non-equivalent between the minimum time path and the minimum distance path, even the minimum time path from point i to point j is also different from the point j to point i path. Hence besides the optimization of travelling schedule of the set points, the transfer paths between machining points also need to be optimized to obtain the minimum transfer time.

In this paper, the minimum time path planning problem for multi points manufacturing is studied. Since the travel schedule of the set points and the detailed transfer path between points must be optimized simultaneously, a mixed integer optimal control formulation is constructed to describe the problem. Based on the start-stop movement in drilling/spot welding task, the problem can be further converted into a pure integer linear programming problem and a series of point to point minimum time transfer path planning problems. In this paper, a typical genetic algorithm (GA) is applied to solve the generated integer linear programming problem. And cubic Hermite interpolation polynomial is used to parameterize the transfer path and then the path parameters are optimized to obtain minimum point to point transfer time.

2 Problem description

In practical applications, the 6-DOF robotic manipulator is usually required to obtain the free position and orientation output of the end effector. The common configuration of a 6-DOF manipulator is that the first three joints are used to locate the position of the end effector and the last three joints realize the orientation adjustment through cooperation.

τ=M(q)q¨+q̇TC(q)q̇+G(q),

(1)

q∈Rn

denotes the vector of joint angular position,

τ∈Rn

denotes the vector of joint toques,

M(q)∈Rn×n

is the inertia matrix of manipulator which is symmetric in which the diagonal elements

M(j,j)

describe the inertia seen by joint

j

and the off-diagonal elements

M(i,j)

represent coupling of acceleration from joint

j

to the generalized force on joint

i⁠

,

C(q)∈Rn×n×n

contains the information of centrifugal and Coriolis forces in which the centripetal torques are proportional to

q̇2(i)⁠

, while the Coriolis torques are proportional to

q̇(i)q̇(j)⁠

,

G(q)∈Rn

is the vector of gravity-induced torques which always exists even when the robot is stationary or moving slowly,

n=3⁠

.

In this paper, we focus on the position optimization at each time and the effector orientation can be calculated automatically according to the manufacturing requirement. Hence, only the first three joints of manipulator are discussed here. The dynamics model of robotic manipulator with first three joints can be formulatedwheredenotes the vector of joint angular position,denotes the vector of joint toques,is the inertia matrix of manipulator which is symmetric in which the diagonal elementsdescribe the inertia seen by jointand the off-diagonal elementsrepresent coupling of acceleration from jointto the generalized force on jointcontains the information of centrifugal and Coriolis forces in which the centripetal torques are proportional to, while the Coriolis torques are proportional tois the vector of gravity-induced torques which always exists even when the robot is stationary or moving slowly,

The goal of this paper is to plan a reasonable path along which the manipulator drills all the given points only by once while the task time is minimum under the dynamics limits of the manipulator.

nc

denote the number of the task points. Define

p1,p2,⋯,pnc

as the effector positions in task space corresponding to the

nc

drilling points and

pi∈R3⁠

. The motion performance of each joint is restricted by the torque constraint,

−τB≤τ≤τB.

(2)

Letdenote the number of the task points. Defineas the effector positions in task space corresponding to thedrilling points and. The motion performance of each joint is restricted by the torque constraint,

−q̇B≤q̇≤q̇B,

(3)

ṗ=J(q)q̇

and

J(q)

denotes the Jacobian matrix of the forward kinematics map.

And the joint velocity constraint,where the joint velocity satisfiesanddenotes the Jacobian matrix of the forward kinematics map.

q̇i=0

corresponding to the

i

th point position

pi

in task space with

i=1,2,⋯,nc⁠

. Above all, the desired minimum time path planning problem for drilling/ spot welding tasks has the following formulation.

minq(t)Tfs.t.{qi−QWi=0,q̇i=0,i=1,2,⋯,nc,∑i=1ncWi=[1,1,⋯,1]ncT,τ=M(q)q¨+C(q,q̇)q̇+G(q),−τB≤τ≤τB,−q̇B≤q̇≤q̇B,q∈Ωq.

(4)

Q=[q1,q2,⋯,qnc]n×nc

contains all the joint positions of task points, and

q̇i

denotes the joint velocity at the

i

th task position,

W∈Znc×nc

act as a enable switch to ensure the manipulator pass all the given points only by once,

Wi∈{0,1}nc

is a

nc

-dimension column vector,

Ωq

denotes the geometry constraint of the joint position,

0=t1<t2<⋯<tnc=Tf⁠

.

Since the end effector need keep still during the drilling/ spot welding process, then we havecorresponding to theth point positionin task space with. Above all, the desired minimum time path planning problem for drilling/ spot welding tasks has the following formulation.where,contains all the joint positions of task points, anddenotes the joint velocity at theth task position,act as a enable switch to ensure the manipulator pass all the given points only by once,is a-dimension column vector,denotes the geometry constraint of the joint position,

Problem (4) is a typical mixed integer optimal control problem. Similar to Dubowsky and Blubaugh [9], since the motion velocity of each joint need drop to zero at the task point, Problem (4) can actually be decomposed into a minimum time TSP and a series of point to point minimum time path planning sub problem with only continuous variables.

In this paper, each point to point path planning subproblem is solved by a direct parameterization approach to obtain minimum transfer time Tij⁠, then minimum time TSP is constructed and solved by a typical genetic algorithm (GA).

3 Sub problem solution-Obtain transfer path and

Tij

qi

to

qj

can be formulated as

minq(t)Tijs.t.{τ=M(q)q¨+C(q,q̇)q̇+G(q),−τB≤τ≤τB,−q̇B≤q̇≤q̇B,q̇(0)=0,q̇(Tij)=0,q(0)=qi,q(Tij)=qj,q∈Ωq.

(5)

The minimum time path planning sub problem from pointtocan be formulated as

s∈[0,1]⁠

, the parametric path from point

i

to point

j

can be described as

q(s)=h00(s)qi+h10(s)ri+h01(s)qj+h11(s)rj,s∈[0,1]

(6)

ri

denotes the initial slope of the path and

rj

denotes the final slope. The Hermite bases in (6) are

h00=2s3−3s2+1,h01=−2s3+3s2,h10=s3−2s2+s,h11=s3−s2.

(7)

In order to generate smooth transfer path, the cubic Hermite polynomial is applied to approximate the path. Define path parameter as, the parametric path from pointto pointcan be described aswheredenotes the initial slope of the path anddenotes the final slope. The Hermite bases in (6) are

s

is

q′(s)=dqds=h00′(s)pi+h10′(s)ri+h01′(s)pj+h11′(s)rj,

(8)

q″(s)=d2qds2=h00″(s)pi+h10″(s)ri+h01″(s)pj+h11″(s)rj.

(9)

Then the gradient information of the path w.r.t parameteris

q̇(t)=q′(s(t))ṡ(t).

(10)

The joint velocity can be equivalent to

τ=m(s)s¨+c(s)ṡ2+g(s),

(11)

m(s)=M(q(s))q′(s)∈Rn,c(s)=M(q(s))q″(s)+C(q(s),q′(s))q′(s)∈Rn,g(s)=G(q(s))∈Rn.

The joint torque becomeswhere,

ri,rj

and the parameter acceleration variable

s¨(t)⁠

. Define new variables

a=ṡ2

and

b=s¨⁠

. Define path variable

u=[riT,rjT]T⁠

, then problem (5) can be rewritten as the following optimal control problem in parameter space.

min(u,b)Tij=∫011adss.t.{τ(s)=m(u,s)b+c(u,s)a+g(u,s),−τB≤τ(s)≤τB,−q̇B≤q′(u,s)a≤q̇B,q̇(u,0)=0,q̇(u,1)=0,q(u,0)=pi,q(u,1)=pj,q(u,s)∈Ωq.

(12)

Hence, the variables, which need to be optimized in problem (5), are the path slopesand the parameter acceleration variable. Define new variablesand. Define path variable, then problem (5) can be rewritten as the following optimal control problem in parameter space.

u

and there is no explicit correlation between the optimizing objective and the path variable

u⁠

. On the other hand, we can see the motion variables

(a,b)

are linear in constraint functions of problem (12) and convex in the optimizing objective. Based on above, a reasonable nest optimization strategy is proposed in this paper [8, ]. Assume the path variable

u

is fixed in problem (12), then a convex optimization solution can be realized since problem (12) has a convex optimal problem formula at this time. So for each variable

u

corresponding to any feasible nonsingular path, there exists a unique optimal variable pair

(a*,b*)

and unique minimum transfer time

Tij*⁠

. Then the minimum time point to point path planning problem can be further described as the following optimization problem.

minu(Tij*),s.t.q(u,s)∈Ωq.

(13)

Usually, problem (12) can be approximated as a NLP problem by the common direct parameterization methods, such as CVP, simultaneous approach, et al, then solved by SQP, BFGS, et al. However, on the one hand, from Equ. (11) we have that the problem (12) is strong nonlinear w.r.t the path variableand there is no explicit correlation between the optimizing objective and the path variable. On the other hand, we can see the motion variablesare linear in constraint functions of problem (12) and convex in the optimizing objective. Based on above, a reasonable nest optimization strategy is proposed in this paper [ 13 ]. Assume the path variableis fixed in problem (12), then a convex optimization solution can be realized since problem (12) has a convex optimal problem formula at this time. So for each variablecorresponding to any feasible nonsingular path, there exists a unique optimal variable pairand unique minimum transfer time. Then the minimum time point to point path planning problem can be further described as the following optimization problem.

The two levels nest optimization strategy for solving problem (13) is shown in Fig. 1, where λ is the searching step in each NLP loop, d is the searching direction which is calculated based on the negative gradient direction. In practice, problem (13) can be solved by using existing NLP solver, such as SQP, BFGS, et al.

Fig. 1

Open in new tabDownload slide

The two levels nest optimization strategy for the point to point minimum time transfer path planning problem.

4 Master problem- minimum time traversal for multi points

The optimal path planning problem for multi points manufacturing applications can actually be described as a TSP. Define matrix D as measurement matrix of the TSP. Then for the minimum distance strategy, there exists Dij=Dji for any i and j which means the distance from point i to j is equal to that from j to i⁠. However, for the minimum time strategy, the element of D denotes the transfer time, written as Dij=Tij* and according to [8, 9] the condition Dij=Dji cannot be satisfied in most cases.

minTf=∑i=1nc∑j=1ncWijDijs.t.{∑i=1ncWij=1,j=1,2,⋯,nc,∑j=1ncWij=1,i=1,2,⋯,nc,Wij∈{0,1},Dii=0.

(14)

The minimum time path for multi points manufacturing process can be obtained by solving the following integer linear programming problem.

In this paper, a classical genetic algorithm is applied to search the optimal traversal path. Simulated natural selection, heredity and mutation processes are executed in our genetic algorithm. The algorithm procedure is programmed as follows:

GA based path selection procedure:

Input: The number of points

nc⁠

, the calculated measurement matrix

D⁠

Output: Optimized traversal path and the minimum time motion trajectory. ProcedureInitialization: Population size

pop_size⁠

;

i=0⁠

; Number of generation

max_gen⁠

; Initialize the traversal order population

Pa_pop(i)

=randperm (

pop_size⁠

,

nc⁠

) under the criterion in problem (14); Based on the measurement matrix

D⁠

, evaluate the corresponding minimum time of each individual of the population

Pa_pop(i)

and select the best solution

Tmin*⁠

Loop: While (

i

<

max_gen⁠

) Step 1. Under the criterion in problem (14), regenerate offspring population

Ch_pop(i)

from

Pa_pop(i)

by applying the crossover and mutation operations; Step 2. According to matrix

D⁠

, evaluate the corresponding minimum time of each individual of the population

Ch_pop(i)

and select the best solution

Tmin⁠

; Step 3. Update the best solution

Tmin*=Tmin⁠

, if current

Tmin*>Tmin⁠

; Step 4. Select new population

Pa_pop(i+1)

from

Pa_pop(i)

and

Ch_pop(i)⁠

; Step 5.

i=i+1⁠

. End while. End Procedure. GA based path selection procedure:

Input: The number of points

nc⁠

, the calculated measurement matrix

D⁠

Output: Optimized traversal path and the minimum time motion trajectory. ProcedureInitialization: Population size

pop_size⁠

;

i=0⁠

; Number of generation

max_gen⁠

; Initialize the traversal order population

Pa_pop(i)

=randperm (

pop_size⁠

,

nc⁠

) under the criterion in problem (14); Based on the measurement matrix

D⁠

, evaluate the corresponding minimum time of each individual of the population

Pa_pop(i)

and select the best solution

Tmin*⁠

Loop: While (

i

<

max_gen⁠

) Step 1. Under the criterion in problem (14), regenerate offspring population

Ch_pop(i)

from

Pa_pop(i)

by applying the crossover and mutation operations; Step 2. According to matrix

D⁠

, evaluate the corresponding minimum time of each individual of the population

Ch_pop(i)

and select the best solution

Tmin⁠

; Step 3. Update the best solution

Tmin*=Tmin⁠

, if current

Tmin*>Tmin⁠

; Step 4. Select new population

Pa_pop(i+1)

from

Pa_pop(i)

and

Ch_pop(i)⁠

; Step 5.

i=i+1⁠

. End while. End Procedure.  Open in new tab

GA based path selection procedure:

Input: The number of points

nc⁠

, the calculated measurement matrix

D⁠

Output: Optimized traversal path and the minimum time motion trajectory. ProcedureInitialization: Population size

pop_size⁠

;

i=0⁠

; Number of generation

max_gen⁠

; Initialize the traversal order population

Pa_pop(i)

=randperm (

pop_size⁠

,

nc⁠

) under the criterion in problem (14); Based on the measurement matrix

D⁠

, evaluate the corresponding minimum time of each individual of the population

Pa_pop(i)

and select the best solution

Tmin*⁠

Loop: While (

i

<

max_gen⁠

) Step 1. Under the criterion in problem (14), regenerate offspring population

Ch_pop(i)

from

Pa_pop(i)

by applying the crossover and mutation operations; Step 2. According to matrix

D⁠

, evaluate the corresponding minimum time of each individual of the population

Ch_pop(i)

and select the best solution

Tmin⁠

; Step 3. Update the best solution

Tmin*=Tmin⁠

, if current

Tmin*>Tmin⁠

; Step 4. Select new population

Pa_pop(i+1)

from

Pa_pop(i)

and

Ch_pop(i)⁠

; Step 5.

i=i+1⁠

. End while. End Procedure. GA based path selection procedure:

Input: The number of points

nc⁠

, the calculated measurement matrix

D⁠

Output: Optimized traversal path and the minimum time motion trajectory. ProcedureInitialization: Population size

pop_size⁠

;

i=0⁠

; Number of generation

max_gen⁠

; Initialize the traversal order population

Pa_pop(i)

=randperm (

pop_size⁠

,

nc⁠

) under the criterion in problem (14); Based on the measurement matrix

D⁠

, evaluate the corresponding minimum time of each individual of the population

Pa_pop(i)

and select the best solution

Tmin*⁠

Loop: While (

i

<

max_gen⁠

) Step 1. Under the criterion in problem (14), regenerate offspring population

Ch_pop(i)

from

Pa_pop(i)

by applying the crossover and mutation operations; Step 2. According to matrix

D⁠

, evaluate the corresponding minimum time of each individual of the population

Ch_pop(i)

and select the best solution

Tmin⁠

; Step 3. Update the best solution

Tmin*=Tmin⁠

, if current

Tmin*>Tmin⁠

; Step 4. Select new population

Pa_pop(i+1)

from

Pa_pop(i)

and

Ch_pop(i)⁠

; Step 5.

i=i+1⁠

. End while. End Procedure.  Open in new tab

5 Cases study

In this section, a drilling task in Y-Z plane is studied to verify the effectiveness of the proposed method. The case study has three parts: one is to verify the effectiveness of the point-point minimum time transfer path planning, the second one is to test the optimization of the minimal operation time schedule compared with the minimal travel distance schedule and the minimal angular travel schedule, the last one is to test the practicability of the proposed algorithm by using a 100 points task. A 3-DOF manipulator (as shown in Fig. 2) is applied in this test and the torque bounds of all three joints are set as [140; 140; 50]N.m. The Y-Z work plane is placed at x=1 m ahead of the robot base and the path geometry constraint is set as no interference between the work plane and the robot effector. Eight drilling points are placed in Y-Z plane as shown in Fig. 3. Based on inverse kinematics calculation, the joint positions of robot corresponding to each drilling points can be also calculated.

Fig. 2

Open in new tabDownload slide

Simulated robot used in the drilling task.

5.1 Point-point minimum time transfer path test

Taking the transfer path planning from point 3 to point 8 as an example to test the effectiveness. The initial path is a straight line to connect the two points. The length of the initial path is 0.8879 m, and the corresponding minimum motion time is 0.4839 s. The optimal torques of all three joints are shown in Fig. 5. By using the method in Section 3, time optimal transfer path from point 3 to point 8 is calculated and shown in Fig. 4. The length of the minimum time path is 1.0346 m, and the corresponding minimum motion time is 0.4510 s. And the optimal torques of all three joints are shown in Fig. 6.

Fig. 4

Open in new tabDownload slide

Initial and Optimized paths in Z-Y plane.

Fig. 5

Open in new tabDownload slide

Minimum time torque curve of each joint for the initial straight path.

Fig. 6

Open in new tabDownload slide

Minimum time torque curve of each joint for the optimized path.

According to the bang-bang torque structures as shown in Figs. 5 and 6, it implies that the corresponding velocity trajectories have approached optimum. Fig. 6 presents the optimized feedrate curves of the initial path and the optimal path. In this test, the minimum time path is longer than the straight line path, however the corresponding motion time can be reduced 6.8% compared with that of the initial path. The reason can be explained as the velocity feasible space of the time optimal path is larger than that of the initial path, hence faster motion velocity and smaller transfer time can be allowed. (Fig. 7)

Fig. 7

Open in new tabDownload slide

Minimum time feedrate curves for the initial straight path and the optimized minimum time path respectively.

5.2 Minimum time traversal test for multi task points

By applying the results in 5.1, we can obtain the elements of measurement matrix D for the minimal operation time strategy. Also the measurement matrixes of the minimal travel distance strategy and the minimal angular travel strategy can be calculated conveniently. As shown in Fig. 8, the travelling schedules of the three strategies are different. Here we record the test data and list them as follows.

Table I

pop_size

 40 

max_gen

 100 Total mutation rate 75% Mutation operations Flip 25% Swap 25% Slide 25% 

pop_size

 40 

max_gen

 100 Total mutation rate 75% Mutation operations Flip 25% Swap 25% Slide 25%  Open in new tab

Table I

pop_size

 40 

max_gen

 100 Total mutation rate 75% Mutation operations Flip 25% Swap 25% Slide 25% 

pop_size

 40 

max_gen

 100 Total mutation rate 75% Mutation operations Flip 25% Swap 25% Slide 25%  Open in new tab

Fig. 8

Open in new tabDownload slide

Optimized paths for the minimal operation time strategy, minimal travel distance strategy and the minimal angular travel strategy, respectively.

(a). The travelling schedule of the minimal travel distance strategy is 7-6-5-3-2-1-4-8-7, and the related path length is 5.456 m, total angular travel distance is 11.046 rad, total motion time is 3.25s.

The length of each transfer path is

0.555 m−0.555 m −0.887 m −0.504 m −0.8 m −0.8 m −0.8 m −0.555 m.

And the corresponding minimum transfer time is 0.43s−0.38s−0.48s−0.33s−0.42s−0.41s−0.41s−0.39s.

(b). The travelling schedule of the minimal angular travel strategy is 7-6-5-2-1-4-3-8-7, and the related path length is 5.613 m, total angular travel distance is 9.386 rad, total motion time is 3.344s.

The length of each transfer path is 0.564 m−0.563 m −0.855 m −0.827 m −0.827 m −0.527 m −0.888 m −0.563 m.

And the corresponding minimum transfer time is 0.44s−0.40s−0.44s−0.41s−0.42s−0.36s−0.48s−0.39s.

(c). The travelling schedule of the minimal operation time strategy is 5-6-3-7-8-4-1-2-5, and the related motion time is 3.04s, path length is 5.858 m, total angular travel distance is 11.495 rad.

The motion time of each transfer path is 0.38s−0.35s−0.35s−0.37s−0.39s−0.41s−0.40s−0.39s.

And corresponding length of transfer path is

0.571 m−0.688 m-0.682 m−0.565 m−0.829 m−0.835 m−0.836 m−0.852 m.

In this test, the path length of minimum time motion is 7.3% longer than that of the minimum distance motion. And the total angular travel distance of minimum time motion is 22.5% larger than of the minimum angular travel motion. However the related optimal motion time of the proposed strategy reduces 6.5% compared with the minimal travel distance strategy and 9.1% compared with the minimal angular travel strategy.

5.3 Practicability test

In this section, the practicability of the proposed algorithm is tested by execute a series of drilling tasks with 10, 25, 50 and 100 points, respectively. The task points are shown in Fig. 9.

Fig. 9

Open in new tabDownload slide

Test examples (From left, 10 points, 25 points, 50 points, 100 points).

The performance comparison between the minimal operation time strategy, minimal travel distance strategy and the minimal angular travel strategy is listed in Table 1. According to Table 1, though the travel distance and angular displacement of the minimal operation time strategy is large than the other two strategies, the operation time is obviously shorter than them. Fig. 10 shows the operation time improvement of our strategy compared with the minimal travel distance strategy and the minimal angular travel strategy. According to the test results of the four examples, the proposed algorithm can improve the productivity about 7%~55% compared with the existing algorithms.

Table 1

Test (Points)

Travel distance (m)

Angular travel (rad)

Operation time (s)

Our Alg

Min Dis

Min Ang

Our Alg

Min Dis

Min Ang

Our Alg

Min Dis

Min Ang

10 3.1597 3.1403 3.6061 5.7865 5.5664 4.6540 2.4113 2.5752 3.5774 25 3.7923 3.7432 5.2141 6.2147 6.0143 5.4928 4.1255 4.4578 7.7990 50 6.8768 6.6944 10.6378 11.2799 11.0951 9.9456 8.0344 8.5892 17.3965 100 12.7616 12.4903 20.1023 20.3051 19.8257 17.4758 14.9291 16.0616 33.1522 Test (Points)

Travel distance (m)

Angular travel (rad)

Operation time (s)

Our Alg

Min Dis

Min Ang

Our Alg

Min Dis

Min Ang

Our Alg

Min Dis

Min Ang

10 3.1597 3.1403 3.6061 5.7865 5.5664 4.6540 2.4113 2.5752 3.5774 25 3.7923 3.7432 5.2141 6.2147 6.0143 5.4928 4.1255 4.4578 7.7990 50 6.8768 6.6944 10.6378 11.2799 11.0951 9.9456 8.0344 8.5892 17.3965 100 12.7616 12.4903 20.1023 20.3051 19.8257 17.4758 14.9291 16.0616 33.1522  Open in new tab

Table 1

Test (Points)

Travel distance (m)

Angular travel (rad)

Operation time (s)

Our Alg

Min Dis

Min Ang

Our Alg

Min Dis

Min Ang

Our Alg

Min Dis

Min Ang

10 3.1597 3.1403 3.6061 5.7865 5.5664 4.6540 2.4113 2.5752 3.5774 25 3.7923 3.7432 5.2141 6.2147 6.0143 5.4928 4.1255 4.4578 7.7990 50 6.8768 6.6944 10.6378 11.2799 11.0951 9.9456 8.0344 8.5892 17.3965 100 12.7616 12.4903 20.1023 20.3051 19.8257 17.4758 14.9291 16.0616 33.1522 Test (Points)

Travel distance (m)

Angular travel (rad)

Operation time (s)

Our Alg

Min Dis

Min Ang

Our Alg

Min Dis

Min Ang

Our Alg

Min Dis

Min Ang

10 3.1597 3.1403 3.6061 5.7865 5.5664 4.6540 2.4113 2.5752 3.5774 25 3.7923 3.7432 5.2141 6.2147 6.0143 5.4928 4.1255 4.4578 7.7990 50 6.8768 6.6944 10.6378 11.2799 11.0951 9.9456 8.0344 8.5892 17.3965 100 12.7616 12.4903 20.1023 20.3051 19.8257 17.4758 14.9291 16.0616 33.1522  Open in new tab

Fig. 10

Open in new tabDownload slide

Performance improvement compared with the minimal travel distance strategy and the minimal angular travel strategy.

Table 2 records the computation time of these three strategies. The theoretical analysis of the algorithm complexity is not concerned in this paper. Yet by using the test results, we can check the algorithm complexity. From the test results, we can see that the presented algorithm is time consuming. This is because a large number of optimization sub processes must be executed to calculate the minimum time transfer paths in the proposed algorithm. However since the algorithm is executed offline, we think the computational cost of the proposed method can be acceptable. Finally, we draw the time optimal travelling path for the 100 points task as shown in Fig. 11.

Table 2

Test

Computation time (H:MIN:S)

Our Algorithm

Min Distance

Min Angular

10 points 00:02:39 00:00:15 00:01:49 25 points 00:15:10 00:00:35 00:12:36 50 points 01:20:23 00:02:10 00:50:49 100 points 02:53:56 00:11:40 01:47:13 Test

Computation time (H:MIN:S)

Our Algorithm

Min Distance

Min Angular

10 points 00:02:39 00:00:15 00:01:49 25 points 00:15:10 00:00:35 00:12:36 50 points 01:20:23 00:02:10 00:50:49 100 points 02:53:56 00:11:40 01:47:13  Open in new tab

Table 2

Test

Computation time (H:MIN:S)

Our Algorithm

Min Distance

Min Angular

10 points 00:02:39 00:00:15 00:01:49 25 points 00:15:10 00:00:35 00:12:36 50 points 01:20:23 00:02:10 00:50:49 100 points 02:53:56 00:11:40 01:47:13 Test

Computation time (H:MIN:S)

Our Algorithm

Min Distance

Min Angular

10 points 00:02:39 00:00:15 00:01:49 25 points 00:15:10 00:00:35 00:12:36 50 points 01:20:23 00:02:10 00:50:49 100 points 02:53:56 00:11:40 01:47:13  Open in new tab

Fig. 11

Open in new tabDownload slide

the time optimal travelling path for the 100 points task.

6 Conclusions

In this paper, a minimum time path planning method is proposed for multi points manufacturing problem in drilling/spot welding task. Within the limits of manipulator dynamics performance, the minimum time path is obtained by optimizing the travel schedule of the set points and the detailed transfer path between points simultaneously. The solution results of the example test indicate that even the proposed minimum time path is longer than the minimum distance path, the operation time can be reduced effectively by using the proposed method. In consequence, the proposed minimal time strategy for multi points task is feasible.

References

[1]

Bobrow

J. E.

,

Dubowsky

S.

,

Gibson

J. S.

Time-Optimal Control of Robotic Manipulators Along Specified Paths

.

Int J Robot Res

,

1985

;

4

(

3

)

3

17

.

[2]

Zhang

K.

,

Gao

X. S.

,

Li

H. B.

,

Yuan

C. M.

A Greedy Algorithm for Feed-rate Planning of CNC Machines along Curved Tool Paths with Confined Jerk for Each Axis

.

Robot Comput Integr Manuf

,

2012

;

28

:

472

483

.

[3]

Zhang

Q.

,

Li

S. R.

Efficient Computation of Smooth Minimum Time Trajectory for CNC Machining

.

Int J Adv Manuf Technol

,

2013

;

68

(

1–4

)

683

692

.

[4]

Zhang

Q.

,

Li

S. R.

,

Gao

X. S.

Practical smooth minimum time trajectory planning for path following Robotic manipulators

.

Am Control Conf, USA, Jun

,

2013

:

17

19

.

[5]

Bobrow

J.

Optimal robot path planning using the minimum time criterion

.

IEEE J Robot Autom

,

1988

;

4

(

4

)

443

450

.

[6]

Erkorkmaz

K.

,

Alzaydi

A.

,

Elfizy

A.

,

Engin

S.

Time-optimal trajectory generation for 5-axis on-the-fly laser drilling

.

CIRP Ann -Manuf Technol

,

2011

;

60

:

411

414

.

[7]

Erkorkmaz

K.

,

Alzaydi

A.

,

Elfizy

A.

,

Engin

S.

Time-optimized hole sequence planning for 5-axis on-the-fly laser drilling

.

CIRP Ann -Manuf Technol

,

2014

;

63

:

377

380

.

[8]

Huang

T.

,

Wang

P. F.

,

Mei

J. P.

,

Zhao

X. M.

,

Chetwynd

D. G.

Time Minimum Trajectory Planning of a 2-DOF Translational Parallel Robot for Pick-and-Place Operations

.

CIRP Ann -Manuf Technol

,

2007

;

56

(

1

)

365

368

.

[9]

Dubowsky

S.

,

Blubaugh

T. D.

Planning time-optimal robtic manipulator motions and work places for point to point tasks

.

IEEE Trans Robot Autom

,

1989

;

5

(

3

)

337

381

.

[10]

Petiot

J. F.

,

Chedmail

P.

,

Hascoet

J. Y.

Contribution to the scheduling of trajectories in robotics

.

Robot Comput -Integr Manuf

,

1998

;

14

:

237

251

.

[11]

Th

Zacharia P.

,

Aspragathos

N. A.

Optimal robot task scheduling based on genetic algorithms

.

Robot Comput -Integr Manuf

,

2005

;

21

:

67

79

.

[12]

Qu

L.

,

Sun

R.

A synergetic approach to genetic algorithms for solving traveling salesman problem

.

Inf Sci

,

1999

;

117

:

267

283

.

[13]

Shiller

Z.

,

Dubowsky

S.

On Computing the Global Time-Optimal Motions of Robotic Manipulators in the Presence of Obstacles

.

IEEE Trans Robot Autom

,

1991

;

7

(

6

)

785

797

.

This is an open access article under the CC BY-NC-ND license ( http://creativecommons.org/licenses/by-nc-nd/4.0/ ).

For more information Welding Manipulator, please get in touch with us!