Adaptive Self-triggered Control of a Remotely Operated Robot

Size: px
Start display at page:

Download "Adaptive Self-triggered Control of a Remotely Operated Robot"

Transcription

1 Adaptive Self-triggered Control of a Remotely Operated Robot Carlos Santos 1, Manuel Mazo Jr. 23, and Felipe Espinosa 1 1 Electronics Department, University of Alcala (Spain). 2 INCAS3, Assen (The Netherlands), 3 Faculty of Mathematics and Natural Sciences, University of Groningen (The Netherlands) Abstract. We consider the problem of remotely operating an autonomous robot through a wireless communication channel. Our goal is to achieve a satisfactory tracking performance while reducing network usage. To attain this objective we implement a self-triggered strategy that adjusts the triggering condition to the observed tracking error. After the theoretical justification we present experimental results from the application of this adaptive self-triggered approach on a P3-DX mobile robot remotely controlled. The experiments show a relevant reduction on the generated network traffic compared to a periodic implementation and to a non-adaptive self-triggered approach, while the tracking performance is barely degraded. 1 Introduction Network Control Systems (NCSs) are spatially distributed systems in which the communication between plants (including sensors and actuators) and controllers occurs through a shared digital network with limited bandwidth [10]. The real-time implementation of these systems using periodic control laws presents two main limitations: the inefficient use of the electronic resources available; and the overload of the communication channel. This has motivated the appearance of many techniques based on the idea of sampling only when necessary [12], [13], [3], [18], [19], [21]. These techniques use feedback from the state of the plant to decide when the control signal needs to be recomputed with recent measurements, two of the most important are event-triggered and self-triggered techniques. In event-triggered control implementations [18], [3], the current state of the plant is measured constantly in order to decide when the control execution must be triggered. Consequently, these implementations require dedicated resources to continuously supervise the state of the plant. The main idea of self-triggered control is to emulate the event-triggered implementation, instead of measuring continuously the state of the plant [12], [13], and determining the next update times from the last measurement acquired. In this way no continuous monitoring of the state of the plant is required. We propose a practical improvement on the self-triggering control technique on [12], [13]. This modification consists on adapting the triggering condition to the tracking error, thus

2 establishing a trade-off between the number of accesses to the wireless channel and the control performance. In the robotics context, NCS are especially interesting for remote control and cooperative guidance. Examples of remote control can be found in [17] where a DC motor is periodically controlled using a TCP/IP network communication; in [15] where a fixed-time sampling PID is remotely implemented to control a thermal system; and in [20] where a robotic vehicle is bilaterally tele-operated by means of a power-based passivity controller implemented with a periodic sampling time. Much work has been devoted to the cooperative guidance of robots, for example the string stability of a convoy is studied in [4] and [22]. Some of the authors of this paper have also designed control solutions for the remote control of a robotic unit [6] and for the guidance of robots platooning [2], [7], [16], [8], but always implemented with periodic sampling. However, in the context of robotics formation or applications based on robotics tele-operation is of foremost importance to minimize the computational load of the on-board electronics system of the mobile unit [9], [14], as well as to reduce the communications burden. This justifies the objective of this paper: the design and implementation of NCS for robotic applications minimizing the wireless communications load enabling other applications to share the channel bandwidth and the on-board electronic resources. As a first approach we consider a scenario where a Pioneer P3-DX robot is remotely guided and controlled from a PC working as remote center. The remote center (RC) runs a self-triggered velocity servo-controller with an adaptive triggering condition. The adaptive solution goal is to relax the performance requirements of the controller when the system is close to the equilibrium point. In this way the wireless network traffic is greatly reduced while the tracking performance is not degraded significantly. 2 Theory In this section we introduce the notions of self-triggered control for time-invariant linear systems on the continuous time domain, the specific problem statement and the interest of applying an adaptive triggering condition to solve it. 2.1 Preliminaries We denote by R + the positive real number, by R + 0 = R+ {0} and by N the natural numbers. The usual Euclidean (l 2 ) vector norm is represented by. We remind the readers of a classic result on stability theory for linear systems in the following theorem, see e.g. [1]. Theorem 1 A linear system ẋ = Ax is exponentially stable, i.e. M, λ R + such that x(t) Me λt x(0), if and only if there exists positive definite matrices P, Q such that: A T P + P A Q. (1) If the linear system is stable then, the function V (t) = x(t) T P x(t) is said to be a Lyapunov function for the system.

