On path planning and optimization using splines

Size: px
Start display at page:

Download "On path planning and optimization using splines"

Transcription

1 On path planning and optimization using splines Mikael Norrlöf Division of Automatic Control Department of Electrical Engineering Linköpings universitet, SE Linköping, Sweden WWW: 7th February 3 AUTOMATIC CONTROL COMMUNICATION SYSTEMS LINKÖPING Report no.: LiTH-ISY-R-49 Submitted to Technical reports from the Control & Communication group in Linköping are available at

2 Abstract This report covers many aspects of path and trajectory generation for industrial robots. Path generation in Cartesian space is discussed, with the limitation that only linear motion is considered. Path generation in joint space is also discussed and in particular representation of the joint path using cubic splines is presented. Different algorithms for spline generation are also discussed and tested on an example. The last step, the trajectory generation is also covered. Two preliminary algorithms that gives limited speed and acceleration in Cartesian space and in joint space are given. It is also indicated that there is more to be done in order to reach an optimal trajectory. At the end of the report a simple spline toolbox for Matlab is described. Keywords: path planning, trajectory generation, cubic spline, cartesian space, joint space

3 Contents Introduction and overview Generate a path in Cartesian space. Motion along straight line A three point linear motion A general case Second order polynomial Two third order polynomials Two fourth and two third order polynomials Matlab implementation of the movel instruction Path generation in joint space 6 3. An iterative spline solution that gives continuous derivative knots knots knots Results from a simulation with the three algorithms An iterative solution that gives continuous first and second derivative Trajectory generation 4. Constant velocity along the Cartesian path Linear motion in Cartesian space Motion along a general path Limitations in Cartesian space Joint space limitations Issues to be studied in more detail A combined algorithm for Cartesian and joint limitations Conclusions and further study Appendix A: A basic spline toolbox i

4 ii

5 Introduction and overview The problem of trajectory generation for industrial robots consists of a number of subproblems. Many research contributions have been in the direction of optimal path planning with velocity, acceleration, and jerk constraints of the robot. Craig [], Sciavicco [], and Chernousko [3] contain good introductions to the topic. Also the PhD thesis of Dahl [4] covers the same problem although there the path generation problem is not covered in such detail. The solution to the trajectory generation problem is a time history of joint position, speed and acceleration for each degree of freedom of the robot. Those trajectories are then used by the robot control system to make the robot follow the programmed path. Trajectory generation as it is defined here assumes that a path in Cartesian space is given by a user. As input to the robot control system we therefore have a high level command such as movel p,v,z,tool movel p3,v3,fine,tool This means that the robot should move along a straight line from a position and orientation in p (not explicitly given) towards the position and orientation given by p and then when inside a zone of mm start moving towards p3. To simplify the path generation in Cartesian space only the positioning problem is considered. The robots that will be used in the examples are the IRB4 robot, described in e.g., [5], and the similar IRB4. The spline generation and analysis is covered in [6] and there is also a toolbox available for Matlab [7] although in this report a toolbox developed by the author (see Appendix A) is used. Generate a path in Cartesian space The representation of the path in Cartesian space is here assumed to be done using polynomials starting with the straight line.. Motion along straight line To give an overview of the problem we start from the simple test case given above, i.e., the movel command. The first step is to parameterize the Cartesian path. This is easy for the linear motion problem where the position along the path can be expressed as p = p + L(p p ), L () The robot is not controlled in Cartesian space and therefore this path has to be transformed into a joint space trajectory. This will be discussed in Section 3.. A three point linear motion When having a motion that passes more than two points the general description of the path is not trivial. The case that will be studied here is given by the following user commands, movel p,v,z,tool movel p3,v3,fine,tool which was also discussed in Section. In principle what we want to achieve is shown in Figure.

6 .5.4 p3 y [m].3.. p p x [m] Figure : The result of two movel instructions with a zone at point p. We will now present three different ways of representing the path inside the zone. The first is based upon a second order polynomial while the second results in two third order polynomials inside the zone. The third solution gives a path inside the zone represented by four polynomials, first a fourth order polynomial, then two third order polynomials and finally a fourth order polynomial..3 A general case When discussing the different ways of representing the path inside the zone, a particular case will be studied. This particular case, referred to as a general case, is shown in Figure. The idea with this general case is that it is always possible to find a coordinate transformation such that the two movel instructions are in a plane and the angle with respect to the y-axis is symmetric and that the second point is in the origin in the x-y-plane. y [m] x [m] Figure : The general case which will be studied in the following sections. A number of requirements can be formulated for the behavior of the path inside the zone. The first and most important is that when interconnecting the two linear sections the path inside the zone must be symmetric. The second requirement that will be adopted here is that the path inside the zone should be close to the one that is achieved by the second order polynomial solution (shown in Figure ). A fundamental requirement is also that the path is continuous with continuous derivative. Two solutions that give a path which has a continuous second derivative will also be presented. The path is represented by sections, P j(l) withl in [ l z,l z] andj as the section number. Notice that l is a path index in p + l(p p ). Since different sections can have different length the

7 derivative of p j,x(l) with respect to l will not necessarily be a continuous function in the point where we go from section j tosectionj. This is the reason why the sections are grouped according to Figure 3. Inside the second section the index l is with respect to p + l(p 3 p ). For the second section l z is the l where p + l(p 3 p ) intersects the zone and l z =. y [m] x [m] Figure 3: Representation of the path in sections. Solid line is section, dashed line is section..4 Second order polynomial We will only consider the polynomials representing the path in x and y since z inthecase described in Section.3. The representation will be as described in the previous section, i.e., the path is represented by sections. The first section from a fine point is trivial to represent since it is enough to represent it as a first order polynomial, where l z can be computed from P (l) =p + l(p p ), l [,l z] () with z thesizeofthezoneatp. l z = z p p (3) The second section (and the general description of a movel section) will consist of two spline sections. The first being a second order polynomial in y and a first order polynomial in x and the second a first order polynomial in x and y. First let p = p + l z(p p ) (4) then the polynomial inside the zone is given by p,x + x(l + l z) P (l) = y l z (l + l z) y(l + l z)+ p,y, l z l l z (5) with and outside the zone x = y = p 3 (6) z P (l) =p + l(p 3 p ), l z <l l z (7) 3

8 Since p, p and p 3 are not in the x-y-plane with p in the origin, p, p =and p 3 are used instead. Now p and p 3 can be found from p, p and p 3 using the following transformations [ p p p 3 p ] = [ xe y e z e ][ p p 3 ] (8) where x e, y e,andz e are the vectors that tells how the x-y-z-axes in Figure 3 are represented in the world coordinates. This mapping can be found by doing the following computations, p + p3 p y e = p + p 3 p x e = (p3 p) ( ) (p 3 p ) y e ye (p 3 p ) ( ) (p 3 p ) y e ye z e = xe ye x e y e (9) The description of the path inside the zone becomes P (l) = [ x e y e z e ] P(l)+p, l z l l z () This kind of description will be used also in the next sections..5 Two third order polynomials The description of the path outside the zone is exactly as in Section.4. The difference is the description inside the zone where P (l) becomes p,x + x(l + l z) y P (l) = (l + l 3l z) 3 y(l + l z)+ p,y, l z l () z and P (l) = y 3l z p,x + x(l + l z) l 3 y l z l + p,y l z y 3, l l z () where is defined in (6). P (l) is computed as in (). In Figure 4 a comparison between the result in this section and what is achieved by using the second order solution from the previous section is shown y [m] x [m] Figure 4: Comparison of the result when using the second order solution in Section.4 (dotted) and the two third order spline solution in Section.5 (solid). 4

9 .6 Two fourth and two third order polynomials To be able to specify the position of the points inside the zone and also include that the function has a continuous second derivative it is necessary to have four conditions in each inner point. Three for continuity and one extra for specifying the position. With two fourth order and two third order polynomials the number of parameters becomes = 8 and the number of conditions = 8. The positions inside the zone are symmetric, i.e., the first v andthethirdpoint v 3 correspond to each other in the following way, v 3,x v,x v 3 = v 3,y = v,y v 3,z v,z with v,z = v 3,z =. Now P,x(l) and P,z(l) arethesameasin()while (3) P,y(l) = P,y(l) = 9 p,y 7 ylz/ v,y +3v,y 5(l z/) 4 (l + l z) p,y +6 ylz +7v,y 3v,y 5(l z/) (l + l z) 3 y(l + l z)+ p,y, l z l lz 6 p,y +3 ylz/+3v,y 7v,y 5(l z/) 3 (l + lz ) (4 p,y ylz 7v,y +3v,y) 5(l z/) (l + lz ) 3( p,y + ylz/+v,y + v,y) 5l z/ (l + lz lz )+v,y, l (4) (5) P,y(l) = 6 p,y 3 ylz/ 3v,y +7v,y 5(l z/) 3 (l + l z) 3 + 3( p,y + ylz/+6v,y 4v,y) (l + l z) + v,y, l lz 5(l z/) (6) P,y(l) = 9 p,y 7 ylz/ v,y +3v,y 5(l z/) 4 (l lz )4 p,y +8 ylz +3v,y 9v,y + (l lz 5(l z/) 3 )3 3(4 p,y yl z 7v,y +3v,y) (l lz 5(l z/) ) 3( p,y + ylz + v,y + v,y) (l lz 5(l z/) )+v,y, l z l lz P (l) is computed as in (). The expression in Equations 4 to 7 have been found using Mathematica. Other combinations of polynomials are easily found using a tool such as Mathematica but those results will not be given as solutions in this report. Interested readers are instead referred to a Mathematica notebook, movelzone.nb, by the author of this report. In Figure 5 a comparison between the result from using the solution described in this section and using the second order spline solution from Section.4 is shown. The resulting path is very similar in the two cases but with the difference that the second derivative for the resulting path described in this section is continuous. (7).7 Matlab implementation of the movel instruction The three different ways to represent the path inside a zone are all implemented in the function movelzone, described below. 5

