Computer Problem 1: SIE Guidance, Navigation, and Control

Size: px
Start display at page:

Download "Computer Problem 1: SIE Guidance, Navigation, and Control"

Transcription

1 Computer Problem 1: SIE 39 - Guidance, Navigation, and Control Roger Skjetne March 12, 23 1 Problem 1 (DSRV) We have the model: m Zẇ Z q ẇ Mẇ I y M q q + ẋ U cos θ + w sin θ ż U sin θ + w cos θ θ q Zw Z q M w M q q w z + M θ θ No. 1a) The restoring moment in pitch can according to equation (3.124) of [1], be written ZδS M δs (1) δ S (2) This gives M BG z W {z } M θ sin θ M θ θ. M θ BG z W<. No. 1b) According to equation (3.275) of [1], assume ẇ w. Then the natural frequency in pitch is With U 4.11 (m/s) we get: s BG z W ω θ (I y M q ) s M θ (I y M q ) s U U. ω θ (rad/s). 1

2 1 8 w U The pitch period for U 4.11 (m/s) becomes: T θ 2π 3.85 (s). ω θ For a neutrally buoyant vessel, there is no natural frequency in heave, since it cannot have a spring force. No. 1c) Firstwehavethat2ξω d m which gives that r k d 2ξmω 2ξm m 2ξ km. We further recall from linear control theory that for a damped system, the poles are in general the complex conjugate pair p 1,2 a ± jω such that (s + a + jω)(s + a jω) s 2 +2as + a 2 + ω 2 s 2 +2ξω s + ω 2. Hence, a ξω and a 2 + ω 2 ω 2 a2 + r 2 ω 2 such that a2 (1 r 2 )ω 2 and Together with the above equation, this gives We have d 2 1 r 2 km which gives: ξ a ω p 1 r 2. d 2 p 1 r 2 km. M q 2 p 1 r q M 2 θ (I y M q ) m Ã! 2 1 r 2 M q 2 p M θ (I y M q ) m r v Ã! u 2 t M q 1 2 p. M θ (I y M q ) Plugging in numbers from DSRV.m s µ r This means that the frequency of the damped system is 13% of the undamped resonans frequency ω θ. 2

3 No. 1d) The dynamical equation is m Zẇ Z q ẇ Mẇ I y M q q Zw Z + q w M w M q q z + M θ θ ZδS M δs δ S and can be written on the form M ν + Dν + Gη b 1 δ S. (Note: we use the approximation U U when defining M θ )Withu we get the stationary equation: ν ss D 1 Gη ss 1 Zw Z q zss M w M q M θ θ ss " # Z q Z wm q+z qm w M θ zss Z w. θ ss Z w M q +Z q M w M θ Therefore w ss Z q Z w M q + Z q M w M θ θ ss Z w q ss M θ θ ss. Z w M q + Z q M w Assuming small angles θ ss so that w ss q ss, the kinematic equations (1) for diving (pitch, heave) can be linearized around these stationary values: ż U sin θ + w cos θ U θ + w θ q or This gives the state-space model ż θ 1 1 w q U + z θ. or in traditional notation, letting x : [η > ν > ] > [z,θ,w,q] >, gives A ẋ Ax + Bδ S 1 I M 1 G M 1 x+ D The numerical values for the system is computed in the file (hydro.m): η ν + A 1 η M ν + Dν + Gη b 1 δ S (3) M 1 b 1 δ S. (4) 3

4 % Hydrodynamic computations for DSRV % % Thor I. Fossen - NTNU U 4.11; Iy.1925; m.36391; Mqdot ; Zqdot -.13; Mwdot -.146; Zwdot ; Mq ; Zq ; Mw.11175; Zw ; Mtheta /U^2; Mdelta ; Zdelta.27695; M [m-zwdot -Zqdot; -Mwdot Iy-Mqdot]; D [-Zw -Zq; -Mw -Mq ]; G [ ; -Mtheta]; A1 [ -U; ]; B [Zdelta; Mdelta]; A [ A1 eye(2); -inv(m)*g -inv(m)*d ]; damp(a) %%%%%% Output: %%%%%% >> Eigenvalue Damping Freq. (rad/s).e+ -1.e+.e e-1 1.e+ 4.15e e e+i 8.52e-1 2.3e e e+i 8.52e-1 2.3e+ >> Notice that there is two complex conjugated poles and two real poles p 1 p 2.42 p 3, ± j 1.6 where the zero eigenvalue correspond to the z-mode. The vessel is therefore critically stable under diving. It is intuitive that the system is only critically stable in heave, since we earlier found that there is no resonans frequancy in this mode due to no spring force. If it was stable in this state, it would have to go to the surface, z(t) as t. We notice that with (w, θ) then ż and thus z(t) z(), t. The entire positive z-axis therefore becomes an equilibrium manifold for the linearized system. In a regulator design, on the other hand, we can easily introduce feedback from z to regulate the depth to any desired depth. Notice also that the resonans frequency for pitch in the multivariable system ω θ.415 (rad/s) which is higher than what you got in the assumed decoupled model in Problem 1b) and c), that is, 13% of 1.63 rad/s.22 rad/s. The reason for this is that the frequency is strongly affected by the coupling between heave and pitch. 4

