Optimal trajectory planning for industrial robots using harmony search algorithm

Youdong Chen (School of Mechanical Engineering and Automation, Beihang University, Beijing, China)
Liang Yan (School of Mechanical Engineering and Automation, Beihang University, Beijing, China)
Hongxing Wei (School of Mechanical Engineering and Automation, Beihang University, Beijing, China)
Tianmiao Wang (School of Mechanical Engineering and Automation, Beihang University, Beijing, China)

Industrial Robot

ISSN: 0143-991X

Article publication date: 16 August 2013

567

Abstract

Purpose

This paper aims to present a technique for optimal trajectory planning of industrial robots that applies a new harmony search (HS) algorithm.

Design/methodology/approach

The new HS optimization algorithm adds one more operation to the original HS algorithm. The objective function to be minimized is the trajectory execution time subject to kinematical and mechanical constraints. The trajectory is built by quintic B‐spline curves and cubic B‐spline curves.

Findings

Simulation experiments have been undertaken using a 6‐DOF robot QH165. The results show that the proposed technique is valid and that the trajectory obtained using quintic B‐spline curves is smoother than the trajectory using cubic B‐spline curves.

Originality/value

The proposed new HS algorithm is more efficient than the sequential quadratic programming method (SQP) and the original HS method. The proposed technique is applicable to any industrial robot and yields smooth and time‐optimal trajectories.

Keywords

Citation

Chen, Y., Yan, L., Wei, H. and Wang, T. (2013), "Optimal trajectory planning for industrial robots using harmony search algorithm", Industrial Robot, Vol. 40 No. 5, pp. 502-512. https://doi.org/10.1108/IR-12-2012-444

Publisher

:

Emerald Group Publishing Limited

Copyright © 2013, Emerald Group Publishing Limited


1 Introduction

Trajectory planning is a fundamental problem for industrial robots that is crucial to ensuring good motion performance of robots, especially for high‐speed operation. It can be described in this way: find an appropriate motion law that forces robots to move from one point to another, or to move along a given path. The planning of the trajectory can be done on‐line (Xiao et al., 2012) or in off‐line programming (OLP) environment (Mendes et al., 2013; Rubio et al., 2012). When considering motion performance, it is crucial for the trajectory to meet specific demands concerning position, velocity, acceleration and jerk. In order to reduce vibration and increase positioning accuracy, the trajectory's acceleration should be continuous so that the jerk's absolute value remains bounded.

Trajectory planning techniques found in the literature aim to minimize an objective function, which is usually defined in terms of execution time (Wang and Horng, 1990; Costantinescu and Croft, 2000; Kim et al., 2010), actuator effort (Field and Stepanenko, 1996; Saramago and Junior, 2000), or jerk (Piazzi and Visioli, 1997; van Dijk et al., 2007). Considering the pressures to increase productivity in the industrial sector, this paper chooses to minimize the execution time. In order to plan an optimal trajectory, a suitable curve needs to be chosen in order to construct the motion trajectory. The early methods employed straight lines or parabolas to construct the trajectory. Polynomials were adopted later. In the scientific literature of recent years, the most commonly used curve is the spline curve such as a cubic spline (Piazzi and Visioli, 2000; Chettibi et al., 2004), or a B‐spline (Wang and Horng, 1990; Gasparetto and Zanotto, 2007). This paper employs a fifth‐order polynomial displacement profile to design the trajectory motion. Hence, the acceleration profile is a cubic polynomial. The continuous jerk is a quadratic polynomial so the absolute value of jerk stays bounded.

Many optimization algorithms have been applied in trajectory optimization in the existing literatures, such as the flexible polyhedron search (FPS) algorithm (Wang and Horng, 1990; Lin et al., 1983), the interval analysis algorithm (Piazzi and Visioli, 2000), and the sequential quadratic programming (SQP) method (Chettibi et al., 2004; Gasparetto and Zanotto, 2010; Zanotto et al., 2011). These algorithms are non‐heuristic and have some common drawbacks: the result may be a local optimum instead of a global optimum, they need a suitable initial solution (which could affect the execution time and even the final result of the optimization algorithm), etc.