10 y [m] x [m] Figure 5: Comparison of the result when using the second order solution from Section.4 (dotted) and the four spline solution in Section.6 (solid). Syntax Description Example [sec,coeffs] = movelzone(p,p,p3,zone,zone3,method); Computes a section represented by a spline in the spline toolbox format described in Appendix A. The argument method can be one of the following: (a) If method== (default) the second order polynomial solution from Section.4 is used. (b) If method== the two third order polynomial solution from Section.5 is used. (c) If method==3 the method described in Section.6 is used. The points p to p3 are the one shown in Figure and the section, returned in sec, is the dashed part in Figure 3. The parameters zone and zone3 are the size of the zones at p and p3, respectively. The result from running the Matlab code below is shown in Figure 6. For a more thorough discussion of the basic spline toolbox used in the example see Appendix A. p = [.5,.5,] ; p = [.,.45,.] ; p3 = [.5,.6,.5] ; zone =.; zone3 = ; sec = movelzone(p,p,p3,zone,zone3,3) plot3([p() p() p3()],... [p() p() p3()],[p(3) p(3) p3(3)], : ) hold on pos = evalsp(sec,sec.brp():.:sec.brp(end)) ; plot3(pos(:,),pos(:,),pos(:,3)); 3 Path generation in joint space Given a path representation in Cartesian space this path has to be transformed into a path representation in joint space. This is in general not possible to do analytically. Instead the path must be transformed using the inverse kinematic model of the robot manipulator at discrete points. The idea that will be adopted here is that given the discrete points in joint space we want to find a spline representation (in joint space) that approximates the true path with a given accuracy. In the next section two different methods to do this will be described and the resulting algorithms will also be analyzed both from an analytical point of view as well as a simulation point of view. 6

11 .5..5 z [m] y [m] x [m].4.5 Figure 6: The result from running the Matlab code in the example describing the movelzone command. 3. An iterative spline solution that gives continuous derivative Three different versions of the algorithm will be discussed in this section. One based on knots, the second on 3 knots and the last on 4 knots. The resulting splines are computed using estimates of the derivative of the path with respect to l (the path index). The estimated derivative can be found in many different ways but here it will be assumed that it can be computed using the Jacobian [5], another solution is to find the inverse kinematic solution close to the endpoints and compute the estimate of the derivative using a difference approximation. 3.. knots The first solution is based on knots. This means that only one cubic spline has to be found. Given the joint position and the joint position derivative in the two knots, φ j and φ j with j = k, k + the solution is found as ˆφ(l) = (φ k φ k+ )+ k (φ k + φ k+) (l l 3 k ) 3 k 3(φ k φ k+ )+ k (φ k + φ k+) (l l k ) k (8) + φ k(l l k )+φ k, l k l l k+ To evaluate the solution the direct kinematics is computed in the intermediate point, l k+/ = l k + l k+ l k, and the resulting Cartesian point is compared to the true position from the spline representation of the path in Cartesian space. If T ( ˆφ(l k+/ )) P (l k+/ ) <γfor some norm and γ then the spline is considered ok, otherwise the step length is changed to k /andanewspline is computed as above. T ( ) represents the direct kinematic model. Algorithm (An iterative algorithm for spline interpolation using knots). Compute the inverse kinematic solution at P (l) and P (l+ l ),resultinginφ(l) and φ(l+ l ).. Find an estimate of dφ(l) and dφ(l+ l) (using for example the Jacobian). dl dl 3. Compute the coefficients in the cubic spline from (8). 4. Evaluate the resulting spline, ˆφ(l) in l + l / T ( ˆφ(l + l /)) P (l + l /) <γ (9) 7

12 where P ( ) is assumed to be the path representation in Cartesian space. If the -norm is used γ represents the maximum error in Cartesian space that is allowed. a. If the inequality in (9) is fulfilled then keep the spline and let l = l + l, l = l b. else let l = l 5. Goto knots The 3 knots solution gives as a result cubic splines given the joint position and the joint position derivative at the first and the last knot, φ j and φ j with j = k, k + and joint position in the middle knot, φ k+. The solution is found as ˆφ(l) = k+ (φ k φ k+ )+ k k+ (4(φ k φ k+ )+ k+ φ k )+ k ( 3φ k++3φ k+ + k+ φ k k+φ k+ ) k k+( k + k+ ) (l l k ) k+ (φ k+ φ k ) 3 k k+ ((φ k φ k+ )+ k+ φ k )+ k (3(φ k+ φ k+ ) 4 k+ φ k + k+φ k+ ) k k+ ( k + k+ ) () (l l k ) + φ k(l l k )+φ k, l k l l k+ ˆφ(l) = k (φ k+ φ k+ )+ k k+ (4(φ k+ φ k+ )+ k φ k+ )+ k+ (3(φ k+ φ k ) k φ k + kφ k+ ) k k+ ( k+ k+ ) (l l k+ ) k(φ k+ φ k+ )+ k+ (3(φ k φ k+ )+ k (φ k φ k+ )) k k+ ( k + k+ ) (l l k+ ) () 3 k (φ k+ φ k+ )+ k+ (3(φ k φ k+ )+ k φ k )+ k k+φ k+ k k+ ( k + k+ (l l ) k+ ) + φ k+, l k+ l l k+ The result in () and () can be simplified if it can be assumed that k = k+. To find the solution in () and () it is assumed that ˆφ(l) ineachintervalisgivenby For the first spline it follows that ˆφ(l) =a + a (l l k )+a 3(l l k ) + a 4(l l k ) 3 () ˆφ (l k )=φ(l k ), ˆφ(l k+ )=φ(l k+ ), ˆφ (l k )=φ (l k ) and for the second spline the conditions become ˆφ (l k+ )=φ(l k+ ), ˆφ (l k+ )=φ (l k+ ) To get a continuous function with continuous first and second derivative at the inner knot we also have the conditions ˆφ (l k+ )= ˆφ (l k+ ), ˆφ (l k+ )= ˆφ (l k+ ), ˆφ (l k+ )= ˆφ (l k+ ) which give a total of 8 conditions. From () we see that each spline has 4 parameters which gives a total of 8 parameters and a system of equations that has one unique solution. This solution is given by () and (). Algorithm (An iterative algorithm for spline interpolation using 3 knots) The limit is not guaranteed and therefore a larger error can be achieved in some other point along the spline. 8

13 . Compute the inverse kinematic solution at P (l), P (l + l ) and P (l + l ),resultinginφ(l), φ(l + l ) and φ(l + l ).. Find an estimate of dφ(l) and dφ(l+ l) (using for example the Jacobian). dl dl 3. Compute the coefficients in the cubic splines from () and (). 4. Evaluate the resulting spline, ˆφ(l) in l + l / and l +3 l / T ( ˆφ(l + l /)) P (l + l /) <γ, T ( ˆφ(l +3 l /)) P (l +3 l /) <γ (3) where P ( ) is assumed to be the path representation in Cartesian space. If the -norm is used γ represents the maximum error in Cartesian space that is allowed. a. If the inequality in (3) is fulfilled then keep the spline and let l = l + l, l = l b. else let l = l 5. Goto knots The solution for this case is not given since it becomes too complex to grasp. To find the solution the same kind of spline representation as given in () is used. For the first spline the following conditions must be fulfilled and for the last spline the conditions become ˆφ (l k )=φ(l k ), ˆφ(l k+ )=φ(l k+ ), ˆφ (l k )=φ (l k ) ˆφ 3(l k+3 )=φ(l k+3 ), ˆφ 3 (l k+3 )=φ (l k+3 ) To get a continuous function with continuous first and second derivative at the inner knot we also have the conditions and ˆφ (l k+ )= ˆφ (l k+ ), ˆφ (l k+ )= ˆφ (l k+ ), ˆφ (l k+ )= ˆφ (l k+ ) ˆφ (l k+ )= ˆφ 3(l k+ ), ˆφ (l k+ )= ˆφ 3(l k+ ), ˆφ (l k+ )= ˆφ 3 (l k+ ) This gives a total of conditions. From () we see that each spline has 4 parameters which gives a total of parameters and a system of equations that has one unique solution. The algorithm for this case is similar to Algorithm with obvious extensions (compare going from Algorithm to Algorithm ) Results from a simulation with the three algorithms Next the results from using the algorithms presented in the three previous sections. The test case that will be used is the path described in the example in Section.7, i.e., p = [.5,.5,] ; p = [.,.45,.] ; p3 = [.5,.6,.5] ; zone =.; zone3 = ; sec = movelzone(p,p,p3,zone,zone3,j) 9

