ENGG 5402 Course Project: Simulation of PUMA 560 Manipulator

Size: px
Start display at page:

Download "ENGG 5402 Course Project: Simulation of PUMA 560 Manipulator"

Transcription

1 ENGG 542 Course Project: Simulation of PUMA 56 Manipulator ZHENG Fan, April 5, 215. Preface This project is to derive programs for simulation of inverse dynamics and control based on the model of PUMA 56 manipulator, with the last 3 joints neglected. PUMA 56 is widely used in academic and industrial application, and has been modeled with several D-H schemes with slightly different measured parameters [1]. Here we adopt the scheme and parameters of B. Armstrong [2], with the configuration and parameters shown below. Figure 1 D-H model

2 Table 1 D-H parameters [mm] Table 2 Link mass [kg] Table 3 Link center of gravity [mm] Table 4 Moment of inertia about COG [kg m 2 ] 1. Inverse Dynamics with Newton-Euler Formulation In this part we make a program to calculate its inverse dynamics using the Newton-Euler formulation and plot the input torques at joints when the first three joints move in trajectories q i = h i sin ω i t. Here we select h 1 = h 2 = h 3 = 1, ω 1 = ω 2 = ω 3 = 1 rad/s. Derive kinematic equations (all expressed in the base frame {x y z}): Write s i = sin q i, c i = cos q i. Rotation matrix: q 1 = q 2 = q 3 = sin t = q q 1 = q 2 = q 3 = cos t = q q 1 = q 2 = q 3 = sin t = q

3 c 1 s 1 c 1 c 2 c 1 s 2 s 1 c 1 c 2+3 c 1 s 2+3 s 1 1R = [ s c 1 ], 2 R = [ s 1 c 2 s 1 s 2 c 1 ], 3 R = [ s 1 c 2+3 s 1 s 2+3 c 1 ] 1 s 2 c 2 s 2+3 c 2+3 Corresponding z axis: s 1 z 1 = [ ], z 2 = z 3 = [ c 1 ] 1 Relative position of frame origin and center of mass: s 2 = Angular velocity and differentiation: Velocity of frame origin: Acceleration of frame origin: Acceleration of center of mass: 2 [ s 1 s 1 =.243 [ c 1 ].432 R ], r 2 = R.93 r 3 = R 3 [ 2 [.7].14 ω 1 = [ ], ω 1 = [ ] q q.68.6 ].16 s 1 s 1 c 1 ω 2 = ω 1 + z 2 q = q [ c 11 ], ω 2 = q [ c 11 ] + q 2 [ s 1 ] 2s 1 2s 1 2c 1 ω 3 = ω 2 + z 3 q = q [ 2c 1 ], ω 3 = q [ 2c 1 ] + q 2 [ 2s 1 ] 1 1 v 1 = v 2 = v 1 + ω 1 s 1 v 3 = v 2 + ω 2 s 2 a 1 = a 2 = a 1 + ω 1 s 1 + ω 1 (ω 1 s 1 ) a 3 = a 2 + ω 2 s 2 + ω 2 (ω 2 s 2 ) a c2 = a 2 + ω 2 r 2 + ω 2 (ω 2 r 2 ) a c3 = a 3 + ω 3 r 3 + ω 3 (ω 3 r 3 )

4 Then derive the backward dynamic equations: Inertia tensor matrix: I xx2 I xx3 I 1 = [ ], I 2 = 2 R [ I yy2 ] 2R T, I 3 = 3 R [ I yy3 I zz1 I zz2 Force and torque at joint: f 3 = m 3 a c3 + [ ] m 3 g n 3 = I 3 ω 3 + ω 3 I 3 ω 3 + r 3 f 3 τ 3 = z 3 T n 3 f 2 = m 2 a c2 + f 3 + [ ] m 2 g n 2 = I 2 ω 2 + ω 2 I 2 ω 2 + n 3 + r 2 f 2 + (s 2 r 2 ) f 3 τ 2 = z 2 T n 2 n 1 = I 1 ω 1 + n 2 + s 1 f 2 τ 1 = z 1 T n 1 3 I zz3 ] R T Finally τ 1, τ 2, τ 3 are the input torques at joints. Write program in MATLAB (see Appix-1) and plot them as below: Figure 2 Inverse dynamic simulation result