5 The true pitch period is therefore: T θ 2π (s)..415 We may therefore conclude that the assumption of a decoupled model is NOT valid, and hence a regulator design should be multivariable. 2 Problem 2 We will develop an LQR PID state space regulator in this problem. The model is given by the linear system (4). Let a reference depth be z r which gives η r [z r ] >. Let η η η r. This gives η η ν + A 1 η ν + A 1 η + A 1 η r ν + A 1 η since A 1 η r. To obtain integral action, define the integrator state Let now the full state be We then have ė z z z r e(t) ė [1 ] η J η. X e η > ν > >. Z t z(τ)dτ Ẋ J A 1 I X+ δ S A e X + B e δ S (5a) M 1 G M 1 D M 1 b 1 y I 3 3 C e X (5b) whereweviewthestatese and η astheoutput.nowwewanttofind the state feedback gain that minimizes the cost function Z J qe e(t) 2 + q z z(t) 2 + q θ θ(t) 2 + rδ S (t) 2 dt Z X > (t)c > e QC e X(t)+rδ S (t) 2 dt (6) where Q diag(q e,q z,q θ ). The optimal control is then given by and P c is the solution to the Algebraic Riccati Equation (ARE): δ s 1 r B> e P c X K pid X (7) P c A e +A > 1 e P c PB e r B> e P c +C > e QC e (8) whichissolvedbythecommandare.m. Recall that for a feasible solution to exist, then (A e, B e ) must be controllable and (C e, A e ) must be observable. We get the closed-loop: Ẋ (A e B e K pid ) X and it is your task to check that this system has negative eigenvalues (which is always true if (A e, B e ) is controllable and (C e, A e ) is observable). A simulation is performed using Simulink, as shown in Figure 1: Remember that the kontroller δ S K pid X is based on the linearized model. In the simulation, we use the true nonlinear plant with saturation on the rudder and nonlinear kinematics. Clearly, going from z 1m to z 1 m is a large step. However, using the weight in the cost function, r 1 and Q diag(.4, 1, 1) will give adequate performance. With initial conditions: x(), e(), and x() [1] > and a step in z :1m 1 m at t 15 s, we get the responses as shown in Figure 2: 5

6 Figure 1: Block diagram of the PID state feedback closed-loop system. We see that the rudder is NOT saturating, even for the BIG step. And the response is nice and smooth. The power of the method is that tuning is easy, since the weights r and Q affects the physical quantities δ S and (e, z,θ) directly in the time-domain. 6

7 z-pos (m) z(t) 1 Responses z(t) θ(t) θ(t) δ (t) s δ s (t) x(t) vs. z(t) x-pos (m) Figure 2: Output responses: a) z(t) b) θ(t) c) δ S (t) d) x(t) vs. z(t) 7

8 3 Problem 3 We will now develop a Kalman filter to estimate all the states of the plant, including the unmeasured states w and q. Assuming the noise covariance matrices are constant, we use a stationary solution to the Riccati equation in our Kalman filter. With the augmented integrator state, the linear plant is given by (9): Ẋ J A 1 I X+ δ S A e X + B e δ S + E e w(t) (9a) M 1 G M 1 D M 1 b 1 y I 3 3 C e X + v(t) (9b) where w is dynamic (process) disturbances and v is measurement noise (both assumed white noise) 1 ω z E e π 18 1, w ω θ ω w, v υ e υ z υ π ω θ q 18 Assume the noise sources are modeled by a Gauss distribution, i.e., w N (, Q w ) og v N (, R v ) where Q w and R v are two weight matrices reflecting the standard deviation of the disturbances. Note that R v are usually accurately given by the specifications of the measurement equipment. Q w on the other hand needs knowledge from environmental disturbance models and statistical data. We assume R v E vv >ª diag(r 1,r 2,r 3 ) and Q w diag(q 1,q 2,q 3,q 4 ). In the simulation of Problem 2, we have verified that this system is both controllable and observable. We design the observer states by copying the plant + an extra injection term Lỹ : The estimation error is Z X ˆX which gives ˆX A e ˆX + B e δ S + L[y ŷ] ŷ C e ˆX. Ż A e X + B e δ S + E e w(t) A e ˆX B e δ S L[y ŷ] A e Z L[C e X + v(t) C e ˆX]+E e w(t) (A e LC e ) Z Lv(t)+E e w(t). (1) Looking at the expected value of (1), we get o E nż E {(A e LC e ) Z Lv(t)+E e w(t)} d dt E {Z} (A e LC e ) E {Z} LE {v(t)} + E e E {w(t)} (A e LC e ) E {Z} since the expected value of white noise is zero (see [2] for details). Consequently, if A e LC e is a Hurwitz matrix (negative n oeigenvalues), then the expected value of the estimation error is regulated to zero. It follows that as t, E ˆX(t) E {X(t)}. In a Luenberger observer, we would choose the gain vector L by pole placement, where the poles of A e LC e should be about 5 1 times faster than the poles of the state feedback closed-loop A e B e K pid. In the Kalman filter, on the other hand, we calculate L from the Riccati equation where L P o (t) C > e R 1 v Ṗ o A e P o +P o A > e P o C > e R 1 v C e P o +E e Q w E > e (11) ³ ³ > P o () E X () ˆX () X () ˆX () 8

9 z-pos (m) z(t) As mentioned above, assuming a stationary solution for (11) we instead solve the algebraic Riccati equation: A e P o +P o A > e P o C > e R 1 v C e P o +E e Q w E > e (12) Notice that this equation is somewhat different than (8) with respect to transposes, etc. This gives the constant gain vector L P o C > e R 1 v that is used in the observer. We have already designed an optimal linear PID controller in Problem 2. Next, we extend that simulation with the observer we just have developed. See the corresponding simulink model for the entire system in file Comp1WithKF.mdl. Since the estimation introduces extra initial transients and the model now contains heavy disturbances, we have changed the settings of the PID controller to: r 1 8, Q diag(.1, 4, 2). Similarly, π we have for the Kalman filter: R v diag(1, 1, 18 ) and Q w.5i 4 4. To see the rest of the parameters, see the corresponding simulink model, and the m-file Comp1WithKF_run.m that runs the simulation Responses z(t) z est (t) θ(t) θ(t) θ (t) est δ (t) s δ s (t) x(t) vs. z(t) x-pos (m) Figure 3: The responses for the total system with a Kalman filter estimating all states. Simulation performed with noisy measurements and process disturbances. We clearly see in Figure 3 that the estimated states track the true states. Also we avoid saturation, even for the 9

10 q(t) w(t) large step z r :1m 1 m. 1.5 Speeds responses w(t) w est (t) q(t) q est (t) Figure 4: Heave speed w(t) and pitch rate q(t) and their estimated values ŵ(t) and ˆq(t). In Figure 4 we see that the estimated speeds track the true speed pretty good, at least in the mean, which is the intention of the Kalman filter Estimation Errors e~ z~ θ~ w~ q~ h Figure 5: Estimation errors for the estimated states ê(t), ẑ(t), ˆθ(t), i ŵ(t), ˆq(t) in the Kalman filter. A large transient happens when the set-point switches for z r, but are regulated fast back to a neighborhood of zero. Finally, we see in Figure 5 that the estimation errors are small, and zero in the mean. References [1] T.I.Fossen,Marine Control Systems: Guidance, Navigation, and Control of Ships, Rigs and Underwater Vehicles, Marine Cybernetics AS, Trondheim, Norway, 22. [2] F. Lewis and V. L. Syrmos, Optimal Control, John Wiley & Sons Ltd, 2 edition, R.S - March 12, 23 1

