Abstract
This article presents a new approach for planning collision-free trajectories of two robots working in a shared workspace. Based on the B-spline knot refinement and the local modification scheme, the approach only changes the local trajectory around the collision area without changing the shape in the global way. The geometric model of dual-robot is employed by two kinds of geometric elements (sphere and capsule). A collision check method calculates the distance between two robots to determine whether the collisions exist. The collision check is converted to calculate the distance between every two elements. The proposed method has been implemented on a dual-robot system composed of two KUKA manipulators. The numerical and simulation results presented in the article illustrate the efficiency of the proposed technique.
Introduction
Dual or multiple robots are employed in many industrial areas from simple material handling to complex assembly. For a dual-robot or multi-robot system in a shared workspace, it is necessary to ensure the robots to move safely without collisions. Collision-free techniques tend to be based on speed adaptation, path deviation by one robot only, path deviation by two robots, or a combination of speed and path adjustments.
In the literature, many different techniques for collision-free trajectory planning of a dual-robot system have been proposed. Shin and Zheng decomposed collision-free multi-robot motion planning into two sequential steps, path planning and trajectory planning, and obtained the time optimality of dual-robot collision-free trajectory planning by delaying one of the two robots. 1 Ju et al. proposed a velocity alteration strategy to account for collision avoidance between links. 2 Spencer et al. presented the input velocity scaling where the path of the robot is not modified, but the motion of the robot along the desired path is slowed in order to avoid collisions. 3 Each of these methods is essentially velocity schedule along a prior planned path. To generate a collision-free trajectory, the velocity of the slave robot is reduced or waiting time intervals in slave robot trajectory are inserted. However, such a method is only effective if the obstacles will move out of the path of the robot after a period of time and makes the robot less efficient.
Lee and Lee developed notions of collision map and time scheduling for realizing a collision-free motion planning. 4 In order to avoid collisions, Chu and ElMaraghy applied heuristic rules to modify the robot path. 5 Cai et al. developed a step-forward approach for collision avoidance in multi-robot systems. 6 Some work on the general collision-free robot navigation problem can also be seen in the study by Hoy et al., 7 Cho and Cho, 8 and Ouyang and Zhang. 9 The robot must change its established path to avoid collisions with static obstacles. For dynamic obstacles, the lower priority robot took a “stopping” or “speed reduction” action to avoid a collision. Path deviations are adopted in these methods. The prior planned trajectories are often optimal according to some objectives. The range and the adjustment of the path deviation should be small enough to avoid collisions and to keep the trajectories as well as possible, which are not considered sufficiently in these articles.
The trajectory planning for a dual-robot system is different from that of a single robot in that each robot is a moving obstacle to the other robot. In a single robot, many trajectory planning techniques are adopted. Parametric curves build the trajectory due to their useful properties. The most commonly used curves are multi-order spline, 10,11 Bezier, and 12,13 B-spline. 14,15 Trajectory planning algorithms found in the literature aim at minimizing some objective function, 16 –18 which are usually execution time, actuator effort, and jerk.
B-spline techniques can realize a fast response to moving obstacles in an environment. Changing one point of the control polygon only affects the corresponding curve locally. Focusing on the performance of sudden changes in a predefined trajectory, Dyllong and Visioli investigated various spline techniques for planning and fast modifications of a trajectory of robot manipulators. 19 Fast changes at a joint level can be implemented by using B-splines. Arney employed an interpolated B-spline to the waypoints, which is only altered in the local area to the obstacle. 20 Shukla et al. proposed a B-spline for the manipulator path which leads to effective collision avoidance. 21 However, one or more control points are changed to modify the path. The range of the path deviation is often relatively wide.
The main contributions of this work are that, A collision-free trajectory planning algorithm strategy for dual-robot working in a shared workspace is proposed. This strategy modifies the trajectory curve around the collision area using the B-spline knot refinement and local modification scheme. The harmony search (HS) algorithm is used to obtain optimal trajectory planning. In order to avoid collision, the HS algorithm is applied to get the adjusting directions and values of joints. An approach of collision checking is presented by employing the geometric models of robots.
Model building and collision checking
The dual-robot system is composed of two 6-degree of freedom (6-DOF) industrial robots, R1 and R2, working in a shared workspace. The reference frame of the dual-robot system is T
0 and the base frames of R1 and R2 are T
01 and T
02, respectively. The coordinate systems of the dual-robot system are shown in Figure 1. In the reference frame T
0, the position of points on robots R1 and R2 can be denoted as