With the development of artificial intelligence and computer techniques, the heuristic algorithm is applied widely and effectively to solve the optimization problem. A new meta‐heuristic algorithm, called harmony search (HS), has been proposed, which imitates the behavior of the music improvisation process where musicians improvise their instruments' pitches searching for a perfect state of harmony (Geem et al., 2001). Some strategies for improving the performance of the HS algorithm were proposed. One more operation (ensemble consideration) was added to the original algorithm structure (Geem, 2006a), which considers the relationships among the decision variables, and the improved HS (IHS) algorithm found better solutions than did the original HS algorithm. Another improvement in the HS algorithm was obtained through the proper tuning of the harmony parameters, and the IHS algorithm is good at finding the global optimum and it is as good as mathematical techniques at fine‐tuning (Mahdavi et al., 2007). Inspired by the concept of swarm intelligence (Omran and Mahdavi, 2008), the method of generating a new harmony vector was changed to enhance the performance of the HS. A new HS variant, whose parameters are automatically adjusted according to its self‐consciousness, was proposed in Wang and Huang (2010). All those HS variants start from a stochastic random search, so no effort is necessary to determine the initial solution. The HS algorithm can determine the global optimal result and it is less of a computational load than other heuristic algorithms. Due to these advantages, the HS has been applied to many engineering and mathematical problems (Lee and Geem, 2005; Geem, 2006a, b; Zou et al., 2011).

In this paper, a minimum‐time trajectory planning algorithm applied to a six‐DOF joint robot is presented. This algorithm employs a new HS variant, with one more operation added to the IHS algorithm. The algorithm takes into account the robot's kinematical constraints: velocity limit, acceleration limit and jerk limit. The kinematical model instead of the dynamical model is adopted in this paper, as the manipulator's dynamical model is very complex and its computational load is heavy. The paper is organized as follows. In Section 2, the trajectory planning algorithm is described. In Section 3, the formulation of B‐spline joint trajectories is described. In Section 4, an IHS algorithm is proposed and the application of the algorithm by means of quintic B‐spline is detailed. In Section 5, the proposed algorithm is executed on a QH165 robot and the results obtained are compared and discussed. Finally, conclusions are presented in Section 6.

2 The trajectory planning algorithm

The trajectory planning technique proposed in this paper assumes that the geometric path of the end effector has been given by users or generated by a path planner in advance. The path consists of a sequence of via points (i.e. positions and orientations of the end effector) in Cartesian space, and each joint's via points can be obtained via inverse kinematics. The trajectory planning algorithm aims to minimize the robot's moving time while ensuring that the joints pass through all the via points. In order to reduce the vibration, which causes mechanical wear of the manipulator, and to not exceed the actuators' drive capability, various kinematical constraints should be taken into account.

We assume that there are R robot joints and m+1 via points for each joint, and that T is the total time for moving from the first via point to the last one. The via points can be expressed as (ti,qi j), where ti is the instantaneous time corresponding to the ith via point and qi j is the ith via point's position value of the jth joint. The optimal trajectory planning problem is defined as: Equation 1 subject to the joint path constraints: Equation 2 and subject to the constraints of position, velocity, acceleration and jerk: Equation 3 where:

Δti=ti+1ti the interval time between two adjacent via points, t∈[t0, tm].

Qj(t) position of the jth joint.

Qj(t) velocity of the jth joint.

Qj(t) acceleration of the jth joint.

Qj(t) jerk of the jth joint.

QC1j lower position limit for the jth joint.

QC2j upper position limit for the jth joint.

VCj velocity limit for the jth joint.

ACj acceleration limit for the jth joint.

JCj jerk limit for the jth joint.

3 Formulation of B‐spline trajectories

In order to optimize the joint trajectories, a suitable type of curve for building the trajectory should be chosen. B‐spline curves are used to formulate the jth joint's trajectory, which can be expressed as: Equation 4 with: Equation 5 where Pi,j is the ith control point of the jth joint's 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 non‐uniform knot vector U={u0, u1, … , un+p+1}.

The knot vector U can be obtained by parameterizing and normalizing interval time Δti, and the knot vector's repetition degree at both ends is p+1: Equation 6 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: Equation 7 The n+1 control points Pi,j can be obtained by solving n+1 equations consisting of interpolation conditions in equation (8) and boundary conditions in equation (9). The interpolation conditions contain m+1 equations: Equation 8 The other nm equations are established by several boundary conditions in equation (9), i.e. the derivatives of boundary points. The dth derivative of Qj(u) is denoted as Qjd(u). For cubic B‐splines, nm=2, the boundary conditions contain velocities (vf, vl) of the first point and the last point. For quintic B‐spline curves, nm=4, the boundary conditions contain velocities (vf, vl) and accelerations (af, al) of the first point and the last point: Equation 9 where Pi,jd is the jth joint's control points of the dth derivative curve, which can be computed in a recursive fashion (Piegl and Tiller, 1997): Equation 10 where i=0, 1, … , np.