14 This means the path shown as a solid line in Figure. In all the simulations j =,, 3 will be tested to see how the different algorithms for creating the path in Cartesian space give an impact on the resulting joint space path. The parameter γ in the algorithms is chosen γ = 5, i.e., the maximum error allowed becomes µm. In Tables to 3 the results from using the three algorithms is shown. In each case the three methods for generating the path in Cartesian space (described in Sections.4 to.6) is tested. From the number of splines it is clear that the path generated with method, a path that has continuous derivative and continuous second derivative, is the easiest to follow using a cubic spline in joint space. Method No. of splines Min/Max step Min/Max error 3.5/. 8. / / / /..7 7 /5. 6 Table : Results from using Algorithm..5 φ φ φ φ φ l Path index l Path index x 5 Method 3 φ Error l Path index Spline number Figure 7: Results from using Algorithm. Angles for method (upper left), (upper right), and 3 (lower left). The resulting estimated error on the arm-side is shown in the lower right plot. The dotted line shows where the zone starts and ends. It is worth noting also that the step length is adjusted in a very simple way in the algorithms presented in Section 3.. The resulting spline does not have a continuous second derivative in joint space either which might be a limitation in the next step when a trajectory in joint space is to be found. In Figures 7 to 9 the resulting knots are shown for the three algorithms (and three cases for each algorithm). For method, which gives a discontinuous second derivative in the Cartesian path when passing the zone, it is clear that it takes many more splines to approximate the function in

15 Method No. of splines Min/Max step Min/Max error./..8 / /..4 7 / / /6.9 6 Table : Results from using Algorithm. the neighborhood of the discontinuity. This is common for all the three algorithms. The path that is most difficult to approximate in all the three cases is the one generated by method 3. This path tries to mimic the one generated by method but still keeps a continuous second derivative. Method No. of splines Min/Max step Min/Max error 4.5/. 8.8 / / / /..8 8 /5.4 6 Table 3: Results from using 3 splines. 3. An iterative solution that gives continuous first and second derivative A tempting solution to the problem of generating a cubic spline function in joint space that has continuous derivative and continuous second derivative is to specify the position, the derivative and the second derivative in the first knot and let the derivative and second derivative be free in the final point. This algorithm can however be proven to be unstable. An alternative that seems more promising is to use a fourth order plus one or more third order polynomials in the computation of the joint path. This method uses a specified position, derivative and second derivative in the starting point but incorporates also the derivative in the final point. This algorithm has shown a stable behavior in simulations and also in a preliminary analysis. 4 Trajectory generation When planning a trajectory in joint space, the first question that will be addressed is how to achieve a constant velocity in Cartesian space. 4. Constant velocity along the Cartesian path From Section it is clear that, at least for some special cases, it is possible to find an analytic description of the path (as a function of path index l) in Cartesian space. From now on it will be assumed that this is the case. To achieve a constant speed along the path it is necessary that P = v, for some desired speed v. If P (l) is given from the geometrical interpolation explained in Section it means that, in general, P (l) isavector,p (l) = ( p x(l) p y(l) p ) T z(l),wherep( ) (l) can be assumed to be a cubic spline (or a lower order polynomial). Along a straight line in Cartesian space the polynomials are only of degree one and therefore the problem becomes much less complicated. We will now however focus on the cubic spline case, since this is the most general situation. When using the geometrical representation from Section it is clear that the following relation holds dp dt = dp dl dl (4) dt

16 .5 φ φ φ φ φ l Path index l Path index x 5 Method 3 φ Error l Path index Spline number Figure 8: Results from using Algorithm. Angles for method (upper left), (upper right), and 3 (lower left). The resulting estimated error on the arm-side is shown in the lower right plot. The dotted line shows where the zone starts and ends.

17 .5 φ φ φ φ φ l Path index l Path index x 5 Method 3 φ Error l Path index Spline number Figure 9: Results from using 3 splines. Angles for method (upper left), (upper right), and 3 (lower left). The resulting estimated error on the arm-side is shown in the lower right plot. The dotted line shows where the zone starts and ends. 3

18 where the chain rule is used. Now, since the velocity along the path is defined as dp it comes as dt a result from (4) that dp dt = dp dl dl (5) dt where it is assumed that dl >. This assumption must hold since we move along the path (in dt Cartesian or joint space) from, e.g., index to, and this must be a monotonic motion. If we assume P (l) to be the general function described above, then dp dl (p = x(l)) +(p y(l)) +(p z(l)) (6) where p ( )(l) is the derivative with respect to l. Whenp ( ) (l) is a cubic spline the derivative becomes a second order polynomial and the corresponding square becomes a fourth order polynomial. The sum of the squared derivatives in (6) therefore becomes a general fourth order polynomial. From (5) and (6) and the assumption that P = v(t) weget If we now introduce a new variable l c that fulfills dlc dt dl dt = v(t) (7) (p x (l)) +(p y(l)) +(p z(l)) = v(t) weget dl = dl c (p x (l)) +(p y(l)) +(p z(l)) Remark The interpretation of l c is that it is equal to the true length of the Cartesian path. Instead of directly considering the cubic spline case we start from the linear motion case. 4.. Linear motion in Cartesian space To describe a linear motion in Cartesian space P (l) becomes a vector of first order polynomials and, hence, dp is a constant vector. This implies that dp is constant and dl dl l c l = dp/dl, dl c(t) = v(t) (8) dt to give a certain velocity profile along the linear motion. 4.. Motion along a general path If the polynomials in P (l) are general polynomials, then dp becomes a higher order polynomial and dl the normalized spline description P (l c) becomes not so easy to compute analytically. It is however always possible to compute the approximate solution using a sum approximation of the integral along the path. In Figure the test-case is shown that will be used in the evaluation of the algorithms for trajectory generation. It consists of four movel instructions with zones of mm in Cartesian coordinates. The kinematic model that has been used in this test-case is the IRB4. The orientation of the tool is included in this path and therefore the resulting joint path includes all 6 joints. By computing l c(l) = l l P ( l + l ) P ( l) (9) the relation between the path index l and the normalized path index l c can be found. The cost of computing the sum in (9) with a high resolution, i.e., a small l is not so high in practice and 4

19 z [m] y [m] x [m].6.8 Figure : The test-case used in the evaluation of the trajectory generation algorithm l c φ path index.5 j l c Figure : The normalized path index l c as a function of the traditional path index l (left). The spline representation of the path in joint space, computed using the normalized path index l c (right). 5

20 this approximation can therefore be made well. In Figure l c(l) is shown for the example treated in this section. Next the idea is to compute the path in joint space as a function of the new index l c according to the algorithms described in Section 3. The result is shown to the right in Figure Limitations in Cartesian space The first problem that will be considered is limitation in Cartesian coordinates. In the first suggested algorithm limitation with respect to speed and acceleration will be considered. The input to the algorithm is desired velocity v d, and maximum acceleration a max. Algorithm 3 (Limitation in Cartesian space). v p =, l p =,andt p =. For each spline interval, do: (a) Get v d for the current spline (b) l n = l c at the beginning of next spline (c) if v p v d % Constant speed t = ln lp v d l c(t) =v d (t t p)+l p else % Acceleration vd a =min(a max, v p ) (l n l p) if a<ɛ t = ln lp v d l c(t) =v d (t t p)+l p else t = vp a ( + vp ) + ln lp a a l c(t) =a/(t tp) + v p(t t p)+l p end end (d) l p = l n (e) t p = t p + t (f) v p = dlc(t) dt t=tp In Algorithm 3 the function l c(t) is created locally for each spline. The spline length is decided based upon the specified path accuracy, compare Algorithms, and the corresponding 4 knots solution from Section This is clearly not an optimal solution which is shown in the next example. Algorithm 3 is applied to the test-case shown in Figure with the desired speed set to v d =[.,.5,.5,.5] m/s and the maximum acceleration is set to m/s. The results from applying Algorithm 3 on this case is shown in Figure. Notice that the spline lengths are not optimal with respect to the performance. For example, if the first spline had been shorter it should have been possible to use thefullaccelerationm/s and hence reach the desired speed earlier. This means a shorter total cycle time. Also when going from. m/s to.5 m/s, and.5 m/s to.5 m/s there is time to be gained by changing the length of the splines. In Figure 3 the resulting joint trajectory is shown. 6

21 d l c (t) / dt.5. d l c (t)/dt t [sec] t [sec] Figure : The resulting Cartesian path speed (left) and the corresponding Cartesian path acceleration (right)..5 d φ(t)/dt d φ(t)/dt.5 j t [sec] 3 j t [sec] Figure 3: The resulting joint angular velocity (left) and the corresponding joint angular acceleration (right) after applying Algorithm 3. 7

22 4..4 Joint space limitations The second step after considering the limitations in the Cartesian space is to consider joint space limitations. The input to this algorithm is the maximum velocity, φmax R n, and the maximum acceleration, φ max R n. The number of joints is equal to n. In general the limits in joint space will depend on the dynamical model of the system but in this simplified case fixed limits are considered. Algorithm 4 (Joint space limitations). v p =, l p =,andt p =. For each spline interval, do: (a) Get φ max and φ max for the current spline (b) l n = l c at the beginning of next spline (c) t n = time at the end of the current l c(t) spline (d) % Check speed at a grid φ eval =[ d ˆφ(l c) dl c dlc tn tp ], t = tp : : dt n tn eval For each joint j [,n], [ ˆφj,max,t j]=max φ j,eval (t) (t j is the time where the maximum is found) (e) % Check speed levels against max levels ˆφ [r, m joint] =max[ ˆφ,max,..., n,max, ] φ,max φ n,max if r> % Reduce the speed v n = dlc(t) dt t=tmjoint /r vn a n = v p (l c(t mjoint ) l p) ( t = vp vp ) a n + a n + ln lp a n t n = t p + t l c(t) = an (t tp) + v p(t t p)+l p end (f) % Check acceleration at a grid φ eval =[ d ˆφ(l c) ( dl c ) + d ˆφ(l c) dl c dt dl c dlc ], t = t dt p : tn tp : n tn eval For each joint j, [ ˆφj,max,t j]=max φ j,eval (t) (g) % Check acceleration levels against max levels ˆφ [r, m joint] =max[ ˆφ,max,..., n,max, ] φ,max φ n,max if r> % Reduce the acceleration v n = v p/ r a n = a r if a n < ɛ t = ln lc v n else t = vp a n + ( vp a n ) + ln lp a n end l c(t) = an (t tp) + v n(t t p)+l p end (h) l p = l n (i) t p = t p + t (j) v p = dlc(t) dt t=tp After applying Algorithm 4 to the test case in Figure the Cartesian speed and acceleration become like in Figure 4. The maximum angular velocity is here set to φ max =[4, 4, 4, 4, 4, 4] 8