5 2. Controller simulation In this part we make programs to simulate the performance of the robot under the control of the PD controller, the PID controller, and the PD plus gravity compensator controller, respectively. First we derive the Lagrange formulation of robot dynamics. Take {x y z} as base frame and plane x-y as zero potential energy plane. Generalized coordinates q = [q 1 q 2 q 3 ] T. Calculating velocities: ω 1 = [ ], ω 1 = [ ] q 1 q 1 q 2s 1 s 1 c 1 ω 2 = ω 1 + z 2 q 2 = [ q 2c 1 ], ω 2 = q [ c 11 ] + q 2 [ s 1 ] q 1 (q 2 + q 3)s 1 2s 1 2c 1 ω 3 = ω 2 + z 3 q = [ (q 2 + q 3)c 1 ], ω 3 = q [ 2c 1 ] + q 2 [ 2s 1 ] q c 1.68s 1 c 2 +.6s 1 s 2.68c 1 s 2.6c 1 c 2 v c2 = v 2 + ω 2 r 2 = q 1 [.984s c 1 c 2.6c 1 s 2 ] + q 2 [.68s 1 s 2.6s 1 c 2 ].68c 2 +.6s 2 Kinetic energy:.921c 1.432s 1 c 2.7s 1 s 2+3 v c3 = v 3 + ω 3 r 3 = q 1 [.921s c 1 c 2 +.7c 1 s 2+3 ].432c 1 s 2 +.7c 1 c 2+3.7c 1 c 2+3 +q 2 [.432s 1 s 2 +.7s 1 c 2+3 ] + q 3 [.7s 1 c 2+3 ].432c 2.7s 2+3.7s 2+3 K = 1 2 (I zz1ω I zz2 ω I zz3 ω m 2 v 2 c2 + m 3 v 2 c3 ) ( c 2 2 )q q q ( s 2 )q 1q 2.3c 2+3 q 1q 3.29q 3q 2 Potential energy: U =.68m 2 gc 2 + m 3 g[.432c 2 +.7c(q 2 + q 3 )] = 31.9c c 3 c 2 3.3s 2 s 3 Lagrangian L = K U. L q = [ 91.9s s 2 c c 2 s 3.9c 2 s 2 q c 2 q 1q 2 +.3s 2+3 q 1q 3 ] 3.3s 3 c s 2 c 3 +.3s 2+3 q 1q 3

6 L (22 +.9c 2 2 )q 1 + ( s 2 )q 2.3c 2+3 q 3 = [ 1.66q 2 + ( s q 2 )q 1.29q 3 ].11q 3.3c 2+3 q 1.29q 2 d L dt q (22 +.9c 2 2 )q 1 + ( s 2 )q 2.3c 2+3 q 3 1.8c 2 s 2 q 1q c 2 q s 2+3 q 2q 3 +.3s 2+3 q 3 2 = [ 1.66q 2 + ( s 2 )q 1.29q c 2 q 1q 2.11q 3.3c 2+3 q 1.29q 2 +.3s 2+3 q 1q 2 +.3s 2+3 q 1q 3 ] Dynamic equation of the manipulator: τ 1 d L L dt q q = [ τ 2 ] τ 3 Based on this dynamic equation, we develop several controller to simulate the robot s performance. Here we consider only position control problem, and select the desired position as q d = [ π 2 π 2 π 2 ] T 1) PD controller: PD controller input is τ = A(q q d ) Bq. Choose proper matrix A and B, construct state space expression and use MATLAB program with ode method (see Appix-2) to simulate the performance. The result is shown below. Figure 3 PD control simulation result

7 It can be seen from the figure that all the 3 joints is stable. However, only joint 1 converge to the desired position, while there exit offset error between desired and actual position in both joint 2 and 3. The offset error is caused by the existence of gravity. We can kill this error by PID control or PD feedback plus gravity compensation. 2) PID controller PID controller input is τ = A(q q d ) Bq C (q q d )dt. Choose proper matrix A, C and B, construct state space expression and use MATLAB program with ode method (see Appix-3) to simulate the performance. The result is shown below. t Figure 4 PID control simulation result As the figure shows, all 3 joints converge to desired values and no offset error exists. 3) PD plus gravity compensator controller PD plus gravity compensator controller input is τ = A(q q d ) Bq + G(q). Choose proper matrix A and B, construct state space expression and use MATLAB program with ode method (see Appix-4) to simulate the performance. The result is shown below.

8 Figure 5 PD control plus gravity compensation simulation result The 3 joints also converge to desired values with no offset error, and with satisfactory transition process. 3. Computed torque control In this part we make a program to simulate the performance of the robot under the control of the computed torque control method. We select desired trajectory as q d = The closed loop system is then π 2 π 2 π + sin t + sin t. The control input is [ + sin t 2 ] τ = C(q, q ) + G(q) + H(q)(q d A(q q d) B(q q d )) q = q d A(q q d) B(q q d ) Choose proper matrix A and B, construct state space expression and use MATLAB program with ode method (see Appix-5) to simulate the performance. The result is shown below.

9 Figure 6 Computed torque control simulation result: joint position Figure 7 Computed torque control simulation result: joint velocity

10 Preferences [1] Corke P I, Armstrong-Helouvry B. A search for consensus among model parameters reported for the PUMA 56 robot[c]//robotics and Automation, Proceedings., 1994 IEEE International Conference on. IEEE, 1994: [2] Armstrong B, Khatib O, Burdick J. The explicit dynamic model and inertial parameters of the PUMA 56 arm[c]//robotics and Automation. Proceedings IEEE International Conference on. IEEE, 1986, 3:

11 Appix All MATLAB code and this report are available in 1. Inverse dynamics simulation code. function main_puma1 tau1 = zeros(1,21); tau2 = zeros(1,21); tau3 = zeros(1,21); for i = :1:2; t = i*.1; q = sin(t); qdot = cos(t); qddot = -sin(t); cq = cos(q); sq = sin(q); c2q = cos(q+q); s2q = sin(q+q); R1 = [cq,-sq,;sq,cq,;,,1]; R2 = [cq*cq,-cq*sq,-sq;sq*cq,-sq*sq,cq;-sq,-cq,]; R3 = [cq*c2q,-cq*s2q,-sq;sq*c2q,-sq*s2q,cq;-s2q,-c2q,]; z1 = [;;1]; z2 = [-sq;cq;]; z3 = z2; s1 =.243*z2; s2 = R2*[.432;;-.93]; r2 = R2*[.68;.6;-.16]; r3 = R3*[;-.7;.14]; w1 = [;;qdot]; w1dot = [;;qddot]; w2 = qdot*(z1+z2); w2dot = qddot*(z1+z2)+qdot*qdot*[-cq;-sq;]; w3 = qdot*(z1+2*z2); w3dot = qddot*(z1+2*z2)+qdot*qdot*[-2*cq;-2*sq;]; v2 = cross(w1,s1); v3 = v2+cross(w2,s2); a2 = cross(w1dot,s1)+cross(w1,cross(w1,s1)); a3 = a2+cross(w2dot,s2)+cross(w2,cross(w2,s2)); ac2 = a2+cross(w2dot,r2)+cross(w2,cross(w2,r2)); ac3 = a3+cross(w3dot,r3)+cross(w3,cross(w3,r3)); m2 = 17.4; m3 = 4.8; I1 =.35; I2 = R2*diag([.13,.542,.539])*R2'; I3 = R3*diag([.66,.125,.86])*R3'; g = 9.8;

12 f3 = m3*ac3+[;;m3*g]; n3 = I3*w3dot+cross(w3,I3*w3)+cross(r3,f3); t3 = z3'*n3; f2 = m2*ac2+f3+[;;m2*g]; n2 = I2*w2dot+cross(w2,I2*w2)+cross(r2,f2)+n3+cross((s2-r2),f3); t2 = z2'*n2; n1 = I1*w1+n2+cross(s1,f2); t1 = z1'*n1; tau1(i+1) = t1; tau2(i+1) = t2; tau3(i+1) = t3; t = :.1:2; plot(t,tau1,'-',t,tau2,'--',t,tau3,'-.'); xlabel('t/s'),ylabel('\tau /Nm'); leg('\tau 1','\tau 2','\tau 3'); 2. PD control simulation code function main_puma_pd [t,x] = ode45(@puma_pd,:.1:2,[ ]); plot(t,x(:,1),'-',t,x(:,2),'--',t,x(:,3),'-.','linewidth',2); leg('q1','q2','q3'); hold on plot(t,pi*ones(1,length(t))/2,'--'); xlabel('t/s'),ylabel('q/rad'); hold off function xdot = puma_pd(~,q) xdot = zeros(6,1); qd = [pi/2; pi/2; pi/2]; A = [5 ; 18 ; 5]; B = [35 ; 5 ; 2]; tau = -A*([q(1);q(2);q(3)]-[qd(1);qd(2);qd(3)])-B*[q(4);q(5);q(6)]; xdot(1) = q(4); xdot(2) = q(5); xdot(3) = q(6); H = [22+.9*cos(q(2))*cos(q(2)), *sin(q(2)), -.3*cos(q(2)+q(3)); *sin(q(2)), 1.66, -.29; -.3*cos(q(2)+q(3)), -.29,.11]; xdot(4:6) = H\(-... [- 1.8*cos(q(2))*sin(q(2))*q(4)*q(5)+1.92*cos(q(2))*q(5)*q(5)+.3*sin(q(2)+q(3))*(q(5)+q(6))* q(6); 91.9*sin(q(2))-3.3*sin(q(2)+q(3))+.9*sin(q(2))*cos(q(2))*q(4)*q(4)-.3*sin(q(2)+q(3))*q(4)*q(6);.3*sin(q(2)+q(3))*q(4)*q(5)-3.3*sin(q(2)+q(3))]+tau);

