Case Study: The Pelican Prototype Robot

Size: px
Start display at page:

Download "Case Study: The Pelican Prototype Robot"

Transcription

1 5 Case Study: The Pelican Prototype Robot The purpose of this chapter is twofold: first, to present in detail the model of the experimental robot arm of the Robotics lab. from the CICESE Research Center, Mexico. Second, to review the topics studied in the previous chapters and to discuss, through this case study, the topics of direct kinematics and inverse kinematics, which are fundamental in determining robot models. For the Pelican, we derive the full dynamic model of the prototype; in particular, we present the numerical values of all the parameters such as mass, inertias, lengths to centers of mass, etc. This is used throughout the rest of the book in numerous examples to illustrate the performance of the controllers that we study. We emphasize that all of these examples contain experimentation results. Thus, the chapter is organized in the following sections: direct kinematics; inverse kinematics; dynamic model; properties of the dynamic model; reference trajectories. For analytical purposes, further on, we refer to Figure 5., which represents the prototype schematically. As is obvious from this figure, the prototype is a planar arm with two links connected through revolute joints, i.e. it possesses DOF. The links are driven by two electrical motors located at the shoulder (base) and at the elbow. This is a direct-drive mechanism, i.e. the axes of the motors are connected directly to the links without gears or belts. The manipulator arm consists of two rigid links of lengths l 1 and l, masses m 1 and m respectively. The robot moves about on the plane x y as is illustrated in Figure 5.. The distances from the rotating axes to the centers of mass are denoted by l c1 and l c for links 1 and, respectively. Finally, I 1 and

2 114 5 Case Study: The Pelican Prototype Robot Figure 5.1. Pelican: experimental robot arm at CICESE, Robotics lab. y g Link 1 l c1 l 1 x I 1 m 1 q 1 m I Link l c q l Figure 5.. Diagram of the -DOF Pelican prototype robot I denote the moments of inertia of the links with respect to the axes that pass through the respective centers of mass and are parallel to the axis x. The degrees of freedom are associated with the angle q 1, which is measured from the vertical position, and q, which is measured relative to the extension of the first link toward the second link, both being positive counterclockwise. The vector of joint positions q is defined as q = [q 1 q ] T.

3 5.1 Direct Kinematics 115 The meaning of the diverse constant parameters involved as well as their numerical values are summarized in Table 5.1. Table 5.1. Physical parameters of Pelican robot arm Description Notation Value Units Length of Link 1 l m Length of Link l 0.6 m Distance to the center of mass (Link 1) l c m Distance to the center of mass (Link ) l c 0.09 m Mass of Link 1 m kg Mass of Link m.0458 kg Inertia rel. to center of mass (Link 1) I kg m Inertia rel. to center of mass (Link ) I kg m Gravity acceleration g 9.81 m/s 5.1 Direct Kinematics The problem of direct kinematics for robot manipulators is formulated as follows. Consider a robot manipulator of n degrees-of-freedom placed on a fixed surface. Define a reference frame also fixed at some point on this surface. This reference frame is commonly referred to as base reference frame. The problem of deriving the direct kinematic model of the robot consists in expressing the position and orientation (when the latter makes sense) of a reference frame fixed to the end of the last link of the robot, referred to the base reference frame in terms of the joint coordinates of the robot. The solution to the so-formulated problem from a mathematical viewpoint, reduces to solving a geometrical problem which always has a closed-form solution. Regarding the Pelican robot, we start by defining the reference frame of base as a Cartesian coordinated system in two dimensions with its origin located exactly on the first joint of the robot, as is illustrated in Figure 5.. The Cartesian coordinates x and y determine the position of the tip of the second link with respect to the base reference frame. Notice that for the present case study of a -DOF system, the orientation of the end-effector of the arm makes no sense. One can clearly appreciate that both Cartesian coordinates, x and

4 116 5 Case Study: The Pelican Prototype Robot y, depend on the joint coordinates q 1 and q. Precisely it is this correlation that defines the direct kinematic model, x = ϕ(q y 1, q ), where ϕ : IR IR. For the case of this robot with DOF, it is immediate to verify that the direct kinematic model is given by x = l 1 sin(q 1 ) + l sin(q 1 + q ) y = l 1 cos(q 1 ) l cos(q 1 + q ). From this model is obtained: the following relation between the velocities ẋ l1 cos(q = 1 ) + l cos(q 1 + q ) l cos(q 1 + q ) q1 ẏ l 1 sin(q 1 ) + l sin(q 1 + q ) l sin(q 1 + q ) q q1 = J(q) q where J(q) = ϕ(q) IR is called the analytical Jacobian matrix or q simply, the Jacobian of the robot. Clearly, the following relationship between accelerations also holds, ẍ d = ÿ dt J(q) q1 q1 + J(q). q q The procedure by which one computes the derivatives of the Jacobian and thereby obtains expressions for the velocities in Cartesian coordinates, is called differential kinematics. This topic is not studied in more detail in this textbook since we do not use it for control. 5. Inverse Kinematics The inverse kinematic model of robot manipulators is of great importance from a practical viewpoint. This model allows us to obtain the joint positions q in terms of the position and orientation of the end-effector of the last link referred to the base reference frame. For the case of the Pelican prototype robot, the inverse kinematic model has the form q1 = ϕ 1 (x, y) q

5 5. Inverse Kinematics 117 where ϕ 1 : Θ IR and Θ IR. The derivation of the inverse kinematic model is in general rather complex and, in contrast to the direct kinematics problem, it may have multiple solutions or no solution at all! The first case is illustrated in Figure 5.3. Notice that for the same position (in Cartesian coordinates x, y) of the arm tip there exist two possible configurations of the links, i.e. two possible values for q. y x q d1 q d Figure 5.3. Two solutions to the inverse kinematics problem So we see that even for this relatively simple robot configuration there exist more than one solution to the inverse kinematics problem. The practical interest of the inverse kinematic model relies on its utility to define desired joint positions q d = [q d1 q d ] T from specified desired positions x d and y d for the robot s end-effector. Indeed, note that physically, it is more intuitive to specify a task for a robot in end-effector coordinates so that interest in the inverse kinematics problem increases with the complexity of the manipulator (number of degrees of freedom). Thus, let us now make [ our ] this discussion more precise by analytically qd1 computing the solutions = ϕ 1 (x d, y d ). The desired joint positions q d q d can be computed using tedious but simple trigonometric manipulations to obtain ( ) ( ) q d1 = tan 1 xd tan 1 l sin(q d ) y d l 1 + l cos(q d ) ( x q d = cos 1 d + yd l 1 l ). l 1 l