23 and the maximum angular acceleration φ max =[,,,,, ]. Compare to the result in Figure 3. Clearly there are no active restrictions until the final segment where the speed is actually too high. This shows that the speed also gives raise to an acceleration term when considering angular acceleration and Cartesian path velocity. In the last segment the path acceleration is limited because joint has an acceleration greater than rad/s. In Figure 5 the resulting angular velocity and acceleration is shown. By applying Algorithm 4, only velocity and acceleration constraints are considered. Deceleration constraints are not taken into account and the deceleration ramp necessary to make the robot stop at the final point is for example not implemented d l c (t) / dt.5. d l c (t)/dt t [sec] t [sec] Figure 4: The resulting Cartesian path speed (left) and the corresponding Cartesian path acceleration (right) after applying Algorithm j d φ(t)/dt d φ(t)/dt.5 j t [sec] t [sec] Figure 5: The resulting joint angular velocity (left) and the corresponding joint angular acceleration (right) after applying Algorithm Issues to be studied in more detail Clearly many aspects need to be considered before claiming that the presented solution is ready. As indicated in the remarks after the discussion on Algorithm 3 this algorithm does not give an optimal solution. To achieve a more optimal solution the length of the splines describing l c(t) needs to be shorter than the corresponding splines used to represent the path, ˆφ(l c). This comment also applies to Algorithm 4. In neither of the two algorithms the deceleration is considered and therefore the limit on the acceleration is not valid for deceleration. The deceleration case should be implemented at least 9

24 in the Cartesian case since otherwise it is possible that the deceleration will be higher than the specified Cartesian acceleration value. 4. A combined algorithm for Cartesian and joint limitations Instead of considering the limitations in Cartesian and joint space separated we will now consider an algorithm that takes both into account. Algorithm 5 (Cartesian and joint space limitations in parallel). v p =, l p =,andt p =. For each spline interval, do: (a) Get φ max and φ max for the current spline (b) l n = l c at the beginning of next spline (c) t n = time at the end of the current l c(t) spline (d) % Check speed at a grid φ eval =[ d ˆφ(l c) dl c dlc tn tp ], t = tp : : dt n tn eval For each joint j [,n], [ ˆφj,max,t j]=max φ j,eval (t) (t j is the time where the maximum is found) (e) % Check speed levels against max levels ˆφ [r, m joint] =max[ ˆφ,max,..., n,max, ] φ,max φ n,max if r> % Reduce the speed v n = dlc(t) dt t=tmjoint /r vn a n = v p (l c(t mjoint ) l p) ( t = vp vp ) a n + a n + ln lp a n t n = t p + t l c(t) = an (t tp) + v p(t t p)+l p end (f) % Check acceleration at a grid φ eval =[ d ˆφ(l c) ( dl c ) + d ˆφ(l c) dl c dt dl c dlc ], t = t dt p : tn tp : n tn eval For each joint j, [ ˆφj,max,t j]=max φ j,eval (t) (g) % Check acceleration levels against max levels ˆφ [r, m joint] =max[ ˆφ,max,..., n,max, ] φ,max φ n,max if r> % Reduce the acceleration v n = v p/ r a n = a r if a n < ɛ t = ln lc v n else t = vp a n + ( vp a n ) + ln lp a n end l c(t) = an (t tp) + v n(t t p)+l p end (h) l p = l n (i) t p = t p + t (j) v p = dlc(t) dt t=tp