13 3. PID control simulation code function main_puma_pid [t,x] = ode45(@puma_pid,:.1:2,[ ]); plot(t,x(:,1),'-',t,x(:,2),'--',t,x(:,3),'-.','linewidth',2); leg('q1','q2','q3'); hold on plot(t,pi*ones(1,length(t))/2,'--'); xlabel('t/s'),ylabel('q/rad'); hold off function xdot = puma_pid(~,q) xdot = zeros(9,1); qd = [pi/2; pi/2; pi/2]; A = [12 ; 18 ; 5]; B = [3 ; 5 ; 1]; C = [3 ; 12 ; 1]; tau = -A*([q(1);q(2);q(3)]-[qd(1);qd(2);qd(3)])-B*[q(4);q(5);q(6)]-C*[q(7);q(8);q(9)]; xdot(1) = q(4); xdot(2) = q(5); xdot(3) = q(6); H = [22+.9*cos(q(2))*cos(q(2)), *sin(q(2)), -.3*cos(q(2)+q(3)); *sin(q(2)), 1.66, -.29; -.3*cos(q(2)+q(3)), -.29,.11]; xdot(4:6) = H\(-... [- 1.8*cos(q(2))*sin(q(2))*q(4)*q(5)+1.92*cos(q(2))*q(5)*q(5)+.3*sin(q(2)+q(3))*(q(5)+q(6))* q(6); 91.9*sin(q(2))-3.3*sin(q(2)+q(3))+.9*sin(q(2))*cos(q(2))*q(4)*q(4)-.3*sin(q(2)+q(3))*q(4)*q(6);.3*sin(q(2)+q(3))*q(4)*q(5)-3.3*sin(q(2)+q(3))]+tau); xdot(7:9) = q(1:3)-qd; 4. PD plus gravity compensation control simulation code function main_puma_pdg [t,x] = ode45(@puma_pdg,:.1:2,[ ]); plot(t,x(:,1),'-',t,x(:,2),'--',t,x(:,3),'-.','linewidth',2); leg('q1','q2','q3'); hold on plot(t,pi*ones(1,length(t))/2,'--'); xlabel('t/s'),ylabel('q/rad'); hold off function xdot = puma_pdg(~,q) xdot = zeros(6,1); qd = [pi/2; pi/2; pi/2]; A = [5 ; 18 ; 5];

14 B = [35 ; 5 ; 2]; tau = -A*([q(1);q(2);q(3)]-[qd(1);qd(2);qd(3)])-B*[q(4);q(5);q(6)]; xdot(1) = q(4); xdot(2) = q(5); xdot(3) = q(6); H = [22+.9*cos(q(2))*cos(q(2)), *sin(q(2)), -.3*cos(q(2)+q(3)); *sin(q(2)), 1.66, -.29; -.3*cos(q(2)+q(3)), -.29,.11]; xdot(4:6) = H\(-... [- 1.8*cos(q(2))*sin(q(2))*q(4)*q(5)+1.92*cos(q(2))*q(5)*q(5)+.3*sin(q(2)+q(3))*(q(5)+q(6))* q(6);.9*sin(q(2))*cos(q(2))*q(4)*q(4)-.3*sin(q(2)+q(3))*q(4)*q(6);.3*sin(q(2)+q(3))*q(4)*q(5)]+tau); 5. Computed torque control simulation code function main_puma_ct [t,x] = ode45(@puma_ct,:.1:2,[ ]); figure(1), plot(t,x(:,1),'-',t,x(:,2),'--',t,x(:,3),'-.','linewidth',2.5); leg('q1','q2','q3'); hold on plot(t,pi/2+sin(t),'--'); xlabel('t/s'),ylabel('q/rad'); hold off figure(2), plot(t,x(:,4),'-',t,x(:,5),'--',t,x(:,6),'-.','linewidth',2.5); leg('w1','w2','w3'); hold on plot(t,cos(t),'--'); xlabel('t/s'),ylabel('w/rad/s'); hold off function xdot = puma_ct(t,q) xdot = zeros(6,1); qd = [pi/2+sin(t); pi/2+sin(t); pi/2+sin(t)]; qddot = [cos(t); cos(t); cos(t)]; qd2dot = -[sin(t); sin(t); sin(t)]; A = [5 ; 18 ; 5]; B = [35 ; 5 ; 2]; xdot(1) = q(4); xdot(2) = q(5); xdot(3) = q(6); xdot(4:6) = qd2dot - A*(q(4:6)-qddot) -B*(q(1:3)-qd);

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

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

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

Multibody simulation

Multibody simulation Multibody simulation Dynamics of a multibody system (Newton-Euler formulation) Dimitar Dimitrov Örebro University June 8, 2012 Main points covered Newton-Euler formulation forward dynamics inverse dynamics

More information

Case Study: The Pelican Prototype Robot

Case Study: The Pelican Prototype Robot 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,

More information