Problem 1: Ship Path-Following Control System (35%)

Problem 1: Ship Path-Following Control System (35%) Problem 1: Ship Path-Following Control System (35%) Consider the kinematic equations: Figure 1: NTNU s research vessel, R/V Gunnerus, and Nomoto model: T ṙ + r = Kδ (1) with T = 22.0 s and K = 0.1 s 1.

More information

Pole placement control: state space and polynomial approaches Lecture 2

Pole placement control: state space and polynomial approaches Lecture 2 : state space and polynomial approaches Lecture 2 : a state O. Sename 1 1 Gipsa-lab, CNRS-INPG, FRANCE Olivier.Sename@gipsa-lab.fr www.gipsa-lab.fr/ o.sename -based November 21, 2017 Outline : a state

More information

Autonomous Helicopter Landing A Nonlinear Output Regulation Perspective

Autonomous Helicopter Landing A Nonlinear Output Regulation Perspective Autonomous Helicopter Landing A Nonlinear Output Regulation Perspective Andrea Serrani Department of Electrical and Computer Engineering Collaborative Center for Control Sciences The Ohio State University

More information

Lecture 9. Introduction to Kalman Filtering. Linear Quadratic Gaussian Control (LQG) G. Hovland 2004

Lecture 9. Introduction to Kalman Filtering. Linear Quadratic Gaussian Control (LQG) G. Hovland 2004 MER42 Advanced Control Lecture 9 Introduction to Kalman Filtering Linear Quadratic Gaussian Control (LQG) G. Hovland 24 Announcement No tutorials on hursday mornings 8-9am I will be present in all practical

More information

Predictive Control of Gyroscopic-Force Actuators for Mechanical Vibration Damping

Predictive Control of Gyroscopic-Force Actuators for Mechanical Vibration Damping ARC Centre of Excellence for Complex Dynamic Systems and Control, pp 1 15 Predictive Control of Gyroscopic-Force Actuators for Mechanical Vibration Damping Tristan Perez 1, 2 Joris B Termaat 3 1 School

More information

TTK4190 Guidance and Control Exam Suggested Solution Spring 2011

TTK4190 Guidance and Control Exam Suggested Solution Spring 2011 TTK4190 Guidance and Control Exam Suggested Solution Spring 011 Problem 1 A) The weight and buoyancy of the vehicle can be found as follows: W = mg = 15 9.81 = 16.3 N (1) B = 106 4 ( ) 0.6 3 3 π 9.81 =

More information

Nonlinear Observer Design for Dynamic Positioning

Nonlinear Observer Design for Dynamic Positioning Author s Name, Company Title of the Paper DYNAMIC POSITIONING CONFERENCE November 15-16, 2005 Control Systems I J.G. Snijders, J.W. van der Woude Delft University of Technology (The Netherlands) J. Westhuis

More information

Output Feedback Control for Maneuvering Systems Using Observer Backstepping

Output Feedback Control for Maneuvering Systems Using Observer Backstepping Output Feedback Control for Maneuvering Systems Using Observer Backstepping Ivar-André F. Ihle 1 RogerSkjetne and Thor I. Fossen 13 Abstract An output feedback design for maneuvering systems is proposed

More information

SYSTEMTEORI - KALMAN FILTER VS LQ CONTROL

SYSTEMTEORI - KALMAN FILTER VS LQ CONTROL SYSTEMTEORI - KALMAN FILTER VS LQ CONTROL 1. Optimal regulator with noisy measurement Consider the following system: ẋ = Ax + Bu + w, x(0) = x 0 where w(t) is white noise with Ew(t) = 0, and x 0 is a stochastic

More information

Control Systems Design

Control Systems Design ELEC4410 Control Systems Design Lecture 18: State Feedback Tracking and State Estimation Julio H. Braslavsky julio@ee.newcastle.edu.au School of Electrical Engineering and Computer Science Lecture 18:

More information

A Discussion About Seakeeping and Manoeuvring Models For Surface Vessels