25 This algorithm suffer from some of the problems indicated in the previous section. It still does not give an optimal solution and the acceleration is reduced more than what is actually necessary. 5 Conclusions and further study This report contains three major parts, path generation in Cartesian space, transformation and representation of the path in joint space, and finally generation of trajectories in Cartesian space and in joint space. It does not give the final answers on exactly how to solve the different problems in these areas but does provide the reader with ideas that can be used in order to solve the different problems. A number of things are however still to do and this is a list of some of the most important items: Path generation in Cartesian space: Generation of other paths than lines. To include also the orientation of the tool in the path representation. Implementation of more general instructions for path generation in Matlab. Considering the problem of connecting circles to lines and circles to circles using zones. Path generation in joint space: Development of algorithms that give continuous first and second derivative with respect to path index. Development of the algorithms so that when reaching a new segment it is guaranteed to be a new spline. Analytical results on which method to choose for interpolating the splines in joint space. A theoretical analysis of the error in the approximation that is achieved when estimating the maximum Cartesian error for the interpolated joint path. Trajectory generation: Sensitivity analysis of the method to compute l c from the Cartesian path using a finite sum approximation of an integration. Development of a more general optimal trajectory generation algorithm that considers Cartesian and joint space in parallel. Further improvements on Algorithm 3 and Algorithm 4 to make them more optimal by making the l c(t) splines not fixed to the joint spline description. Study the effect of the smoothness of the path generated in Cartesian space and in joint space (different levels of continuity. References [] John J. Craig. Introduction to robotics: Mechanics and control. Addison-Wesley Publishing Company, second edition, 989. [] L. Sciavicco and B. Siciliano. Modelling and Control of Robot Manipulators. Springer,. [3] F.L. Chernousko. Optimization in control of robots. International Series of Numerical Mathematics, 5:9 8, 994. [4] Ola Dahl. Path Constrained Robot Control. PhD thesis, Department of Automatic Control, Lund Institute of Technology, 99. [5] M. Norrlöf. Modeling of industrial robots. Technical Report LiTH-ISY-R-8, Department of Electrical Engineering, Linköpings universitet, Dec 999. [6] Carl de Boor. A Practical Guide to Splines. Springer-Verlag, 978. [7] Carl de Boor. Spline Toolbox, For Use with MATLAB TM. The MathWorks Inc., Natric, MA, USA, Jan. 999.

26 Appendix A: A basic spline toolbox To be able to use splines without the commercial spline toolbox in Matlab, a basic set of functions has been developed. This includes a data structure to represent splines as well as some functions to construct a spline and to evaluate the spline at certain points plus some more functions. Next the functions in the basic spline toolbox is described. Syntax Description Example sp = makesp(brp,coefs,order); Constructs a spline from a set of break points (knots), brp, coefficientsincoefs, and an optional vector order that contains the order of the different polynomials (if they are not the same). Creation of a simple spline function >> sp = makesp([ ],[ 3 6]) sp = brp: [ ] coefs: [ 3 6] order: maxorder: dim: Syntax value = evalsp(sp,x); Description Evaluate the spline sp in the point given by x. Example Evaluation of the spline created in the makesp example >> evalsp(sp,.56) ans = Syntax Description Example dsp = dersp(sp); Differentiate the spline sp and returns the result as a spline in dsp. Differentiate the polynomial created in the makesp example >> dsp = dersp(sp) dsp = brp: [ ] maxorder: coefs: [ 4 ] order: dim: Syntax Description Example nsp = appendsp(sp,asp); Append the spline given by asp to the splines in sp. The result is returned as a new spline. If the two splines are of different order the result is always of the maximum order of the two. Append a spline to the spline created in the makesp example (note that the order of sp is one less than that of sp while the result is that of sp) >> sp = makesp([ 3],[- 9]); >> nsp = appendsp(sp,sp) nsp = brp: [ 3] maxorder: coefs: [ 3 6-9] order: dim:

27 Syntax Description Example csp = completesp(brp,p,[d d]); Compute the complete spline, i.e., a number of cubic splines with knots in brp having functions values given by p. The derivative in the first and the last knot is given by [d d]. Compute the complete spline with knots in [.5.5] with function value [.5.5] and derivative [.5 -] >> csp = completesp([.5.5],[.5.5],[.5 -]) csp = brp: [.5.5] coefs: [x double] order: 3 maxorder: 3 dim: In Figure 6 the resulting function and its derivative is shown (generated by using plot(:.:.5,evalsp(csp,:.:.5)) and plot(:.:.5,evalsp(dersp(csp),:.:.5))) f(x) f (x) x x Figure 6: Example of a complete spline (function left and its derivative right). 3

28 Avdelning, Institution Division, Department Division of Automatic Control Department of Electrical Engineering Datum Date 3--7 Språk Language Svenska/Swedish X Engelska/English... Rapporttyp Report category Licentiatavhandling Examensarbete C-uppsats D-uppsats X Övrig rapport... ISBN... ISRN... Serietitel och serienummer Title of series, numbering ISSN URL för elektronisk version LiTH-ISY-R-49 Titel Title Författare Author On path planning and optimization using splines Mikael Norrlöf, Sammanfattning Abstract This report covers many aspects of path and trajectory generation for industrial robots. Path generation in Cartesian space is discussed, with the limitation that only linear motion is considered. Path generation in joint space is also discussed and in particular representation of the joint path using cubic splines is presented. Different algorithms for spline generation are also discussed and tested on an example. The last step, the trajectory generation is also covered. Two preliminary algorithms that gives limited speed and acceleration in Cartesian space and in joint space are given. It is also indicated that there is more to be done in order to reach an optimal trajectory. At the end of the report a simple spline toolbox for Matlab is described.. Nyckelord Keywords path planning, trajectory generation, cubic spline, cartesian space, joint space

PGT - A path generation toolbox for Matlab (v0.1)

PGT - A path generation toolbox for Matlab (v0.1) PGT - A path generation toolbox for Matlab (v0.1) Maria Nyström, Mikael Norrlöf Division of Automatic Control Department of Electrical Engineering Linköpings universitet, SE-581 83 Linköping, Sweden WWW:

More information

Manipulator trajectory planning

Manipulator trajectory planning Manipulator trajectory planning Václav Hlaváč Czech Technical University in Prague Faculty of Electrical Engineering Department of Cybernetics Czech Republic http://cmp.felk.cvut.cz/~hlavac Courtesy to

More information

1 Trajectories. Class Notes, Trajectory Planning, COMS4733. Figure 1: Robot control system.

1 Trajectories. Class Notes, Trajectory Planning, COMS4733. Figure 1: Robot control system. Class Notes, Trajectory Planning, COMS4733 Figure 1: Robot control system. 1 Trajectories Trajectories are characterized by a path which is a space curve of the end effector. We can parameterize this curve

More information

WORKSPACE AGILITY FOR ROBOTIC ARM Karna Patel

WORKSPACE AGILITY FOR ROBOTIC ARM Karna Patel ISSN 30-9135 1 International Journal of Advance Research, IJOAR.org Volume 4, Issue 1, January 016, Online: ISSN 30-9135 WORKSPACE AGILITY FOR ROBOTIC ARM Karna Patel Karna Patel is currently pursuing

More information

Robots are built to accomplish complex and difficult tasks that require highly non-linear motions.

Robots are built to accomplish complex and difficult tasks that require highly non-linear motions. Path and Trajectory specification Robots are built to accomplish complex and difficult tasks that require highly non-linear motions. Specifying the desired motion to achieve a specified goal is often a

More information

Optimization of a two-link Robotic Manipulator

Optimization of a two-link Robotic Manipulator Optimization of a two-link Robotic Manipulator Zachary Renwick, Yalım Yıldırım April 22, 2016 Abstract Although robots are used in many processes in research and industry, they are generally not customized

More information

Prof. Fanny Ficuciello Robotics for Bioengineering Trajectory planning

Prof. Fanny Ficuciello Robotics for Bioengineering Trajectory planning Trajectory planning to generate the reference inputs to the motion control system which ensures that the manipulator executes the planned trajectories path and trajectory joint space trajectories operational

More information

An introduction to interpolation and splines

An introduction to interpolation and splines An introduction to interpolation and splines Kenneth H. Carpenter, EECE KSU November 22, 1999 revised November 20, 2001, April 24, 2002, April 14, 2004 1 Introduction Suppose one wishes to draw a curve

More information

INSTITUTE OF AERONAUTICAL ENGINEERING

INSTITUTE OF AERONAUTICAL ENGINEERING Name Code Class Branch Page 1 INSTITUTE OF AERONAUTICAL ENGINEERING : ROBOTICS (Autonomous) Dundigal, Hyderabad - 500 0 MECHANICAL ENGINEERING TUTORIAL QUESTION BANK : A7055 : IV B. Tech I Semester : MECHANICAL

More information

Singularity Loci of Planar Parallel Manipulators with Revolute Joints

Singularity Loci of Planar Parallel Manipulators with Revolute Joints Singularity Loci of Planar Parallel Manipulators with Revolute Joints ILIAN A. BONEV AND CLÉMENT M. GOSSELIN Département de Génie Mécanique Université Laval Québec, Québec, Canada, G1K 7P4 Tel: (418) 656-3474,

More information

Jacobian: Velocities and Static Forces 1/4

Jacobian: Velocities and Static Forces 1/4 Jacobian: Velocities and Static Forces /4 Advanced Robotic - MAE 6D - Department of Mechanical & Aerospace Engineering - UCLA Kinematics Relations - Joint & Cartesian Spaces A robot is often used to manipulate

More information

A New Algorithm for Measuring and Optimizing the Manipulability Index

A New Algorithm for Measuring and Optimizing the Manipulability Index DOI 10.1007/s10846-009-9388-9 A New Algorithm for Measuring and Optimizing the Manipulability Index Ayssam Yehia Elkady Mohammed Mohammed Tarek Sobh Received: 16 September 2009 / Accepted: 27 October 2009

More information

The Application of Spline Functions and Bézier Curves to AGV Path Planning

The Application of Spline Functions and Bézier Curves to AGV Path Planning IEEE ISIE 2005, June 20-23, 2005, Dubrovnik, Croatia The Application of Spline Functions and Bézier Curves to AGV Path Planning K. Petrinec, Z. Kova i University of Zagreb / Faculty of Electrical Engineering

More information

The ARCUS Planning Framework for UAV Surveillance with EO/IR Sensors

The ARCUS Planning Framework for UAV Surveillance with EO/IR Sensors Technical report from Automatic Control at Linköpings universitet The ARCUS Planning Framework for UAV Surveillance with EO/IR Sensors Per Skoglar Division of Automatic Control E-mail: skoglar@isy.liu.se

More information

Cecilia Laschi The BioRobotics Institute Scuola Superiore Sant Anna, Pisa

Cecilia Laschi The BioRobotics Institute Scuola Superiore Sant Anna, Pisa University of Pisa Master of Science in Computer Science Course of Robotics (ROB) A.Y. 2016/17 cecilia.laschi@santannapisa.it http://didawiki.cli.di.unipi.it/doku.php/magistraleinformatica/rob/start Robot

More information

1724. Mobile manipulators collision-free trajectory planning with regard to end-effector vibrations elimination

1724. Mobile manipulators collision-free trajectory planning with regard to end-effector vibrations elimination 1724. Mobile manipulators collision-free trajectory planning with regard to end-effector vibrations elimination Iwona Pajak 1, Grzegorz Pajak 2 University of Zielona Gora, Faculty of Mechanical Engineering,

More information

Institutionen för datavetenskap Department of Computer and Information Science

Institutionen för datavetenskap Department of Computer and Information Science Institutionen för datavetenskap Department of Computer and Information Science Final thesis Load management for a telecom charging system by Johan Bjerre LIU-IDA/LITH-EX-A--08/043--SE 2008-10-13 1 Linköpings

More information

Mathematically, the path or the trajectory of a particle moving in space in described by a function of time.

Mathematically, the path or the trajectory of a particle moving in space in described by a function of time. Module 15 : Vector fields, Gradient, Divergence and Curl Lecture 45 : Curves in space [Section 45.1] Objectives In this section you will learn the following : Concept of curve in space. Parametrization

More information

10/11/07 1. Motion Control (wheeled robots) Representing Robot Position ( ) ( ) [ ] T

10/11/07 1. Motion Control (wheeled robots) Representing Robot Position ( ) ( ) [ ] T 3 3 Motion Control (wheeled robots) Introduction: Mobile Robot Kinematics Requirements for Motion Control Kinematic / dynamic model of the robot Model of the interaction between the wheel and the ground

More information

Hand-Eye Calibration from Image Derivatives

Hand-Eye Calibration from Image Derivatives Hand-Eye Calibration from Image Derivatives Abstract In this paper it is shown how to perform hand-eye calibration using only the normal flow field and knowledge about the motion of the hand. The proposed

More information

1. Introduction 1 2. Mathematical Representation of Robots

1. Introduction 1 2. Mathematical Representation of Robots 1. Introduction 1 1.1 Introduction 1 1.2 Brief History 1 1.3 Types of Robots 7 1.4 Technology of Robots 9 1.5 Basic Principles in Robotics 12 1.6 Notation 15 1.7 Symbolic Computation and Numerical Analysis

More information

Ch. 6: Trajectory Generation

Ch. 6: Trajectory Generation 6.1 Introduction Ch. 6: Trajectory Generation move the robot from Ti to Tf specify the path points initial + via + final points spatial + temporal constraints smooth motion; continuous function and its

More information

MA 323 Geometric Modelling Course Notes: Day 21 Three Dimensional Bezier Curves, Projections and Rational Bezier Curves

MA 323 Geometric Modelling Course Notes: Day 21 Three Dimensional Bezier Curves, Projections and Rational Bezier Curves MA 323 Geometric Modelling Course Notes: Day 21 Three Dimensional Bezier Curves, Projections and Rational Bezier Curves David L. Finn Over the next few days, we will be looking at extensions of Bezier

More information

Robot. A thesis presented to. the faculty of. In partial fulfillment. of the requirements for the degree. Master of Science. Zachary J.

Robot. A thesis presented to. the faculty of. In partial fulfillment. of the requirements for the degree. Master of Science. Zachary J. Uncertainty Analysis throughout the Workspace of a Macro/Micro Cable Suspended Robot A thesis presented to the faculty of the Russ College of Engineering and Technology of Ohio University In partial fulfillment

More information

PS Geometric Modeling Homework Assignment Sheet I (Due 20-Oct-2017)

PS Geometric Modeling Homework Assignment Sheet I (Due 20-Oct-2017) Homework Assignment Sheet I (Due 20-Oct-2017) Assignment 1 Let n N and A be a finite set of cardinality n = A. By definition, a permutation of A is a bijective function from A to A. Prove that there exist

More information

Simulation of Robot Manipulator Trajectory Optimization Design

Simulation of Robot Manipulator Trajectory Optimization Design International Journal of Research in Engineering and Science (IJRES) ISSN (Online): -96, ISSN (Print): -956 Volume 5 Issue ǁ Feb. 7 ǁ PP.7-5 Simulation of Robot Manipulator Trajectory Optimization Design

More information

Planar Robot Kinematics

Planar Robot Kinematics V. Kumar lanar Robot Kinematics The mathematical modeling of spatial linkages is quite involved. t is useful to start with planar robots because the kinematics of planar mechanisms is generally much simpler

More information

Institutionen för systemteknik

Institutionen för systemteknik Institutionen för systemteknik Department of Electrical Engineering Examensarbete Design and Implementation of a DMA Controller for Digital Signal Processor Examensarbete utfört i Datorteknik vid Tekniska

More information

Kinematics, Kinematics Chains CS 685

Kinematics, Kinematics Chains CS 685 Kinematics, Kinematics Chains CS 685 Previously Representation of rigid body motion Two different interpretations - as transformations between different coord. frames - as operators acting on a rigid body

More information

Video 11.1 Vijay Kumar. Property of University of Pennsylvania, Vijay Kumar

Video 11.1 Vijay Kumar. Property of University of Pennsylvania, Vijay Kumar Video 11.1 Vijay Kumar 1 Smooth three dimensional trajectories START INT. POSITION INT. POSITION GOAL Applications Trajectory generation in robotics Planning trajectories for quad rotors 2 Motion Planning

More information

Spline Curves. Spline Curves. Prof. Dr. Hans Hagen Algorithmic Geometry WS 2013/2014 1

Spline Curves. Spline Curves. Prof. Dr. Hans Hagen Algorithmic Geometry WS 2013/2014 1 Spline Curves Prof. Dr. Hans Hagen Algorithmic Geometry WS 2013/2014 1 Problem: In the previous chapter, we have seen that interpolating polynomials, especially those of high degree, tend to produce strong

More information

NMT EE 589 & UNM ME 482/582 ROBOT ENGINEERING. Dr. Stephen Bruder NMT EE 589 & UNM ME 482/582

NMT EE 589 & UNM ME 482/582 ROBOT ENGINEERING. Dr. Stephen Bruder NMT EE 589 & UNM ME 482/582 ROBOT ENGINEERING Dr. Stephen Bruder Course Information Robot Engineering Classroom UNM: Woodward Hall room 147 NMT: Cramer 123 Schedule Tue/Thur 8:00 9:15am Office Hours UNM: After class 10am Email bruder@aptec.com

More information

A New Algorithm for Measuring and Optimizing the Manipulability Index

A New Algorithm for Measuring and Optimizing the Manipulability Index A New Algorithm for Measuring and Optimizing the Manipulability Index Mohammed Mohammed, Ayssam Elkady and Tarek Sobh School of Engineering, University of Bridgeport, USA. Mohammem@bridgeport.edu Abstract:

More information

Lecture 8. Divided Differences,Least-Squares Approximations. Ceng375 Numerical Computations at December 9, 2010

Lecture 8. Divided Differences,Least-Squares Approximations. Ceng375 Numerical Computations at December 9, 2010 Lecture 8, Ceng375 Numerical Computations at December 9, 2010 Computer Engineering Department Çankaya University 8.1 Contents 1 2 3 8.2 : These provide a more efficient way to construct an interpolating

More information

SPEED CONTROL IN NUMERIC CONTROLLED SYSTEMS

SPEED CONTROL IN NUMERIC CONTROLLED SYSTEMS Математички Билтен ISSN 0351-336X Vol. 39(LXV) No. 1 UDC: 519.713-74 015 (49-63) Скопје, Македонија SPEED CONTROL IN NUMERIC CONTROLLED SYSTEMS Igor Dimovski 1, Samoil Samak, Dijana Cvetkoska 3, Mirjana

More information

[9] D.E. Whitney, "Resolved Motion Rate Control of Manipulators and Human Prostheses," IEEE Transactions on Man-Machine Systems, 1969.

[9] D.E. Whitney, Resolved Motion Rate Control of Manipulators and Human Prostheses, IEEE Transactions on Man-Machine Systems, 1969. 160 Chapter 5 Jacobians: velocities and static forces [3] I. Shames, Engineering Mechanics, 2nd edition, Prentice-Hall, Englewood Cliffs, NJ, 1967. [4] D. Orin and W. Schrader, "Efficient Jacobian Determination

More information

MOTION TRAJECTORY PLANNING AND SIMULATION OF 6- DOF MANIPULATOR ARM ROBOT

MOTION TRAJECTORY PLANNING AND SIMULATION OF 6- DOF MANIPULATOR ARM ROBOT MOTION TRAJECTORY PLANNING AND SIMULATION OF 6- DOF MANIPULATOR ARM ROBOT Hongjun ZHU ABSTRACT:In order to better study the trajectory of robot motion, a motion trajectory planning and simulation based

More information

Motion Control (wheeled robots)

Motion Control (wheeled robots) Motion Control (wheeled robots) Requirements for Motion Control Kinematic / dynamic model of the robot Model of the interaction between the wheel and the ground Definition of required motion -> speed control,

More information

10. Cartesian Trajectory Planning for Robot Manipulators

10. Cartesian Trajectory Planning for Robot Manipulators V. Kumar 0. Cartesian rajectory Planning for obot Manipulators 0.. Introduction Given a starting end effector position and orientation and a goal position and orientation we want to generate a smooth trajectory

More information

Research on time optimal trajectory planning of 7-DOF manipulator based on genetic algorithm

Research on time optimal trajectory planning of 7-DOF manipulator based on genetic algorithm Acta Technica 61, No. 4A/2016, 189 200 c 2017 Institute of Thermomechanics CAS, v.v.i. Research on time optimal trajectory planning of 7-DOF manipulator based on genetic algorithm Jianrong Bu 1, Junyan

More information

Optimal Trajectory Generation for Nonholonomic Robots in Dynamic Environments

Optimal Trajectory Generation for Nonholonomic Robots in Dynamic Environments 28 IEEE International Conference on Robotics and Automation Pasadena, CA, USA, May 19-23, 28 Optimal Trajectory Generation for Nonholonomic Robots in Dynamic Environments Yi Guo and Tang Tang Abstract

More information

Trajectory planning in Cartesian space

Trajectory planning in Cartesian space Robotics 1 Trajectory planning in Cartesian space Prof. Alessandro De Luca Robotics 1 1 Trajectories in Cartesian space! in general, the trajectory planning methods proposed in the joint space can be applied

More information

which is shown in Fig We can also show that the plain old Puma cannot reach the point we specified

which is shown in Fig We can also show that the plain old Puma cannot reach the point we specified 152 Fig. 7.8. Redundant manipulator P8 >> T = transl(0.5, 1.0, 0.7) * rpy2tr(0, 3*pi/4, 0); The required joint coordinates are >> qi = p8.ikine(t) qi = -0.3032 1.0168 0.1669-0.4908-0.6995-0.1276-1.1758

More information

Structural Algorithms for Diagnostic System Design Using Simulink Models

Structural Algorithms for Diagnostic System Design Using Simulink Models Structural Algorithms for Diagnostic System Design Using Simulink Models Master s thesis performed in Vehicular Systems by Lars Eriksson Reg nr: LiTH-ISY-EX-3601-2004 10th January 2005 Structural Algorithms

More information

PPGEE Robot Dynamics I

PPGEE Robot Dynamics I PPGEE Electrical Engineering Graduate Program UFMG April 2014 1 Introduction to Robotics 2 3 4 5 What is a Robot? According to RIA Robot Institute of America A Robot is a reprogrammable multifunctional

More information

Optimal Segmentation and Understanding of Motion Capture Data

Optimal Segmentation and Understanding of Motion Capture Data Optimal Segmentation and Understanding of Motion Capture Data Xiang Huang, M.A.Sc Candidate Department of Electrical and Computer Engineering McMaster University Supervisor: Dr. Xiaolin Wu 7 Apr, 2005

More information

1498. End-effector vibrations reduction in trajectory tracking for mobile manipulator

1498. End-effector vibrations reduction in trajectory tracking for mobile manipulator 1498. End-effector vibrations reduction in trajectory tracking for mobile manipulator G. Pajak University of Zielona Gora, Faculty of Mechanical Engineering, Zielona Góra, Poland E-mail: g.pajak@iizp.uz.zgora.pl

More information

lecture 10: B-Splines

lecture 10: B-Splines 9 lecture : -Splines -Splines: a basis for splines Throughout our discussion of standard polynomial interpolation, we viewed P n as a linear space of dimension n +, and then expressed the unique interpolating

More information

Visualization and Analysis of Inverse Kinematics Algorithms Using Performance Metric Maps

Visualization and Analysis of Inverse Kinematics Algorithms Using Performance Metric Maps Visualization and Analysis of Inverse Kinematics Algorithms Using Performance Metric Maps Oliver Cardwell, Ramakrishnan Mukundan Department of Computer Science and Software Engineering University of Canterbury

More information

Trajectory Planning for Automatic Machines and Robots

Trajectory Planning for Automatic Machines and Robots Luigi Biagiotti Claudio Melchiorri Trajectory Planning for Automatic Machines and Robots Springer 1 Trajectory Planning 1 1.1 A General Overview on Trajectory Planning 1 1.2 One-dimensional Trajectories

More information

2D Spline Curves. CS 4620 Lecture 13

2D Spline Curves. CS 4620 Lecture 13 2D Spline Curves CS 4620 Lecture 13 2008 Steve Marschner 1 Motivation: smoothness In many applications we need smooth shapes [Boeing] that is, without discontinuities So far we can make things with corners

More information

Fli;' HEWLETT. A Kinematically Stable Hybrid Position/Force Control Scheme

Fli;' HEWLETT. A Kinematically Stable Hybrid Position/Force Control Scheme Fli;' HEWLETT a:~ PACKARD A Kinematically Stable Hybrid Position/Force Control Scheme William D. Fisher, M. Shahid Mujtaba Measurement and Manufacturing Systems Laboratory HPL-91-154 October, 1991 hybrid

More information

CS 450 Numerical Analysis. Chapter 7: Interpolation

CS 450 Numerical Analysis. Chapter 7: Interpolation Lecture slides based on the textbook Scientific Computing: An Introductory Survey by Michael T. Heath, copyright c 2018 by the Society for Industrial and Applied Mathematics. http://www.siam.org/books/cl80

More information

FREE SINGULARITY PATH PLANNING OF HYBRID PARALLEL ROBOT

FREE SINGULARITY PATH PLANNING OF HYBRID PARALLEL ROBOT Proceedings of the 11 th International Conference on Manufacturing Research (ICMR2013), Cranfield University, UK, 19th 20th September 2013, pp 313-318 FREE SINGULARITY PATH PLANNING OF HYBRID PARALLEL

More information

An Efficient Method for Solving the Direct Kinematics of Parallel Manipulators Following a Trajectory

An Efficient Method for Solving the Direct Kinematics of Parallel Manipulators Following a Trajectory An Efficient Method for Solving the Direct Kinematics of Parallel Manipulators Following a Trajectory Roshdy Foaad Abo-Shanab Kafr Elsheikh University/Department of Mechanical Engineering, Kafr Elsheikh,

More information

Chapter 2 Intelligent Behaviour Modelling and Control for Mobile Manipulators

Chapter 2 Intelligent Behaviour Modelling and Control for Mobile Manipulators Chapter Intelligent Behaviour Modelling and Control for Mobile Manipulators Ayssam Elkady, Mohammed Mohammed, Eslam Gebriel, and Tarek Sobh Abstract In the last several years, mobile manipulators have

More information

Interpolation by Spline Functions

Interpolation by Spline Functions Interpolation by Spline Functions Com S 477/577 Sep 0 007 High-degree polynomials tend to have large oscillations which are not the characteristics of the original data. To yield smooth interpolating curves

More information

Jacobians. 6.1 Linearized Kinematics. Y: = k2( e6)

Jacobians. 6.1 Linearized Kinematics. Y: = k2( e6) Jacobians 6.1 Linearized Kinematics In previous chapters we have seen how kinematics relates the joint angles to the position and orientation of the robot's endeffector. This means that, for a serial robot,

More information

COLLISION-FREE TRAJECTORY PLANNING FOR MANIPULATORS USING GENERALIZED PATTERN SEARCH

COLLISION-FREE TRAJECTORY PLANNING FOR MANIPULATORS USING GENERALIZED PATTERN SEARCH ISSN 1726-4529 Int j simul model 5 (26) 4, 145-154 Original scientific paper COLLISION-FREE TRAJECTORY PLANNING FOR MANIPULATORS USING GENERALIZED PATTERN SEARCH Ata, A. A. & Myo, T. R. Mechatronics Engineering

More information

Model identification of linear parameter varying aircraft systems

Model identification of linear parameter varying aircraft systems Technical report from Automatic Control at Linköpings universitet Model identification of linear parameter varying aircraft systems Atsushi Fujimori, Lennart Ljung Division of Automatic Control E-mail:

More information

A DH-parameter based condition for 3R orthogonal manipulators to have 4 distinct inverse kinematic solutions

A DH-parameter based condition for 3R orthogonal manipulators to have 4 distinct inverse kinematic solutions Wenger P., Chablat D. et Baili M., A DH-parameter based condition for R orthogonal manipulators to have 4 distinct inverse kinematic solutions, Journal of Mechanical Design, Volume 17, pp. 150-155, Janvier

More information

On-line mission planning based on Model Predictive Control

On-line mission planning based on Model Predictive Control On-line mission planning based on Model Predictive Control Zoran Sjanic LiTH-ISY-EX-3221-2001 2001-12-05 On-line mission planning based on Model Predictive Control Master thesis Division of Automatic

More information

This week. CENG 732 Computer Animation. Warping an Object. Warping an Object. 2D Grid Deformation. Warping an Object.

This week. CENG 732 Computer Animation. Warping an Object. Warping an Object. 2D Grid Deformation. Warping an Object. CENG 732 Computer Animation Spring 2006-2007 Week 4 Shape Deformation Animating Articulated Structures: Forward Kinematics/Inverse Kinematics This week Shape Deformation FFD: Free Form Deformation Hierarchical

More information

Interpolation and Splines

Interpolation and Splines Interpolation and Splines Anna Gryboś October 23, 27 1 Problem setting Many of physical phenomenona are described by the functions that we don t know exactly. Often we can calculate or measure the values

More information

DETC APPROXIMATE MOTION SYNTHESIS OF SPHERICAL KINEMATIC CHAINS

DETC APPROXIMATE MOTION SYNTHESIS OF SPHERICAL KINEMATIC CHAINS Proceedings of the ASME 2007 International Design Engineering Technical Conferences & Computers and Information in Engineering Conference IDETC/CIE 2007 September 4-7, 2007, Las Vegas, Nevada, USA DETC2007-34372

More information

Kinematics of Closed Chains

Kinematics of Closed Chains Chapter 7 Kinematics of Closed Chains Any kinematic chain that contains one or more loops is called a closed chain. Several examples of closed chains were encountered in Chapter 2, from the planar four-bar

More information

Inverse Kinematics of Robot Manipulators with Multiple Moving Control Points

Inverse Kinematics of Robot Manipulators with Multiple Moving Control Points Inverse Kinematics of Robot Manipulators with Multiple Moving Control Points Agostino De Santis and Bruno Siciliano PRISMA Lab, Dipartimento di Informatica e Sistemistica, Università degli Studi di Napoli

More information

The goal is the definition of points with numbers and primitives with equations or functions. The definition of points with numbers requires a

The goal is the definition of points with numbers and primitives with equations or functions. The definition of points with numbers requires a The goal is the definition of points with numbers and primitives with equations or functions. The definition of points with numbers requires a coordinate system and then the measuring of the point with

More information

An Adaptive Stencil Linear Deviation Method for Wave Equations

An Adaptive Stencil Linear Deviation Method for Wave Equations 211 An Adaptive Stencil Linear Deviation Method for Wave Equations Kelly Hasler Faculty Sponsor: Robert H. Hoar, Department of Mathematics ABSTRACT Wave Equations are partial differential equations (PDEs)

More information

CHAPTER 6 Parametric Spline Curves

CHAPTER 6 Parametric Spline Curves CHAPTER 6 Parametric Spline Curves When we introduced splines in Chapter 1 we focused on spline curves, or more precisely, vector valued spline functions. In Chapters 2 and 4 we then established the basic

More information

CMPUT 412 Motion Control Wheeled robots. Csaba Szepesvári University of Alberta

CMPUT 412 Motion Control Wheeled robots. Csaba Szepesvári University of Alberta CMPUT 412 Motion Control Wheeled robots Csaba Szepesvári University of Alberta 1 Motion Control (wheeled robots) Requirements Kinematic/dynamic model of the robot Model of the interaction between the wheel

More information

Institutionen för systemteknik

Institutionen för systemteknik Institutionen för systemteknik Department of Electrical Engineering Examensarbete Baseband Processing Using the Julia Language Examensarbete utfört i Elektroteknik vid Tekniska högskolan vid Linköpings

More information

Jacobian: Velocities and Static Forces 1/4

Jacobian: Velocities and Static Forces 1/4 Jacobian: Velocities and Static Forces /4 Models of Robot Manipulation - EE 54 - Department of Electrical Engineering - University of Washington Kinematics Relations - Joint & Cartesian Spaces A robot

More information

Kinematics and dynamics analysis of micro-robot for surgical applications

Kinematics and dynamics analysis of micro-robot for surgical applications ISSN 1 746-7233, England, UK World Journal of Modelling and Simulation Vol. 5 (2009) No. 1, pp. 22-29 Kinematics and dynamics analysis of micro-robot for surgical applications Khaled Tawfik 1, Atef A.

More information

Kinematics of the Stewart Platform (Reality Check 1: page 67)

Kinematics of the Stewart Platform (Reality Check 1: page 67) MATH 5: Computer Project # - Due on September 7, Kinematics of the Stewart Platform (Reality Check : page 7) A Stewart platform consists of six variable length struts, or prismatic joints, supporting a

More information

SUBDIVISION ALGORITHMS FOR MOTION DESIGN BASED ON HOMOLOGOUS POINTS

SUBDIVISION ALGORITHMS FOR MOTION DESIGN BASED ON HOMOLOGOUS POINTS SUBDIVISION ALGORITHMS FOR MOTION DESIGN BASED ON HOMOLOGOUS POINTS M. Hofer and H. Pottmann Institute of Geometry Vienna University of Technology, Vienna, Austria hofer@geometrie.tuwien.ac.at, pottmann@geometrie.tuwien.ac.at

More information

Terrain Rendering using Multiple Optimally Adapting Meshes (MOAM)

Terrain Rendering using Multiple Optimally Adapting Meshes (MOAM) Examensarbete LITH-ITN-MT-EX--04/018--SE Terrain Rendering using Multiple Optimally Adapting Meshes (MOAM) Mårten Larsson 2004-02-23 Department of Science and Technology Linköpings Universitet SE-601 74

More information

Flank Millable Surface Design with Conical and Barrel Tools

Flank Millable Surface Design with Conical and Barrel Tools 461 Computer-Aided Design and Applications 2008 CAD Solutions, LLC http://www.cadanda.com Flank Millable Surface Design with Conical and Barrel Tools Chenggang Li 1, Sanjeev Bedi 2 and Stephen Mann 3 1

More information

Motion Planning for a Reversing Full-Scale Truck and Trailer System

Motion Planning for a Reversing Full-Scale Truck and Trailer System Master of Science Thesis in Department of Electrical Engineering, Linköping University, 216 Motion Planning for a Reversing Full-Scale Truck and Trailer System Olov Holmer Master of Science Thesis in Motion

More information

MATH 31A HOMEWORK 9 (DUE 12/6) PARTS (A) AND (B) SECTION 5.4. f(x) = x + 1 x 2 + 9, F (7) = 0

MATH 31A HOMEWORK 9 (DUE 12/6) PARTS (A) AND (B) SECTION 5.4. f(x) = x + 1 x 2 + 9, F (7) = 0 FROM ROGAWSKI S CALCULUS (2ND ED.) SECTION 5.4 18.) Express the antiderivative F (x) of f(x) satisfying the given initial condition as an integral. f(x) = x + 1 x 2 + 9, F (7) = 28.) Find G (1), where