(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

Design Artificial Nonlinear Controller Based on Computed Torque like Controller with Tunable Gain

Design Artificial Nonlinear Controller Based on Computed Torque like Controller with Tunable Gain World Applied Sciences Journal 14 (9): 1306-1312, 2011 ISSN 1818-4952 IDOSI Publications, 2011 Design Artificial Nonlinear Controller Based on Computed Torque like Controller with Tunable Gain Samira Soltani

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 NMT EE 589 & UNM ME 482/582 ROBOT ENGINEERING NMT EE 589 & UNM ME 482/582 Simplified drive train model of a robot joint Inertia seen by the motor Link k 1 I I D ( q) k mk 2 kk Gk Torque amplification G

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

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

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

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

Rigid Manipulator Control

Rigid Manipulator Control Rigid Manipulator Control The control problem consists in the design of control algorithms for the robot motors, such that the TCP motion follows a specified task in the cartesian space Two types of task

More information

Robot Control Basics CS 685

Robot Control Basics CS 685 Robot Control Basics CS 685 Control basics Use some concepts from control theory to understand and learn how to control robots Control Theory general field studies control and understanding of behavior

More information

Dynamic Model of Space Robot Manipulator

Dynamic Model of Space Robot Manipulator Applied Mathematical Sciences, Vol. 9, 215, no. 94, 465-4659 HIKARI Ltd, www.m-hikari.com http://dx.doi.org/1.12988/ams.215.56429 Dynamic Model of Space Robot Manipulator Polina Efimova Saint-Petersburg

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

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

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

6. 3D Kinematics DE2-EA 2.1: M4DE. Dr Connor Myant

6. 3D Kinematics DE2-EA 2.1: M4DE. Dr Connor Myant DE2-EA 2.1: M4DE Dr Connor Myant 6. 3D Kinematics Comments and corrections to connor.myant@imperial.ac.uk Lecture resources may be found on Blackboard and at http://connormyant.com Contents Three-Dimensional

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

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

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

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

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

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

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

Dynamics. 1 Copyright c 2015 Roderic Grupen

Dynamics. 1 Copyright c 2015 Roderic Grupen Dynamics The branch of physics that treats the action of force on bodies in motion or at rest; kinetics, kinematics, and statics, collectively. Websters dictionary Outline Conservation of Momentum Inertia

More information

Quadrotor Modeling and Control

Quadrotor Modeling and Control 16-311 Introduction to Robotics Guest Lecture on Aerial Robotics Quadrotor Modeling and Control Nathan Michael February 05, 2014 Lecture Outline Modeling: Dynamic model from first principles Propeller

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

Dynamic Modeling of Rotary Double Inverted Pendulum Using Classical Mechanics

Dynamic Modeling of Rotary Double Inverted Pendulum Using Classical Mechanics ISBN 978-93-84468-- Proceedings of 5 International Conference on Future Computational echnologies (ICFC'5) Singapore, March 9-3, 5, pp. 96-3 Dynamic Modeling of Rotary Double Inverted Pendulum Using Classical

More information

STATE VARIABLE (SV) SYSTEMS

STATE VARIABLE (SV) SYSTEMS Copyright F.L. Lewis 999 All rights reserved Updated:Tuesday, August 05, 008 STATE VARIABLE (SV) SYSTEMS A natural description for dynamical systems is the nonlinear state-space or state variable (SV)

More information

Time Response of Dynamic Systems! Multi-Dimensional Trajectories Position, velocity, and acceleration are vectors

Time Response of Dynamic Systems! Multi-Dimensional Trajectories Position, velocity, and acceleration are vectors Time Response of Dynamic Systems Robert Stengel Robotics and Intelligent Systems MAE 345, Princeton University, 217 Multi-dimensional trajectories Numerical integration Linear and nonlinear systems Linearization

More information

Robust Control of Robot Manipulator by Model Based Disturbance Attenuation

Robust Control of Robot Manipulator by Model Based Disturbance Attenuation IEEE/ASME Trans. Mechatronics, vol. 8, no. 4, pp. 511-513, Nov./Dec. 2003 obust Control of obot Manipulator by Model Based Disturbance Attenuation Keywords : obot manipulators, MBDA, position control,

More information

Robotics & Automation. Lecture 25. Dynamics of Constrained Systems, Dynamic Control. John T. Wen. April 26, 2007

Robotics & Automation. Lecture 25. Dynamics of Constrained Systems, Dynamic Control. John T. Wen. April 26, 2007 Robotics & Automation Lecture 25 Dynamics of Constrained Systems, Dynamic Control John T. Wen April 26, 2007 Last Time Order N Forward Dynamics (3-sweep algorithm) Factorization perspective: causal-anticausal

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

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

Design On-Line Tunable Gain Artificial Nonlinear Controller

Design On-Line Tunable Gain Artificial Nonlinear Controller Journal of Computer Engineering 1 (2009) 3-11 Design On-Line Tunable Gain Artificial Nonlinear Controller Farzin Piltan, Nasri Sulaiman, M. H. Marhaban and R. Ramli Department of Electrical and Electronic

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

Robot Dynamics - Rotary Wing UAS: Control of a Quadrotor

Robot Dynamics - Rotary Wing UAS: Control of a Quadrotor Robot Dynamics Rotary Wing AS: Control of a Quadrotor 5-85- V Marco Hutter, Roland Siegwart and Thomas Stastny Robot Dynamics - Rotary Wing AS: Control of a Quadrotor 7..6 Contents Rotary Wing AS. Introduction

More information

Dynamics and control of mechanical systems

Dynamics and control of mechanical systems Dynamics and control of mechanical systems Date Day 1 (03/05) - 05/05 Day 2 (07/05) Day 3 (09/05) Day 4 (11/05) Day 5 (14/05) Day 6 (16/05) Content Review of the basics of mechanics. Kinematics of rigid

More information

1/30. Rigid Body Rotations. Dave Frank

1/30. Rigid Body Rotations. Dave Frank . 1/3 Rigid Body Rotations Dave Frank A Point Particle and Fundamental Quantities z 2/3 m v ω r y x Angular Velocity v = dr dt = ω r Kinetic Energy K = 1 2 mv2 Momentum p = mv Rigid Bodies We treat a rigid

More information

A Sliding Mode Controller Using Neural Networks for Robot Manipulator

A Sliding Mode Controller Using Neural Networks for Robot Manipulator ESANN'4 proceedings - European Symposium on Artificial Neural Networks Bruges (Belgium), 8-3 April 4, d-side publi., ISBN -9337-4-8, pp. 93-98 A Sliding Mode Controller Using Neural Networks for Robot

More information

MSMS Matlab Problem 02

MSMS Matlab Problem 02 MSMS 2014-2015 Matlab Problem 02 Basilio Bona DAUIN PoliTo Problem formulation The planar system illustrated in Figure 1 consists of a cart C sliding with friction along the horizontal rail; the cart supports

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

Manipulator Dynamics (1) Read Chapter 6

Manipulator Dynamics (1) Read Chapter 6 Manipulator Dynamics (1) Read Capter 6 Wat is dynamics? Study te force (torque) required to cause te motion of robots just like engine power required to drive a automobile Most familiar formula: f = ma

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

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

An experimental robot load identification method for industrial application

An experimental robot load identification method for industrial application An experimental robot load identification method for industrial application Jan Swevers 1, Birgit Naumer 2, Stefan Pieters 2, Erika Biber 2, Walter Verdonck 1, and Joris De Schutter 1 1 Katholieke Universiteit

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

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

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

Explicit Lagrangian Formulation of the Dynamic Regressors for Serial Manipulators

Explicit Lagrangian Formulation of the Dynamic Regressors for Serial Manipulators Explicit Lagrangian Formulation of the Dynamic Regressors for Serial Manipulators M Gabiccini 1 A Bracci 1 D De Carli M Fredianelli A Bicchi 1 Dipartimento di Ingegneria Meccanica Nucleare e della Produzione

More information

Real-time Motion Control of a Nonholonomic Mobile Robot with Unknown Dynamics

Real-time Motion Control of a Nonholonomic Mobile Robot with Unknown Dynamics Real-time Motion Control of a Nonholonomic Mobile Robot with Unknown Dynamics TIEMIN HU and SIMON X. YANG ARIS (Advanced Robotics & Intelligent Systems) Lab School of Engineering, University of Guelph

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

Physics 121, March 25, Rotational Motion and Angular Momentum. Department of Physics and Astronomy, University of Rochester

Physics 121, March 25, Rotational Motion and Angular Momentum. Department of Physics and Astronomy, University of Rochester Physics 121, March 25, 2008. Rotational Motion and Angular Momentum. Physics 121. March 25, 2008. Course Information Topics to be discussed today: Review of Rotational Motion Rolling Motion Angular Momentum

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

3-D Kinetics of Rigid Bodies

3-D Kinetics of Rigid Bodies 3-D Kinetics of Rigid Bodies Angular Momentum Generalized Newton s second law for the motion for a 3-D mass system Moment eqn for 3-D motion will be different than that obtained for plane motion Consider

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

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

Physics 4A Solutions to Chapter 10 Homework

Physics 4A Solutions to Chapter 10 Homework Physics 4A Solutions to Chapter 0 Homework Chapter 0 Questions: 4, 6, 8 Exercises & Problems 6, 3, 6, 4, 45, 5, 5, 7, 8 Answers to Questions: Q 0-4 (a) positive (b) zero (c) negative (d) negative Q 0-6

More information

Chapter 5. . Dynamics. 5.1 Introduction

Chapter 5. . Dynamics. 5.1 Introduction Chapter 5. Dynamics 5.1 Introduction The study of manipulator dynamics is essential for both the analysis of performance and the design of robot control. A manipulator is a multilink, highly nonlinear

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

1. The first thing you need to find is the mass of piece three. In order to find it you need to realize that the masses of the three pieces must be

1. The first thing you need to find is the mass of piece three. In order to find it you need to realize that the masses of the three pieces must be 1. The first thing you need to find is the mass of piece three. In order to find it you need to realize that the masses of the three pieces must be equal to the initial mass of the starting rocket. Now

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

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

Physics 201. Professor P. Q. Hung. 311B, Physics Building. Physics 201 p. 1/1

Physics 201. Professor P. Q. Hung. 311B, Physics Building. Physics 201 p. 1/1 Physics 201 p. 1/1 Physics 201 Professor P. Q. Hung 311B, Physics Building Physics 201 p. 2/1 Rotational Kinematics and Energy Rotational Kinetic Energy, Moment of Inertia All elements inside the rigid

More information

General Definition of Torque, final. Lever Arm. General Definition of Torque 7/29/2010. Units of Chapter 10

General Definition of Torque, final. Lever Arm. General Definition of Torque 7/29/2010. Units of Chapter 10 Units of Chapter 10 Determining Moments of Inertia Rotational Kinetic Energy Rotational Plus Translational Motion; Rolling Why Does a Rolling Sphere Slow Down? General Definition of Torque, final Taking

More information

System simulation using Matlab, state plane plots

System simulation using Matlab, state plane plots System simulation using Matlab, state plane plots his lab is mainly concerned with making state plane (also referred to as phase plane ) plots for various linear and nonlinear systems with two states he

More information

Fundamental principles

Fundamental principles Dynamics and control of mechanical systems Date Day 1 (03/05) - 05/05 Day (07/05) Day 3 (09/05) Day 4 (11/05) Day 5 (14/05) Day 6 (16/05) Content Review of the basics of mechanics. Kinematics of rigid

More information

Robotics 2 Robot Interaction with the Environment

Robotics 2 Robot Interaction with the Environment Robotics 2 Robot Interaction with the Environment Prof. Alessandro De Luca Robot-environment interaction a robot (end-effector) may interact with the environment! modifying the state of the environment

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

Rigid body simulation. Once we consider an object with spatial extent, particle system simulation is no longer sufficient

Rigid body simulation. Once we consider an object with spatial extent, particle system simulation is no longer sufficient Rigid body dynamics Rigid body simulation Once we consider an object with spatial extent, particle system simulation is no longer sufficient Rigid body simulation Unconstrained system no contact Constrained

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

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

III. Work and Energy

III. Work and Energy Rotation I. Kinematics - Angular analogs II. III. IV. Dynamics - Torque and Rotational Inertia Work and Energy Angular Momentum - Bodies and particles V. Elliptical Orbits The student will be able to:

More information

Kinetic energy. Analytical Mechanics: Link Mechanisms. Kinetic energy. Agenda. Kinematics of two link open mechanism.

Kinetic energy. Analytical Mechanics: Link Mechanisms. Kinetic energy. Agenda. Kinematics of two link open mechanism. Analtical Mechanics: Link Mechanisms Shinichi Hirai Dept. Robotics, Ritsumeikan Univ. Kinetic energ velocit of the center of mass of link : angular velocit of link : kinetic energ of link : ẋ c l c θ S

More information

Center of Gravity Pearson Education, Inc.

Center of Gravity Pearson Education, Inc. Center of Gravity = The center of gravity position is at a place where the torque from one end of the object is balanced by the torque of the other end and therefore there is NO rotation. Fulcrum Point

More information

3- DOF Scara type Robot Manipulator using Mamdani Based Fuzzy Controller

3- DOF Scara type Robot Manipulator using Mamdani Based Fuzzy Controller 659 3- DOF Scara type Robot Manipulator using Mamdani Based Fuzzy Controller Nitesh Kumar Jaiswal *, Vijay Kumar ** *(Department of Electronics and Communication Engineering, Indian Institute of Technology,

More information

Introduction to Robotics (CS223A) (Winter 2006/2007) Homework #5 solutions

Introduction to Robotics (CS223A) (Winter 2006/2007) Homework #5 solutions Introduction to Robotics (CS3A) Handout (Winter 6/7) Hoework #5 solutions. (a) Derive a forula that transfors an inertia tensor given in soe frae {C} into a new frae {A}. The frae {A} can differ fro frae

More information

Dynamics and control of mechanical systems

Dynamics and control of mechanical systems Dynamics and control of mechanical systems Date Day 1 (03/05) - 05/05 Day 2 (07/05) Day 3 (09/05) Day 4 (11/05) Day 5 (14/05) Day 6 (16/05) Content Review of the basics of mechanics. Kinematics of rigid

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

LAWS OF GYROSCOPES / CARDANIC GYROSCOPE

LAWS OF GYROSCOPES / CARDANIC GYROSCOPE LAWS OF GYROSCOPES / CARDANC GYROSCOPE PRNCPLE f the axis of rotation of the force-free gyroscope is displaced slightly, a nutation is produced. The relationship between precession frequency or nutation

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

Lesson Rigid Body Dynamics

Lesson Rigid Body Dynamics Lesson 8 Rigid Body Dynamics Lesson 8 Outline Problem definition and motivations Dynamics of rigid bodies The equation of unconstrained motion (ODE) User and time control Demos / tools / libs Rigid Body

More information

Research Article A New Methodology for Solving Trajectory Planning and Dynamic Load-Carrying Capacity of a Robot Manipulator

Research Article A New Methodology for Solving Trajectory Planning and Dynamic Load-Carrying Capacity of a Robot Manipulator Mathematical Problems in Engineering Volume 16 Article ID 1337 8 pages http://dx.doi.org/1.11/16/1337 Research Article A New Methodology for Solving Trajectory Planning and Dynamic Load-Carrying Capacity

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

Chapter 3 Numerical Methods

Chapter 3 Numerical Methods Chapter 3 Numerical Methods Part 3 3.4 Differential Algebraic Systems 3.5 Integration of Differential Equations 1 Outline 3.4 Differential Algebraic Systems 3.4.1 Constrained Dynamics 3.4.2 First and Second

More information

Contents. Dynamics and control of mechanical systems. Focus on

Contents. Dynamics and control of mechanical systems. Focus on Dynamics and control of mechanical systems Date Day 1 (01/08) Day 2 (03/08) Day 3 (05/08) Day 4 (07/08) Day 5 (09/08) Day 6 (11/08) Content Review of the basics of mechanics. Kinematics of rigid bodies

More information

Passive Magnetic Attitude Control for CubeSat Spacecraft

Passive Magnetic Attitude Control for CubeSat Spacecraft Passive Magnetic Attitude Control for CubeSat Spacecraft David Gerhardt Advisor: Dr. Scott Palo University of Colorado at Boulder Department of Aerospace Engineering Sciences August 11, 2010 Motivation

More information

9 Kinetics of 3D rigid bodies - rotating frames

9 Kinetics of 3D rigid bodies - rotating frames 9 Kinetics of 3D rigid bodies - rotating frames 9. Consider the two gears depicted in the figure. The gear B of radius R B is fixed to the ground, while the gear A of mass m A and radius R A turns freely

More information

Dynamics. Dynamics of mechanical particle and particle systems (many body systems)

Dynamics. Dynamics of mechanical particle and particle systems (many body systems) Dynamics Dynamics of mechanical particle and particle systems (many body systems) Newton`s first law: If no net force acts on a body, it will move on a straight line at constant velocity or will stay at

More information

Video 2.1a Vijay Kumar and Ani Hsieh

Video 2.1a Vijay Kumar and Ani Hsieh Video 2.1a Vijay Kumar and Ani Hsieh Robo3x-1.3 1 Introduction to Lagrangian Mechanics Vijay Kumar and Ani Hsieh University of Pennsylvania Robo3x-1.3 2 Analytical Mechanics Aristotle Galileo Bernoulli

More information

Flipping Physics Lecture Notes: Demonstrating Rotational Inertia (or Moment of Inertia)

Flipping Physics Lecture Notes: Demonstrating Rotational Inertia (or Moment of Inertia) Flipping Physics Lecture Notes: Demonstrating Rotational Inertia (or Moment of Inertia) Have you ever struggled to describe Rotational Inertia to your students? Even worse, have you ever struggled to understand

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

Seul Jung, T. C. Hsia and R. G. Bonitz y. Robotics Research Laboratory. University of California, Davis. Davis, CA 95616

Seul Jung, T. C. Hsia and R. G. Bonitz y. Robotics Research Laboratory. University of California, Davis. Davis, CA 95616 On Robust Impedance Force Control of Robot Manipulators Seul Jung, T C Hsia and R G Bonitz y Robotics Research Laboratory Department of Electrical and Computer Engineering University of California, Davis

More information

Introduction to centralized control

Introduction to centralized control ROBOTICS 01PEEQW Basilio Bona DAUIN Politecnico di Torino Control Part 2 Introduction to centralized control Independent joint decentralized control may prove inadequate when the user requires high task

More information

A Miniaturized Satellite Attitude Determination and Control System with Autonomous Calibration Capabilities

A Miniaturized Satellite Attitude Determination and Control System with Autonomous Calibration Capabilities A Miniaturized Satellite Attitude Determination and Control System with Autonomous Calibration Capabilities Sanny Omar Dr. David Beale Dr. JM Wersinger Introduction ADACS designed for CubeSats CubeSats

More information

Dynamic model of robots:

Dynamic model of robots: Robotics 2 Dynamic model of robots: Analysis, properties, extensions, parametrization, identification, uses Prof. Alessandro De Luca Analysis of inertial couplings! Cartesian robot! Cartesian skew robot!

More information

Chapter 8: Momentum, Impulse, & Collisions. Newton s second law in terms of momentum:

Chapter 8: Momentum, Impulse, & Collisions. Newton s second law in terms of momentum: linear momentum: Chapter 8: Momentum, Impulse, & Collisions Newton s second law in terms of momentum: impulse: Under what SPECIFIC condition is linear momentum conserved? (The answer does not involve collisions.)

More information

Adaptive Jacobian Tracking Control of Robots With Uncertainties in Kinematic, Dynamic and Actuator Models

Adaptive Jacobian Tracking Control of Robots With Uncertainties in Kinematic, Dynamic and Actuator Models 104 IEEE TRANSACTIONS ON AUTOMATIC CONTROL, VOL. 51, NO. 6, JUNE 006 Adaptive Jacobian Tracking Control of Robots With Uncertainties in Kinematic, Dynamic and Actuator Models C. C. Cheah, C. Liu, and J.

More information