A Discussion About Seakeeping and Manoeuvring Models For Surface Vessels A Discussion About Seakeeping and Manoeuvring Models For Surface Vessels Tristan Perez, Thor I. Fossen and Asgeir Sørensen Technical Report (MSS-TR-001) Marine System Simulator (MSS) Group (http://www.cesos.ntnu.no/mss/)

More information

Optimization-Based Control

Optimization-Based Control Optimization-Based Control Richard M. Murray Control and Dynamical Systems California Institute of Technology DRAFT v1.7a, 19 February 2008 c California Institute of Technology All rights reserved. This

More information

Nonlinear Formation Control of Marine Craft

Nonlinear Formation Control of Marine Craft Nonlinear Formation Control of Marine Craft Roger Skjetne, Sonja Moi, and Thor I. Fossen Abstract This paper investigates formation control of a fleet of ships. The control objective for each ship is to

More information

EL 625 Lecture 10. Pole Placement and Observer Design. ẋ = Ax (1)

EL 625 Lecture 10. Pole Placement and Observer Design. ẋ = Ax (1) EL 625 Lecture 0 EL 625 Lecture 0 Pole Placement and Observer Design Pole Placement Consider the system ẋ Ax () The solution to this system is x(t) e At x(0) (2) If the eigenvalues of A all lie in the

More information

Optimization-Based Control

Optimization-Based Control Optimization-Based Control Richard M. Murray Control and Dynamical Systems California Institute of Technology DRAFT v2.1a, January 3, 2010 c California Institute of Technology All rights reserved. This

More information

5. Observer-based Controller Design

5. Observer-based Controller Design EE635 - Control System Theory 5. Observer-based Controller Design Jitkomut Songsiri state feedback pole-placement design regulation and tracking state observer feedback observer design LQR and LQG 5-1

More information

Linear State Feedback Controller Design

Linear State Feedback Controller Design Assignment For EE5101 - Linear Systems Sem I AY2010/2011 Linear State Feedback Controller Design Phang Swee King A0033585A Email: king@nus.edu.sg NGS/ECE Dept. Faculty of Engineering National University

More information

ME 132, Fall 2015, Quiz # 2

ME 132, Fall 2015, Quiz # 2 ME 132, Fall 2015, Quiz # 2 # 1 # 2 # 3 # 4 # 5 # 6 Total NAME 14 10 8 6 14 8 60 Rules: 1. 2 sheets of notes allowed, 8.5 11 inches. Both sides can be used. 2. Calculator is allowed. Keep it in plain view

More information

CONTROL DESIGN FOR SET POINT TRACKING

CONTROL DESIGN FOR SET POINT TRACKING Chapter 5 CONTROL DESIGN FOR SET POINT TRACKING In this chapter, we extend the pole placement, observer-based output feedback design to solve tracking problems. By tracking we mean that the output is commanded

More information

Final Exam TTK 4190 Guidance and Control

Final Exam TTK 4190 Guidance and Control Page 1 of 8 Contact person during the exam: University lecturer Morten Breivik, Department of Engineering Cybernetics, Gløshaugen Phone: 73 5(9 43 62) Cell: 41 52 58 81 Final Exam TTK 4190 Guidance and

More information

Chapter 3. LQ, LQG and Control System Design. Dutch Institute of Systems and Control

Chapter 3. LQ, LQG and Control System Design. Dutch Institute of Systems and Control Chapter 3 LQ, LQG and Control System H 2 Design Overview LQ optimization state feedback LQG optimization output feedback H 2 optimization non-stochastic version of LQG Application to feedback system design

More information

Control Systems Design, SC4026. SC4026 Fall 2010, dr. A. Abate, DCSC, TU Delft

Control Systems Design, SC4026. SC4026 Fall 2010, dr. A. Abate, DCSC, TU Delft Control Systems Design, SC426 SC426 Fall 2, dr A Abate, DCSC, TU Delft Lecture 5 Controllable Canonical and Observable Canonical Forms Stabilization by State Feedback State Estimation, Observer Design

More information

Optimization-Based Control

Optimization-Based Control Optimization-Based Control Richard M. Murray Control and Dynamical Systems California Institute of Technology DRAFT v1.7b, 23 February 2008 c California Institute of Technology All rights reserved. This

More information

Lecture 8. Applications

Lecture 8. Applications Lecture 8. Applications Ivan Papusha CDS270 2: Mathematical Methods in Control and System Engineering May 8, 205 / 3 Logistics hw7 due this Wed, May 20 do an easy problem or CYOA hw8 (design problem) will

More information

State Regulator. Advanced Control. design of controllers using pole placement and LQ design rules

State Regulator. Advanced Control. design of controllers using pole placement and LQ design rules Advanced Control State Regulator Scope design of controllers using pole placement and LQ design rules Keywords pole placement, optimal control, LQ regulator, weighting matrixes Prerequisites Contact state

More information

High-Gain Observers in Nonlinear Feedback Control. Lecture # 3 Regulation

High-Gain Observers in Nonlinear Feedback Control. Lecture # 3 Regulation High-Gain Observers in Nonlinear Feedback Control Lecture # 3 Regulation High-Gain ObserversinNonlinear Feedback ControlLecture # 3Regulation p. 1/5 Internal Model Principle d r Servo- Stabilizing u y

More information

CALIFORNIA INSTITUTE OF TECHNOLOGY Control and Dynamical Systems. CDS 110b

CALIFORNIA INSTITUTE OF TECHNOLOGY Control and Dynamical Systems. CDS 110b CALIFORNIA INSTITUTE OF TECHNOLOGY Control and Dynamical Systems CDS 110b R. M. Murray Kalman Filters 14 January 2007 Reading: This set of lectures provides a brief introduction to Kalman filtering, following

More information

Adaptive Nonlinear Control A Tutorial. Miroslav Krstić

Adaptive Nonlinear Control A Tutorial. Miroslav Krstić Adaptive Nonlinear Control A Tutorial Miroslav Krstić University of California, San Diego Backstepping Tuning Functions Design Modular Design Output Feedback Extensions A Stochastic Example Applications

More information

Multi-Model Adaptive Regulation for a Family of Systems Containing Different Zero Structures

Multi-Model Adaptive Regulation for a Family of Systems Containing Different Zero Structures Preprints of the 19th World Congress The International Federation of Automatic Control Multi-Model Adaptive Regulation for a Family of Systems Containing Different Zero Structures Eric Peterson Harry G.

More information

D(s) G(s) A control system design definition

D(s) G(s) A control system design definition R E Compensation D(s) U Plant G(s) Y Figure 7. A control system design definition x x x 2 x 2 U 2 s s 7 2 Y Figure 7.2 A block diagram representing Eq. (7.) in control form z U 2 s z Y 4 z 2 s z 2 3 Figure

More information

Model Reference Adaptive Control of Underwater Robotic Vehicle in Plane Motion

Model Reference Adaptive Control of Underwater Robotic Vehicle in Plane Motion Proceedings of the 11th WSEAS International Conference on SSTEMS Agios ikolaos Crete Island Greece July 23-25 27 38 Model Reference Adaptive Control of Underwater Robotic Vehicle in Plane Motion j.garus@amw.gdynia.pl

More information

Underactuated Dynamic Positioning of a Ship Experimental Results

Underactuated Dynamic Positioning of a Ship Experimental Results 856 IEEE TRANSACTIONS ON CONTROL SYSTEMS TECHNOLOGY, VOL. 8, NO. 5, SEPTEMBER 2000 Underactuated Dynamic Positioning of a Ship Experimental Results Kristin Y. Pettersen and Thor I. Fossen Abstract The

More information

Nonlinear Tracking Control of Underactuated Surface Vessel

Nonlinear Tracking Control of Underactuated Surface Vessel American Control Conference June -. Portland OR USA FrB. Nonlinear Tracking Control of Underactuated Surface Vessel Wenjie Dong and Yi Guo Abstract We consider in this paper the tracking control problem

More information

Breu, Frequency Detuning of Parametric Roll

Breu, Frequency Detuning of Parametric Roll Frequency Detuning of Parametric Roll Conference on CeSOS Highlights and AMOS Visions, May 29, 2013 Dominik Breu Department of Engineering Cybernetics, NTNU, Trondheim, Norway Centre for Ships and Ocean

More information

EL2520 Control Theory and Practice

EL2520 Control Theory and Practice EL2520 Control Theory and Practice Lecture 8: Linear quadratic control Mikael Johansson School of Electrical Engineering KTH, Stockholm, Sweden Linear quadratic control Allows to compute the controller

More information

Exam. 135 minutes, 15 minutes reading time

Exam. 135 minutes, 15 minutes reading time Exam August 6, 208 Control Systems II (5-0590-00) Dr. Jacopo Tani Exam Exam Duration: 35 minutes, 5 minutes reading time Number of Problems: 35 Number of Points: 47 Permitted aids: 0 pages (5 sheets) A4.

More information

4 Optimal State Estimation

4 Optimal State Estimation 4 Optimal State Estimation Consider the LTI system ẋ(t) = Ax(t)+B w w(t), y(t) = C y x(t)+d yw w(t), z(t) = C z x(t) Problem: Compute (Â,F) such that the output of the state estimator ˆx(t) = ˆx(t) Fy(t),

More information

Automatic Control II Computer exercise 3. LQG Design

Automatic Control II Computer exercise 3. LQG Design Uppsala University Information Technology Systems and Control HN,FS,KN 2000-10 Last revised by HR August 16, 2017 Automatic Control II Computer exercise 3 LQG Design Preparations: Read Chapters 5 and 9

More information

Linear control of inverted pendulum

Linear control of inverted pendulum Linear control of inverted pendulum Deep Ray, Ritesh Kumar, Praveen. C, Mythily Ramaswamy, J.-P. Raymond IFCAM Summer School on Numerics and Control of PDE 22 July - 2 August 213 IISc, Bangalore http://praveen.cfdlab.net/teaching/control213

More information

6 OUTPUT FEEDBACK DESIGN

6 OUTPUT FEEDBACK DESIGN 6 OUTPUT FEEDBACK DESIGN When the whole sate vector is not available for feedback, i.e, we can measure only y = Cx. 6.1 Review of observer design Recall from the first class in linear systems that a simple

More information

Topic # Feedback Control

Topic # Feedback Control Topic #5 6.3 Feedback Control State-Space Systems Full-state Feedback Control How do we change the poles of the state-space system? Or,evenifwecanchangethepolelocations. Where do we put the poles? Linear

More information

LQR, Kalman Filter, and LQG. Postgraduate Course, M.Sc. Electrical Engineering Department College of Engineering University of Salahaddin

LQR, Kalman Filter, and LQG. Postgraduate Course, M.Sc. Electrical Engineering Department College of Engineering University of Salahaddin LQR, Kalman Filter, and LQG Postgraduate Course, M.Sc. Electrical Engineering Department College of Engineering University of Salahaddin May 2015 Linear Quadratic Regulator (LQR) Consider a linear system

More information

Design of a Heading Autopilot for Mariner Class Ship with Wave Filtering Based on Passive Observer

Design of a Heading Autopilot for Mariner Class Ship with Wave Filtering Based on Passive Observer Design of a Heading Autopilot for Mariner Class Ship with Wave Filtering Based on Passive Observer 1 Mridul Pande, K K Mangrulkar 1, Aerospace Engg Dept DIAT (DU), Pune Email: 1 mridul_pande000@yahoo.com

More information

x(n + 1) = Ax(n) and y(n) = Cx(n) + 2v(n) and C = x(0) = ξ 1 ξ 2 Ex(0)x(0) = I

x(n + 1) = Ax(n) and y(n) = Cx(n) + 2v(n) and C = x(0) = ξ 1 ξ 2 Ex(0)x(0) = I A-AE 567 Final Homework Spring 213 You will need Matlab and Simulink. You work must be neat and easy to read. Clearly, identify your answers in a box. You will loose points for poorly written work. You

More information

Problem Description The problem we consider is stabilization of a single-input multiple-state system with simultaneous magnitude and rate saturations,

Problem Description The problem we consider is stabilization of a single-input multiple-state system with simultaneous magnitude and rate saturations, SEMI-GLOBAL RESULTS ON STABILIZATION OF LINEAR SYSTEMS WITH INPUT RATE AND MAGNITUDE SATURATIONS Trygve Lauvdal and Thor I. Fossen y Norwegian University of Science and Technology, N-7 Trondheim, NORWAY.

More information

= 0 otherwise. Eu(n) = 0 and Eu(n)u(m) = δ n m

= 0 otherwise. Eu(n) = 0 and Eu(n)u(m) = δ n m A-AE 567 Final Homework Spring 212 You will need Matlab and Simulink. You work must be neat and easy to read. Clearly, identify your answers in a box. You will loose points for poorly written work. You

More information

PID Control. Objectives

PID Control. Objectives PID Control Objectives The objective of this lab is to study basic design issues for proportional-integral-derivative control laws. Emphasis is placed on transient responses and steady-state errors. The

More information

1 (30 pts) Dominant Pole

1 (30 pts) Dominant Pole EECS C8/ME C34 Fall Problem Set 9 Solutions (3 pts) Dominant Pole For the following transfer function: Y (s) U(s) = (s + )(s + ) a) Give state space description of the system in parallel form (ẋ = Ax +

More information

Controlling the Inverted Pendulum

Controlling the Inverted Pendulum Controlling the Inverted Pendulum Steven A. P. Quintero Department of Electrical and Computer Engineering University of California, Santa Barbara Email: squintero@umail.ucsb.edu Abstract The strategies

More information

Final Exam TTK4190 Guidance and Control

Final Exam TTK4190 Guidance and Control Trondheim Department of engineering Cybernetics Contact person: Professor Thor I. Fossen Phone: 73 59 43 61 Cell: 91 89 73 61 Email: tif@itk.ntnu.no Final Exam TTK4190 Guidance and Control Friday May 15,

More information

Multi-Robotic Systems

Multi-Robotic Systems CHAPTER 9 Multi-Robotic Systems The topic of multi-robotic systems is quite popular now. It is believed that such systems can have the following benefits: Improved performance ( winning by numbers ) Distributed

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

Feedback Control part 2

Feedback Control part 2 Overview Feedback Control part EGR 36 April 19, 017 Concepts from EGR 0 Open- and closed-loop control Everything before chapter 7 are open-loop systems Transient response Design criteria Translate criteria

More information

CALIFORNIA INSTITUTE OF TECHNOLOGY Control and Dynamical Systems. CDS 110b

CALIFORNIA INSTITUTE OF TECHNOLOGY Control and Dynamical Systems. CDS 110b CALIFORNIA INSTITUTE OF TECHNOLOGY Control and Dynamical Systems CDS 110b R. M. Murray Kalman Filters 25 January 2006 Reading: This set of lectures provides a brief introduction to Kalman filtering, following

More information

Here represents the impulse (or delta) function. is an diagonal matrix of intensities, and is an diagonal matrix of intensities.

Here represents the impulse (or delta) function. is an diagonal matrix of intensities, and is an diagonal matrix of intensities. 19 KALMAN FILTER 19.1 Introduction In the previous section, we derived the linear quadratic regulator as an optimal solution for the fullstate feedback control problem. The inherent assumption was that

More information

Topic # Feedback Control Systems

Topic # Feedback Control Systems Topic #17 16.31 Feedback Control Systems Deterministic LQR Optimal control and the Riccati equation Weight Selection Fall 2007 16.31 17 1 Linear Quadratic Regulator (LQR) Have seen the solutions to the

More information

Chap. 3. Controlled Systems, Controllability

Chap. 3. Controlled Systems, Controllability Chap. 3. Controlled Systems, Controllability 1. Controllability of Linear Systems 1.1. Kalman s Criterion Consider the linear system ẋ = Ax + Bu where x R n : state vector and u R m : input vector. A :

More information

Wind Turbine Control

Wind Turbine Control Wind Turbine Control W. E. Leithead University of Strathclyde, Glasgow Supergen Student Workshop 1 Outline 1. Introduction 2. Control Basics 3. General Control Objectives 4. Constant Speed Pitch Regulated

More information

COMBINED ADAPTIVE CONTROLLER FOR UAV GUIDANCE

COMBINED ADAPTIVE CONTROLLER FOR UAV GUIDANCE COMBINED ADAPTIVE CONTROLLER FOR UAV GUIDANCE B.R. Andrievsky, A.L. Fradkov Institute for Problems of Mechanical Engineering of Russian Academy of Sciences 61, Bolshoy av., V.O., 199178 Saint Petersburg,

More information

EE C128 / ME C134 Final Exam Fall 2014

EE C128 / ME C134 Final Exam Fall 2014 EE C128 / ME C134 Final Exam Fall 2014 December 19, 2014 Your PRINTED FULL NAME Your STUDENT ID NUMBER Number of additional sheets 1. No computers, no tablets, no connected device (phone etc.) 2. Pocket

More information

Comparison of Feedback Controller for Link Stabilizing Units of the Laser Based Synchronization System used at the European XFEL

Comparison of Feedback Controller for Link Stabilizing Units of the Laser Based Synchronization System used at the European XFEL Comparison of Feedback Controller for Link Stabilizing Units of the Laser Based Synchronization System used at the European XFEL M. Heuer 1 G. Lichtenberg 2 S. Pfeiffer 1 H. Schlarb 1 1 Deutsches Elektronen

More information

Comparison of four state observer design algorithms for MIMO system

Comparison of four state observer design algorithms for MIMO system Archives of Control Sciences Volume 23(LIX), 2013 No. 2, pages 131 144 Comparison of four state observer design algorithms for MIMO system VINODH KUMAR. E, JOVITHA JEROME and S. AYYAPPAN A state observer

More information

Lec 6: State Feedback, Controllability, Integral Action

Lec 6: State Feedback, Controllability, Integral Action Lec 6: State Feedback, Controllability, Integral Action November 22, 2017 Lund University, Department of Automatic Control Controllability and Observability Example of Kalman decomposition 1 s 1 x 10 x

More information

A FEEDBACK STRUCTURE WITH HIGHER ORDER DERIVATIVES IN REGULATOR. Ryszard Gessing

A FEEDBACK STRUCTURE WITH HIGHER ORDER DERIVATIVES IN REGULATOR. Ryszard Gessing A FEEDBACK STRUCTURE WITH HIGHER ORDER DERIVATIVES IN REGULATOR Ryszard Gessing Politechnika Śl aska Instytut Automatyki, ul. Akademicka 16, 44-101 Gliwice, Poland, fax: +4832 372127, email: gessing@ia.gliwice.edu.pl

More information

Problem Set 4 Solution 1

Problem Set 4 Solution 1 Massachusetts Institute of Technology Department of Electrical Engineering and Computer Science 6.245: MULTIVARIABLE CONTROL SYSTEMS by A. Megretski Problem Set 4 Solution Problem 4. For the SISO feedback

More information

Every real system has uncertainties, which include system parametric uncertainties, unmodeled dynamics

Every real system has uncertainties, which include system parametric uncertainties, unmodeled dynamics Sensitivity Analysis of Disturbance Accommodating Control with Kalman Filter Estimation Jemin George and John L. Crassidis University at Buffalo, State University of New York, Amherst, NY, 14-44 The design

More information

Neural Network Model Reference Adaptive Control of a Surface Vessel

Neural Network Model Reference Adaptive Control of a Surface Vessel Neural Network Model Reference Adaptive Control of a Surface Vessel Alexander Leonessa and Tannen S. VanZwieten Abstract A neural network model reference adaptive controller for trajectory tracking of

More information

Spacecraft Attitude Control with RWs via LPV Control Theory: Comparison of Two Different Methods in One Framework

Spacecraft Attitude Control with RWs via LPV Control Theory: Comparison of Two Different Methods in One Framework Trans. JSASS Aerospace Tech. Japan Vol. 4, No. ists3, pp. Pd_5-Pd_, 6 Spacecraft Attitude Control with RWs via LPV Control Theory: Comparison of Two Different Methods in One Framework y Takahiro SASAKI,),