The coordinate systems of a dual-robot system.
where p01 is the position vectors of points on robot R1 in base frame T
01; p02 is the position vectors of points on robot R2 in base frame T
02;
The two robot positions can be expressed uniformly in the reference frame T 0 via equations (1) and (2). They can be used to calculate the distance to judge if there is collision between the two robots.
As the links and joints of a 6-DOF robot are irregular and complex, in order to calculate the distance between two robots, it is necessary to model the robot links and joints by geometric primitives. Sphere and capsule (composed of a cylinder and two hemispheres in the ends of the cylinder) are adopted as geometric primitives in this article. The wrist is modeled by the sphere S and the links are modeled by the capsules C1, C2, and C3, as shown in Figure 2(a). As the former three links determine the position of the robot end-effector and the last three links only affect the orientation of the robot end-effector, it is the angular positions of first three joints that determine whether the robots collide. Hence, the 6-DOF robot can be simplified as a three-DOF robot, as shown in Figure 2(b).

Geometric model of a dual-robot system.
The safety margin to avoid a collision between two robots is defined as the minimum necessary distance between two robots. Given the minimum necessary safety distance ds (≥0), a robot trajectory must obey the following constraint
where the braking time
The distance r between the robots R1 and R2 is
where ea,b denotes the bth primitive of the robot a. The condition for collision avoidance is r ≥ ds. Fulfilling this criterion means that the robots will never meet in the same region by defining a circle with the radius ds, which is called a non-overlapping criterion.
According to the geometric model of a robot, the distance between the two robots can be converted to distances between primitives, as shown in Figure 3. The minimum distance between a pair of objects is called the critical distance. The distance between centers or axes of the geometric primitives (spheres or capsules) is L. The radii of the primitives are rA and rB, respectively. If there is

Distance between two geometric elements.
Trajectory planning for robots based on B-spline curves
Assuming that the path in the Cartesian space consists of a sequence of via-points (positions and orientations of the end-effector), the robot has f joints, there are m+1 via-points for each joint, and T is the total time for traveling from the first via-point to the last one.
B-spline curves are used to formulate the jth joint trajectory, which can be expressed as
with
where Pi,j is the ith control point of the jth joint B-spline trajectory, n+1 is the number of control points, and the pth order polynomial Ni,p(u) is the B-spline basis function defined on the nonuniform knot vector
The knot vector U can be obtained by parameterizing and normalizing the interval time Δti, and the knot vector repetition degree in both ends is p+1
The trajectory must pass through m+1 via-points, and the corresponding B-spline curve has m segments. The expression of ith segment is described as
The n+1 control points Pi,j can be obtained by solving n+1 equations which consist of interpolation conditions in equation (7) and boundary conditions in equation (8). The interpolation conditions contain m+1 equations
where
Given Δti, the control points can be computed by solving n+1 equations consisting of equations (6) and (7), and control points of the derivative curve can be obtained by equation (8). Then, the trajectories of robot joints constructed by B-spline curves are obtained.
Collision-free trajectory planning for a dual-robot system
The B-spline trajectory of a manipulator can be obtained by applying the above proposed trajectory planning algorithm. The trajectories of robots R1 and R2 are S1 and S2, respectively. The two robots may collide when they move along the trajectories S1 and S2. In this case, the trajectories should be modified to avoid the collision. There are methods which modify the whole trajectory to avoid collisions. In this article, the trajectory is partly modified to avoid collisions by applying the local modification scheme of B-spline curves. B-spline curves have local modification scheme property: changing the position of control point Pi only affects the curve Q(u) on the interval [ui , ui +p+1]. We can modify a curve locally without changing the overall shape.
Both the trajectories can be modified to avoid collisions. A trajectory which will be modified is determined according to the priority. If one robot needs higher efficiency or accuracy, its priority is higher, otherwise they are the same priority. The higher priority trajectory will not be changed such that much more important trajectories remain unchanged, while the less important one is modified. If they have the same priority, either of them can be modified.
In order to less modify the trajectory, the knot refinement of B-splines is implemented. Knot refinement or knot insertion is exactly what the name suggests: extension of a given knot vector by adding new knots.
Before modifying the trajectory, we refine the trajectory around the collision area so that the affected area could be restricted to a narrow region. According to the demand, the knot refinement could be accomplished by inserting one or several knots. The method of inserting a knot is detailed as follows.
For convenience,
Q(u) could be expressed with the knot vector
where
where
After refining the trajectory, the control points are adjusted to fine-turn the shape of the trajectory around the time t′, while the remaining curve segments of the trajectory stay in their original place without any change. We only need to recheck the partial modified trajectory to determine whether there is a collision. If there is no collision, the whole trajectory is collision free. If there is a collision, the control point is adjusted repeatedly till no collision occurs. Assuming that P′ is the control point that will be adjusted, ΔP is the value of the control point adjusted one time, d(P′) and d(P′ + ΔP) are the distances between two robots. The following pseudo codes describe the process of adjusting the control point. The procedure of the collision-free trajectory planning is shown in Figure 4.
if
δ = ΔP // The adjusting direction is the same with the joint moving direction
else // The distance decreases when control point P′ subtracts ΔP
δ = −ΔP // The adjusting direction is opposite to the joint moving direction
while d(P′) < ds // Adjust the control point repeatedly till the distances are larger than ds
P′ = P′ + δ // Adjust δ every time