6 118 5 Case Study: The Pelican Prototype Robot The desired joint velocities and accelerations may be obtained via the differential kinematics 1 and its time derivative. In doing this one must keep in mind that the expressions obtained are valid only as long as the robot does not fall into a singular configuration, that is, as long as the Jacobian J(q d ) is square and nonsingular. These expressions are qd1 = J 1 ẋd (q d ) q d qd1 q d ẏ d d = J 1 (q d ) dt J(q d) J 1 (q d ) }{{} J 1 (q d ) = d dt [ J 1 (q d ) ] [ ẋd ẏ d ] + J 1 (q d ) where J 1 (q d ) and d dt [J(q d)] denote the inverse of the Jacobian matrix and its time derivative respectively, evaluated at q = q d. These are given by S 1 C 1 l 1 S l 1 S l 1 S 1 l S 1 l 1 l S l 1 C 1 + l C 1 l 1 l S, [ ẍd ÿ d ] and d dt [J(q d)] = l 1S 1 q d1 l S 1 ( q d1 + q d ) l S 1 ( q d1 + q d ), l 1 C 1 q d1 + l C 1 ( q d1 + q d ) l C 1 ( q d1 + q d ) where, for simplicity, we have used the notation S 1 = sin(q d1 ), S = sin(q d ), C 1 = cos(q d1 ), S 1 = sin(q d1 + q d ), C 1 = cos(q d1 + q d ). Notice that the term S appears in the denominator of all terms in J(q) 1 hence, q d = nπ, with n {0, 1,,...} and any q d1 also correspond to singular configurations. Physically, these configurations (for any valid n) represent the second link being completely extended or bent over the first, as is illustrated in Figure 5.4. Typically, singular configurations are those in which the endeffector of the robot is located at the physical boundary of the workspace (that is, the physical space that the end-effector can reach). For instance, the singular configuration corresponding to being stretched out corresponds to the end-effector being placed anywhere on the circumference of radius l 1 + l, which is the boundary of the robot s workspace. As for Figure 5.4 the origin of the coordinates frame constitute another point of this boundary. Having illustrated the inverse kinematics problem through the planar manipulator of Figure 5. we stop our study of inverse kinematics since it is 1 For a definition and a detailed treatment of differential kinematics see the book (Sciavicco, Siciliano 000) cf. Bibliography at the end of Chapter 1.

7 5.3 Dynamic Model 119 y q d x q d1 Figure 5.4. Bent-over singular configuration beyond the scope of this text. However, we stress that what we have seen in the previous paragraphs extends in general. In summary, we can say that if the control is based on the Cartesian coordinates of the end-effector, when designing the desired task for a manipulator s end-effector one must take special care that the configurations for the latter do not yield singular configurations. Concerning the controllers studied in this textbook, the reader should not worry about singular configurations since the Jacobian is not used at all: the reference trajectories are given in joint coordinates and we measure joint coordinates. This is what is called control in joint space. Thus, we leave the topic of kinematics to pass to the stage of modeling that is more relevant for control, from the viewpoint of this textbook, i.e. dynamics. 5.3 Dynamic Model In this section we derive the Lagrangian equations for the CICESE prototype shown in Figure 5.1 and then we present in detail, useful bounds on the matrices of inertia, centrifugal and Coriolis forces, and on the vector of gravitational torques. Certainly, the model that we derive here applies to any planar manipulator following the same convention of coordinates as for our prototype Lagrangian Equations Consider the -DOF robot manipulator shown in Figure 5.. As we have learned from Chapter 3, to derive the Lagrangian dynamics we start by writing

8 10 5 Case Study: The Pelican Prototype Robot the kinetic energy function, K(q, q), defined in (3.15). For this manipulator, it may be decomposed into the sum of the two parts: the product of half the mass times the square of the speed of the center of mass; plus the product of half its moment of inertia (referred to the center of mass) times the square of its angular velocity (referred to the center of mass). That is, we have K(q, q) = K 1 (q, q)+k (q, q) where K 1 (q, q) and K (q, q) are the kinetic energies associated with the masses m 1 and m respectively. Let us now develop in more detail, the corresponding mathematical expressions. To that end, we first observe that the coordinates of the center of mass of link 1, expressed on the plane x y, are x 1 = l c1 sin(q 1 ) y 1 = l c1 cos(q 1 ). The velocity vector v 1 of the center of mass of such a link is then, ẋ1 lc1 cos(q v 1 = = 1 ) q 1. ẏ 1 l c1 sin(q 1 ) q 1 Therefore, the speed squared, v 1 = v T 1v 1, of the center of mass becomes v T 1v 1 = l c1 q 1. Finally, the kinetic energy corresponding to the motion of link 1 can be obtained as K 1 (q, q) = 1 m 1v T 1v I 1 q 1 = 1 m 1l c1 q I 1 q 1. (5.1) On the other hand, the coordinates of the center of mass of link, expressed on the plane x y are x = l 1 sin(q 1 ) + l c sin(q 1 + q ) y = l 1 cos(q 1 ) l c cos(q 1 + q ). Consequently, the velocity vector v of the center of mass of such a link is ẋ v = ẏ l1 cos(q = 1 ) q 1 + l c cos(q 1 + q )[ q 1 + q ]. l 1 sin(q 1 ) q 1 + l c sin(q 1 + q )[ q 1 + q ]

9 5.3 Dynamic Model 11 Therefore, using the trigonometric identities cos(θ) + sin(θ) = 1 and sin(q 1 )sin(q 1 + q ) + cos(q 1 )cos(q 1 + q ) = cos(q ) we conclude that the speed squared, v = v T v, of the center of mass of link satisfies v T v = l1 q 1 + lc [ q 1 + q 1 q + q ] + l1 l c q 1 + q 1 q cos(q ) which implies that K (q, q) = 1 m v T v + 1 I [ q 1 + q ] = m l 1 q 1 + m [ l c q 1 + q 1 q + q ] + m l 1 l c q 1 + q 1 q cos(q ) + 1 I [ q 1 + q ]. Similarly, the potential energy may be decomposed as the sum of the terms U(q) = U 1 (q)+u (q), where U 1 (q) and U (q) are the potential energies associated with the masses m 1 and m respectively. Thus, assuming that the potential energy is zero at y = 0, we obtain U 1 (q) = m 1 l c1 g cos(q 1 ) and U (q) = m l 1 g cos(q 1 ) m l c g cos(q 1 + q ). (5.) From Equations (5.1) (5.) we obtain the Lagrangian as L(q, q) = K(q, q) U(q) = K 1 (q, q) + K (q, q) U 1 (q) U (q) = 1 [m 1lc1 + m l1] q m lc [ q 1 + q 1 q + q ] + m l 1 l c cos(q ) [ q 1 ] + q 1 q + [m 1 l c1 + m l 1 ]g cos(q 1 ) + m gl c cos(q 1 + q ) + 1 I 1 q I [ q 1 + q ]. From this last equation we obtain the following expression: L q 1 = [m 1 l c1 + m l 1] q 1 + m l c q 1 + m l c q + m l 1 l c cos(q ) q 1 + m l 1 l c cos(q ) q + I 1 q 1 + I [ q 1 + q ].

10 1 5 Case Study: The Pelican Prototype Robot d dt L = [ m 1 lc1 + m l1 + m lc + m l 1 l c cos(q ) ] q 1 q 1 + [ m l c + m l 1 l c cos(q ) ] q m l 1 l c sin(q ) q 1 q m l 1 l c sin(q ) q + I 1 q 1 + I [ q 1 + q ]. L = [m 1 l c1 + m l 1 ]g sin(q 1 ) m gl c sin(q 1 + q ). L q = m l c q 1 + m l c q + m l 1 l c cos(q ) q 1 + I [ q 1 + q ]. d dt L = m l q c q 1 + m lc q + m l 1 l c cos(q ) q 1 m l 1 l c sin(q ) q 1 q + I [ q 1 + q ]. L = m l 1 l c sin(q ) [ q 1 q + q ] 1 m gl c sin(q 1 + q ). q The dynamic equations that model the robot arm are obtained by applying Lagrange s Equations (3.4), d L L = τ i i = 1, dt q i q i from which we finally get and τ 1 = [ m 1 l c1 + m l 1 + m l c + m l 1 l c cos(q ) + I 1 + I ] q1 + [ m l c + m l 1 l c cos(q ) + I ] q m l 1 l c sin(q ) q 1 q m l 1 l c sin(q ) q + [m 1 l c1 + m l 1 ]g sin(q 1 ) + m gl c sin(q 1 + q ) (5.3) τ = [ m l c + m l 1 l c cos(q ) + I ] q1 + [m l c + I ] q + m l 1 l c sin(q ) q 1 + m gl c sin(q 1 + q ), (5.4) where τ 1 and τ, are the external torques delivered by the actuators at joints 1 and. Thus, the dynamic equations of the robot (5.3)-(5.4) constitute a set of two nonlinear differential equations of the state variables x = [q T q T ] T, that is, of the form (3.1).

11 5.3 Dynamic Model Model in Compact Form For control purposes, it is more practical to rewrite the Lagrangian dynamic model of the robot, that is, Equations (5.3) and (5.4), in the compact form (3.18), i.e. M11 (q) M 1 (q) C11 (q, q) C q + 1 (q, q) g1 (q) q + = τ, where M 1 (q) M (q) }{{} M(q) C 1 (q, q) C (q, q) }{{} C(q, q) g (q) }{{} g(q) M 11 (q) = m 1 l c1 + m [ l 1 + l c + l 1 l c cos(q ) ] + I 1 + I M 1 (q) = m [ l c + l 1 l c cos(q ) ] + I M 1 (q) = m [ l c + l 1 l c cos(q ) ] + I M (q) = m l c + I C 11 (q, q) = m l 1 l c sin(q ) q C 1 (q, q) = m l 1 l c sin(q ) [ q 1 + q ] C 1 (q, q) = m l 1 l c sin(q ) q 1 C (q, q) = 0 g 1 (q) = [m 1 l c1 + m l 1 ] g sin(q 1 ) + m l c g sin(q 1 + q ) g (q) = m l c g sin(q 1 + q ). We emphasize that the appropriate state variables to describe the dynamic model of the robot are the positions q 1 and q and the velocities q 1 and q. In terms of these state variables, the dynamic model of the robot may be written as d dt q 1 q q 1 q = q 1 q M(q) 1 [τ (t) C(q, q) q g(q)]. Properties of the Dynamic Model We present now the derivation of certain bounds on the inertia matrix, the matrix of centrifugal and Coriolis forces and the vector of gravitational torques. The bounds that we derive are fundamental to properly tune the gains of the controllers studied in the succeeding chapters. We emphasize that, as studied in Chapter 4, some bounds exist for any manipulator with only revolute rigid joints. Here, we show how they can be computed for CICESE s Pelican prototype illustrated in Figure 5..

12 14 5 Case Study: The Pelican Prototype Robot Derivation of λ min {M} We start with the property of positive definiteness of the inertia matrix. For a symmetric matrix M11 (q) M 1 (q) M 1 (q) M (q) to be positive definite for all q IR n, it is necessary and sufficient that M 11 (q) > 0 and its determinant also be positive for all q IR n. M 11 (q)m (q) M 1 (q) In the worst-case scenario M 11 (q) = m 1 l c1 + I 1 + I + m (l 1 l c ) > 0, we only need to compute the determinant of M(q), that is, det[m(q)] = I 1 I + I [l c1m 1 + l 1m ] + l cm I 1 + l c1l cm 1 m + l 1l cm [1 cos (q )]. Notice that only the last term depends on q and is positive or zero. Hence, we conclude that M(q) is positive definite for all q IR n, that is 3 for all q IR n, where λ min {M} > 0. x T M(q)x λ min {M} x (5.5) Inequality (5.5) constitutes an important property for control purposes since for instance, it guarantees that M(q) 1 is positive definite and bounded for all q IR n. Let us continue with the computation of the constants β, k M, k C1, k C and k g from the properties presented in Chapter 4. Derivation of λ Max {M} Consider the inertia matrix M(q). From its components it may be verified that Consider the partitioned matrix A B B T. C If A = A T > 0, C = C T > 0 and C B T A 1 B 0 (resp. C B T A 1 B > 0 ), then this matrix is positive semidefinite (resp. positive definite). See Horn R. A., Johnson C. R., 1985, Matrix analysis, p See also Remark.1 on page 5.

13 5.3 Dynamic Model 15 max i,j,q M ij(q) = m 1 l c1 + m [ l 1 + l c + l 1 l c ] + I1 + I. According to Table 4.1, the constant β may be obtained as a value larger or equal to n times the previous expression, i.e. β n [ m 1 l c1 + m [ l 1 + l c + l 1 l c ] + I1 + I ]. Hence, defining, λ Max {M} = β we see that x T M(q)x λ Max {M} x for all q IR n. Moreover, using the numerical values presented in Table 5.1, we get β = kg m, that is, λ Max {M} = kg m. Derivation of k M Consider the inertia matrix M(q). From its components it may be verified that M 11 (q) M 11 (q) = 0, = m l 1 l c sin(q ) q M 1 (q) = 0, M 1 (q) = 0, M (q) = 0, M 1 (q) q = m l 1 l c sin(q ) M 1 (q) q = m l 1 l c sin(q ) M (q) q = 0. According to Table 4.1, the constant k M may be determined as ( ) k M n max M ij (q) i,j,k,q q k, hence, this constant may be chosen to satisfy k M n m l 1 l c. Using the numerical values presented in Table 5.1 we get k M = kg m. Derivation of k C1 Consider the vector of centrifugal and Coriolis forces C(q, q) q written as C(q, q) q = m l 1 l c sin(q ) ( ) q 1 q + q m l 1 l c sin(q ) q 1

14 16 5 Case Study: The Pelican Prototype Robot C 1 (q) T [{}} ]{ q1 0 m l 1 l c sin(q ) q1 q m l 1 l c sin(q ) m l 1 l c sin(q ) q =. (5.6) T q1 m l 1 l c sin(q ) 0 q1 q 0 0 q }{{} C (q) According to Table 4.1, the constant k C1 may be derived as ( k C1 n max C kij (q) ) i,j,k,q hence, this constant may be chosen so that k C1 n m l 1 l c Consequently, in view of the numerical values from Table 5.1 we find that k C1 = kg m. Derivation of k C Consider again the vector of centrifugal and Coriolis forces C(q, q) q written as in (5.6). From the matrices C 1 (q) and C (q) it may easily be verified that C 111 (q) C 11 (q) C 11 (q) C 1 (q) C 11 (q) C 1 (q) C 1 (q) = 0, C 1 11(q) q = 0 = 0, C 1 1(q) q = m l 1 l c cos(q ) = 0, C 1 1(q) q = m l 1 l c cos(q ) = 0, C 1 (q) q = m l 1 l c cos(q ) = 0, C 11(q) q = m l 1 l c cos(q ) = 0, C 1 (q) q = 0 = 0, C 1(q) q = 0

15 5.3 Dynamic Model 17 C (q) = 0, C (q) q = 0. Furthermore, according to Table 4.1 the constant k C may be taken to satisfy ( ) k C n 3 max C kij (q) i,j,k,l,q q l. Therefore, we may choose k C as k C n 3 m l 1 l c, which, in view of the numerical values from Table 5.1, takes the numerical value k C = kg m : Derivation of k g According to the components of the gravitational torques vector g(q) we have g 1 (q) = (m 1 l c1 + m l 1 ) g cos(q 1 ) + m l c g cos(q 1 + q ) g 1 (q) q = m l c g cos(q 1 + q ) g (q) = m l c g cos(q 1 + q ) g (q) q = m l c g cos(q 1 + q ). Notice that the Jacobian matrix g(q) corresponds in fact, to the Hessian q matrix (i.e. the second partial derivative) of the potential energy function U(q), and is a symmetric matrix even though not necessarily positive definite. The positive constant k g may be derived from the information given in Table 4.1 as k g n max g i (q) i,j,q q j. That is, k g n [m 1 l c1 + m l 1 + m l c ] g and using the numerical values from Table 5.1 may be given the numerical value k g = 3.94 kg m /s.

16 18 5 Case Study: The Pelican Prototype Robot Table 5.. Numeric values of the parameters for the CICESE prototype Parameter Value Units λ Max{M} kg m k M kg m k C kg m k C kg m k g 3.94 kg m /s Summary The numerical values of the constants λ Max {M}, k M, k C1, k C and k g obtained above are summarized in Table Desired Reference Trajectories With the aim of testing in experiments the performance of the controllers presented in this book, on the Pelican robot, we have selected the following reference trajectories in joint space: q d1 = b 1[1 e.0 t 3 ] + c 1 [1 e.0 t3 ] sin(ω 1 t) [rad] (5.7) b [1 e.0 t3 ] + c [1 e.0 t3 ] sin(ω t) q d where b 1 = π/4 [rad], c 1 = π/9 [rad] and ω 1 = 4 [rad/s], are parameters for the desired position reference for the first joint and b = π/3 [rad], c = π/6 [rad] and ω = 3 [rad/s] correspond to parameters that determine the desired position reference for the second joint. Figure 5.5 shows graphs of these reference trajectories against time. Note the following important features in these reference trajectories: the trajectory contains a sinusoidal term to evaluate the performance of the controller following relatively fast periodic motions. This test is significant since such motions excite nonlinearities in the system. It also contains a slowly increasing term to bring the robot to the operating point without driving the actuators into saturation. The module and frequency of the periodic signal must be chosen with care to avoid both torque and speed saturation in the actuators. In other

17 5.4 Desired Reference Trajectories 19.0 [rad] 1.5 q d 1.0 q d t [s] Figure 5.5. Desired reference trajectories words, the reference trajectories must be such that the evolution of the robot dynamics along these trajectories gives admissible velocities and torques for the actuators. Otherwise, the desired reference is physically unfeasible. Using the expressions of the desired position trajectories, (5.7), we may obtain analytically expressions for the desired velocity reference trajectories. These are obtained by direct differentiation, i.e. q d1 = 6b 1 t e.0 t3 + 6c 1 t e.0 t3 sin(ω 1 t) + [c 1 c 1 e.0 t3 ] cos (ω 1 t)ω 1, q d = 6b t e.0 t3 + 6c t e.0 t3 sin(ω t) + [c c e.0 t3 ] cos (ω t)ω, (5.8) in [ rad/s ]. In the same way we may proceed to compute the reference accelerations to obtain q d1 = 1b 1 te.0 t3 36b 1 t 4 e.0 t3 + 1c 1 te.0 t3 sin(ω 1 t) 36c 1 t 4 e.0 t3 sin(ω 1 t) + 1c 1 t e.0 t3 cos (ω 1 t)ω 1 [c 1 c 1 e.0 t3 ]sin(ω 1 t)ω1 [ rad/s ], q d = 1b te.0 t3 36b t 4 e.0 t3 + 1c te.0 t3 sin (ω t) 36c t 4 e.0 t3 sin (ω t) + 1c t e.0 t3 cos (ω t)ω [c c e.0 t3 ] sin (ω t)ω [ rad/s ]. (5.9)

18 130 5 Case Study: The Pelican Prototype Robot q d (t) [rad] t [s] q d (t) [ rad s ].4 Figure 5.6. Norm of the desired positions t [s] Figure 5.7. Norm of the desired velocities vector Figures 5.6, 5.7 and 5.8 show the evolution in time of the norms corresponding to the desired joint positions, velocities and accelerations respectively. From these figures we deduce the following upper-bounds on the norms q d Max 1.9 [rad] q d Max.33 [rad/s] q d Max 9.5 [rad/s ].

19 Problems 131 q d (t) [ rad s ] t [s] Figure 5.8. Norm of the desired accelerations vector Bibliography The schematic diagram of the robot depicted in Figure 5. and elsewhere throughout the book, corresponds to a real experimental prototype robot arm designed and constructed in the CICESE Research Center, Mexico 4. The numerical values that appear in Table 5.1 are taken from: Campa R., Kelly R., Santibáñez V., 004, Windows-based real-time control of direct-drive mechanisms: platform description and experiments, Mechatronics, Vol. 14, No. 9, pp The constants listed in Table 5. may be computed based on data reported in Moreno J., Kelly R., Campa R., 003, Manipulator velocity control using friction compensation, IEE Proceedings - Control Theory and Applications, Vol. 150, No.. Problems 1. Consider the [ matrices M(q) ] and C(q, q) from Section Show that 1 the matrix Ṁ(q) C(q, q) is skew-symmetric.. According to Property 4., the centrifugal and Coriolis forces matrix C(q, q), of the dynamic model of an n-dof robot is not unique. In Section 5.3. we computed the elements of the matrix C(q, q) of the Pelican 4 Centro de Investigación Científica y de Educación Superior de Ensenada.

20 13 5 Case Study: The Pelican Prototype Robot robot presented in this chapter. Prove also that the matrix C(q, q) whose elements are given by C 11 (q, q) = m l 1 l c sin(q ) q C 1 (q, q) = m l 1 l c sin(q ) q C 1 (q, q) = m l 1 l c sin(q ) q 1 C (q, q) = 0 characterizes the centrifugal and Coriolis forces, C(q, q) q. With this definition of C(q, q), is Ṁ(q) [ C(q, q) skew-symmetric? 1 ] Does it hold that q T Ṁ(q) 1 C(q, q) q = 0? Explain.

21

(W: 12:05-1:50, 50-N202)

(W: 12:05-1:50, 50-N202) 2016 School of Information Technology and Electrical Engineering at the University of Queensland Schedule of Events Week Date Lecture (W: 12:05-1:50, 50-N202) 1 27-Jul Introduction 2 Representing Position

More information

Lecture Schedule Week Date Lecture (M: 2:05p-3:50, 50-N202)

Lecture Schedule Week Date Lecture (M: 2:05p-3:50, 50-N202) J = x θ τ = J T F 2018 School of Information Technology and Electrical Engineering at the University of Queensland Lecture Schedule Week Date Lecture (M: 2:05p-3:50, 50-N202) 1 23-Jul Introduction + Representing

More information

Trajectory-tracking control of a planar 3-RRR parallel manipulator

Trajectory-tracking control of a planar 3-RRR parallel manipulator Trajectory-tracking control of a planar 3-RRR parallel manipulator Chaman Nasa and Sandipan Bandyopadhyay Department of Engineering Design Indian Institute of Technology Madras Chennai, India Abstract

More information

q 1 F m d p q 2 Figure 1: An automated crane with the relevant kinematic and dynamic definitions.

q 1 F m d p q 2 Figure 1: An automated crane with the relevant kinematic and dynamic definitions. Robotics II March 7, 018 Exercise 1 An automated crane can be seen as a mechanical system with two degrees of freedom that moves along a horizontal rail subject to the actuation force F, and that transports

More information

Dynamics. describe the relationship between the joint actuator torques and the motion of the structure important role for

Dynamics. describe the relationship between the joint actuator torques and the motion of the structure important role for Dynamics describe the relationship between the joint actuator torques and the motion of the structure important role for simulation of motion (test control strategies) analysis of manipulator structures

More information

We are IntechOpen, the world s leading publisher of Open Access books Built by scientists, for scientists. International authors and editors

We are IntechOpen, the world s leading publisher of Open Access books Built by scientists, for scientists. International authors and editors We are IntechOpen, the world s leading publisher of Open Access books Built by scientists, for scientists 3,350 108,000 1.7 M Open access books available International authors and editors Downloads Our

More information

Multibody simulation

Multibody simulation Multibody simulation Dynamics of a multibody system (Euler-Lagrange formulation) Dimitar Dimitrov Örebro University June 16, 2012 Main points covered Euler-Lagrange formulation manipulator inertia matrix

More information

In this section of notes, we look at the calculation of forces and torques for a manipulator in two settings:

In this section of notes, we look at the calculation of forces and torques for a manipulator in two settings: Introduction Up to this point we have considered only the kinematics of a manipulator. That is, only the specification of motion without regard to the forces and torques required to cause motion In this

More information

Exponential Controller for Robot Manipulators

Exponential Controller for Robot Manipulators Exponential Controller for Robot Manipulators Fernando Reyes Benemérita Universidad Autónoma de Puebla Grupo de Robótica de la Facultad de Ciencias de la Electrónica Apartado Postal 542, Puebla 7200, México

More information

Robot Dynamics II: Trajectories & Motion

Robot Dynamics II: Trajectories & Motion Robot Dynamics II: Trajectories & Motion Are We There Yet? METR 4202: Advanced Control & Robotics Dr Surya Singh Lecture # 5 August 23, 2013 metr4202@itee.uq.edu.au http://itee.uq.edu.au/~metr4202/ 2013

More information

8 Velocity Kinematics

8 Velocity Kinematics 8 Velocity Kinematics Velocity analysis of a robot is divided into forward and inverse velocity kinematics. Having the time rate of joint variables and determination of the Cartesian velocity of end-effector

More information

Differential Kinematics

Differential Kinematics Differential Kinematics Relations between motion (velocity) in joint space and motion (linear/angular velocity) in task space (e.g., Cartesian space) Instantaneous velocity mappings can be obtained through

More information

Artificial Intelligence & Neuro Cognitive Systems Fakultät für Informatik. Robot Dynamics. Dr.-Ing. John Nassour J.

Artificial Intelligence & Neuro Cognitive Systems Fakultät für Informatik. Robot Dynamics. Dr.-Ing. John Nassour J. Artificial Intelligence & Neuro Cognitive Systems Fakultät für Informatik Robot Dynamics Dr.-Ing. John Nassour 25.1.218 J.Nassour 1 Introduction Dynamics concerns the motion of bodies Includes Kinematics

More information

Nonholonomic Constraints Examples

Nonholonomic Constraints Examples Nonholonomic Constraints Examples Basilio Bona DAUIN Politecnico di Torino July 2009 B. Bona (DAUIN) Examples July 2009 1 / 34 Example 1 Given q T = [ x y ] T check that the constraint φ(q) = (2x + siny

More information

Nonlinear PD Controllers with Gravity Compensation for Robot Manipulators

Nonlinear PD Controllers with Gravity Compensation for Robot Manipulators BULGARIAN ACADEMY OF SCIENCES CYBERNETICS AND INFORMATION TECHNOLOGIES Volume 4, No Sofia 04 Print ISSN: 3-970; Online ISSN: 34-408 DOI: 0.478/cait-04-00 Nonlinear PD Controllers with Gravity Compensation

More information

Linköping University Electronic Press

Linköping University Electronic Press Linköping University Electronic Press Report Simulation Model of a 2 Degrees of Freedom Industrial Manipulator Patrik Axelsson Series: LiTH-ISY-R, ISSN 400-3902, No. 3020 ISRN: LiTH-ISY-R-3020 Available

More information

Introduction to Robotics

Introduction to Robotics J. Zhang, L. Einig 277 / 307 MIN Faculty Department of Informatics Lecture 8 Jianwei Zhang, Lasse Einig [zhang, einig]@informatik.uni-hamburg.de University of Hamburg Faculty of Mathematics, Informatics

More information

Advanced Robotic Manipulation

Advanced Robotic Manipulation Advanced Robotic Manipulation Handout CS37A (Spring 017 Solution Set # Problem 1 - Redundant robot control The goal of this problem is to familiarize you with the control of a robot that is redundant with

More information

Control of the Inertia Wheel Pendulum by Bounded Torques

Control of the Inertia Wheel Pendulum by Bounded Torques Proceedings of the 44th IEEE Conference on Decision and Control, and the European Control Conference 5 Seville, Spain, December -5, 5 ThC6.5 Control of the Inertia Wheel Pendulum by Bounded Torques Victor

More information

Dynamics. Basilio Bona. Semester 1, DAUIN Politecnico di Torino. B. Bona (DAUIN) Dynamics Semester 1, / 18

Dynamics. Basilio Bona. Semester 1, DAUIN Politecnico di Torino. B. Bona (DAUIN) Dynamics Semester 1, / 18 Dynamics Basilio Bona DAUIN Politecnico di Torino Semester 1, 2016-17 B. Bona (DAUIN) Dynamics Semester 1, 2016-17 1 / 18 Dynamics Dynamics studies the relations between the 3D space generalized forces

More information

Robotics I. Classroom Test November 21, 2014

Robotics I. Classroom Test November 21, 2014 Robotics I Classroom Test November 21, 2014 Exercise 1 [6 points] In the Unimation Puma 560 robot, the DC motor that drives joint 2 is mounted in the body of link 2 upper arm and is connected to the joint

More information

DYNAMICS OF SERIAL ROBOTIC MANIPULATORS

DYNAMICS OF SERIAL ROBOTIC MANIPULATORS DYNAMICS OF SERIAL ROBOTIC MANIPULATORS NOMENCLATURE AND BASIC DEFINITION We consider here a mechanical system composed of r rigid bodies and denote: M i 6x6 inertia dyads of the ith body. Wi 6 x 6 angular-velocity

More information

Robotics. Dynamics. Marc Toussaint U Stuttgart

Robotics. Dynamics. Marc Toussaint U Stuttgart Robotics Dynamics 1D point mass, damping & oscillation, PID, dynamics of mechanical systems, Euler-Lagrange equation, Newton-Euler recursion, general robot dynamics, joint space control, reference trajectory

More information

Robotics I. Figure 1: Initial placement of a rigid thin rod of length L in an absolute reference frame.

Robotics I. Figure 1: Initial placement of a rigid thin rod of length L in an absolute reference frame. Robotics I September, 7 Exercise Consider the rigid body in Fig., a thin rod of length L. The rod will be rotated by an angle α around the z axis, then by an angle β around the resulting x axis, and finally

More information

Advanced Robotic Manipulation

Advanced Robotic Manipulation Advanced Robotic Manipulation Handout CS37A (Spring 017) Solution Set #3 Problem 1 - Inertial properties In this problem, you will explore the inertial properties of a manipulator at its end-effector.

More information

Robotics I. Test November 29, 2013

Robotics I. Test November 29, 2013 Exercise 1 [6 points] Robotics I Test November 9, 013 A DC motor is used to actuate a single robot link that rotates in the horizontal plane around a joint axis passing through its base. The motor is connected

More information

Inverse differential kinematics Statics and force transformations

Inverse differential kinematics Statics and force transformations Robotics 1 Inverse differential kinematics Statics and force transformations Prof Alessandro De Luca Robotics 1 1 Inversion of differential kinematics! find the joint velocity vector that realizes a desired

More information

Advanced Robotic Manipulation

Advanced Robotic Manipulation Lecture Notes (CS327A) Advanced Robotic Manipulation Oussama Khatib Stanford University Spring 2005 ii c 2005 by Oussama Khatib Contents 1 Spatial Descriptions 1 1.1 Rigid Body Configuration.................

More information

Robotics. Dynamics. University of Stuttgart Winter 2018/19

Robotics. Dynamics. University of Stuttgart Winter 2018/19 Robotics Dynamics 1D point mass, damping & oscillation, PID, dynamics of mechanical systems, Euler-Lagrange equation, Newton-Euler, joint space control, reference trajectory following, optimal operational

More information

Position and orientation of rigid bodies

Position and orientation of rigid bodies Robotics 1 Position and orientation of rigid bodies Prof. Alessandro De Luca Robotics 1 1 Position and orientation right-handed orthogonal Reference Frames RF A A p AB B RF B rigid body position: A p AB

More information

Lecture «Robot Dynamics»: Dynamics and Control

Lecture «Robot Dynamics»: Dynamics and Control Lecture «Robot Dynamics»: Dynamics and Control 151-0851-00 V lecture: CAB G11 Tuesday 10:15 12:00, every week exercise: HG E1.2 Wednesday 8:15 10:00, according to schedule (about every 2nd week) Marco

More information

Robotics I June 11, 2018

Robotics I June 11, 2018 Exercise 1 Robotics I June 11 018 Consider the planar R robot in Fig. 1 having a L-shaped second link. A frame RF e is attached to the gripper mounted on the robot end effector. A B y e C x e Figure 1:

More information

Gain Scheduling Control with Multi-loop PID for 2-DOF Arm Robot Trajectory Control

Gain Scheduling Control with Multi-loop PID for 2-DOF Arm Robot Trajectory Control Gain Scheduling Control with Multi-loop PID for 2-DOF Arm Robot Trajectory Control Khaled M. Helal, 2 Mostafa R.A. Atia, 3 Mohamed I. Abu El-Sebah, 2 Mechanical Engineering Department ARAB ACADEMY FOR

More information

Fuzzy Based Robust Controller Design for Robotic Two-Link Manipulator

Fuzzy Based Robust Controller Design for Robotic Two-Link Manipulator Abstract Fuzzy Based Robust Controller Design for Robotic Two-Link Manipulator N. Selvaganesan 1 Prabhu Jude Rajendran 2 S.Renganathan 3 1 Department of Instrumentation Engineering, Madras Institute of

More information

MEAM 520. More Velocity Kinematics

MEAM 520. More Velocity Kinematics MEAM 520 More Velocity Kinematics Katherine J. Kuchenbecker, Ph.D. General Robotics, Automation, Sensing, and Perception Lab (GRASP) MEAM Department, SEAS, University of Pennsylvania Lecture 12: October

More information

Robotics I. April 1, the motion starts and ends with zero Cartesian velocity and acceleration;

Robotics I. April 1, the motion starts and ends with zero Cartesian velocity and acceleration; Robotics I April, 6 Consider a planar R robot with links of length l = and l =.5. he end-effector should move smoothly from an initial point p in to a final point p fin in the robot workspace so that the

More information

EN Nonlinear Control and Planning in Robotics Lecture 2: System Models January 28, 2015

EN Nonlinear Control and Planning in Robotics Lecture 2: System Models January 28, 2015 EN53.678 Nonlinear Control and Planning in Robotics Lecture 2: System Models January 28, 25 Prof: Marin Kobilarov. Constraints The configuration space of a mechanical sysetm is denoted by Q and is assumed

More information

Robust Control of Cooperative Underactuated Manipulators

Robust Control of Cooperative Underactuated Manipulators Robust Control of Cooperative Underactuated Manipulators Marcel Bergerman * Yangsheng Xu +,** Yun-Hui Liu ** * Automation Institute Informatics Technology Center Campinas SP Brazil + The Robotics Institute

More information

Robotics I Midterm classroom test November 24, 2017

Robotics I Midterm classroom test November 24, 2017 xercise [8 points] Robotics I Midterm classroom test November, 7 Consider the -dof (RPR) planar robot in ig., where the joint coordinates r = ( r r r have been defined in a free, arbitrary way, with reference

More information

Adaptive Robust Tracking Control of Robot Manipulators in the Task-space under Uncertainties

Adaptive Robust Tracking Control of Robot Manipulators in the Task-space under Uncertainties Australian Journal of Basic and Applied Sciences, 3(1): 308-322, 2009 ISSN 1991-8178 Adaptive Robust Tracking Control of Robot Manipulators in the Task-space under Uncertainties M.R.Soltanpour, M.M.Fateh

More information

Dynamics of Open Chains

Dynamics of Open Chains Chapter 9 Dynamics of Open Chains According to Newton s second law of motion, any change in the velocity of a rigid body is caused by external forces and torques In this chapter we study once again the

More information

Ch. 5: Jacobian. 5.1 Introduction

Ch. 5: Jacobian. 5.1 Introduction 5.1 Introduction relationship between the end effector velocity and the joint rates differentiate the kinematic relationships to obtain the velocity relationship Jacobian matrix closely related to the

More information

Lecture «Robot Dynamics»: Dynamics 2

Lecture «Robot Dynamics»: Dynamics 2 Lecture «Robot Dynamics»: Dynamics 2 151-0851-00 V lecture: CAB G11 Tuesday 10:15 12:00, every week exercise: HG E1.2 Wednesday 8:15 10:00, according to schedule (about every 2nd week) office hour: LEE

More information

Exercise 1b: Differential Kinematics of the ABB IRB 120

Exercise 1b: Differential Kinematics of the ABB IRB 120 Exercise 1b: Differential Kinematics of the ABB IRB 120 Marco Hutter, Michael Blösch, Dario Bellicoso, Samuel Bachmann October 5, 2016 Abstract The aim of this exercise is to calculate the differential

More information

DIFFERENTIAL KINEMATICS. Geometric Jacobian. Analytical Jacobian. Kinematic singularities. Kinematic redundancy. Inverse differential kinematics

DIFFERENTIAL KINEMATICS. Geometric Jacobian. Analytical Jacobian. Kinematic singularities. Kinematic redundancy. Inverse differential kinematics DIFFERENTIAL KINEMATICS relationship between joint velocities and end-effector velocities Geometric Jacobian Analytical Jacobian Kinematic singularities Kinematic redundancy Inverse differential kinematics

More information

GAIN SCHEDULING CONTROL WITH MULTI-LOOP PID FOR 2- DOF ARM ROBOT TRAJECTORY CONTROL

GAIN SCHEDULING CONTROL WITH MULTI-LOOP PID FOR 2- DOF ARM ROBOT TRAJECTORY CONTROL GAIN SCHEDULING CONTROL WITH MULTI-LOOP PID FOR 2- DOF ARM ROBOT TRAJECTORY CONTROL 1 KHALED M. HELAL, 2 MOSTAFA R.A. ATIA, 3 MOHAMED I. ABU EL-SEBAH 1, 2 Mechanical Engineering Department ARAB ACADEMY

More information

112 Dynamics. Example 5-3

112 Dynamics. Example 5-3 112 Dynamics Gravity Joint 1 Figure 6-7: Remotely driven two d.o.r. planar manipulator. Note that, since no external force acts on the endpoint, the generalized forces coincide with the joint torques,

More information

, respectively to the inverse and the inverse differential problem. Check the correctness of the obtained results. Exercise 2 y P 2 P 1.

, respectively to the inverse and the inverse differential problem. Check the correctness of the obtained results. Exercise 2 y P 2 P 1. Robotics I July 8 Exercise Define the orientation of a rigid body in the 3D space through three rotations by the angles α β and γ around three fixed axes in the sequence Y X and Z and determine the associated

More information

Lecture Note 12: Dynamics of Open Chains: Lagrangian Formulation

Lecture Note 12: Dynamics of Open Chains: Lagrangian Formulation ECE5463: Introduction to Robotics Lecture Note 12: Dynamics of Open Chains: Lagrangian Formulation Prof. Wei Zhang Department of Electrical and Computer Engineering Ohio State University Columbus, Ohio,

More information

Lecture «Robot Dynamics» : Kinematics 3

Lecture «Robot Dynamics» : Kinematics 3 Lecture «Robot Dynamics» : Kinematics 3 151-0851-00 V lecture: CAB G11 Tuesday 10:15-12:00, every week exercise: HG G1 Wednesday 8:15-10:00, according to schedule (about every 2nd week) office hour: LEE

More information

Robotics: Tutorial 3

Robotics: Tutorial 3 Robotics: Tutorial 3 Mechatronics Engineering Dr. Islam Khalil, MSc. Omar Mahmoud, Eng. Lobna Tarek and Eng. Abdelrahman Ezz German University in Cairo Faculty of Engineering and Material Science October

More information

The Dynamics of Fixed Base and Free-Floating Robotic Manipulator

The Dynamics of Fixed Base and Free-Floating Robotic Manipulator The Dynamics of Fixed Base and Free-Floating Robotic Manipulator Ravindra Biradar 1, M.B.Kiran 1 M.Tech (CIM) Student, Department of Mechanical Engineering, Dayananda Sagar College of Engineering, Bangalore-560078

More information

Control of industrial robots. Centralized control

Control of industrial robots. Centralized control Control of industrial robots Centralized control Prof. Paolo Rocco (paolo.rocco@polimi.it) Politecnico di Milano ipartimento di Elettronica, Informazione e Bioingegneria Introduction Centralized control

More information

ROBOTICS Laboratory Problem 02

ROBOTICS Laboratory Problem 02 ROBOTICS 2015-2016 Laboratory Problem 02 Basilio Bona DAUIN PoliTo Problem formulation The planar system illustrated in Figure 1 consists of a cart C sliding with or without friction along the horizontal

More information

Robotics I. June 6, 2017

Robotics I. June 6, 2017 Robotics I June 6, 217 Exercise 1 Consider the planar PRPR manipulator in Fig. 1. The joint variables defined therein are those used by the manufacturer and do not correspond necessarily to a Denavit-Hartenberg

More information

CONTROL OF THE NONHOLONOMIC INTEGRATOR

CONTROL OF THE NONHOLONOMIC INTEGRATOR June 6, 25 CONTROL OF THE NONHOLONOMIC INTEGRATOR R. N. Banavar (Work done with V. Sankaranarayanan) Systems & Control Engg. Indian Institute of Technology, Bombay Mumbai -INDIA. banavar@iitb.ac.in Outline

More information

Rotational & Rigid-Body Mechanics. Lectures 3+4

Rotational & Rigid-Body Mechanics. Lectures 3+4 Rotational & Rigid-Body Mechanics Lectures 3+4 Rotational Motion So far: point objects moving through a trajectory. Next: moving actual dimensional objects and rotating them. 2 Circular Motion - Definitions

More information

A Benchmark Problem for Robust Control of a Multivariable Nonlinear Flexible Manipulator

A Benchmark Problem for Robust Control of a Multivariable Nonlinear Flexible Manipulator Proceedings of the 17th World Congress The International Federation of Automatic Control Seoul, Korea, July 6-11, 28 A Benchmark Problem for Robust Control of a Multivariable Nonlinear Flexible Manipulator

More information

ENGG 5402 Course Project: Simulation of PUMA 560 Manipulator

ENGG 5402 Course Project: Simulation of PUMA 560 Manipulator ENGG 542 Course Project: Simulation of PUMA 56 Manipulator ZHENG Fan, 115551778 mrzhengfan@gmail.com April 5, 215. Preface This project is to derive programs for simulation of inverse dynamics and control

More information

Lecture 14: Kinesthetic haptic devices: Higher degrees of freedom

Lecture 14: Kinesthetic haptic devices: Higher degrees of freedom ME 327: Design and Control of Haptic Systems Autumn 2018 Lecture 14: Kinesthetic haptic devices: Higher degrees of freedom Allison M. Okamura Stanford University (This lecture was not given, but the notes

More information

Control of constrained spatial three-link flexible manipulators

Control of constrained spatial three-link flexible manipulators Control of constrained spatial three-link flexible manipulators Sinan Kilicaslan, M. Kemal Ozgoren and S. Kemal Ider Gazi University/Mechanical Engineering Department, Ankara, Turkey Middle East Technical

More information

Trigonometric Saturated Controller for Robot Manipulators

Trigonometric Saturated Controller for Robot Manipulators Trigonometric Saturated Controller for Robot Manipulators FERNANDO REYES, JORGE BARAHONA AND EDUARDO ESPINOSA Grupo de Robótica de la Facultad de Ciencias de la Electrónica Benemérita Universidad Autónoma

More information

MSMS Basilio Bona DAUIN PoliTo

MSMS Basilio Bona DAUIN PoliTo MSMS 214-215 Basilio Bona DAUIN PoliTo Problem 2 The planar system illustrated in Figure 1 consists of a bar B and a wheel W moving (no friction, no sliding) along the bar; the bar can rotate around an

More information

Robotics & Automation. Lecture 17. Manipulability Ellipsoid, Singularities of Serial Arm. John T. Wen. October 14, 2008

Robotics & Automation. Lecture 17. Manipulability Ellipsoid, Singularities of Serial Arm. John T. Wen. October 14, 2008 Robotics & Automation Lecture 17 Manipulability Ellipsoid, Singularities of Serial Arm John T. Wen October 14, 2008 Jacobian Singularity rank(j) = dimension of manipulability ellipsoid = # of independent

More information

Research Article On the Dynamics of the Furuta Pendulum

Research Article On the Dynamics of the Furuta Pendulum Control Science and Engineering Volume, Article ID 583, 8 pages doi:.55//583 Research Article On the Dynamics of the Furuta Pendulum Benjamin Seth Cazzolato and Zebb Prime School of Mechanical Engineering,

More information

DYNAMICS OF PARALLEL MANIPULATOR

DYNAMICS OF PARALLEL MANIPULATOR DYNAMICS OF PARALLEL MANIPULATOR PARALLEL MANIPULATORS 6-degree of Freedom Flight Simulator BACKGROUND Platform-type parallel mechanisms 6-DOF MANIPULATORS INTRODUCTION Under alternative robotic mechanical

More information

EE Homework 3 Due Date: 03 / 30 / Spring 2015

EE Homework 3 Due Date: 03 / 30 / Spring 2015 EE 476 - Homework 3 Due Date: 03 / 30 / 2015 Spring 2015 Exercise 1 (10 points). Consider the problem of two pulleys and a mass discussed in class. We solved a version of the problem where the mass was

More information

A SIMPLE ITERATIVE SCHEME FOR LEARNING GRAVITY COMPENSATION IN ROBOT ARMS

A SIMPLE ITERATIVE SCHEME FOR LEARNING GRAVITY COMPENSATION IN ROBOT ARMS A SIMPLE ITERATIVE SCHEME FOR LEARNING GRAVITY COMPENSATION IN ROBOT ARMS A. DE LUCA, S. PANZIERI Dipartimento di Informatica e Sistemistica Università degli Studi di Roma La Sapienza ABSTRACT The set-point

More information

Robotics I Kinematics, Dynamics and Control of Robotic Manipulators. Velocity Kinematics

Robotics I Kinematics, Dynamics and Control of Robotic Manipulators. Velocity Kinematics Robotics I Kinematics, Dynamics and Control of Robotic Manipulators Velocity Kinematics Dr. Christopher Kitts Director Robotic Systems Laboratory Santa Clara University Velocity Kinematics So far, we ve

More information

EML5311 Lyapunov Stability & Robust Control Design

EML5311 Lyapunov Stability & Robust Control Design EML5311 Lyapunov Stability & Robust Control Design 1 Lyapunov Stability criterion In Robust control design of nonlinear uncertain systems, stability theory plays an important role in engineering systems.

More information

13 Path Planning Cubic Path P 2 P 1. θ 2

13 Path Planning Cubic Path P 2 P 1. θ 2 13 Path Planning Path planning includes three tasks: 1 Defining a geometric curve for the end-effector between two points. 2 Defining a rotational motion between two orientations. 3 Defining a time function

More information

available online at CONTROL OF THE DOUBLE INVERTED PENDULUM ON A CART USING THE NATURAL MOTION

available online at   CONTROL OF THE DOUBLE INVERTED PENDULUM ON A CART USING THE NATURAL MOTION Acta Polytechnica 3(6):883 889 3 Czech Technical University in Prague 3 doi:.43/ap.3.3.883 available online at http://ojs.cvut.cz/ojs/index.php/ap CONTROL OF THE DOUBLE INVERTED PENDULUM ON A CART USING

More information

EXPERIMENTAL COMPARISON OF TRAJECTORY TRACKERS FOR A CAR WITH TRAILERS

EXPERIMENTAL COMPARISON OF TRAJECTORY TRACKERS FOR A CAR WITH TRAILERS 1996 IFAC World Congress San Francisco, July 1996 EXPERIMENTAL COMPARISON OF TRAJECTORY TRACKERS FOR A CAR WITH TRAILERS Francesco Bullo Richard M. Murray Control and Dynamical Systems, California Institute

More information

Video 3.1 Vijay Kumar and Ani Hsieh

Video 3.1 Vijay Kumar and Ani Hsieh Video 3.1 Vijay Kumar and Ani Hsieh Robo3x-1.3 1 Dynamics of Robot Arms Vijay Kumar and Ani Hsieh University of Pennsylvania Robo3x-1.3 2 Lagrange s Equation of Motion Lagrangian Kinetic Energy Potential

More information

MEM04: Rotary Inverted Pendulum

MEM04: Rotary Inverted Pendulum MEM4: Rotary Inverted Pendulum Interdisciplinary Automatic Controls Laboratory - ME/ECE/CHE 389 April 8, 7 Contents Overview. Configure ELVIS and DC Motor................................ Goals..............................................3

More information

Open-loop Control for 2DOF Robot Manipulators with Antagonistic Bi-articular Muscles

Open-loop Control for 2DOF Robot Manipulators with Antagonistic Bi-articular Muscles Open-loop Control for DOF Robot Manipulators with Antagonistic Bi-articular Muscles Keisuke Sano, Hiroyuki Kawai, Toshiyuki Murao and Masayuki Fujita Abstract This paper investigates open-loop control,

More information

INSTRUCTIONS TO CANDIDATES:

INSTRUCTIONS TO CANDIDATES: NATIONAL NIVERSITY OF SINGAPORE FINAL EXAMINATION FOR THE DEGREE OF B.ENG ME 444 - DYNAMICS AND CONTROL OF ROBOTIC SYSTEMS October/November 994 - Time Allowed: 3 Hours INSTRCTIONS TO CANDIDATES:. This

More information

In most robotic applications the goal is to find a multi-body dynamics description formulated

In most robotic applications the goal is to find a multi-body dynamics description formulated Chapter 3 Dynamics Mathematical models of a robot s dynamics provide a description of why things move when forces are generated in and applied on the system. They play an important role for both simulation

More information

PLANAR KINETICS OF A RIGID BODY: WORK AND ENERGY Today s Objectives: Students will be able to: 1. Define the various ways a force and couple do work.

PLANAR KINETICS OF A RIGID BODY: WORK AND ENERGY Today s Objectives: Students will be able to: 1. Define the various ways a force and couple do work. PLANAR KINETICS OF A RIGID BODY: WORK AND ENERGY Today s Objectives: Students will be able to: 1. Define the various ways a force and couple do work. In-Class Activities: 2. Apply the principle of work

More information

Emulation of an Animal Limb with Two Degrees of Freedom using HIL

Emulation of an Animal Limb with Two Degrees of Freedom using HIL Emulation of an Animal Limb with Two Degrees of Freedom using HIL Iván Bautista Gutiérrez, Fabián González Téllez, Dario Amaya H. Abstract The Bio-inspired robotic systems have been a focus of great interest

More information

DYNAMIC MODEL FOR AN ARTICULATED MANIPULATOR. Luis Arturo Soriano, Jose de Jesus Rubio, Salvador Rodriguez and Cesar Torres

DYNAMIC MODEL FOR AN ARTICULATED MANIPULATOR. Luis Arturo Soriano, Jose de Jesus Rubio, Salvador Rodriguez and Cesar Torres ICIC Express Letters Part B: Applications ICIC International c 011 ISSN 185-766 Volume, Number, April 011 pp 415 40 DYNAMIC MODEL FOR AN ARTICULATED MANIPULATOR Luis Arturo Soriano, Jose de Jesus Rubio,

More information

Newton-Euler Dynamics of Robots

Newton-Euler Dynamics of Robots 4 NewtonEuler Dynamics of Robots Mark L. Nagurka Marquette University BenGurion University of the Negev 4.1 Introduction Scope Background 4.2 Theoretical Foundations NewtonEuler Equations Force and Torque

More information

Kinematics and Force Analysis of a Five-Link Mechanism by the Four Spaces Jacoby Matrix

Kinematics and Force Analysis of a Five-Link Mechanism by the Four Spaces Jacoby Matrix БЪЛГАРСКА АКАДЕМИЯ НА НАУКИТЕ. ULGARIAN ACADEMY OF SCIENCES ПРОБЛЕМИ НА ТЕХНИЧЕСКАТА КИБЕРНЕТИКА И РОБОТИКАТА PROLEMS OF ENGINEERING CYERNETICS AND ROOTICS София. 00. Sofia Kinematics and Force Analysis

More information

The Jacobian. Jesse van den Kieboom

The Jacobian. Jesse van den Kieboom The Jacobian Jesse van den Kieboom jesse.vandenkieboom@epfl.ch 1 Introduction 1 1 Introduction The Jacobian is an important concept in robotics. Although the general concept of the Jacobian in robotics

More information

Robot Manipulator Control. Hesheng Wang Dept. of Automation

Robot Manipulator Control. Hesheng Wang Dept. of Automation Robot Manipulator Control Hesheng Wang Dept. of Automation Introduction Industrial robots work based on the teaching/playback scheme Operators teach the task procedure to a robot he robot plays back eecute

More information

Virtual Passive Controller for Robot Systems Using Joint Torque Sensors

Virtual Passive Controller for Robot Systems Using Joint Torque Sensors NASA Technical Memorandum 110316 Virtual Passive Controller for Robot Systems Using Joint Torque Sensors Hal A. Aldridge and Jer-Nan Juang Langley Research Center, Hampton, Virginia January 1997 National

More information

Dynamics modeling of an electro-hydraulically actuated system

Dynamics modeling of an electro-hydraulically actuated system Dynamics modeling of an electro-hydraulically actuated system Pedro Miranda La Hera Dept. of Applied Physics and Electronics Umeå University xavier.lahera@tfe.umu.se Abstract This report presents a discussion

More information

Flexible Space Robotic Manipulator with Passively Switching Free Joint to Drive Joint

Flexible Space Robotic Manipulator with Passively Switching Free Joint to Drive Joint IEEE International Conference on Robotics and Automation Anchorage Convention District May 3-8,, Anchorage, Alaska, USA Flexible Space Robotic Manipulator with Passively Switching Free Joint to Drive Joint

More information

NONLINEAR MECHANICAL SYSTEMS (MECHANISMS)

NONLINEAR MECHANICAL SYSTEMS (MECHANISMS) NONLINEAR MECHANICAL SYSTEMS (MECHANISMS) The analogy between dynamic behavior in different energy domains can be useful. Closer inspection reveals that the analogy is not complete. One key distinction

More information

Video 1.1 Vijay Kumar and Ani Hsieh

Video 1.1 Vijay Kumar and Ani Hsieh Video 1.1 Vijay Kumar and Ani Hsieh 1 Robotics: Dynamics and Control Vijay Kumar and Ani Hsieh University of Pennsylvania 2 Why? Robots live in a physical world The physical world is governed by the laws

More information

Manipulator Dynamics 2. Instructor: Jacob Rosen Advanced Robotic - MAE 263D - Department of Mechanical & Aerospace Engineering - UCLA

Manipulator Dynamics 2. Instructor: Jacob Rosen Advanced Robotic - MAE 263D - Department of Mechanical & Aerospace Engineering - UCLA Manipulator Dynamics 2 Forward Dynamics Problem Given: Joint torques and links geometry, mass, inertia, friction Compute: Angular acceleration of the links (solve differential equations) Solution Dynamic

More information

Chapter 2 Coordinate Systems and Transformations

Chapter 2 Coordinate Systems and Transformations Chapter 2 Coordinate Systems and Transformations 2.1 Coordinate Systems This chapter describes the coordinate systems used in depicting the position and orientation (pose) of the aerial robot and its manipulator

More information

Balancing of an Inverted Pendulum with a SCARA Robot

Balancing of an Inverted Pendulum with a SCARA Robot Balancing of an Inverted Pendulum with a SCARA Robot Bernhard Sprenger, Ladislav Kucera, and Safer Mourad Swiss Federal Institute of Technology Zurich (ETHZ Institute of Robotics 89 Zurich, Switzerland

More information

Example: RR Robot. Illustrate the column vector of the Jacobian in the space at the end-effector point.

Example: RR Robot. Illustrate the column vector of the Jacobian in the space at the end-effector point. Forward kinematics: X e = c 1 + c 12 Y e = s 1 + s 12 = s 1 s 12 c 1 + c 12, = s 12 c 12 Illustrate the column vector of the Jacobian in the space at the end-effector point. points in the direction perpendicular

More information

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

Video 8.1 Vijay Kumar. Property of University of Pennsylvania, Vijay Kumar Video 8.1 Vijay Kumar 1 Definitions State State equations Equilibrium 2 Stability Stable Unstable Neutrally (Critically) Stable 3 Stability Translate the origin to x e x(t) =0 is stable (Lyapunov stable)

More information

ROBOTICS: ADVANCED CONCEPTS & ANALYSIS

ROBOTICS: ADVANCED CONCEPTS & ANALYSIS ROBOTICS: ADVANCED CONCEPTS & ANALYSIS MODULE 5 VELOCITY AND STATIC ANALYSIS OF MANIPULATORS Ashitava Ghosal 1 1 Department of Mechanical Engineering & Centre for Product Design and Manufacture Indian

More information

Passivity-based Control for 2DOF Robot Manipulators with Antagonistic Bi-articular Muscles

Passivity-based Control for 2DOF Robot Manipulators with Antagonistic Bi-articular Muscles Passivity-based Control for 2DOF Robot Manipulators with Antagonistic Bi-articular Muscles Hiroyuki Kawai, Toshiyuki Murao, Ryuichi Sato and Masayuki Fujita Abstract This paper investigates a passivity-based

More information

Lagrangian Dynamics: Generalized Coordinates and Forces

Lagrangian Dynamics: Generalized Coordinates and Forces Lecture Outline 1 2.003J/1.053J Dynamics and Control I, Spring 2007 Professor Sanjay Sarma 4/2/2007 Lecture 13 Lagrangian Dynamics: Generalized Coordinates and Forces Lecture Outline Solve one problem

More information

CONTROL OF ROBOT CAMERA SYSTEM WITH ACTUATOR S DYNAMICS TO TRACK MOVING OBJECT

CONTROL OF ROBOT CAMERA SYSTEM WITH ACTUATOR S DYNAMICS TO TRACK MOVING OBJECT Journal of Computer Science and Cybernetics, V.31, N.3 (2015), 255 265 DOI: 10.15625/1813-9663/31/3/6127 CONTROL OF ROBOT CAMERA SYSTEM WITH ACTUATOR S DYNAMICS TO TRACK MOVING OBJECT NGUYEN TIEN KIEM

More information

Kinematics. Chapter Multi-Body Systems

Kinematics. Chapter Multi-Body Systems Chapter 2 Kinematics This chapter first introduces multi-body systems in conceptual terms. It then describes the concept of a Euclidean frame in the material world, following the concept of a Euclidean

More information