More information

Lecture 15: H Control Synthesis

Lecture 15: H Control Synthesis c A. Shiriaev/L. Freidovich. March 12, 2010. Optimal Control for Linear Systems: Lecture 15 p. 1/14 Lecture 15: H Control Synthesis Example c A. Shiriaev/L. Freidovich. March 12, 2010. Optimal Control

More information

Optimal control and estimation

Optimal control and estimation Automatic Control 2 Optimal control and estimation Prof. Alberto Bemporad University of Trento Academic year 2010-2011 Prof. Alberto Bemporad (University of Trento) Automatic Control 2 Academic year 2010-2011

More information

Controls Problems for Qualifying Exam - Spring 2014

Controls Problems for Qualifying Exam - Spring 2014 Controls Problems for Qualifying Exam - Spring 2014 Problem 1 Consider the system block diagram given in Figure 1. Find the overall transfer function T(s) = C(s)/R(s). Note that this transfer function

More information

1. Find the solution of the following uncontrolled linear system. 2 α 1 1

1. Find the solution of the following uncontrolled linear system. 2 α 1 1 Appendix B Revision Problems 1. Find the solution of the following uncontrolled linear system 0 1 1 ẋ = x, x(0) =. 2 3 1 Class test, August 1998 2. Given the linear system described by 2 α 1 1 ẋ = x +