Procedure of the collision-free trajectory planning.
The adjusting directions and values of multiple joints are not straightforward to determine. Some optimization algorithms, for example, the HS algorithm, can be applied. The HS imitates the music improvisation process where music players search for a better state of harmony. 23 The HS can be used to obtain optimal trajectory planning. 24 The HS can determine the optimal result and is convergent. There have been improvements in order to avoid the HS falling into local minimal. 25 The algorithm is less of a computational load than other heuristic algorithms. 26 The HS is applied to obtain the adjusting values and directions.
Assuming that the robot has n joints. Without loss of generality, we assume that only one control point of each joint trajectory should be changed, and Pi is the control point that will be adjusted for the ith joint trajectory. The detailed processes are described as follows:
Step 1: Initialize the optimization problem and algorithm parameters.
The optimization problem is defined as
where xi = ΔPi is the adjusted value of the control point of ith joint trajectory. xiL and xiu are the lower and upper bounds for variables which are determined by Pi, respectively. The limits of the joints d0(> 0) are an extra term to make d(xi,t)−ds always positive, which will be proved later.
The HS algorithm parameters are the number of decision variables, bandwidth bw, the harmony memory size HMS, the harmony memory considering rate HMCR, the pitch adjusting rate PAR, and the stopping criterion D(Xbest) < d0.
Step 2: Initialize the harmony memory:
where
Step 3: Execute the local search.
Find the best solution vector and the worst one
Then, execute the feasible direction method to obtain the local optimal solution vector X′, using the vector V = Xbest − Xworst as the search direction. Finally, replace Xworst with X′.
Step 4: Improvise a new harmony with three different mechanisms: memory consideration, pitch adjustment, and random selection.
Step 5: Harmony memory update. If D(Xnew) < D(Xworst), replace Xworst with Xnew.
Step 6: Repeat steps 3–5 until the stopping criterion is satisfied.
Step 7: Find the best harmony vector Xbest in the final HM as the global optimal solution vector.
Now, we prove d(Xbest,t) > ds. From the stopping criterion, D(Xbest) < d0, that is
So
Obviously,
Additionally, we can tag on velocity or jerk constraints in the stopping criterion to obtain smoother trajectories.
Simulation
To show the validity of the proposed collision-free trajectory planning approach, a case study of two KUKA KR1000_TITAN robots is carried out. The robot Denavit-Hartenberg (DH) parameters are detailed in Table 1. The transformation matrixes of the base frame T
01 and T02 with respect to the reference frame T
0 are
Link parameters of KR1000_TITAN.
Assuming that R1 and R2 have the same priority. R1 moves from the point E1(0,860,3600) to the point F1(0,3360,2150) and R2 moves from the point E2(0,3140,3600) to the point F2(0,3360,650) in the Cartesian space. As shown in Table 2, the joints’ positions of starting point and end point are obtained by inverse kinematics. Assuming that the start and end velocities are set to zero, and the total time is 3.5 s, the trajectories of R1 and R2 (in Figure 5) are built with cubic B-splines on knot vectors U 1 = {0, 0, 0, 0,0.4,0.5, 1, 1, 1, 1} by applying the trajectory planning algorithm for a single robot.
The starting and end point in joint space.