More information

Vocabulary Unit 2-3: Linear Functions & Healthy Lifestyles. Scale model a three dimensional model that is similar to a three dimensional object.

Vocabulary Unit 2-3: Linear Functions & Healthy Lifestyles. Scale model a three dimensional model that is similar to a three dimensional object. Scale a scale is the ratio of any length in a scale drawing to the corresponding actual length. The lengths may be in different units. Scale drawing a drawing that is similar to an actual object or place.

More information

Some algebraic geometry problems arising in the field of mechanism theory. J-P. Merlet INRIA, BP Sophia Antipolis Cedex France

Some algebraic geometry problems arising in the field of mechanism theory. J-P. Merlet INRIA, BP Sophia Antipolis Cedex France Some algebraic geometry problems arising in the field of mechanism theory J-P. Merlet INRIA, BP 93 06902 Sophia Antipolis Cedex France Abstract Mechanism theory has always been a favorite field of study

More information

Reflector profile optimisation using Radiance

Reflector profile optimisation using Radiance Reflector profile optimisation using Radiance 1,4 1,2 1, 8 6 4 2 3. 2.5 2. 1.5 1..5 I csf(1) csf(2). 1 2 3 4 5 6 Giulio ANTONUTTO Krzysztof WANDACHOWICZ page 1 The idea Krzysztof WANDACHOWICZ Giulio ANTONUTTO