More information

State Observers and the Kalman filter

State Observers and the Kalman filter Modelling and Control of Dynamic Systems State Observers and the Kalman filter Prof. Oreste S. Bursi University of Trento Page 1 Feedback System State variable feedback system: Control feedback law:u =

More information

A Ship Heading and Speed Control Concept Inherently Satisfying Actuator Constraints

A Ship Heading and Speed Control Concept Inherently Satisfying Actuator Constraints A Ship Heading and Speed Control Concept Inherently Satisfying Actuator Constraints Mikkel Eske Nørgaard Sørensen, Morten Breivik and Bjørn-Olav H. Eriksen Abstract Satisfying actuator constraints is often

More information

= m(0) + 4e 2 ( 3e 2 ) 2e 2, 1 (2k + k 2 ) dt. m(0) = u + R 1 B T P x 2 R dt. u + R 1 B T P y 2 R dt +

= m(0) + 4e 2 ( 3e 2 ) 2e 2, 1 (2k + k 2 ) dt. m(0) = u + R 1 B T P x 2 R dt. u + R 1 B T P y 2 R dt + ECE 553, Spring 8 Posted: May nd, 8 Problem Set #7 Solution Solutions: 1. The optimal controller is still the one given in the solution to the Problem 6 in Homework #5: u (x, t) = p(t)x k(t), t. The minimum