Position of robots R1 and R2.
The robot geometric model is built with the elements of sphere and capsule, and the element dimensions are given according to the robot physical dimension. The radii of the sphere, the hemispheres in the capsules ends, and the length of the capsules central segments are shown in Table 3. The distances between two robots (shown in Figure 6) are calculated by applying the collision checking method presented in the section “Model building and collision checking.” As Figure 6 (blue color dotted line) shows, R1 and R2 are closest at t′ = 2.38 s and the distances between 2.17 s and 2.66 s are smaller than 0 (here ds is simplified as zero), so there are collisions in the period between 2.17 s and 2.66 s.
The elements’ geometric dimensions.

Distance between R1 and R2 before and after modifying trajectories with case 1.
In order to obtain collision-free trajectories, we need to modify the obtained trajectories. Assuming that robots R1 and R2 have the same priority, it is available to modify one robot trajectories or the trajectories of both R1 and R2. Two cases of adjusting trajectories are implemented and compared. We insert three knots around the collision, and the knot vectors are
Case 1: Only modify the trajectories of R2, the trajectories of Robot R1 stay in the original shape. Apply the collision-free trajectory planning algorithm and change control points with and without knot refinement, respectively. The adjusting values and directions of control points are obtained by the HS algorithm. The initial solution of the HS algorithm is set as
where the elements of the first and second columns are the adjusted values of the fifth control points on the refined B-spline trajectories for the second and third joints of robot R2, respectively. The parameters of the HS algorithm are set as follows: number of decision variables = 2, HMS = 5; HMCR = 0.7; PAR = 0.3; bw = 0.1; d 0 = 10.
The modified trajectories of robot R2 are obtained, shown in Figure 7. After modifying trajectories with and without knot refinement in case 1, the distances between R1 and R2 are larger than zero all the time. Both modification schemes with and without knot refinement can obtain collision-free trajectories. Because of the local modification property, all trajectories are locally changed. With respect to the modifying scheme with knot refinement, the curve changing area could be restricted to a smaller sector after refining the curve. For a sudden obstacle, the modification scheme with knot refinement can be more flexible and effective. After avoiding the obstacle, the robot can go back to the original planned path as soon as possible. The velocities and accelerations meet the kinematic constraints. The running time of the proposed method is about 0.07 s.

Joint trajectories after modifying trajectories with case 1.
Case 2: Modify the trajectories of both R1 and R2. Apply the collision-free trajectory planning algorithm. The initial solution of the HS algorithm is set as
where the elements of the first and second columns are the adjusted values of the fifth control points on the refined B-spline trajectories for the second and third joints of robot R1, respectively, and that of the third and fourth columns are the adjusted values of the fifth control points on the refined B-spline trajectories for the second and third joints of robot R2, respectively. The parameters of the HS algorithm are set as follows: number of decision variables = 4; HMS = 5; HMCR = 0.7; PAR = 0.3; bw = 0.1; d 0 = 10.
The modified trajectories of R1 and R2 are obtained (shown in Figures 8 and 9). The distances between two robots after modifying trajectories with case 2 are shown in Figure 10. The running time of the proposed method is about 0.1 s.

Joint trajectories of R1 after modifying trajectories with case 2.

Joint trajectories of R2 after modifying trajectories with case 2.

Distance between R1 and R2 after modifying trajectories with case 2.
For the trajectories modified with case 1, the positions have been changed by a large margin resulting in that the velocities and accelerations are very large. For the trajectories modified with case 2, the velocities and the accelerations are smaller than that of case 1. The trajectories are smoother and the robots run more smoothly. To make the generated trajectories have better kinematic characteristics, it is suggested that the trajectories of both the robots should be modified simultaneously if the robots have the same priority.
Conclusions
This article proposes an approach to generate collision-free trajectories of two industrial robots working in a shared workspace by applying the B-spline knot refinement and the local modification scheme. When a collision exists, only local trajectories around the collision area are changed, while the remaining curve segments of the trajectory stay in their original place without any change. An approach of collision checking is presented by employing the geometric models of robots. The HS algorithm is applied to adjust directions and values of multi-joints. The results of the simulation show that the proposed approach can obtain collision-free and smooth trajectories for dual-robot systems.
One possible method for improving the smoothness of acceleration is to further refine knots, which will be our next work.
Footnotes
Declaration of conflicting interests
The author(s) declared no potential conflicts of interest with respect to the research, authorship, and/or publication of this article.
Funding
The author(s) disclosed receipt of the following financial support for the research, authorship, and/or publication of this article: This article is supported by the Beijing Science and Technology Plan (D161100003116002) and the National Key Technology R&D program (2015BAF01B04).