More information

Parallel Robots. Mechanics and Control H AMID D. TAG HI RAD. CRC Press. Taylor & Francis Group. Taylor & Francis Croup, Boca Raton London NewYoric

Parallel Robots. Mechanics and Control H AMID D. TAG HI RAD. CRC Press. Taylor & Francis Group. Taylor & Francis Croup, Boca Raton London NewYoric Parallel Robots Mechanics and Control H AMID D TAG HI RAD CRC Press Taylor & Francis Group Boca Raton London NewYoric CRC Press Is an Imprint of the Taylor & Francis Croup, an informs business Contents

More information

Application Note #3412

Application Note #3412 Application Note #3412 Smoothing Velocity Profiling (using IT and VT commands) Background: Moving a motor from one position to another involves accelerating the motor to a certain velocity, traveling at

More information

ME 115(b): Final Exam, Spring

ME 115(b): Final Exam, Spring ME 115(b): Final Exam, Spring 2011-12 Instructions 1. Limit your total time to 5 hours. That is, it is okay to take a break in the middle of the exam if you need to ask me a question, or go to dinner,

More information

Institutionen för systemteknik

Institutionen för systemteknik Institutionen för systemteknik Department of Electrical Engineering Examensarbete Automated Fault Tree Generation from Requirement Structures Examensarbete utfört i Fordonssystem vid Tekniska högskolan