In the process of planning the trajectory with a certain optimization algorithm, given Δti, the control points can be computed by solving n+1 equations consisting of equations (8) and (9), and the derivative curve's control points can be obtained by equation (10). Then the trajectories of robot joints constructed by B‐spline curves are obtained. The procedure for optimization using a B‐spline trajectory is shown in Figure 1.

4 Optimizing the trajectory using HS algorithm

HS algorithm

The HS algorithm is a recently developed stochastic algorithm that imitates the music improvisation process where music players search for a better state of harmony (Geem et al., 2001). Figure 2 shows the analogy between improvisation and optimization. There are k music players and k variables. Each music player (pianist, violinist, … , and piper) in the figure corresponds to each decision variable (x1, x2, … , and xk), and the candidate range of each music instrument (piano={Do, Re,…}; violin={Mi, Fa,…};…; flute={Sol, La,…}) corresponds to the candidate range of each variable value (x1={a, b,…}; x2={c, d,…};…; xk={e, f,…}). If the pianist sounds Do, the violinist sounds Mi, … , and the piper sounds Sol, then all these notes combine into a new harmony (Do, Mi, … , Sol). If this new harmony shows better quality than the pre‐existing harmony, it will be kept in each musician's memory. Likewise, if a new solution vector (a, c, … , e) is generated during the optimization process and it has better fitness in terms of the objective function F than other pre‐existing solution vectors, it will be kept in computer memory. This activity is repeated many times until a (near‐) optimal solution is reached.

Generally, the HS algorithm consists of the following steps:

  • Step 1. Initialize the optimization problem and algorithm parameters. The optimization problem is defined as: Equation 11 xiL and xiU are the lower and upper bounds for variables.

    The HS parameters are the number of decision variables, bandwidth bw, the harmony memory size HMS, harmony memory considering rate HMCR, pitch adjusting rate PAR, and the number of improvisations NI or stopping criterion.

  • Step 2. Initialize the harmony memory (HM). The initial HM is randomly generated in a feasible region [xiL, xiU] (i=1, 2, … , k). It is done as follows: Equation 12 rand( ) is generated randomly from a uniform distribution over the interval [0, 1].

  • Step 3. Improvise a new harmony with three different mechanisms.

The new vector X′=(x1,x2, … ,xm) is obtained with three mechanisms: memory consideration, pitch adjustment and random selection. It works as the following pseudo‐codes:

for (i=1:m) do

 if rand( ) ≤ HMCR then

  xi=xi j(j=1,2, … ,HMS) //memory consideration

  if rand( ) ≤ PAR

   xi=xi±rand( )×bw //pitch adjustment.

 end

 else

  xi=xiL+rand( )×(xiUxiL) //random selection

end

  • Step 4. Harmony memory update. If the improvised harmony vector X′ is better than the worst harmony vector, replace the worst harmony vector in the HM with X′.

  • Step 5. Repeat Steps 3 and 4 until the stopping criterion is satisfied.

  • Step 6. Find the best harmony vector in the final HM.

In the above HS algorithm, the parameters are constants whose values are difficult to choose correctly. If the parameters are not suitable, then the algorithm may be inefficient and even not feasible. Therefore, many improvements have been developed since the HS algorithm was proposed, one of which is the IHS that allows the parameters to be tuned properly (Mahdavi et al., 2007). The IHS algorithm performed well both in terms of the number of fitness function evaluations required and in terms of the quality of the solutions that it found.

Proposal for a new HS

We proposed a new improvement strategy that adds an iterations step before the new harmony improvisation (Step 3), which can improve the local searchability. The feasible direction method is used to search for the local optimal solution. The details of this step are presented as follows:

  • Find the best solution Xbest and the worst one Xworst in the existing HM, according to the objective function f(X).

  • Execute iterative computations with the vector D=XbesetXworst as the search direction, until the local optimal solution X′ is obtained. It works as follows:

while(1) do

X′=Xworst+D · StepSize // StepSize is a constant set as the step size of each search process//

