arXiv:0705.1284v1 [cs.RO] 9 May 2007 WORKSPACE ANALYSIS OF THE ORTHOGLIDE USING INTERVAL ANALYSIS D. Chablat, Ph. Wenger Institut de Recherche en Communications et Cybern ́ etique de Nantes, 1, rue de la No ̈ e, 44321 Nantes, France Damien.Chablat@irccyn.ec-nantes.fr J. Merlet INRIA Sophia-Antipolis, 2004 Route des Lucioles, 06902 Sophia Antipolis, France Merlet@sophia.inria.fr Abstract This paper addresses the workspace analysis of the orthoglide, a 3-DOF parallel mechanism designed for machining applications. This machine features three fixed parallel linear joints which are mounted orthogonally and a mobile platform which moves in the Cartesian x - y - z space with fixed orientation. The workspace analysis is conducted on the bases of prescribed kinetostatic performances. The interesting features of the or- thoglide are a regular Cartesian workspace shape, uniform performances in all directions and good compactness. Interval analysis based methods for computing the dextrous workspace and the largest cube enclosed in this workspace are presented. Keywords: Optimal design, Parallel Mechanism, Machining, Workspace, Interval Analysis, Transmission factor. 1. Introduction Parallel kinematic machines (PKM) are commonly claimed to offer several advantages over their serial counterparts, like high structural rigidity, high dynamic capacities and high accuracy (Treib and Zirn, 1998; Wenger et al., 1999). Thus, PKM are interesting alternative de- signs for high-speed machining applications. This is why parallel kinematic machine-tools attract the interest of more and more researchers and companies. Since the first prototype presented in 1994 during the IMTS in Chicago by Gidding&Lewis (the Variax), many other prototypes have appeared. However, the existing PKM suffer from two major drawbacks, namely, a complex Cartesian workspace and highly non linear input/output rela- tions. For most PKM, the Jacobian matrix which relates the joint rates to the output velocities is not constant and not isotropic. Consequently, the performances (e.g. maximum speeds, forces accuracy and rigidity) vary considerably for different points in the Cartesian workspace and for different directions at one given point. This is a serious drawback for machining applications (Kim et al., 1997; Treib and Zirn, 1998; Wenger et al., 2001). To be of interest for machining applications, a PKM should preserve good workspace properties, that is, regular shape and accept- able kinetostatic performances throughout. In milling applications, the machining conditions must remain constant along the whole tool path ( Rehsteiner et al., 1999; Rehsteiner et al., 1999). In many research papers, this criterion is not taking into account in the algorithmic methods used for the optimization of the workspace volume (Luh et al., 1996; Merlet, 1999; Ottaviano, (1991)). The orthoglide is a 3-axis PKM with the advantages a classical serial PPP machine tool but not its drawbacks. It is an optimized version of the Delta mechanism defined by Clavel, (1990). Most industrial 3-axis machine-tool have a serial PPP kinematic architecture with orthogonal linear joint axes along the x, y and z directions. Thus, the motion of the tool in any of these directions is linearly related to the motion of one of the three actuated axes. Also, the performances are constant in the most part of the Cartesian workspace, which is a parallelepiped. The main drawback is inherent to the serial arrangement of the links, namely, poor dynamic performances. The orthoglide is a PKM with three fixed linear joints mounted or- thogonally. The mobile platform is connected to the linear joints by three articulated parallelograms and moves in the Cartesian x-y-z space with fixed orientation. Its workspace shape is close to a cube whose sides are parallel to the planes xy , yz and xz respectively. The interval analysis is conducted on the basis of prescribed bounded velocity and force transmission factors. Interval analysis based method is used to compute dextrous workspace as well as the largest cube enclosed in this workspace (Merlet, 2000). 2. Description of the Orthoglide Most existing PKM can be classified into two main families. The PKM of the first family have fixed foot points and variable length struts and are generally called “hexapods”. The second family of PKM has been more recently investigated and have variable foot points and fixed length struts. PKMs of the second family are more interesting because the actuators are fixed and thus the moving masses are lower than in the hexapods and tripods. The orthoglide studied in this article is a 3-axis translational parallel kinematic machine and is belongs to the second family. Figure 1 shows the general kinematic architecture of the orthoglide. The orthoglide has three parallel P RP aR identical chains (where P , R and P a stands for Prismatic, Revolute and Parallelogram joint, respectively). The actu- ated joints are the three orthogonal linear joints. These joints can be actuated by means of linear motors or by conventional rotary motors with ball screws. The output body is connected to the linear joints through a set of three parallelograms of equal lengths L = B i C i , so that it can move only in translation. The first linear joint axis is parallel to the x -axis, the second one is parallel to the y -axis and the third one is parallel to the z -axis. In figure 1, the base points A 1 , A 2 and A 3 are fixed on the i th linear axis such that A 1 A 2 = A 1 A 3 = A 2 A 3 , B i is at the intersection of the first revolute axis i i and the second revolute axis j i of the i th parallelogram, and C i is at the intersection of the last two revolute joints of the i th parallelogram. When each B i C i is aligned with the linear joint axis A i B i , the orthoglide is in an isotropic configuration and the tool center point P is located at the intersection of the three linear joint axes. In this configuration, the base points A 1 , A 2 and A 3 are equally distant from P . The symmetric design and the simplicity of the kinematic chains (all joints have only one degree of freedom, fig. 2) should contribute to lower the manufacturing cost of the orthoglide. The orthoglide is free of singularities and self-collisions. The workspace has a regular, quasi-cubic shape. The input/output equations are simple and the velocity transmission factors are equal to one along the x , y and z direction at the isotropic configuration, like in a serial P P P machine ( Wenger and Chablat, 2001). 3. Kinematic Equations and Singularity Analysis We recall briefly here the kinematics of the Orthoglide (See Wenger and Chablat, 2001 for more details). 3.1 Kinematic Equations Let θ i and β i denote the joint angles of the parallelogram about the axes i i and j i , respectively (fig. 2). Let ρ 1 , ρ 2 , ρ 3 denote the linear joint variables, ρ i = A i B i and L denote the length of the tree legs, B i C i . The position vector p of the tool center point P is defined in a reference frame (O, x , y , z ) centered at the intersection of the three linear joint axes (note that the reference frame has been translated in Fig. 1 for more legibility). Let ̇ ρ be referred to as the vector of actuated joint rates and ̇ p as the velocity vector of point P : ̇ ρ = [ ̇ ρ 1 ̇ ρ 2 ̇ ρ 3 ] T , ̇ p = [ ̇ x ̇ y ̇ z ] T ̇ p can be written in three different ways by traversing the three chains A i B i C i P : ̇ p = n 1 ̇ ρ 1 + ( ̇ θ 1 i 1 + ̇ β 1 j 1 ) × ( c 1 − b 1 ) (1a) ̇ p = n 2 ̇ ρ 1 + ( ̇ θ 2 i 2 + ̇ β 2 j 2 ) × ( c 2 − b 2 ) (1b) ̇ p = n 3 ̇ ρ 3 + ( ̇ θ 3 i 3 + ̇ β 3 j 3 ) × ( c 3 − b 3 ) (1c) where b i and c i are the position vectors of the points B i and C i , respec- tively, and n i is the direction vector of the linear joints, for i = 1 , 2 , 3. B 1 i 1 P x z y j 1 A 1 C 1 A 2 B 2 C 2 A 3 C 3 B 3 Figure 1. Orthoglide kinematic architecture i i j i r i P q i b i B i A i C i L Figure 2. Leg kinematics 3.2 Singular configurations We want to eliminate the two idle joint rates ̇ θ i and ̇ β i from Eqs. (1a– c), which we do upon dot-multiplying Eqs. (1a–c) by c i − b i : ( c 1 − b 1 ) T ̇ p = ( c 1 − b 1 ) T n 1 ̇ ρ 1 (2a) ( c 2 − b 2 ) T ̇ p = ( c 2 − b 2 ) T n 2 ̇ ρ 2 (2b) ( c 3 − b 3 ) T ̇ p = ( c 3 − b 3 ) T n 3 ̇ ρ 3 (2c) Equations (2a–c) can now be cast in vector form, namely A ̇ p = B ̇ ρ where A and B are the parallel and serial Jacobian matrices, respec- tively: A =    ( c 1 − b 1 ) T ( c 2 − b 2 ) T ( c 3 − b 3 ) T    and B =   η 1 0 0 0 η 2 0 0 0 η 3   (3) with η i = ( c i − b i ) T n i for i = 1 , 2 , 3. Parallel singularities (Chablat and Wenger, 1998) occur when the de- terminant of the matrix A vanishes, i.e. when det ( A ) = 0. In such configurations, it is possible to move locally the mobile platform whereas the actuated joints are locked. These singularities are particularly un- desirable because the structure cannot resist any force. Eq. (3a) shows that the parallel singularities occur when: ( c 1 − b 1 ) = α ( c 2 − b 2 ) + λ ( c 3 − b 3 ) that is when the points B 1 , C 1 , B 2 , C 2 , B 3 and C 3 are coplanar. A particular case occurs when the links B i C i are parallel: ( c 1 − b 1 ) // ( c 2 − b 2 ) and ( c 2 − b 2 ) // ( c 3 − b 3 ) and ( c 3 − b 3 ) // ( c 1 − b 1 ) Serial singularities arise when the serial Jacobian matrix B is no longer invertible i.e. when det ( B ) = 0. At a serial singularity a direction exists along which any cartesian velocity cannot be produced. Eq. (3b) shows that det( B ) = 0 when for one leg i , ( b i − a i ) ⊥ ( c i − b i ). When A and B are not singular, we obtain the relations, ̇ p = J ̇ ρ with J = A − 1 B (4) 3.3 Velocity transmission factors For joint rates belonging to a unit ball, namely, || ̇ ρ || ≤ 1, the Cartesian velocities belong to an ellipsoid such that: ̇ p T ( JJ T ) ̇ p ≤ 1 The eigenvectors of matrix JJ T define the direction of its principal axes of this ellipsoid and the square roots ψ 1 , ψ 2 and ψ 3 of the eigenvalues σ 1 , σ 2 and σ 3 of JJ T , i.e. the lengths of the aforementioned principal axes are the velocity transmission factors in the directions. To limit the variations of this factor in the Cartesian workspace, we set ψ min ≤ ψ i ≤ ψ max (5) throughout the workspace. To simplify the problem, we set ψ min = 1 /ψ max where the value of ψ max depends on the performance require- ments. 4. Determination of the dextrous workspace The dextrous workspace W is here defined as the loci of the points for which all the eigenvalues of the matrix JJ T , i.e. the velocity transmis- sion factors, lie within a predefined range [ σ min , σ max ]. These eigenvalues are determined by solving the third degree characteristic polynomial of the matrix which is defined only for the points within the intersection I of the three cylinders defined by x 2 + y 2 ≤ L x 2 + z 2 ≤ L y 2 + z 2 ≤ L (6) To solve numerically the above equations, the length of the legs is nor- malized, i.e. we set L = 1. Our purpose in this section is to determine an approximation of W as a set of 3D Cartesian boxes for any point of which we are sure that the constraints on the eigenvalues are satisfied. The width of all the boxes in the list will be greater than a given threshold and the value of this threshold will define the quality of the approximation. 4.1 Box verification A basic tool of the algorithm is a module M ( B ) that takes as input a box B belonging to I and whose output is: either that for any point in the box the eigenvalues lie in the range [ σ min , σ max ] or that for any point in the box one of the eigenvalues is either lower than σ min or larger than σ max or that the two previous conditions does not hold for all the points of the box i.e. that for some points the eigenvalues lie in the range [ σ min , σ max ] while this is not true for some other points The first step of this module consists in considering an arbitrary point of the box (e.g. its center) and to compute the eigenvalues at this point: either all of them lie in the range [ σ min , σ max ] or at least one of them lie outside this range. In the first case if we are able to check that there is no point in B such that the eigenvalue at this point may be equal to σ min or σ max , then we may guarantee that for any point of B the eigenvalues will be in the range [ σ min , σ max ]. Indeed assume that at a given point of B the lowest eigenvalue is lower than σ min : this implies that somewhere along the line joining this point to the center of the box the lowest eigenvalue will be exactly σ min . To perform this check we substitute in the polynomial λ successively by σ min and σ max to get a polynomial in x, y, z only. We have now to verify if there is at least one value for these three variables that cancel the polynomial, being understood that these values have to define a point belonging to B : this is done by using an interval analysis algorithm from the ALIAS library (Merlet, 2000). Assume now that at the center of the box the largest eigenvalue is greater than σ max . If we are to determine that there is no point of B such that one of the eigenvalue is equal to σ max , then we may guarantee that for any point of B the largest eigenvalue will always be greater than σ max . This check is performed by using the same method than in the previous case. Hence the M module will return: 1: if for all points of B the eigenvalues lie in [ σ min , σ max ] (hence B is in the dextrous workspace) -1: if for all points of B either the largest eigenvalue is always greater than σ max or the lowest eigenvalue is lower than σ min (hence B is outside the dextrous workspace). 0: in the other cases i.e. parts of B may be either outside or inside the dextrous workspace 4.2 Algorithm for the determination of the dextrous workspace The principle of the algorithm is pretty simple: we will maintain a list L of boxes, indexed by i , which is is initialized with the box [-1,1], [-1,1], [-1,1]. A minimal width ǫ for the ranges in a box is defined and the operator W ( B i ) will return the largest width of the ranges in B i . An error index E will be computed as the total volume of the boxes that are not in the approximation but may contain points that are inside the dextrous workspace. We then apply M ( B i ): if M ( B i )=1: we store B i as part of the dextrous workspace and consider the next box in L if M ( B i )=-1: we consider the next box in L if M ( B i )=0: – if W ( B i ) ≥ ǫ : we create 2 new boxes from B i by bisecting the range of B i with the largest width. The two new boxes are put at the end of L – otherwise we add the volume of B i to E The algorithm stops when all the boxes in L have been processed. Note that this basic algorithm has to be modified in order to consider only boxes that belongs to I but this can be done using the same principle. The algorithm returns a description of the dextrous workspace as a list of boxes and the comparison between the volume of the approximation and E allows to determine the quality of the approximation. Note that E is very conservative as part of this volume consists in points that do not belong to I or to the dextrous workspace. 4.3 Implementation and results The previous algorithms has been implemented in Maple with a sys- tem call to a C++ program that implements the M module. For an ǫ of 0.05 we found in about 5 hours that the volume of the dextrous workspace is 1.468 with an error bound of [0,0.48] with σ min = 0 . 25 and σ max = 4, i.e. ψ min = 1 / 2 and ψmax = 2 (Fig. 3). 5. Determination of the largest cube enclosed in the dextrous workspace For usual machine tools, the Cartesian workspace is generally given as a function of the size of a right-angled parallelepiped. Due to the symmetrical architecture of the orthoglide, the Cartesian workspace has a fairly regular shape in which it is possible to include a cube whose sides are parallel to the planes xy , yz and xz respectively (Fig. 4). Figure 3. Dextrous workspace of the Orthoglide mechanism x z y L Workspace Figure 4. Cartesian workspace and isotropic configuration of the Orthoglide mechanism We will now describe a method for determining a cube that is enclosed in this workspace whose edge length is 2 R such that there is no other cube enclosed in the workspace with an edge length of 2( R + α ), where α is an accuracy threshold fixed in advance. The first step is to determine the largest cube enclosed in the workspace with a center located at (0,0,0). This is done by using the M module on the box [ − A − kα, A + kα ] , [ − A − kα, A + kα ] , [ − A − kα, A + kα ] where k is an integer initialized to 1 and A a number initialized to 0. Each time the M module returns 1 (which means that the cube with edge length 2( A + kα ) is enclosed in the dextrous workspace) we set A to A + kα and we double the value of k . When this module returns -1 if k is greater than 1 we reset k to 1 and restart the process, otherwise the process stops and we have determined that the cube with edge length 2 A is enclosed in the workspace while the cube with edge length 2( A + α ) is not: thus A is an initial value for R . We use then the same algorithm than for the determination of the workspace with the following modifications: for each box B i in L we test if at the 8 corners of the cube cen- tered at the center of the box and with edge length 2( R + α ) the eigenvalues satisfies the constraints: – if this not the case let u be the maximal half-width of the ranges of B i and assume that u 1 = R − u > 0. If for at least for one corner of the cube C with center of B i and edge length u 1 the eigenvalues do not satisfy the constraint, then the center of the largest cube cannot be located in B i : indeed any cube with a center in B i and edge length 2 R will include all the corners of C and thus contain at least a point for which the eigenvalues do not satisfy the constraints. – if at the corners the eigenvalues are all valid then we search for the largest cube centered at the center of the box using the same method than for the determination of the largest cube centered at (0,0,0). If we find a cube with a larger edge length than 2 R , then the value of R is updated. the boxes are bisected only if the largest width of their ranges is greater than 2 α : indeed even if the largest cube has a center located in such box, then the maximal edge length will be at most 2( R + α ). Using this algorithm with a value of 0.001 for α we found out that the largest cube has its center located at (0 . 085938 , 0 . 085938 , 0 . 085938) and that its edge length was L W orkspace = 0 . 643950 while we may guarantee that there is no cube with edge length larger than 0 . 643952 enclosed in the workspace 6. Conclusions The dextrous Cartesian workspace and the largest cube enclosed in this workspace is computed using interval analysis based method for the Orthoglide. Unlike most existing PKMs, the dextrous workspace is fairly regular and the performances are homogeneous in it. Thus, the entire workspace is really available for tool paths. The bounds of ve- locity and force transmission factors used in this paper are given as an example because it depends on the performance requirements for ma- chining applications. A 1:3-scale prototype of this mechanism is under construction in our laboratory with these bound contraints. References Treib, T. and Zirn, O. (1998), “Similarity laws of serial and parallel manipulators for machine tools”, Proc. Int. Seminar on Improving Machine Tool Performance, pp. 125–131, Vol. 1. Wenger, P. Gosselin, C. and Maille. B. (1999), “A Comparative Study of Serial and Parallel Mechanism Topologies for Machine Tools”, Proc. PKM’99, Milano, pp. 23–32. Kim J. , Park C., Kim J. and Park F.C., (1997), “Performance Analysis of Parallel Manipulator Architectures for CNC Machining Applications”, Proc. IMECE Symp. On Machine Tools, Dallas. Wenger, P. Gosselin, C. and Chablat, D. (2001), “A Comparative Study of Parallel Kinematic Architectures for Machining Applications”, Proc. Workshop on Com- putational Kinematics’, Seoul, Korea, pp. 249–258. Rehsteiner, F., Neugebauer, R. Spiewak, S. and Wieland, F., (1999), “Putting Parallel Kinematics Machines (PKM) to Productive Work”, Annals of the CIRP, Vol. 48:1, pp. 345–350. Tlusty, J., Ziegert, J, and Ridgeway, S., (1999), “Fundamental Comparison of the Use of Serial and Parallel Kinematics for Machine Tools”, Annals of the CIRP, Vol. 48:1, pp. 351–356. Luh C-M., Adkins F. A., Haug E. J. and Qui C. C., (1996), “Working Capability Analysis of Stewart platforms”, Transactions of ASME, pp. 220–227. Merlet J-P., (1999), “Determination of 6D Workspace of Gough-Type Parallel Manip- ulator and Comparison between Different Geometries”, The Int. Journal of Robotic Research, Vol. 19, No. 9, pp. 902–916. Golub, G. H. and Van Loan, C. F., (1989), Matrix Computations, The John Hopkins University Press, Baltimore. Salisbury J-K. and Craig J-J., (1982), “Articulated Hands: Force Control and Kine- matic Issues”, The Int. J. Robotics Res., Vol. 1, No. 1, pp. 4–17. Angeles J., (1997), Fundamentals of Robotic Mechanical Systems, Springer-Verlag. Wenger, P., and Chablat, D., (2000), “Kinematic Analysis of a new Parallel Machine Tool: the Orthoglide”, in Lenarˇ ciˇ c, J. and Staniˇ si ́ c, M.M. (editors), Advances in Robot Kinematic , Kluwer Academic Publishers, June, pp. 305–314. Chablat D. and Wenger P., (1998), “Working Modes and Aspects in Fully-Parallel Manipulator”, IEEE Int. Conf. On Robotics and Automation, pp. 1964–1969. Merlet J-P., (2000), “ALIAS: an interval analysis based library for solving and ana- lyzing system of equations”, SEA, June. Automation, pp. 1964–1969. Clavel, R., (1990), “Device for the Movement and Positioning of an Element in Space”, US Patent No. 4,976,582, December 11. Ottaviano E., Ceccarelli M., (2001), “Optimal Design of CAPAMAN (Cassino Par- allel Manipulator) with Prescribed Workspace”, 2nd Workshop on Computational Kinematics CK 2001, Seoul. pp.35-44. x z y x z y –0.6 –0.4 –0.2 0 0.2 0.4 0.6 x –0.6 –0.4 –0.2 0 0.2 0.4 0.6 y –0.6 –0.4 –0.2 0 0.2 0.4 0.6 z