3 2.2 Self-triggered Control Review In this section, we briefly review the self-triggering policy presented in [12]. The system under consideration is ẋ(t) = Ax(t) + Bu(t) y(t) = Cx(t) where A R nxn, B R nxr, C R mxn are the characteristic matrices and x(t) R n, u(t) R r and y(t) R m the state, input and output vectors respectively. If the pair (A, B) is stabilizable we find a linear feedback controller rendering the closed loop asymptotically stable: u(t) = Kx(t) The resulting closed loop system is thus described by the equation: ẋ(t) = (A + BK)x(t) If the closed loop system is asymptotically stable, there exists a Lyapunov function of the form V (t) = x(t) T P x(t) where function V (t) is considered to be positive-definite. Given a symmetric and positive-definite matrix Q, P is the solution to the Lyapunov equation (1). Now we define the state measurement error as e(t) = x(t k ) x(t), t [t k, t k+1 [ where t k is the latest actuation update instant. At the sampling instant t k, the state variable vector x(t k ) is available through measurement and provides the current plant information. That is, at times t k the controller is recomputed with fresh measurements and the input kept constant until a new measurement is received, i.e.: u(t) = kx(t k ), t [t k, t k+1 [ The closed loop dynamics under this sample and hold implementation of the controller is: [ẋ(t) ] [ ] [ ] A + BK BK x(t) = t [t ė(t) A BK BK e(t) k, t k+1 [ (2) e(t k ) = 0 The objective of the self-triggered control strategy is finding a sequence of update times {t k } such that the number of updates is minimized while stability is preserved. This sequence will be implicitly defined as the times when some triggering condition is violated. To guarantee the stability of the closed loop implementation we introduce a performance function S : R + 0 Rn R + 0.

4 This function is forced to upper-bound the evolution of V, thus determining the desired performance of the implementation. Hence, the update times {t k } are determined by the time instants at which: V (t, x t0 ) S(t, x t0 ), t t 0 is violated. The inter-executions times (t k+1 t k ) should be lower bounded by some positive quantity τ min in order to avoid Zeno executions 4 [23] of the hybrid system (2). In order to guarantee inter-execution times greater than zero it is sufficient to design S satisfying V (t k ) < Ṡ(t k) at the execution times t k. In [12] it is suggested the use of a function S(t) given by: S(t) := x s (t) T P x s (t) x s (t) = A s x s (t k ), t [t k, t k+1 [ x s (t k ) = x(t k ) where A s is a Hurwitz matrix 5 satisfying the Lyapunov equation: A T s P + P A s = R with 0 < R < Q, which guarantees that V (t k ) < Ṡ(t k). The matrix R describes the stability requirements for the implementation as it defines A s, which in turn determines S(t). Finally, how can one compute the next time the controller needs to be refreshed with new measurements? Following the technique in [13], one can predict from a measurement at time t k and the dynamics of the system, the evolution of the state x(t k + τ), τ R +. Thus, one can compute ahead of time V and S at times separated units of time, and check if V (t k + p, x tk ) S(t k + p, x tk ), p [1, 2,..., N], for N N some pre-specified horizon. Then, one can compute t k+1 = t k + p such that: either p = N or V (t k + (p + 1), x tk ) > S(t k + (p + 1), x tk ). Note that the discretization time selected for the implementation should be greater than τ min. In our application we want to perform tracking of piecewise constant reference signals. This means that for non-zero references the equilibrium of the system x eq is different than the origin, while all the above discussion is performed assuming the equilibrium of the system to be the origin. Nonetheless, this poses no problem, as the new equilibrium point is easily computed from the reference, and a simple change of coordinates: x = x x eq, brings the equilibrium back to the origin. 4 A Zeno execution, in our context, is an execution of the system in which an infinite number of discrete events (transmissions) happen within a finite time interval. 5 A square matrix A is said to be Hurwitz if all of its eigenvalues have strictly negative real part.

5 2.3 Adaptive Self-triggering Condition One of the contributions of this work, besides the practical demonstration on a robotics application, is the proposal of an adaptive self-triggering condition. To assure the condition V (t k ) < Ṡ(t k), we pick R = σq where 0 < σ < 1. The choice of σ provides a trade-off between the number of updates and the stability requirements. In a qualitative way, it can be said that if σ 0 we achieve a significant reduction on the controller updates and a corresponding degradation of the performance. On the other hand, when σ 1 one obtains a better performance at the cost of an increase in the number of updates. To evaluate the performance of the control system the Integral of the Squared Error (ISE) [5] Index is applied to the output tracking: ISE = ˆ 0 y(t) y ref (t) 2 dt. In our experiments we compute the ISE from sampled measurements, thus instead of the formula above we use: ISE = y(k ) y ref (k ) 2. k=0 The key idea of the adaptive triggering condition is to take advantage of the benefits of executions reduction (σ 0) without losing performance (σ 1). In order to achieve this, we select the value of σ depending on the deviation of the state vector of its equilibrium point, that means x(t) x eq. When x(t) x eq is significant we work with the highest range of the triggering condition (σ 1) to achieve a fast response of the control system. On the other hand, when x(t) x eq is small enough we work with the lowest range (σ 0) to obtain a significant reduction of the controller updates. The threshold values delimiting the mentioned ranges of x(t) x eq are selected ad-hoc after experimental tests on the under study as it is explained in next section. 3 Experimental Set-up and Results The objective of this work is the evaluation of a remote adaptive self-triggered servo-controller of a minimally instrumented robotic unit. The robotic unit only incorporates the lowest control level associated to the active wheels and a digital observer to recover the full state of the robot from odometric information (providing linear and angular velocities of the mobile). The remote center, a PC in the same wireless network as the robot, deals with three main tasks: generation of the velocity reference vector, calculation of the robotic control vector and execution of the self-triggered scheduler. The last one is responsible for deciding when the control action has to be applied and, at the same time, when the plant

6 state vector estimation has to be updated. It is clear that the highest the interval inter-executions the lowest the load of the wireless channel. Figure 1 shows the global structure of the self-triggered control remotely implemented and Figure 2 presents a picture of the actual setup. Fig. 1. Structure of the implemented self-triggered servo control Fig. 2. P3-DX robot tele-operated from a remote center. 3.1 Plant Model The first stage for the experimental set-up is modeling the P3-DX robot from the remote center side, that means including the wireless channel as part of the plant to be controlled. For this matter, we consider an idealized channel without disturbances and/or packet dropouts, and thus the delay exhibited by the channel can be considered constant. The plant model has been obtained with standard system identification techniques and validated through experimental trials. Linear and angular velocity references (components of input vector u) were sent to the robot (including its embedded control loops) and the open-loop robotic response (linear and angular velocities as output vector y) was registered. A constant channel delay of L seconds is included as part of the plant model, where this non-linear element is approximated through a P ade (1, 1) approximation [5], [11]. A P ade (p, q) method approximates in the Laplace domain a delay by a rational model, being p the

7 numerator degree and q the denominator degree. In our case, the channel delay L is approximated as: e Ls 1 L 2 s 1 + L 2 s. The resulting continuous state-space model of the P3-DX robotic unit is: where: ṙ(t) = A d r(t) + B d u(t) = r(t) u(t) [ ] y(t) = C d r(t) = r(t) r(t) R 4 is the plant state vector; the first two components correspond with the output plant and the other ones are related to the wireless channel delays. u(t) R 2 is the input state vector (linear and angular velocities sent to the robot); y(t) R 2 is the measurement vector (linear and angular velocities obtained from the odometric system). 3.2 Servocontroller Design for Robotic Guidance To properly track the linear and angular velocities references we designed a servo-system. The structure of the servo-system, shown in Figure 3, assures null tracking error in steady state. Because the full state of the system r is not accessible from measurements, an observer is included in the robot to provide, based on the output measurements y, estimates of the state. Nevertheless, we design our controller relying on the separation principle [5] (between estimation and control) and apply an LQR design technique to the original dynamics extended with the integrator state n. In doing this, we are assuming the full state vector is available, i.e. we design the controller constants K I and K R for the following system: [ ] [ ] [ ] [ ] ṙ(t) Ad 0 r(t) Bd [ ] [ ] [ ] r(t) 0 = + KR K ṅ(t) C d 0 n(t) 0 I + y n(t) I ref (t). The weighting matrices used in the LQR design are: [ ] 0.1I2x2 0 Q LQR = 2x4 ; R 0 4x2 I LQR = I 2x2 4x4 and the resulting constants of the controller K R and K I are: [ ] [ K R = K I = ].

8 Fig. 3. Block diagram of the remote servo control for the robot guidance. Wireless links are represented by dotted arrows. The matrix P used in the self-triggered implementation is the one resulting from solving equation (1) with: [ ] [ ] Ad 0 Bd [ ] A = + KR K C d 0 0 I ; Q = I. (3) For a maximum value of σ = 0.9, with the provided design, the resulting minimum inter-transmission times is 35ms., and therefore we selected a sampling time of 10ms. for the sensors of the robot. This is also the time-step used in the self-triggered implementation to predict the next measurements transmission, as described in [12] and reviewed in Section 2.2. Independently of the controller design, we construct a discrete time Luenberger observer [11] (for the discretized system with sampling time ). The designed observer gain in discrete time is: L = The observer is periodically executed at every discretization step ( = 10ms) at the robot, which provides with the same granularity at which the self-triggered implementation runs, thus avoiding any issues when using the estimates in the self-triggered controller implementation Adaptive Self-triggered Implementation As previously stated, the triggering condition is chosen depending on the deviation from the equilibrium state x(t) x eq, being x(t) = [r(t) T n(t) T ] T and x eq = A 1 [0, y eq ] T, where A is defined as in (3). In other words, choosing the right σ values we achieve a balance between reduction on the number of updates of the remote control and the system performance level, as described in Section 2.3.

9 From all the possibilities for the triggering condition, σ ]0, 1[, we consider only three values, each one applied to the case of: lowest magnitude (σ 1 ), middle magnitude (σ 2 ) and highest magnitude (σ 3 ) of the tracking error. 1. σ 1 = 0.1, for values of x(t) x eq 0.01, that means state variables near to equilibrium point; 2. σ 2 = 0.5, for values of 0.01 < x(t) x eq 0.1, for half-way situations; 3. σ 3 = 0.9, for values of x(t) x eq > 0.1, when a change in the reference is applied and a quick answer of the servo-control is required. 3.4 Experimental results In order to evaluate the proposal we carried out three experiments on the remote guidance of the robotic unit. A combination of linear and angular velocities have been chosen as references and the servo-control is implemented in the remote center according to the block diagram shown in Figure 3. Every time the triggering condition is violated the control action is sent to the P3-DX robotic unit and the remote center receives information of the plant state variables. We considered for comparison purposes three different implementations of the controller: 1. A periodic implementation with constant sampling period equal to the discretization step = 10ms. 2. A conventional self triggered implementation presented in [12] with two fixed triggered conditions: one close to 0 (σ = 0.1) and other close to 1 (σ = 0.9). 3. An adaptive self-triggered implementation applying the triggering condition described in section 3.3. In Figure 4, the linear velocity (first component of the output vector y(t)) captured from the P3-DX through the odometric system with different implementations. The left top figure corresponds to a fixed sampling time (10ms), and from it a good tracking solution is appreciated. The top right figure shows a high-performance self-triggered implementation (σ = 0.9), the bottom-left figure shows a low-performance self-triggered implementation (σ = 0.1), and the bottom-right figure shows our adaptive self-triggered solution. It can be appreciated that the highest the value of σ the best the servo-control performance. Nevertheless, the adaptive self-triggering solution presents a balanced solution with lower number of channel access and a good control performance. A similar behavior was observed for the tracking of the angular velocity (second component of the output vector y(t)), which for the sake of space are omitted from the paper. These observed behavior is confirmed employing a performance measure as the ISE to measure the quality of the tracking, and the number of transmissions for the network load. Table 1 summarizes these performance measurements allowing to compare the previously mentioned experiments and confirming the benefits of the authors proposal. The adaptive solution presents, without a significant system performance degradation, a number of updates (wireless transmissions)

10 Fig. 4. Linear velocity registered (red line) when a reference (blue line) is applied to the robot. Results from different implementations are shown: periodic sampling (upper left corner), fixed high value of the sigma parameter (upper right corner), fixed low value of the sigma parameter (lower left corner) and adaptive solution proposed by the authors (lower right corner). σ = 0.1 σ = 0.9 σadaptive Periodic 10 ms Updates(Wifi Tx) Average time between updates (ms) ISE performance index Table 1. Key parameters for comparison of the experimental results concerning the different control strategies

11 significantly lower than the periodic case and the non-adaptive self-triggered solution with σ = 0.9. Finally, we want to note how in the self-triggered implementations there is a certain delay in reacting to changes on the commands. This is due to the fact that transmissions are scheduled before hand when a measurement was received. Thus, if the reference is updated before the next scheduled measurements the system does not react to it until the next measurement arrives. This can easily be addressed by requesting from the RC forced measurements whenever the reference changes and it will be included in our future developments. 4 Conclusions and future work We have shown in a real mobile robot how a rather simple implementation of a tracking controller in self-triggered form can greatly reduce the amount of changes in the control signals applied to the robot. This in turn helps reducing the network traffic when applied in a tele-robotics context. In this way, communications resources are liberated for other applications, e.g. video streams, sharing the channel bandwidth. One critical shortcoming of the self-triggered technique employed is the necessity of state-feedback, while, as illustrated in our application, it is quite common to not have access to the full state from measurements. Inspired by the classic separation principle we designed an observer running at the robot to obtain that way state estimates that could be used by the control scheme. A more detailed and careful theoretical study might be required to have a more solid theoretical justification of the efficacy of this solution. In the current implementation we also assumed constant delays, which given our single robot set-up was a reasonable assumption. Nevertheless, our goal is to have a set of robots moving in convoy and on real (not laboratory) conditions. This more realistic setup will present variable delays in the communications, which need also to be handled in a more elaborate way. References 1. Antsaklis, P., Michel, A.N.: Linear Systems. McGraw-Hill (1997) 2. Bocos, A., Espinosa, F., Salazar, M., Valdés, F.: Compensation of channel packet dropout based on TVKF optimal estimator for robotics teleoperation. In: International Conference on Robotics and Automation (ICRA) (2008) 3. Cogill, R.: Event-based control using quadratic approximate value functions. In: Proceedings of the 48th IEEE Conference on Decision and Control. pp (Dec 2009) 4. Dunbar, W., Caveney, D.: Distributed receding horizon control of vehicle platoons: Stability and string stability. IEEE Transactions on Automatic Control 57(3), (march 2012) 5. Duton, K., Thompson, S., Barraclough, B.: The art of control engineering. Addison- Wesley (1997) 6. Espinosa, F., Salazar, M., Pizarro, D., Valdés, F.: Electronics proposal for telerobotics operation of P3-DX units. In: INTECH (ed.) Remote and Telerobotics, pp (2010)

12 7. Espinosa, F., Salazar, M., Valdés, F., Bocos, A.: Communication architecture based on player/stage and sockets for cooperative guidance of robotic units. In: 16th Mediterranean Conference on Control and Automation. pp (June 2008) 8. Espinosa, F., Santos, C., Marrón-Romera, M., Pizarro, D., Valdés, F., Dongil, J.: Odometry and laser scanner fusion based on a discrete extended kalman filter for robotic platooning guidance. Sensors 11(9), (2011), 9. Hashimoto, H.: Present state and future of intelligent spaces - discussion on the implementation of rt in our enviorement. In: Artificial Life and Robotics, vol. 11, pp. 1 7 (2007) 10. Hespanha, J., Naghshtabrizi, P., Xu, Y.: A survey of recent results in networked control systems. Proceedings of the IEEE 95(1), (jan 2007) 11. Levine, W.: The control handbook. IEEE-Press (1996) 12. Mazo Jr, M., Anta, A., Tabuada, P.: On self-triggered control for linear systems: Guarantees and complexity. In: European Control Conference (2009) 13. Mazo Jr., M., Anta, A., Tabuada, P.: An ISS self-triggered implementation of linear controller. Automatica 46(8), (Aug 2010) 14. Monekosso, D., Remagnino, P., Kuno, Y.: Intelligent environments: methods, algorithms and applications. Springer (2009) 15. Santana, I., Ferre, M., Izaguirre, E., Aracil, R., Hernandez, L.: Remote laboratories for education and research purposes in automatic control systems. IEEE Transactions on Industrial Informatics PP(99), 1 (2012) 16. Santos, C., Espinosa, F., Pizarro, D., Valdés, F., Santiso, E., Díaz, I.: Fuzzy decentralized control for guidance of a convoy of robots in non-linear trajectories. In: IEEE Conference on Emerging Technologies and Factory Automation (ETFA). pp. 1 8 (Sept 2010) 17. Stefan, O., Codrean, A., Dragomir, T., Silea, I.: Time delay and information loss compensation in a network control system for a dc motor. In: 6th IEEE International Symposium on Applied Computational Intelligence and Informatics (SACI). pp (May 2011) 18. Tabuada, P.: Event-triggered real-time scheduling of stabilizing control tasks. IEEE Transactions on Automatic Control 52(9), (Sept 2007) 19. Wang, X., Lemmon, M.: Event design in event-triggered feedback control systems. In: 47th IEEE Conference on Decision and Control. pp (Dec 2008) 20. Ware, J., Pan, Y.J.: Realisation of a bilaterally teleoperated robotic vehicle platform with passivity control. Control Theory Applications, IET 5(8), (may 2011) 21. Xue, Y., Liu, K.: Controller design for variable-sampling networked control systems with dynamic output feedback. In: 7th World Congress on Intelligent Control and Automation, WCICA. pp (June 2008) 22. Yazbeck, J., Scheuer, A., Simonin, O., Charpillet, F.: Improving near-to-near lateral control of platoons without communication. In: IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS). pp (Sept 2011) 23. Zhang, J., Johansson, K.H., Lygeros, J., Sastry, S.: Dynamical systems revisited: Hybrid systems with Zeno executions. In: Krogh, B., Lynch, N. (eds.) Hybrid Systems: Computation and Control, Lecture Notes in Computer Science, vol Springer-Verlag, New York (2000)

Event-Triggered Decentralized Dynamic Output Feedback Control for LTI Systems

Event-Triggered Decentralized Dynamic Output Feedback Control for LTI Systems Event-Triggered Decentralized Dynamic Output Feedback Control for LTI Systems Pavankumar Tallapragada Nikhil Chopra Department of Mechanical Engineering, University of Maryland, College Park, 2742 MD,

More information

A Novel Integral-Based Event Triggering Control for Linear Time-Invariant Systems

A Novel Integral-Based Event Triggering Control for Linear Time-Invariant Systems 53rd IEEE Conference on Decision and Control December 15-17, 2014. Los Angeles, California, USA A Novel Integral-Based Event Triggering Control for Linear Time-Invariant Systems Seyed Hossein Mousavi 1,

More information

Zeno-free, distributed event-triggered communication and control for multi-agent average consensus

Zeno-free, distributed event-triggered communication and control for multi-agent average consensus Zeno-free, distributed event-triggered communication and control for multi-agent average consensus Cameron Nowzari Jorge Cortés Abstract This paper studies a distributed event-triggered communication and

More information

Event-Triggered Output Feedback Control for Networked Control Systems using Passivity: Time-varying Network Induced Delays

Event-Triggered Output Feedback Control for Networked Control Systems using Passivity: Time-varying Network Induced Delays 5th IEEE Conference on Decision and Control and European Control Conference (CDC-ECC) Orlando, FL, USA, December -5, Event-Triggered Output Feedback Control for Networked Control Systems using Passivity:

More information

Networked Control Systems, Event-Triggering, Small-Gain Theorem, Nonlinear

Networked Control Systems, Event-Triggering, Small-Gain Theorem, Nonlinear EVENT-TRIGGERING OF LARGE-SCALE SYSTEMS WITHOUT ZENO BEHAVIOR C. DE PERSIS, R. SAILER, AND F. WIRTH Abstract. We present a Lyapunov based approach to event-triggering for large-scale systems using a small

More information

Average-Consensus of Multi-Agent Systems with Direct Topology Based on Event-Triggered Control

Average-Consensus of Multi-Agent Systems with Direct Topology Based on Event-Triggered Control Outline Background Preliminaries Consensus Numerical simulations Conclusions Average-Consensus of Multi-Agent Systems with Direct Topology Based on Event-Triggered Control Email: lzhx@nankai.edu.cn, chenzq@nankai.edu.cn

More information

arxiv: v2 [math.oc] 3 Feb 2011

arxiv: v2 [math.oc] 3 Feb 2011 DECENTRALIZED EVENT-TRIGGERED CONTROL OVER WIRELESS SENSOR/ACTUATOR NETWORKS MANUEL MAZO JR AND PAULO TABUADA arxiv:14.477v2 [math.oc] 3 Feb 211 Abstract. In recent years we have witnessed a move of the

More information

Input-to-state stability of self-triggered control systems

Input-to-state stability of self-triggered control systems Input-to-state stability of self-triggered control systems Manuel Mazo Jr. and Paulo Tabuada Abstract Event-triggered and self-triggered control have recently been proposed as an alternative to periodic

More information

An Event-Triggered Consensus Control with Sampled-Data Mechanism for Multi-agent Systems

An Event-Triggered Consensus Control with Sampled-Data Mechanism for Multi-agent Systems Preprints of the 19th World Congress The International Federation of Automatic Control An Event-Triggered Consensus Control with Sampled-Data Mechanism for Multi-agent Systems Feng Zhou, Zhiwu Huang, Weirong

More information

A Simple Self-triggered Sampler for Nonlinear Systems

A Simple Self-triggered Sampler for Nonlinear Systems Proceedings of the 4th IFAC Conference on Analysis and Design of Hybrid Systems ADHS 12 June 6-8, 212. A Simple Self-triggered Sampler for Nonlinear Systems U. Tiberi, K.H. Johansson, ACCESS Linnaeus Center,

More information

STATE AND OUTPUT FEEDBACK CONTROL IN MODEL-BASED NETWORKED CONTROL SYSTEMS

STATE AND OUTPUT FEEDBACK CONTROL IN MODEL-BASED NETWORKED CONTROL SYSTEMS SAE AND OUPU FEEDBACK CONROL IN MODEL-BASED NEWORKED CONROL SYSEMS Luis A Montestruque, Panos J Antsalis Abstract In this paper the control of a continuous linear plant where the sensor is connected to

More information

Event-triggered Control for Discrete-Time Systems

Event-triggered Control for Discrete-Time Systems Event-triggered Control for Discrete-Time Systems Alina Eqtami, Dimos V. Dimarogonas and Kostas J. Kyriakopoulos Abstract In this paper, event-triggered strategies for control of discrete-time systems

More information

AN EVENT-TRIGGERED TRANSMISSION POLICY FOR NETWORKED L 2 -GAIN CONTROL

AN EVENT-TRIGGERED TRANSMISSION POLICY FOR NETWORKED L 2 -GAIN CONTROL 4 Journal of Marine Science and echnology, Vol. 3, No., pp. 4-9 () DOI:.69/JMS-3-3-3 AN EVEN-RIGGERED RANSMISSION POLICY FOR NEWORKED L -GAIN CONROL Jenq-Lang Wu, Yuan-Chang Chang, Xin-Hong Chen, and su-ian

More information

Distributed Event-Based Control for Interconnected Linear Systems

Distributed Event-Based Control for Interconnected Linear Systems 211 5th IEEE Conference on Decision and Control and European Control Conference (CDC-ECC Orlando, FL, USA, December 12-15, 211 Distributed Event-Based Control for Interconnected Linear Systems M Guinaldo,

More information

Communication constraints and latency in Networked Control Systems

Communication constraints and latency in Networked Control Systems Communication constraints and latency in Networked Control Systems João P. Hespanha Center for Control Engineering and Computation University of California Santa Barbara In collaboration with Antonio Ortega

More information

Decentralized Event-triggered Broadcasts over Networked Control Systems

Decentralized Event-triggered Broadcasts over Networked Control Systems Decentralized Event-triggered Broadcasts over Networked Control Systems Xiaofeng Wang and Michael D. Lemmon University of Notre Dame, Department of Electrical Engineering, Notre Dame, IN, 46556, USA, xwang13,lemmon@nd.edu

More information

OUTPUT CONSENSUS OF HETEROGENEOUS LINEAR MULTI-AGENT SYSTEMS BY EVENT-TRIGGERED CONTROL

OUTPUT CONSENSUS OF HETEROGENEOUS LINEAR MULTI-AGENT SYSTEMS BY EVENT-TRIGGERED CONTROL OUTPUT CONSENSUS OF HETEROGENEOUS LINEAR MULTI-AGENT SYSTEMS BY EVENT-TRIGGERED CONTROL Gang FENG Department of Mechanical and Biomedical Engineering City University of Hong Kong July 25, 2014 Department

More information

WEIGHTING MATRICES DETERMINATION USING POLE PLACEMENT FOR TRACKING MANEUVERS

WEIGHTING MATRICES DETERMINATION USING POLE PLACEMENT FOR TRACKING MANEUVERS U.P.B. Sci. Bull., Series D, Vol. 75, Iss. 2, 2013 ISSN 1454-2358 WEIGHTING MATRICES DETERMINATION USING POLE PLACEMENT FOR TRACKING MANEUVERS Raluca M. STEFANESCU 1, Claudiu L. PRIOROC 2, Adrian M. STOICA

More information

IMPULSIVE CONTROL OF DISCRETE-TIME NETWORKED SYSTEMS WITH COMMUNICATION DELAYS. Shumei Mu, Tianguang Chu, and Long Wang

IMPULSIVE CONTROL OF DISCRETE-TIME NETWORKED SYSTEMS WITH COMMUNICATION DELAYS. Shumei Mu, Tianguang Chu, and Long Wang IMPULSIVE CONTROL OF DISCRETE-TIME NETWORKED SYSTEMS WITH COMMUNICATION DELAYS Shumei Mu Tianguang Chu and Long Wang Intelligent Control Laboratory Center for Systems and Control Department of Mechanics

More information

Event-triggered control subject to actuator saturation

Event-triggered control subject to actuator saturation Event-triggered control subject to actuator saturation GEORG A. KIENER Degree project in Automatic Control Master's thesis Stockholm, Sweden 212 XR-EE-RT 212:9 Diploma Thesis Event-triggered control subject

More information

ELEC4631 s Lecture 2: Dynamic Control Systems 7 March Overview of dynamic control systems

ELEC4631 s Lecture 2: Dynamic Control Systems 7 March Overview of dynamic control systems ELEC4631 s Lecture 2: Dynamic Control Systems 7 March 2011 Overview of dynamic control systems Goals of Controller design Autonomous dynamic systems Linear Multi-input multi-output (MIMO) systems Bat flight

More information

SENSE: Abstraction-Based Synthesis of Networked Control Systems

SENSE: Abstraction-Based Synthesis of Networked Control Systems SENSE: Abstraction-Based Synthesis of Networked Control Systems Mahmoud Khaled, Matthias Rungger, and Majid Zamani Hybrid Control Systems Group Electrical and Computer Engineering Technical University

More information

Packet-loss Dependent Controller Design for Networked Control Systems via Switched System Approach

Packet-loss Dependent Controller Design for Networked Control Systems via Switched System Approach Proceedings of the 47th IEEE Conference on Decision and Control Cancun, Mexico, Dec. 9-11, 8 WeC6.3 Packet-loss Dependent Controller Design for Networked Control Systems via Switched System Approach Junyan

More information

Distributed Event-Based Control Strategies for Interconnected Linear Systems

Distributed Event-Based Control Strategies for Interconnected Linear Systems Distributed Event-Based Control Strategies for Interconnected Linear Systems M. Guinaldo, D. V. Dimarogonas, K. H. Johansson, J. Sánchez, S. Dormido January 9, 213 Abstract This paper presents a distributed

More information

QSR-Dissipativity and Passivity Analysis of Event-Triggered Networked Control Cyber-Physical Systems

QSR-Dissipativity and Passivity Analysis of Event-Triggered Networked Control Cyber-Physical Systems QSR-Dissipativity and Passivity Analysis of Event-Triggered Networked Control Cyber-Physical Systems arxiv:1607.00553v1 [math.oc] 2 Jul 2016 Technical Report of the ISIS Group at the University of Notre

More information

Event-based control of input-output linearizable systems

Event-based control of input-output linearizable systems Milano (Italy) August 28 - September 2, 2 Event-based control of input-output linearizable systems Christian Stöcker Jan Lunze Institute of Automation and Computer Control, Ruhr-Universität Bochum, Universitätsstr.

More information

Event-based Motion Coordination of Multiple Underwater Vehicles Under Disturbances

Event-based Motion Coordination of Multiple Underwater Vehicles Under Disturbances Event-based Motion Coordination of Multiple Underwater Vehicles Under Disturbances Pedro V. Teixeira, Dimos V. Dimarogonas, Karl H. Johansson and João Sousa Abstract The problem of driving a formation

More information

FAULT-TOLERANT CONTROL OF CHEMICAL PROCESS SYSTEMS USING COMMUNICATION NETWORKS. Nael H. El-Farra, Adiwinata Gani & Panagiotis D.

FAULT-TOLERANT CONTROL OF CHEMICAL PROCESS SYSTEMS USING COMMUNICATION NETWORKS. Nael H. El-Farra, Adiwinata Gani & Panagiotis D. FAULT-TOLERANT CONTROL OF CHEMICAL PROCESS SYSTEMS USING COMMUNICATION NETWORKS Nael H. El-Farra, Adiwinata Gani & Panagiotis D. Christofides Department of Chemical Engineering University of California,

More information

EE C128 / ME C134 Feedback Control Systems

EE C128 / ME C134 Feedback Control Systems EE C128 / ME C134 Feedback Control Systems Lecture Additional Material Introduction to Model Predictive Control Maximilian Balandat Department of Electrical Engineering & Computer Science University of

More information

CONTROL SYSTEMS, ROBOTICS AND AUTOMATION - Vol. VII - System Characteristics: Stability, Controllability, Observability - Jerzy Klamka

CONTROL SYSTEMS, ROBOTICS AND AUTOMATION - Vol. VII - System Characteristics: Stability, Controllability, Observability - Jerzy Klamka SYSTEM CHARACTERISTICS: STABILITY, CONTROLLABILITY, OBSERVABILITY Jerzy Klamka Institute of Automatic Control, Technical University, Gliwice, Poland Keywords: stability, controllability, observability,

More information

Observer-based quantized output feedback control of nonlinear systems

Observer-based quantized output feedback control of nonlinear systems Proceedings of the 17th World Congress The International Federation of Automatic Control Observer-based quantized output feedback control of nonlinear systems Daniel Liberzon Coordinated Science Laboratory,

More information

MOST control systems are designed under the assumption

MOST control systems are designed under the assumption 2076 IEEE TRANSACTIONS ON AUTOMATIC CONTROL, VOL. 53, NO. 9, OCTOBER 2008 Lyapunov-Based Model Predictive Control of Nonlinear Systems Subject to Data Losses David Muñoz de la Peña and Panagiotis D. Christofides

More information

Event-Triggered Broadcasting across Distributed Networked Control Systems

Event-Triggered Broadcasting across Distributed Networked Control Systems Event-Triggered Broadcasting across Distributed Networked Control Systems Xiaofeng Wang and Michael D. Lemmon Abstract This paper examines event-triggered broadcasting of state information in distributed

More information

Target Localization and Circumnavigation Using Bearing Measurements in 2D

Target Localization and Circumnavigation Using Bearing Measurements in 2D Target Localization and Circumnavigation Using Bearing Measurements in D Mohammad Deghat, Iman Shames, Brian D. O. Anderson and Changbin Yu Abstract This paper considers the problem of localization and

More information

Lyapunov Stability of Linear Predictor Feedback for Distributed Input Delays

Lyapunov Stability of Linear Predictor Feedback for Distributed Input Delays IEEE TRANSACTIONS ON AUTOMATIC CONTROL VOL. 56 NO. 3 MARCH 2011 655 Lyapunov Stability of Linear Predictor Feedback for Distributed Input Delays Nikolaos Bekiaris-Liberis Miroslav Krstic In this case system

More information

Decentralized Event-Triggering for Control of Nonlinear Systems

Decentralized Event-Triggering for Control of Nonlinear Systems Decentralized Event-Triggering for Control of Nonlinear Systems Pavankumar Tallapragada and Nikhil Chopra arxiv:32.49v3 [cs.sy] 3 Jun 24 Abstract This paper considers nonlinear systems with full state

More information

Delay compensation in packet-switching network controlled systems

Delay compensation in packet-switching network controlled systems Delay compensation in packet-switching network controlled systems Antoine Chaillet and Antonio Bicchi EECI - L2S - Université Paris Sud - Supélec (France) Centro di Ricerca Piaggio - Università di Pisa

More information

On a small-gain approach to distributed event-triggered control

On a small-gain approach to distributed event-triggered control On a small-gain approach to distributed event-triggered control Claudio De Persis, Rudolf Sailer Fabian Wirth Fac Mathematics & Natural Sciences, University of Groningen, 9747 AG Groningen, The Netherlands

More information

Control Systems I. Lecture 2: Modeling. Suggested Readings: Åström & Murray Ch. 2-3, Guzzella Ch Emilio Frazzoli

Control Systems I. Lecture 2: Modeling. Suggested Readings: Åström & Murray Ch. 2-3, Guzzella Ch Emilio Frazzoli Control Systems I Lecture 2: Modeling Suggested Readings: Åström & Murray Ch. 2-3, Guzzella Ch. 2-3 Emilio Frazzoli Institute for Dynamic Systems and Control D-MAVT ETH Zürich September 29, 2017 E. Frazzoli

More information

MATH4406 (Control Theory) Unit 1: Introduction Prepared by Yoni Nazarathy, July 21, 2012

MATH4406 (Control Theory) Unit 1: Introduction Prepared by Yoni Nazarathy, July 21, 2012 MATH4406 (Control Theory) Unit 1: Introduction Prepared by Yoni Nazarathy, July 21, 2012 Unit Outline Introduction to the course: Course goals, assessment, etc... What is Control Theory A bit of jargon,

More information

NETWORKED control systems (NCS), that are comprised

NETWORKED control systems (NCS), that are comprised 1 Event-Triggered H Control: a Switching Approach Anton Selivanov and Emilia Fridman, Senior Member, IEEE Abstract Event-triggered approach to networked control systems is used to reduce the workload of

More information

Learning Model Predictive Control for Iterative Tasks: A Computationally Efficient Approach for Linear System

Learning Model Predictive Control for Iterative Tasks: A Computationally Efficient Approach for Linear System Learning Model Predictive Control for Iterative Tasks: A Computationally Efficient Approach for Linear System Ugo Rosolia Francesco Borrelli University of California at Berkeley, Berkeley, CA 94701, USA

More information

Discrete Event-Triggered Sliding Mode Control With Fast Output Sampling Feedback

Discrete Event-Triggered Sliding Mode Control With Fast Output Sampling Feedback Discrete Event-Triggered Sliding Mode Control With Fast Output Sampling Feedback Abhisek K Behera and Bijnan Bandyopadhyay Systems and Control Engineering Indian Institute of Technology Bombay Mumbai 4

More information

Self-triggered and team-triggered control of. networked cyber-physical systems

Self-triggered and team-triggered control of. networked cyber-physical systems Self-triggered and team-triggered control of 1 networked cyber-physical systems Cameron Nowzari Jorge Cortés I. INTRODUCTION This chapter describes triggered control approaches for the coordination of

More information

Limit Cycles in High-Resolution Quantized Feedback Systems

Limit Cycles in High-Resolution Quantized Feedback Systems Limit Cycles in High-Resolution Quantized Feedback Systems Li Hong Idris Lim School of Engineering University of Glasgow Glasgow, United Kingdom LiHonIdris.Lim@glasgow.ac.uk Ai Poh Loh Department of Electrical

More information

Stabilization of Large-scale Distributed Control Systems using I/O Event-driven Control and Passivity

Stabilization of Large-scale Distributed Control Systems using I/O Event-driven Control and Passivity 11 5th IEEE Conference on Decision and Control and European Control Conference (CDC-ECC) Orlando, FL, USA, December 1-15, 11 Stabilization of Large-scale Distributed Control Systems using I/O Event-driven

More information

Bilateral Teleoperation over the Internet: the Time Varying Delay Problem 1

Bilateral Teleoperation over the Internet: the Time Varying Delay Problem 1 Bilateral Teleoperation over the Internet: the Time Varying Delay Problem 1 Nikhil Chopra and Mark W. Spong Coordinated Science Laboratory University of Illinois at Urbana-Champaign 14 S. Mathews Avenue

More information

Feedback Control CONTROL THEORY FUNDAMENTALS. Feedback Control: A History. Feedback Control: A History (contd.) Anuradha Annaswamy

Feedback Control CONTROL THEORY FUNDAMENTALS. Feedback Control: A History. Feedback Control: A History (contd.) Anuradha Annaswamy Feedback Control CONTROL THEORY FUNDAMENTALS Actuator Sensor + Anuradha Annaswamy Active adaptive Control Laboratory Massachusetts Institute of Technology must follow with» Speed» Accuracy Feeback: Measure

More information

Event-triggered PI control: Saturating actuators and anti-windup compensation

Event-triggered PI control: Saturating actuators and anti-windup compensation Event-triggered PI control: Saturating actuators and anti-windup compensation Daniel Lehmann, Georg Aleander Kiener and Karl Henrik Johansson Abstract Event-triggered control aims at reducing the communication

More information

Self-Triggering in Nonlinear Systems: A Small-Gain Theorem Approach

Self-Triggering in Nonlinear Systems: A Small-Gain Theorem Approach Self-Triggering in Nonlinear Systems: A Small-Gain Theorem Approach Domagoj Tolić, Ricardo G. Sanfelice and Rafael Fierro Abstract This paper investigates stability of nonlinear control systems under intermittent

More information

ON SEPARATION PRINCIPLE FOR THE DISTRIBUTED ESTIMATION AND CONTROL OF FORMATION FLYING SPACECRAFT

ON SEPARATION PRINCIPLE FOR THE DISTRIBUTED ESTIMATION AND CONTROL OF FORMATION FLYING SPACECRAFT ON SEPARATION PRINCIPLE FOR THE DISTRIBUTED ESTIMATION AND CONTROL OF FORMATION FLYING SPACECRAFT Amir Rahmani (), Olivia Ching (2), and Luis A Rodriguez (3) ()(2)(3) University of Miami, Coral Gables,

More information

NOWADAYS, many control applications have some control

NOWADAYS, many control applications have some control 1650 IEEE TRANSACTIONS ON AUTOMATIC CONTROL, VOL 49, NO 10, OCTOBER 2004 Input Output Stability Properties of Networked Control Systems D Nešić, Senior Member, IEEE, A R Teel, Fellow, IEEE Abstract Results

More information

Predicting Time-Delays under Real-Time Scheduling for Linear Model Predictive Control

Predicting Time-Delays under Real-Time Scheduling for Linear Model Predictive Control 23 International Conference on Computing, Networking and Communications, Workshops Cyber Physical System Predicting Time-Delays under Real-Time Scheduling for Linear Model Predictive Control Zhenwu Shi

More information

Module 09 Decentralized Networked Control Systems: Battling Time-Delays and Perturbations

Module 09 Decentralized Networked Control Systems: Battling Time-Delays and Perturbations Module 09 Decentralized Networked Control Systems: Battling Time-Delays and Perturbations Ahmad F. Taha EE 5243: Introduction to Cyber-Physical Systems Email: ahmad.taha@utsa.edu Webpage: http://engineering.utsa.edu/

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

Event-based Stabilization of Nonlinear Time-Delay Systems

Event-based Stabilization of Nonlinear Time-Delay Systems Preprints of the 19th World Congress The International Federation of Automatic Control Event-based Stabilization of Nonlinear Time-Delay Systems Sylvain Durand Nicolas Marchand J. Fermi Guerrero-Castellanos

More information

QUANTIZED SYSTEMS AND CONTROL. Daniel Liberzon. DISC HS, June Dept. of Electrical & Computer Eng., Univ. of Illinois at Urbana-Champaign

QUANTIZED SYSTEMS AND CONTROL. Daniel Liberzon. DISC HS, June Dept. of Electrical & Computer Eng., Univ. of Illinois at Urbana-Champaign QUANTIZED SYSTEMS AND CONTROL Daniel Liberzon Coordinated Science Laboratory and Dept. of Electrical & Computer Eng., Univ. of Illinois at Urbana-Champaign DISC HS, June 2003 HYBRID CONTROL Plant: u y

More information

AQUANTIZER is a device that converts a real-valued

AQUANTIZER is a device that converts a real-valued 830 IEEE TRANSACTIONS ON AUTOMATIC CONTROL, VOL 57, NO 4, APRIL 2012 Input to State Stabilizing Controller for Systems With Coarse Quantization Yoav Sharon, Member, IEEE, Daniel Liberzon, Senior Member,

More information

Delay-dependent Stability Analysis for Markovian Jump Systems with Interval Time-varying-delays

Delay-dependent Stability Analysis for Markovian Jump Systems with Interval Time-varying-delays International Journal of Automation and Computing 7(2), May 2010, 224-229 DOI: 10.1007/s11633-010-0224-2 Delay-dependent Stability Analysis for Markovian Jump Systems with Interval Time-varying-delays

More information

Lectures 25 & 26: Consensus and vehicular formation problems

Lectures 25 & 26: Consensus and vehicular formation problems EE 8235: Lectures 25 & 26 Lectures 25 & 26: Consensus and vehicular formation problems Consensus Make subsystems (agents, nodes) reach agreement Distributed decision making Vehicular formations How does

More information

ECE557 Systems Control

ECE557 Systems Control ECE557 Systems Control Bruce Francis Course notes, Version.0, September 008 Preface This is the second Engineering Science course on control. It assumes ECE56 as a prerequisite. If you didn t take ECE56,

More information

Hybrid Systems Techniques for Convergence of Solutions to Switching Systems

Hybrid Systems Techniques for Convergence of Solutions to Switching Systems Hybrid Systems Techniques for Convergence of Solutions to Switching Systems Rafal Goebel, Ricardo G. Sanfelice, and Andrew R. Teel Abstract Invariance principles for hybrid systems are used to derive invariance

More information

Event-separation properties of event-triggered control systems

Event-separation properties of event-triggered control systems Event-separation properties of event-triggered control systems D.P. Borgers and W.P.M.H. Heemels Abstract In this paper we study fundamental properties of minimum inter-event times for several event-triggered

More information

Models for Control and Verification

Models for Control and Verification Outline Models for Control and Verification Ian Mitchell Department of Computer Science The University of British Columbia Classes of models Well-posed models Difference Equations Nonlinear Ordinary Differential

More information

Encoder Decoder Design for Event-Triggered Feedback Control over Bandlimited Channels

Encoder Decoder Design for Event-Triggered Feedback Control over Bandlimited Channels Encoder Decoder Design for Event-Triggered Feedback Control over Bandlimited Channels LEI BAO, MIKAEL SKOGLUND AND KARL HENRIK JOHANSSON IR-EE- 26: Stockholm 26 Signal Processing School of Electrical Engineering

More information

NONLINEAR PATH CONTROL FOR A DIFFERENTIAL DRIVE MOBILE ROBOT

NONLINEAR PATH CONTROL FOR A DIFFERENTIAL DRIVE MOBILE ROBOT NONLINEAR PATH CONTROL FOR A DIFFERENTIAL DRIVE MOBILE ROBOT Plamen PETROV Lubomir DIMITROV Technical University of Sofia Bulgaria Abstract. A nonlinear feedback path controller for a differential drive

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

Discrete-time Consensus Filters on Directed Switching Graphs

Discrete-time Consensus Filters on Directed Switching Graphs 214 11th IEEE International Conference on Control & Automation (ICCA) June 18-2, 214. Taichung, Taiwan Discrete-time Consensus Filters on Directed Switching Graphs Shuai Li and Yi Guo Abstract We consider

More information

Encoder Decoder Design for Event-Triggered Feedback Control over Bandlimited Channels

Encoder Decoder Design for Event-Triggered Feedback Control over Bandlimited Channels Encoder Decoder Design for Event-Triggered Feedback Control over Bandlimited Channels Lei Bao, Mikael Skoglund and Karl Henrik Johansson Department of Signals, Sensors and Systems, Royal Institute of Technology,

More information

Linear System Theory. Wonhee Kim Lecture 1. March 7, 2018

Linear System Theory. Wonhee Kim Lecture 1. March 7, 2018 Linear System Theory Wonhee Kim Lecture 1 March 7, 2018 1 / 22 Overview Course Information Prerequisites Course Outline What is Control Engineering? Examples of Control Systems Structure of Control Systems

More information

An Introduction to Model-based Predictive Control (MPC) by

An Introduction to Model-based Predictive Control (MPC) by ECE 680 Fall 2017 An Introduction to Model-based Predictive Control (MPC) by Stanislaw H Żak 1 Introduction The model-based predictive control (MPC) methodology is also referred to as the moving horizon

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

Multi-Modal Control of Systems with Constraints

Multi-Modal Control of Systems with Constraints Multi-Modal Control of Systems with Constraints WeM12-3 T. John Koo Department of EECS University of California Berkeley, CA 9720 koo@eecs.berkeley.edu George J. Pappas Department of EE University of Pennsylvania

More information

Discrete and continuous dynamic systems

Discrete and continuous dynamic systems Discrete and continuous dynamic systems Bounded input bounded output (BIBO) and asymptotic stability Continuous and discrete time linear time-invariant systems Katalin Hangos University of Pannonia Faculty

More information

Introduction. Introduction. Introduction. Standard digital control loop. Resource-aware control

Introduction. Introduction. Introduction. Standard digital control loop. Resource-aware control Introduction 2/52 Standard digital control loop Resource-aware control Maurice Heemels All control tasks executed periodically and triggered by time Zandvoort, June 25 Where innovation starts Introduction

More information

Event-Triggered Interactive Gradient Descent for Real-Time Multi-Objective Optimization

Event-Triggered Interactive Gradient Descent for Real-Time Multi-Objective Optimization Event-Triggered Interactive Gradient Descent for Real-Time Multi-Objective Optimization Pio Ong and Jorge Cortés Abstract This paper proposes an event-triggered interactive gradient descent method for

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

Formation Control Over Delayed Communication Networks

Formation Control Over Delayed Communication Networks 28 IEEE International Conference on Robotics and Automation Pasadena, CA, USA, May 19-23, 28 Formation Control Over Delayed Communication Networks Cristian Secchi and Cesare Fantuzzi DISMI, University

More information

To sample or not to sample: Self-triggered control for nonlinear systems

To sample or not to sample: Self-triggered control for nonlinear systems arxiv:86.79v1 [math.oc] 4 Jun 28 To sample or not to sample: Self-triggered control for nonlinear systems Adolfo Anta and Paulo Tabuada This research was partially supported by the National Science Foundation

More information

Subject: Optimal Control Assignment-1 (Related to Lecture notes 1-10)

Subject: Optimal Control Assignment-1 (Related to Lecture notes 1-10) Subject: Optimal Control Assignment- (Related to Lecture notes -). Design a oil mug, shown in fig., to hold as much oil possible. The height and radius of the mug should not be more than 6cm. The mug must

More information

Stability of networked control systems with variable sampling and delay

Stability of networked control systems with variable sampling and delay Stability of networked control systems with variable sampling and delay Payam Naghshtabrizi and Joao P Hespanha Abstract We consider Networked Control Systems (NCSs) consisting of a LTI plant; a linear

More information

Detectability and Output Feedback Stabilizability of Nonlinear Networked Control Systems

Detectability and Output Feedback Stabilizability of Nonlinear Networked Control Systems Proceedings of the 44th IEEE Conference on Decision and Control, and the European Control Conference 2005 Seville, Spain, December 12-15, 2005 ThC14.2 Detectability and Output Feedback Stabilizability

More information

ABSTRACT. Pavankumar Tallapragada, Doctor of Philosophy, 2013

ABSTRACT. Pavankumar Tallapragada, Doctor of Philosophy, 2013 ABSTRACT Title of dissertation: UTILITY DRIVEN SAMPLED DATA CONTROL UNDER IMPERFECT INFORMATION Pavankumar Tallapragada, Doctor of Philosophy, 2013 Dissertation directed by: Dr. Nikhil Chopra Department

More information

Technical report bds:00-21

Technical report bds:00-21 Delft University of Technology Fac. of Information Technology and Systems Control Systems Engineering Technical report bds:00-21 Stability Analysis of Discrete Event Systems (by K.M. Passino and K.L. Burgess,

More information

Stability of Nonlinear Control Systems Under Intermittent Information with Applications to Multi-Agent Robotics

Stability of Nonlinear Control Systems Under Intermittent Information with Applications to Multi-Agent Robotics Introduction Stability Optimal Intermittent Fdbk Summary Stability of Nonlinear Control Systems Under Intermittent Information with Applications to Multi-Agent Robotics Domagoj Tolić Fakultet Elektrotehnike

More information

Distributed Receding Horizon Control of Cost Coupled Systems

Distributed Receding Horizon Control of Cost Coupled Systems Distributed Receding Horizon Control of Cost Coupled Systems William B. Dunbar Abstract This paper considers the problem of distributed control of dynamically decoupled systems that are subject to decoupled

More information

On Lyapunov Sampling for Event-driven Controllers

On Lyapunov Sampling for Event-driven Controllers Joint 48th IEEE Conference on Decision and Control and 28th Chinese Control Conference Shanghai, PR China, December 6-8, 29 ThCIn64 On Lyapunov Sampling for Event-driven Controllers Manel Velasco, Pau

More information

A Stable Block Model Predictive Control with Variable Implementation Horizon

A Stable Block Model Predictive Control with Variable Implementation Horizon American Control Conference June 8-,. Portland, OR, USA WeB9. A Stable Block Model Predictive Control with Variable Implementation Horizon Jing Sun, Shuhao Chen, Ilya Kolmanovsky Abstract In this paper,

More information

Model based tracking control using Jerky behavior in platoon of vehicles

Model based tracking control using Jerky behavior in platoon of vehicles 213 European Control Conference (ECC) July 17-19, 213, Zürich, Switzerland. Model based tracking control using Jerky behavior in platoon of vehicles R. Merzouki, B. Conrard, P. Kumar and V. Coelen Abstract

More information

Disturbance Attenuation for a Class of Nonlinear Systems by Output Feedback

Disturbance Attenuation for a Class of Nonlinear Systems by Output Feedback Disturbance Attenuation for a Class of Nonlinear Systems by Output Feedback Wei in Chunjiang Qian and Xianqing Huang Submitted to Systems & Control etters /5/ Abstract This paper studies the problem of

More information

On Design of Reduced-Order H Filters for Discrete-Time Systems from Incomplete Measurements

On Design of Reduced-Order H Filters for Discrete-Time Systems from Incomplete Measurements Proceedings of the 47th IEEE Conference on Decision and Control Cancun, Mexico, Dec. 9-11, 2008 On Design of Reduced-Order H Filters for Discrete-Time Systems from Incomplete Measurements Shaosheng Zhou

More information

ON CHATTERING-FREE DISCRETE-TIME SLIDING MODE CONTROL DESIGN. Seung-Hi Lee

ON CHATTERING-FREE DISCRETE-TIME SLIDING MODE CONTROL DESIGN. Seung-Hi Lee ON CHATTERING-FREE DISCRETE-TIME SLIDING MODE CONTROL DESIGN Seung-Hi Lee Samsung Advanced Institute of Technology, Suwon, KOREA shl@saitsamsungcokr Abstract: A sliding mode control method is presented

More information

Stability of Switched Linear Hyperbolic Systems by Lyapunov Techniques

Stability of Switched Linear Hyperbolic Systems by Lyapunov Techniques 2196 IEEE TRANSACTIONS ON AUTOMATIC CONTROL, VOL. 59, NO. 8, AUGUST 2014 Stability of Switched Linear Hyperbolic Systems by Lyapunov Techniques Christophe Prieur, Antoine Girard, Emmanuel Witrant Abstract

More information

Distributed Optimization, Estimation, and Control of Networked Systems through Event-triggered Message Passing

Distributed Optimization, Estimation, and Control of Networked Systems through Event-triggered Message Passing Distributed Optimization, Estimation, and Control of Networked Systems through Event-triggered Message Passing 1 Introduction This project will investigate distributed optimization, estimation, and control

More information

Advanced Adaptive Control for Unintended System Behavior

Advanced Adaptive Control for Unintended System Behavior Advanced Adaptive Control for Unintended System Behavior Dr. Chengyu Cao Mechanical Engineering University of Connecticut ccao@engr.uconn.edu jtang@engr.uconn.edu Outline Part I: Challenges: Unintended

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

Control Systems I. Lecture 7: Feedback and the Root Locus method. Readings: Jacopo Tani. Institute for Dynamic Systems and Control D-MAVT ETH Zürich

Control Systems I. Lecture 7: Feedback and the Root Locus method. Readings: Jacopo Tani. Institute for Dynamic Systems and Control D-MAVT ETH Zürich Control Systems I Lecture 7: Feedback and the Root Locus method Readings: Jacopo Tani Institute for Dynamic Systems and Control D-MAVT ETH Zürich November 2, 2018 J. Tani, E. Frazzoli (ETH) Lecture 7:

More information

Research Article. World Journal of Engineering Research and Technology WJERT.

Research Article. World Journal of Engineering Research and Technology WJERT. wjert, 2015, Vol. 1, Issue 1, 27-36 Research Article ISSN 2454-695X WJERT www.wjert.org COMPENSATOR TUNING FOR DISTURBANCE REJECTION ASSOCIATED WITH DELAYED DOUBLE INTEGRATING PROCESSES, PART I: FEEDBACK

More information

Adaptive Predictive Observer Design for Class of Uncertain Nonlinear Systems with Bounded Disturbance

Adaptive Predictive Observer Design for Class of Uncertain Nonlinear Systems with Bounded Disturbance International Journal of Control Science and Engineering 2018, 8(2): 31-35 DOI: 10.5923/j.control.20180802.01 Adaptive Predictive Observer Design for Class of Saeed Kashefi *, Majid Hajatipor Faculty of

More information

Stabilisation of network controlled systems with a predictive approach

Stabilisation of network controlled systems with a predictive approach Stabilisation of network controlled systems with a predictive approach Emmanuel Witrant with D. Georges, C. Canudas de Wit and O. Sename Laboratoire d Automatique de Grenoble, UMR CNRS 5528 ENSIEG-INPG,

More information