More information

Jane Li. Assistant Professor Mechanical Engineering Department, Robotic Engineering Program Worcester Polytechnic Institute

Jane Li. Assistant Professor Mechanical Engineering Department, Robotic Engineering Program Worcester Polytechnic Institute Jane Li Assistant Professor Mechanical Engineering Department, Robotic Engineering Program Worcester Polytechnic Institute (3 pts) Compare the testing methods for testing path segment and finding first

More information

Skåne University Hospital Lund, Lund, Sweden 2 Deparment of Numerical Analysis, Centre for Mathematical Sciences, Lund University, Lund, Sweden

Skåne University Hospital Lund, Lund, Sweden 2 Deparment of Numerical Analysis, Centre for Mathematical Sciences, Lund University, Lund, Sweden Volume Tracking: A New Method for Visualization of Intracardiac Blood Flow from Three-Dimensional, Time-Resolved, Three-Component Magnetic Resonance Velocity Mapping Appendix: Theory and Numerical Implementation

More information

Triangulation: A new algorithm for Inverse Kinematics

Triangulation: A new algorithm for Inverse Kinematics Triangulation: A new algorithm for Inverse Kinematics R. Müller-Cajar 1, R. Mukundan 1, 1 University of Canterbury, Dept. Computer Science & Software Engineering. Email: rdc32@student.canterbury.ac.nz

More information

Hw 4 Due Feb 22. D(fg) x y z (

Hw 4 Due Feb 22. D(fg) x y z ( Hw 4 Due Feb 22 2.2 Exercise 7,8,10,12,15,18,28,35,36,46 2.3 Exercise 3,11,39,40,47(b) 2.4 Exercise 6,7 Use both the direct method and product rule to calculate where f(x, y, z) = 3x, g(x, y, z) = ( 1

More information

Singularity Handling on Puma in Operational Space Formulation

Singularity Handling on Puma in Operational Space Formulation Singularity Handling on Puma in Operational Space Formulation Denny Oetomo, Marcelo Ang Jr. National University of Singapore Singapore d oetomo@yahoo.com mpeangh@nus.edu.sg Ser Yong Lim Gintic Institute

More information

Inverse and Implicit functions

Inverse and Implicit functions CHAPTER 3 Inverse and Implicit functions. Inverse Functions and Coordinate Changes Let U R d be a domain. Theorem. (Inverse function theorem). If ϕ : U R d is differentiable at a and Dϕ a is invertible,

More information

Inverse Kinematics (part 1) CSE169: Computer Animation Instructor: Steve Rotenberg UCSD, Winter 2018

Inverse Kinematics (part 1) CSE169: Computer Animation Instructor: Steve Rotenberg UCSD, Winter 2018 Inverse Kinematics (part 1) CSE169: Computer Animation Instructor: Steve Rotenberg UCSD, Winter 2018 Welman, 1993 Inverse Kinematics and Geometric Constraints for Articulated Figure Manipulation, Chris

More information

This blog addresses the question: how do we determine the intersection of two circles in the Cartesian plane?

This blog addresses the question: how do we determine the intersection of two circles in the Cartesian plane? Intersecting Circles This blog addresses the question: how do we determine the intersection of two circles in the Cartesian plane? This is a problem that a programmer might have to solve, for example,

More information

Kinematics of Wheeled Robots

Kinematics of Wheeled Robots CSE 390/MEAM 40 Kinematics of Wheeled Robots Professor Vijay Kumar Department of Mechanical Engineering and Applied Mechanics University of Pennsylvania September 16, 006 1 Introduction In this chapter,

More information

Scientific Computing: Interpolation

Scientific Computing: Interpolation Scientific Computing: Interpolation Aleksandar Donev Courant Institute, NYU donev@courant.nyu.edu Course MATH-GA.243 or CSCI-GA.22, Fall 25 October 22nd, 25 A. Donev (Courant Institute) Lecture VIII /22/25

More information

Graphing Techniques. Domain (, ) Range (, ) Squaring Function f(x) = x 2 Domain (, ) Range [, ) f( x) = x 2

Graphing Techniques. Domain (, ) Range (, ) Squaring Function f(x) = x 2 Domain (, ) Range [, ) f( x) = x 2 Graphing Techniques In this chapter, we will take our knowledge of graphs of basic functions and expand our ability to graph polynomial and rational functions using common sense, zeros, y-intercepts, stretching

More information

Torque-Position Transformer for Task Control of Position Controlled Robots

Torque-Position Transformer for Task Control of Position Controlled Robots 28 IEEE International Conference on Robotics and Automation Pasadena, CA, USA, May 19-23, 28 Torque-Position Transformer for Task Control of Position Controlled Robots Oussama Khatib, 1 Peter Thaulad,

More information

Animation. Computer Graphics COMP 770 (236) Spring Instructor: Brandon Lloyd 4/23/07 1

Animation. Computer Graphics COMP 770 (236) Spring Instructor: Brandon Lloyd 4/23/07 1 Animation Computer Graphics COMP 770 (236) Spring 2007 Instructor: Brandon Lloyd 4/23/07 1 Today s Topics Interpolation Forward and inverse kinematics Rigid body simulation Fluids Particle systems Behavioral

More information