if (X′ satisfies the constraints && StepSize is small enough) // the local optimal solution has been obtained

 break;

while(X′ satisfies the constraints) do

Xworst=X

X′=Xworst+D · StepSize

end

StepSize=StepSize * 0.5 //step size reduces by half

end

  • Update the HM replacing Xworst with X′.

The local optimal solution can be found rapidly through this added step. The new HS variant is employed to minimize the robot's total execution time. The detailed processes are described as follows:
  • Step 1. Initialize the optimization problem and algorithm parameters.

These parameters are specified according to the HS algorithm. The decision variable Δti is denoted by xi. The harmony memory size is set as H. The optimization problem is specified as follows: Equation 13 where m is the number of variables (there are m+1 via points and m time intervals Δti), the upper limit ubi, j is set freely, and the lower limit lbi, j is determined indirectly by the velocity limits of the robot's jth joint: Equation 14 where VCj is the velocity limits of the jth joint.
  • Step 2. Initialize the harmony memory: Equation 15 Equation 16 where Xk=(x0k, x1k, … ,xm−1k) is the kth solution vector, and its ith component xik is generated according to equation (14).

  • Step 3. Execute the local search.

First, find the best solution vector and the worst one: Equation 17 Second, execute the feasible direction method to obtain the local optimal solution vector X′, using the vector D=XbestXworst as the search direction.

Finally, replace Xworst with X′:

  • Step 4. Improvise a new harmony vector. The component of the new vector xinew is improvised using three mechanisms: memory consideration, pitch adjustment and random selection.

  • Step 5. Update the harmony memory. Judge whether the new solution is better than the worst vector in HM. If f(Xnew)<f(Xworst), replace Xworst with Xnew.

  • Step 6. Check the termination criterion. Repeat Steps 3‐5 until the number of iterations reaches the maximum or the best harmony solution vector is close to the worst one.

  • Step 7. Find the best harmony vector Xbest in the final HM as the global optimal solution vector.

5 Implementation results

Evaluation of the effect of the trajectory planning algorithm on the motion performance and execution time is made using the example of a six‐DOF jointed arm robot QH165, shown in Figure 3. The QH165 robot's D‐H parameters are shown in Table I and its kinematical constraints are shown in Table II. The trajectory planning algorithm described in the above section can be run using equation (1) for a quintic B‐spline trajectory. The proposed HS algorithm is applied to plan the trajectory, which is a combinatorial optimization problem to find the minimum execution time while satisfying kinematical constraints.

The algorithm starts from a geometric path, defined in the operative space. This geometric path is transformed into a sequence of via points in the joint space by applying a kinematic inversion. The resulting sequence of points is interpolated by quintic B‐splines, so as to ensure the continuity of position, velocity, acceleration and jerk along the path. The coordinates of the via points in Cartesian operation space are given in Table III. The via points in joint space are given in Table IV. The optimization procedure that was used is shown in Figure 1. The output of the algorithm is given by the values of any time interval ti between each pair of consecutive via points.

In order to test the new HS algorithm, the optimization problem is solved by the SQP method, the HS algorithm and the proposed new HS algorithm. The initial solution for SQP is set as {2.0, 2.0, 2.0, 2.0, 2.0}, and the parameters of the HS algorithm and the new HS algorithm are set as follows: number of decision variables=5; H=10, HMCR=0.95; PAR=0.35; bw=0.1.

The programs implementing the three algorithms were all run on an Intel Pentium® Dual‐Core 2.50 GHz processor. In order to compare their efficiencies, the programs were set to stop when the total trajectory time was less than 6.3 s. Each program was run ten times, and the individual running times are reported in Table V. It shows that, to reach the same optimization objective, the average running time is 112.8 s for the SQP algorithm, 87.4 s for the HS algorithm, and 73.1 s for the proposed new HS algorithm. It is evident that the HS and the new HS algorithm are more efficient than the SQP algorithm. And adding an iteration step, the new HS is more efficient than HS algorithm. A disadvantage of the SQP method is that it requires a suitable initial solution, and this can affect the execution time and even the final result, as the initial solution may be a local optimal.