More information

EECS C128/ ME C134 Final Wed. Dec. 15, am. Closed book. Two pages of formula sheets. No calculators.

EECS C128/ ME C134 Final Wed. Dec. 15, am. Closed book. Two pages of formula sheets. No calculators. Name: SID: EECS C28/ ME C34 Final Wed. Dec. 5, 2 8- am Closed book. Two pages of formula sheets. No calculators. There are 8 problems worth points total. Problem Points Score 2 2 6 3 4 4 5 6 6 7 8 2 Total

More information

Problem Set 2 Solutions 1

Problem Set 2 Solutions 1 Massachusetts Institute of echnology Department of Electrical Engineering and Computer Science 6.45: MULIVARIABLE CONROL SYSEMS by A. Megretski Problem Set Solutions Problem. For each of the statements

More information

6.241 Dynamic Systems and Control

6.241 Dynamic Systems and Control 6.241 Dynamic Systems and Control Lecture 24: H2 Synthesis Emilio Frazzoli Aeronautics and Astronautics Massachusetts Institute of Technology May 4, 2011 E. Frazzoli (MIT) Lecture 24: H 2 Synthesis May

More information

Global stabilization of an underactuated autonomous underwater vehicle via logic-based switching 1

Global stabilization of an underactuated autonomous underwater vehicle via logic-based switching 1 Proc. of CDC - 4st IEEE Conference on Decision and Control, Las Vegas, NV, December Global stabilization of an underactuated autonomous underwater vehicle via logic-based switching António Pedro Aguiar

More information

Numerics and Control of PDEs Lecture 1. IFCAM IISc Bangalore

Numerics and Control of PDEs Lecture 1. IFCAM IISc Bangalore 1/1 Numerics and Control of PDEs Lecture 1 IFCAM IISc Bangalore July 22 August 2, 2013 Introduction to feedback stabilization Stabilizability of F.D.S. Mythily R., Praveen C., Jean-Pierre R. 2/1 Q1. Controllability.

More information

Chapter 9 Observers, Model-based Controllers 9. Introduction In here we deal with the general case where only a subset of the states, or linear combin

Chapter 9 Observers, Model-based Controllers 9. Introduction In here we deal with the general case where only a subset of the states, or linear combin Lectures on Dynamic Systems and Control Mohammed Dahleh Munther A. Dahleh George Verghese Department of Electrical Engineering and Computer Science Massachuasetts Institute of Technology c Chapter 9 Observers,

More information

Topic # Feedback Control Systems

Topic # Feedback Control Systems Topic #15 16.31 Feedback Control Systems State-Space Systems Open-loop Estimators Closed-loop Estimators Observer Theory (no noise) Luenberger IEEE TAC Vol 16, No. 6, pp. 596 602, December 1971. Estimation

More information

Extensions and applications of LQ

Extensions and applications of LQ Extensions and applications of LQ 1 Discrete time systems 2 Assigning closed loop pole location 3 Frequency shaping LQ Regulator for Discrete Time Systems Consider the discrete time system: x(k + 1) =

More information

State estimation and the Kalman filter

State estimation and the Kalman filter State estimation and the Kalman filter PhD, David Di Ruscio Telemark university college Department of Technology Systems and Control Engineering N-3914 Porsgrunn, Norway Fax: +47 35 57 52 50 Tel: +47 35

More information

ECEn 483 / ME 431 Case Studies. Randal W. Beard Brigham Young University

ECEn 483 / ME 431 Case Studies. Randal W. Beard Brigham Young University ECEn 483 / ME 431 Case Studies Randal W. Beard Brigham Young University Updated: December 2, 2014 ii Contents 1 Single Link Robot Arm 1 2 Pendulum on a Cart 9 3 Satellite Attitude Control 17 4 UUV Roll