For comparative analysis, cubic B‐splines and quintic B‐splines were used to formulate the trajectory. The results for the cubic B‐spline trajectory and the quintic B‐spline trajectory, shown in Figures 4‐7, are obtained separately by running the new HS for 80 s. The cubic B‐spline trajectory and quintic B‐spline trajectory are shown in Figures 4‐7. They show that both of the trajectories satisfy the constraints of position, velocity, acceleration and jerk. Figure 4 shows plots of the two sets of trajectories for each joint, with each trajectory passing through all of the specified joint via points. The total time of the quintic B‐spline trajectory is slightly longer than that of cubic B‐spline trajectory, while the continuity feature of the quintic B‐spline is much better, as shown in Figures 6 and 7. The acceleration and jerk response curves obtained when using the quintic B‐spline trajectory are both continuous and smooth, while the acceleration of the cubic B‐spline trajectory is not smooth and the jerk of the cubic B‐spline trajectory is discontinuous. Compared to a cubic B‐spline trajectory, the quintic B‐spline trajectory is smooth enough to reduce the vibrations.

6 Conclusion

In this paper, an algorithm for trajectory planning of industrial robots by applying an IHS algorithm has been described. Application to a six‐DOF joint robot has been carried out and the results show that the proposed new HS algorithm, which has added one more operation to the original HS algorithm, is more efficient than the SQP and the original HS algorithms. The simulation results obtained here have compared the cubic B‐spline trajectory and quintic B‐spline trajectory, and the quintic B‐spline produces better continuity. The proposed algorithm is applicable to any industrial robot and the adopted kinematical approach is easy to be carried out. As the actual acceleration kinematical limits vary with the robot's position, compared to the kinematical model, the dynamical model would allow a more precise formulation of a real minimum‐time problem. In our future work, the dynamical model will be formulated to improve the performance of the algorithm for time‐optimal trajectory planning.

Figure 1   Procedure for optimization using B‐spline trajectory

Figure 1

Procedure for optimization using B‐spline trajectory

Figure 2   Analogy between improvisation and optimization

Figure 2

Analogy between improvisation and optimization

Figure 3   The QH165 robot for testing the algorithm

Figure 3

The QH165 robot for testing the algorithm

Figure 4   Position of cubic B‐spline trajectory and quintic B‐spline trajectory

Figure 4

Position of cubic B‐spline trajectory and quintic B‐spline trajectory

Figure 5   Velocity of cubic B‐spline trajectory and quintic B‐spline trajectory

Figure 5

Velocity of cubic B‐spline trajectory and quintic B‐spline trajectory

Figure 6   Acceleration of cubic B‐spline trajectory and quintic B‐spline trajectory

Figure 6

Acceleration of cubic B‐spline trajectory and quintic B‐spline trajectory

Figure 7   Jerk of cubic B‐spline trajectory and quintic B‐spline trajectory

Figure 7

Jerk of cubic B‐spline trajectory and quintic B‐spline trajectory

Table I   D‐H parameters of QH165

Table I

D‐H parameters of QH165

Table II   Kinematical constraints

Table II

Kinematical constraints

Table III   Via points in Cartesian space

Table III

Via points in Cartesian space

Table IV   Via points in joint space

Table IV

Via points in joint space

Table V   Run times of the three optimization algorithms

Table V

Run times of the three optimization algorithms

Corresponding author

Youdong Chen can be contacted at: [email protected]

References

Chettibi, T., Lehtihet, H., Haddad, M. and Hanchi, S. (2004), “Minimum cost trajectory planning for industrial robots”, European Journal of Mechanics‐A/Solids, Vol. 23 No. 4, pp. 703715.

Costantinescu, D. and Croft, E. (2000), “Smooth and time‐optimal trajectory planning for industrial manipulators along specified paths”, Journal of Robotic Systems, Vol. 17 No. 5, pp. 233249.

Field, G. and Stepanenko, Y. (1996), “Iterative dynamic programming: an approach to minimum energy trajectory planning for robotic manipulators”, Proceedings of the IEEE International Conference on Robotics and Automation, pp. 27552760.

Gasparetto, A. and Zanotto, V. (2007), “A new method for smooth trajectory planning of robot manipulators”, Mechanism and Machine Theory, Vol. 42 No. 4, pp. 455471.

Gasparetto, A. and Zanotto, V. (2010), “Optimal trajectory planning for industrial robots”, Advances in Engineering Software, Vol. 41 No. 4, pp. 548556.

Geem, Z.W. (2006a), “Improved harmony search from ensemble of music players”, in Gabrys, B., Howlett, R.J. and Jain, L.C. (Eds), Knowledge‐Based Intelligent Information and Engineering Systems, Pt 1, Proceedings, Springer, Heidelberg, pp. 8693.