More information

State Feedback MAE 433 Spring 2012 Lab 7

State Feedback MAE 433 Spring 2012 Lab 7 State Feedback MAE 433 Spring 1 Lab 7 Prof. C. Rowley and M. Littman AIs: Brandt Belson, onathan Tu Princeton University April 4-7, 1 1 Overview This lab addresses the control of an inverted pendulum balanced

More information

Autonomous Mobile Robot Design

Autonomous Mobile Robot Design Autonomous Mobile Robot Design Topic: Guidance and Control Introduction and PID Loops Dr. Kostas Alexis (CSE) Autonomous Robot Challenges How do I control where to go? Autonomous Mobile Robot Design Topic:

More information

1 Steady State Error (30 pts)

1 Steady State Error (30 pts) Professor Fearing EECS C28/ME C34 Problem Set Fall 2 Steady State Error (3 pts) Given the following continuous time (CT) system ] ẋ = A x + B u = x + 2 7 ] u(t), y = ] x () a) Given error e(t) = r(t) y(t)

More information

Exam - TTK 4190 Guidance & Control Eksamen - TTK 4190 Fartøysstyring

Exam - TTK 4190 Guidance & Control Eksamen - TTK 4190 Fartøysstyring Page 1 of 6 Norges teknisk- naturvitenskapelige universitet Institutt for teknisk kybernetikk Faglig kontakt / contact person: Navn: Morten Pedersen, Universitetslektor Tlf.: 41602135 Exam - TTK 4190 Guidance

More information

OBJECTIVE DIRECTED CONTROL USING LOCAL MINIMISATION FOR AN AUTONOMOUS UNDERWATER VEHICLE

OBJECTIVE DIRECTED CONTROL USING LOCAL MINIMISATION FOR AN AUTONOMOUS UNDERWATER VEHICLE OBJECTIVE DIRECTED CONTROL USING LOCAL MINIMISATION FOR AN AUTONOMOUS UNDERWATER VEHICLE Lars Alminde, Jan D. Bendtsen, Jakob Stoustrup and Kristin Y. Pettersen Department of Electronic Systems, Section

More information

Chapter 4 The Equations of Motion

Chapter 4 The Equations of Motion Chapter 4 The Equations of Motion Flight Mechanics and Control AEM 4303 Bérénice Mettler University of Minnesota Feb. 20-27, 2013 (v. 2/26/13) Bérénice Mettler (University of Minnesota) Chapter 4 The Equations

More information

Topic # /31 Feedback Control Systems. Analysis of Nonlinear Systems Lyapunov Stability Analysis

Topic # /31 Feedback Control Systems. Analysis of Nonlinear Systems Lyapunov Stability Analysis Topic # 16.30/31 Feedback Control Systems Analysis of Nonlinear Systems Lyapunov Stability Analysis Fall 010 16.30/31 Lyapunov Stability Analysis Very general method to prove (or disprove) stability of

More information

Department of Electronics and Instrumentation Engineering M. E- CONTROL AND INSTRUMENTATION ENGINEERING CL7101 CONTROL SYSTEM DESIGN Unit I- BASICS AND ROOT-LOCUS DESIGN PART-A (2 marks) 1. What are the

More information

DESIGN OF A HYBRID POWER/TORQUE THRUSTER CONTROLLER WITH LOSS ESTIMATION. Øyvind N. Smogeli, Asgeir J. Sørensen and Thor I. Fossen

DESIGN OF A HYBRID POWER/TORQUE THRUSTER CONTROLLER WITH LOSS ESTIMATION. Øyvind N. Smogeli, Asgeir J. Sørensen and Thor I. Fossen DESIGN OF A HYBRID POWER/TORQUE THRUSTER CONTROLLER WITH LOSS ESTIMATION Øyvind N. Smogeli, Asgeir J. Sørensen and Thor I. Fossen Department of Marine Technology Norwegian University of Science and Technology

More information

EEE 184: Introduction to feedback systems

EEE 184: Introduction to feedback systems EEE 84: Introduction to feedback systems Summary 6 8 8 x 7 7 6 Level() 6 5 4 4 5 5 time(s) 4 6 8 Time (seconds) Fig.. Illustration of BIBO stability: stable system (the input is a unit step) Fig.. step)

More information

State space control for the Two degrees of freedom Helicopter

State space control for the Two degrees of freedom Helicopter State space control for the Two degrees of freedom Helicopter AAE364L In this Lab we will use state space methods to design a controller to fly the two degrees of freedom helicopter. 1 The state space

More information

Adaptive Output Feedback Based on Closed-Loop. Reference Models for Hypersonic Vehicles

Adaptive Output Feedback Based on Closed-Loop. Reference Models for Hypersonic Vehicles Adaptive Output Feedback Based on Closed-Loop Reference Models for Hypersonic Vehicles Daniel P. Wiese 1 and Anuradha M. Annaswamy 2 Massachusetts Institute of Technology, Cambridge, MA 02139 Jonathan

More information

Linear Quadratic Gausssian Control Design with Loop Transfer Recovery

Linear Quadratic Gausssian Control Design with Loop Transfer Recovery Linear Quadratic Gausssian Control Design with Loop Transfer Recovery Leonid Freidovich Department of Mathematics Michigan State University MI 48824, USA e-mail:leonid@math.msu.edu http://www.math.msu.edu/

More information

Topic # Feedback Control. State-Space Systems Closed-loop control using estimators and regulators. Dynamics output feedback

Topic # Feedback Control. State-Space Systems Closed-loop control using estimators and regulators. Dynamics output feedback Topic #17 16.31 Feedback Control State-Space Systems Closed-loop control using estimators and regulators. Dynamics output feedback Back to reality Copyright 21 by Jonathan How. All Rights reserved 1 Fall

More information

Dynamics and Control of Rotorcraft

Dynamics and Control of Rotorcraft Dynamics and Control of Rotorcraft Helicopter Aerodynamics and Dynamics Abhishek Department of Aerospace Engineering Indian Institute of Technology, Kanpur February 3, 2018 Overview Flight Dynamics Model

More information