Geem, Z.W. (2006b), “Optimal cost design of water distribution networks using harmony search”, Engineering Optimization, Vol. 38 No. 3, pp. 259280.

Geem, Z.W., Kim, J.H. and Loganathan, G.V. (2001), “A new heuristic optimization algorithm: harmony search”, Simulation, Vol. 76 No. 2, pp. 6068.

Kim, J., Kim, S.‐R., Kim, S.‐J. and Kim, D.‐H. (2010), “A practical approach for minimum‐time trajectory planning for industrial robots”, Industrial Robot: An International Journal, Vol. 37 No. 1, pp. 5161.

Lee, K.S. and Geem, Z.W. (2005), “A new meta‐heuristic algorithm for continuous engineering optimization: harmony search theory and practice”, Computer Methods in Applied Mechanics and Engineering, Vol. 194 Nos 36‐38, pp. 39023933.

Lin, C.S., Chang, P.R. and Luh, J. (1983), “Formulation and optimization of cubic polynomial joint trajectories for industrial robots”, IEEE Transactions on Automatic Control, Vol. 28 No. 12, pp. 10661074.

Mahdavi, M., Fesanghary, M. and Damangir, E. (2007), “An improved harmony search algorithm for solving optimization problems”, Applied Mathematics and Computation, Vol. 188 No. 2, pp. 15671579.

Mendes, N., Neto, P., Pires, J.N. and Loureiro, A. (2013), “Discretization and fitting of nominal data for autonomous robots”, Expert Systems with Applications, Vol. 40, pp. 11431151.

Omran, M.G.H. and Mahdavi, M. (2008), “Global‐best harmony search”, Applied Mathematics and Computation, Vol. 198 No. 2, pp. 643656.

Piazzi, A. and Visioli, A. (1997), “An interval algorithm for minimum‐jerk trajectory planning of robot manipulators”, Proceedings of the 36th Conference on Decision and Control, San Diego, CA, pp. 19241927.

Piazzi, A. and Visioli, A. (2000), “Global minimum‐jerk trajectory planning of robot manipulators”, IEEE Transactions on Industrial Electronics, Vol. 47 No. 1, pp. 140149.

Piegl, L.A. and Tiller, W. (1997), The NURBS Book, 2nd ed., Springer, Berlin.

Rubio, F., Abu‐Dakka, F.J., Valero, F. and Mata, V. (2012), “Comparing the efficiency of five algorithms applied to path planning for industrial robots”, Industrial Robot: An International Journal, Vol. 39 No. 6, pp. 580591.

Saramago, S.F.P. and Junior, V.S. (2000), “Optimal trajectory planning of robot manipulators in the presence of moving obstacles”, Mechanism and Machine Theory, Vol. 35 No. 8, pp. 10791094.

van Dijk, N., van de Wouw, N., Nijmeijer, H. and Pancras, W. (2007), “Path‐constrained motion planning for robotics based on kinematic constraints”, Proceedings of the ASME 2007 International Design Engineering Technical Conferences & Computers and Information in Engineering Conference, Las Vegas, pp. 10711080.

Wang, C.H. and Horng, J.G. (1990), “Constrained minimum‐time path planning for robot manipulators via virtual knots of the cubic B‐spline functions”, IEEE Transactions on Automatic Control, Vol. 35 No. 5, pp. 573577.

Wang, C.M. and Huang, Y.F. (2010), “Self‐adaptive harmony search algorithm for optimization”, Expert Systems with Applications, Vol. 37 No. 4, pp. 28262837.

Xiao, Y.Q., Du, Z.J. and Dong, W. (2012), “Smooth and near time‐optimal trajectory planning of industrial robots for online applications”, Industrial Robot: An International Journal, Vol. 39 No. 2, pp. 169177.

Zanotto, V., Gasparetto, A., Lanzutti, A., Boscariol, P. and Vidoni, R. (2011), “Experimental validation of minimum time‐jerk algorithms for industrial robots”, Journal of Intelligent & Robotic Systems, Vol. 64 No. 2, pp. 197219.

Zou, D.X., Gao, L.Q., Li, S. and Wu, J.H. (2011), “Solving 0‐1 knapsack problem by a novel global harmony search algorithm”, Applied Soft Computing, Vol. 11 No. 2, pp. 15561564.

Related articles