<<

Optimal nonlinear model predictive control based on Bernstein polynomial approach

Bhagyesh V. Patil§ and K. V. Ling† and J. M. Maciejowski‡

Abstract— In this paper, we compare the performance of global optimization procedures (cf. [11], [12]). The challenge Bernstein global optimization based nonlinear model involved in NMPC is two fold: predictive control (NMPC) with a power system stabilizer and (i) Can we complete the nonlinear iteration procedure until a linear model predictive control (MPC) for the excitation control of a single machine infinite bus power system. The control pre-specified convergence criterion is met so as to guarantee studies with Bernstein algorithm based NMPC show the optimal solution of the optimization problem? improvement in the system damping and settling time when (ii) can we achieve (i) in a pre-specified sampling time limit? compared with respect to a power system stabilizer and linear Concerning these facts, our previous works have introduced MPC scheme. Further, the efficacy of the Bernstein algorithm is Bernstein global optimization procedures for NMPC appli- also compared with global optimization solver BMIBNB from YALMIP toolbox in terms of NMPC scheme and results are cations (cf. [13], [14]). Optimization procedures based on found to be satisfactory. this Bernstein form, also called Bernstein global optimization , have shown good promise to solve hard noncon- I.INTRODUCTION vex optimization problems. This procedure is based on the Over the past decades, model predictive control (MPC) Bernstein form of polynomials [15], and uses several nice has emerged as one of the prominent advanced control ‘geometrical’ properties associated with this Bernstein form. methodology for multivariable control. At the heart of MPC The current scope of the work is based on the sequential lies a system model, which predicts the future evolution of improvement of our previous works in [13], [14]. Specif- the system states. It generates control actions by iteratively ically, in this work we implement a hull pruning feature optimizing a performance criterion over a finite-time moving for the Bernstein global optimization algorithm to solve a window with reference to system constraints, and based nonconvex optimization problem at each NMPC iteration. on predictions of the system model [1], [2]. In practice, The hull pruning aids in discarding regions from solution MPC implementations utilizing linear models (a.k.a ‘linear search spaces that surely do not contain the global solution. MPC’) are preferred. This facilitates use of linear/convex As this feature provides the means to narrow the search programming techniques to exactly solve optimization prob- region for the optimization problem, we call it a narrowing lems at each sampling instant. However, some applications (‘hull pruning’) operator. The applicability of the Bernstein (like power systems) have significant nonlinear behaviour, algorithm with this hull pruning feature is demonstrated and for such applications, a linear MPC scheme may not by simulating a nonlinear model predictive control scheme yield desirable closed-loop performance [3], [4]. Hence, to for a classical single machine infinite bus (SMIB) power mitigate problems arising from the system nonlinearities, system [16]. SMIB has a strong nonlinear characteristics and many researchers have pursued MPC approach based on exhibits accurate representation of the synchronous generator nonlinear system models. This approach under large variation behaviour. The findings of our nonlinear MPC scheme based of dynamic behaviour of the system, may provide more on the Bernstein algorithm with hull pruning operator are satisfactory control than linear MPC. Model predictive con- compared with respect to well-established power system trol using nonlinear system models, usually called ‘nonlinear stabilizer (PSS) [16] and linear MPC. We also investigate our MPC’ (or NMPC), hence has attracted many researchers over findings with nonlinear MPC based on the YALMIP global the past decade [5], [6], [7], [8], [9], [10]. optimization solver BMIBNB [17]. We note that an NMPC formulation usually requires the In the rest of the paper, we first introduce a nonlinear solution of a nonlinear, usually nonconvex, optimization MPC formulation (Section 2). Next, we briefly describe the problem at each sampling instant. Therefore, NMPC requires Bernstein form and the hull pruning operator, followed by the presentation of the Bernstein global optimization algorithm §Bhagyesh V. Patil is with Cambridge Centre for Advanced Research and Education in Singapore (CARES), 50 Nanyang Ave, Singapore. (Section 3). We then report the simulation studies on a [email protected] nonlinear SMIB power system (Section 4). Finally, some †K. V. Ling is with the School of Electrical and Electronic Engi- concluding remarks are given in Section 5. neering, Nanyang Technological University, 50 Nanyang Ave, Singapore. [email protected] II.NMPC CONTROLLER FORMULATION ‡J. M. Maciejowski is with Department of Engineering, University of Cambridge, Cambridge CB2 1PZ, United Kingdom. We consider a class of continuous-time systems described [email protected] by the following nonlinear model This research is supported by the National Research Foundation, Prime Minister’s Office, Singapore, under its Campus for Research Excellence and Technological Enterprise (CREATE) programme. x˙ = f (x,u), x(t0) = x0 (1) n m where x ∈ R and u ∈ R denote the vectors of states and control inputs, respectively. In practice, the continuous-time model (1) used for predictions is discretized with a sampling time ∆t, such as Euler’s method Constraint handling c(xk, uk) <= 0 * Optimization solver u 0 x xk+1 = xk + ∆t. f (xk,uk) (2) B(xk, uk) (BBB algorithm Plant in Section III) where k denotes sampling instant. Use of Lemma 1

The nonlinear optimization problem in the NMPC formu- Nonlinear optimization problem Measurement Unit lation at each sampling instant k is stated by (3)-(6). The (Equations 3-6) control objective is to maintain equilibrium point (origin), by minimizing the cost (3) subjected to discretized nonlinear Prediction xk (Equation 2) predictive model (2), and fulfilling constraints of the form (5). Fig. 1. Schematic of Bernstein algorithm based NMPC. N−1 min L (xk,uk) (3) u ∑ k k=0 subject to xk+1 = xk + ∆t. f (xk,uk) (4) brevity, we only present notions about the univariate Bern- stein form (see [18] for the multivariate case). c(x ,u ) ≤ 0 (5) k k We can write a generic polynomial of degree l as for k = 0,1,...,N − 1 (6) l i where N(> 1) denotes the prediction horizon and c(xk,uk) p(x) = ∑ aix , ai ∈ R (9) are the nonlinear constraints arising due to safety and oper- i=0 ational requirements of the control system. It may be noted where x is the variable, and {a0,a1,...,al} are the coeffi- that, c(xk,uk) subsume the constraints on the state and input cients of the power basis Bp given by the following set of of the following form: monomials 2 l min max Bp = {1,x,x ,...,x }. (10) xk ≤ xk ≤ xk . (7) min max uk ≤ uk ≤ uk . (8) We assume that p(x) is defined over a real bounded and x = [ , ] ∗ ∗ closed interval 0 1 . The unit interval is not a restriction, We assume at the equilibrium point xk,uk , the cost (3) ∗ ∗ since any nonempty compact interval can be mapped affinely should be zero, i.e. L (xk,uk) = 0. onto it. The NMPC algorithm at each sampling instant k involves Now the polynomial p can be expressed into the Bernstein the following steps: polynomial form of the same degree [15]: (a) Measure the state xk of the system (we assume in the l above NMPC formulation all states are available for l p(x) = ∑ biBi (x) (11) measurement). i=0 (b) Solve the nonlinear optimization problem (3)-(6) with l where B (x) are the Bernstein basis polynomials and bi are initial state xk. Denote the obtained optimal control i sequence as u∗, u∗,..., u∗ . the Bernstein coefficients: 0 1 N−1   (c) Implement the first step of the optimal control sequence, l l i l−i ∗ Bi(x) = x (1 − x) . (12) u0 to the system (1) to obtain a new updated state until i the next sampling instant.   (d) Repeat from (a). i i The overall scheme of the Bernstein algorithm based j bi = ∑  a j, i = 0,...,l. (13) NMPC is depicted in Fig. 1. The Bernstein algorithm can j=0 l be applied when the system model, cost function and the j constraints are polynomials. In many other applications the Equation (11) is referred as the Bernstein form of (9) and problem can be approximated (as closely as desired) by satisfies the following range enclosure property [15]: polynomials (such as our example in Section IV).

III.BERNSTEINGLOBALOPTIMIZATIONAPPROACH p(x) ⊆ B(x) := [min bi, max bi]. (14) In the NMPC formulation (Section II), we solve a nonlin- where p(x) denote the range of p on a given interval x. ear optimization problem at each sampling instant to derive a control law for the nonlinear system (1). [5] and [7] Remark 1: Equation (14) says that the minimum and max- report some optimization approaches to achieve this goal. imum coefficients of bi provide lower and upper bounds for This section briefly introduces one such (global) optimization the range of p. This forms the Bernstein range enclosure, approach based on the Bernstein form of polynomials. For defined by B(x). Further, this Bernstein range enclosure 2 can successively be sharpened by the continuous domain Example: Consider a constraint x2 = x1, x1 ∈ [1,2] and subdivision procedure (see, for instance [19]). x2 ∈ [0,2.5]. First perform constraint inversion and interval The following properties follow immediately from the arithmetic operations for x1 Bernstein range enclosure (14). 0 1 x1 = (x2) 2 1 Lemma 1: Let B(x) be the Bernstein range enclosure = [0,2.5] 2 for a polynomial p(x) on a given box x. Then, the following = [0,1.5812] identities hold x = x0 ∩ x 1) B(x) ≤ 0 ⇒ p(x) ≤ 0 for all x ∈ x. 1,consistent 1 1 2) B(x) > 0 ⇒ p(x) > 0 for all x ∈ x. = [0,1.5812] ∩ [1,2] 3)0 ∈/ B(x) ⇒ p(x) 6= 0 for all x ∈ x. = [1,1.5812] 4) B(x) ⊆ [−εzero,εzero] ⇒ p(x) ∈ [−εzero,εzero] for all x ∈ x, Similarly, we can achieve pruning for x as x = where εzero > 0. 2 2,consistent [1,2.5]. Fig. 2 illustrates the complete hull pruning for constraint x = x2 for x ∈ [1,2] and x ∈ [0,2.5]. Vertex condition [15] Consider the Bernstein form in equa- 2 1 1 2 tion (14) for a polynomial p of degree l, and let the range In our hull pruning operator, we perform constraint inver- sion and operations using the Bernstein p(x) = [a,b]. Then range enclosure B(x) in (14). a = min (bi) if and only if min (bi) = min (bi) 0≤i≤l 0≤i≤l i∈{0,l} b = max (bi) if and only if max (bi) = max (bi) 0≤i≤l 0≤i≤l i∈{0,l}

Remark 2: The above vertex condition says that the lower bound (respectively, upper bound) is sharp if and only if min bi (respectively, max bi) is attained at a vertex Bernstein coefficient (that is, b0, bl). Further, the vertex condition is said to be met within a given tolerance ε f , if

bk − min bi ≤ ε f , k = 0,l. (15) 0≤i≤l A. Hull pruning operator Fig. 2. Computation of consistent set of values (pruning) from x1 ∈ [1,2] 2 As mentioned earlier, NMPC solves a nonlinear program- and x2 ∈ [0,2.5] with respect to the constraint x2 = x1. ming (NLP) problem of the form (3)-(6). This NLP has a nonlinear set of constraints and a search space (box) representing the variable domains. The hull pruning oper- B. Main Bernstein branch-and-prune algorithm ation removes inconsistent values from a box that surely do ∗ ∗ [ f ,x ] = BBB( f ,gi,h j,x,ε f ,εzero) not contribute in locating global solution. It achieves this goal using the constraint inversion procedure and interval Inputs: The cost function (3) as f , equality constraints (4) arithmetic operations†. as h j, and inequality constraints (5) as gi, the initial search Consider a multivariate equality constraint h(x) = 0. To box for uk as x, the tolerance parameter ε f on the global apply hull pruning, we keep one term on the left hand minimum, and the tolerance parameter εzero to which the side (say variable xr from which has to be pruned) and equality constraints are to be satisfied. remaining all other terms are taken on the right hand side, I that is, we write the constraint in the form aIx = h1(x) Outputs: The global minimum f ∗ and global minimizer x∗. where, x = (x1,...,xr,...,xl) and I = (i1,i2,...,ir,...,il). I Now, replacing all x by their respective intervals and h1(x) BEGIN Algorithm by its interval evaluation, we can write interval x0 (for the r Initialization step (R) variable xr, which has to be pruned) as • Compute the range enclosures for f , g , and h , respec- 1/i i j 0 ! r 0 h1 tively as b f ,bgi , and bh j over x. Set fb to the minimum xr = , k = 1,2,...,l. (16) ik Bernstein coefficient of b and f = f . aI ∏xk f e b • Construct L ← {( fb,b f ,bgi ,bh ,x)}, L ← {}. Then the new pruned interval for the variable xr can be j obtained as below Sorting and Pruning step (SP) 0 • If L is empty, go to step T. Else sort item(s)† in L in xr,consistent = xr ∩ xr (17) ascending order of fb. †Interval arithmetic operations are set theoretic extensions of the corre- † sponding real (floating-point) operations [20]. Each item in the list L is of the form: ( fb,b f ,bgi ,bh j ,x). • Pick the first item from L removing its entry. mechanical input power to the generator which is assumed to • Apply hull pruning operator based on Bernstein range be constant, Kd is the damping constant of the generator, Pe enclosure property to the set of constraints (4)-(5) and is the electrical power delivered by the generator, e f d is the 0 obtain the contracted box as x . Compute the range field voltage of the generator, Vt is the terminal voltage of the

enclosures for f , gi, and h j, respectively as b f ,bgi , and generator, and u is the control input from the controller which 0 bh j over x . modulates e f d. All parameters are expressed in per unit (pu) Feasibility and Bounding step (FB) and their equilibrium points values used in the simulation are listed in Table I. For all , we have shifted the • Check the constraint feasibility (see Lemma 1). If actual equilibrium point to the origin using the appropriate the constraint is not strictly feasible, then go to the transformation. branching step. • Check the vertex condition for item (see Remark 2). If TABLE I sol ‘true’, then update fe= bk and add that item to L . Go LISTOF SMIB PARAMETERS AND DATA [16]. to step SP. Parameter Parameter Value Branching step (B) Base angular frequency ΩB 2π × 50 rad/sec Network bus voltage νr 0.90081 pu • Partition the (feasible) search space x into two subre- 0 d-axis transient time constant Td0 8 sec gions (such that, x = x1 ∪ x2). d-axis reactance Xd 1.81 pu d-axis transient reactance X0 0.3 pu • Compute the Bernstein range enclosures for f , gi, and d q-axis reactance Xq 1.76 pu h j over x1 and x2. Transmission line reactance Xr 0.475 pu • Discard xk, k = 1,2 for which min(b f ,k) > fe. Enter Mechanical power Pm 0.9 pu   Generator exciter gain KA 200 ( fbk,b f ,k,bgi,k ,bh j,k ,x) into the list L fbk := min(b f ,k) . Generator exciter time constant TA 0.001 sec Generator inertia constant H 3.5 sec 0 Termination step (T) Stable equilibrium point [δ ω eq e f d ] [1.225 1 1.023 2.42] • If maximum number of the subdivisions are not reached or L is not empty, then repeat SP-FB-B. Else go to the next step. • Find that item in Lsol for which the first entry is equal to fe. Denote that item by I f . ∗ • I f : the first entry is a global minimum f , last entry is the global minimizer x∗. • Return the global solution ( f ∗, x∗). END Algorithm

IV. NMPC APPLICATION: POWERSYSTEM Fig. 3. Classical single machine infinite bus power system network [16]. In this section, we present our findings with Bernstein algorithm (BBB) based NMPC (henceforth, referred as BN- MPC) for nonlinear excitation control of a single machine For the nonlinear control simulation studies we consider infinite bus (SMIB) power system (shown in Fig. 3). We the following two scenarios: use the following SMIB system dynamical model in a d −q Scenario I: A short-circuit fault occurring at one of the reference frame [16]. two parallel transmission lines shown in Fig. 3 (mechanical ˙ δ = ΩB(ω − ωr) (18) power Pm is assumed to be constant at 0.9 pu). 1 Scenario II ω˙ = (Pm − Pe − Kd(ω − ωr)) (19) : 5 % and 10 % step changes of the input 2H mechanical power to the generator.  X e0 0  0 1 dr q (Xdr − Xdr) For both scenarios, we simulate an BNMPC scheme which e˙q = 0 − 0 + 0 νr cos(δ) + e f d (20) Td0 Xdr Xdr regulates the SMIB system about its equilibrium point. We 1 KA KA consider the nonlinear model in (18)-(21) as the system, and e˙f d = − e f d + (1 −Vt ) + u (21) TA TA TA the NMPC control law is derived by solving an NLP of where the form (3)-(6) using the Bernstein algorithm BBB. The solution for the updated states is computed based on the e0 ν sin(δ) (X − X0 ) q r dr dr 2 set of given initial conditions and first optimal control move Pe = 0 + 0 νr cos(δ)sin(δ). Xdr XqrXdr derived by a BNMPC control law. We adopted the cost L q N−1 T T 0 0 2 0 2 in (3) as ∑ x Qxk + u Ruk with the following parameter Vt = (eq − XdId) + (XqIq) . k=0 k k values for the simulation: 0 0 Xdr = Xd + Xr, Xqr = Xq + Xr, X = X + Xr. dr d • sampling time of 0.03 seconds where δ is the rotor angle of the generator, ω is the rotor • prediction horizon, N = 3 T speed, H is the inertia constant of the generator, Pm is the • Q = diag(1 1 1 1) and R = 1 as weighting matrices T • initial condition, x0 = [0 0 0 0] and u0 = 0 oscillations at the cost of offering better damping during the • constraints on the control input, −0.1 6 u 6 0.1 post-fault state. This is evident from the system responses • tolerances, ε f = εzero = 0.001 in the algorithm BBB shown in Figs. 4-6. • maximum number of subdivisions to be 100 in the Scenario II: We now simulate the power system with ini- algorithm BBB tial nominal mechanical power (Pm = 0.9). Then we assume a To compare the performance of an NMPC scheme with the sudden disturbance on the input side of the generator (such Bernstein algorithm (BNMPC), we choose a well-established as, drop in the steam pressure used to rotate the turbines) control scheme from the power systems literature, namely which result in a change in the mechanical power (Pm) of a power system stabilizer (PSS). The tuned parameters of the generator. We consider a 5% step change in Pm from its PSS were adopted from [16, p. 865]. Further, we also nominal value (i.e. 0.9 to 0.8548) at 2 seconds and again 20% choose to compare with respect to linear MPC scheme step change in Pm (i.e. 0.8548 to 1.0258) at 5 seconds. For and NMPC scheme based on YALMIP global optimization the first step change in Pm and constant load, the difference solver BMIBNB [17]. The linear MPC is designed based between the electrical power generated and the desired load on the linearized model of (18)-(21) around the equilibrium is met by reducing the rotor speed (ω) and as a result the 0 point, δ = 1.225, ω = 1, eq = 1.023, and e f d = 2.42. The rotor angle (δ) settles down to a lower equilibrium value. resulting optimization problems were solved using MATLAB The opposite is observed when Pm is increased by 20% from ‘quadprog’ solver [21]. Note that for all control schemes, the its nominal value. control law (u) derived was injected directly to the nonlinear The resulting rotor angle (δ) is shown in Fig. 8. The system (18)-(21). All control simulations were performed in dotted line indicates the system response with the classical the MATLAB environment [21] on a desktop PC running an PSS; solid red line indicates case with our BNMPC; whereas IntelrCore i7-5500U CPU processor at 2.40 GHz with a 8 solid blue line shows the system behavior with the linear GB RAM. We now briefly discuss the simulation results of MPC scheme. It can be observed that the BNMPC scheme the two scenarios. is superior than the PSS in terms of the damping and settling Scenario I: In order to validate the effectiveness of an time. The performance of linear MPC and BNMPC are BNMPC scheme under a disturbance, a short-circuit fault almost equal for the first step change in Pm at 2 seconds. On lasting 100 milliseconds is considered between the two the other hand, for the second step change in Pm at 5 seconds parallel transmission lines. The fault occurs at t = 3 seconds our BNMPC performs better than linear MPC (≈ 7 % and is cleared at t = 3.1 seconds. This event perturbs the reduction in the overshoot). 0 states (δ, ω, eq, e f d) from their equilibrium. The system Fig. 9 shows the generator terminal voltage response may become unstable during the post-fault period due to to the changes in the mechanical power Pm. It can be insufficient damping. Hence, the controller has two roles: i) observed that in this large transient period the PSS scheme to stabilize the system in the post-fault period; and ii) to responds poorly. On the other hand, the BNMPC scheme bring the states back to their equilibrium point. performs satisfactorily, keeping the terminal voltage close to Fig. 4 shows the rotor angle (δ) response of the syn- its nominal value of 1. In this case too the performance of chronous generator. The dotted line indicates the system our BNMPC is better than linear MPC, particularly for the response with the classical PSS; solid red line indicates case second step change in Pm at 5 seconds. with our BNMPC; whereas solid blue line shows the system To assess computational time demand of our BNMPC behaviour with the linear MPC scheme. It can be observed scheme, we compare it with YALMIP global optimization that the BNMPC scheme results in better damping compared solver BMIBNB embedded in an NMPC and the linear MPC to the PSS with quickly bringing the rotor angle back to the schemes. Specifically, we compare the computational times equilibrium point (≈ 28 % reduction in the settling time) and under the aforementioned Scenario I. Fig. 10 shows the time slightly better settling time when compared with the linear taken to compute the control move at each sampling instant MPC. (i.e. to solve an NLP of the form (3)-(6)) by a BMIBNB Similarly, we note that the synchronous generator speed solver, algorithm BBB, and MATLAB linprog solver. We deviation (∆ω) is also disturbed by the short-circuit event. observe that BMIBNB and quadprog solvers resulted in a Fig. 5 shows the speed deviation response of the generator, average time of 0.12 and 0.003 seconds, respectively for where the dotted line indicates the system response with the the control move computation. Further, we observed that for classical PSS; solid red line indicates case with our BNMPC; BNMPC without the use of hull pruning operator resulted whereas solid blue line shows the system behaviour with the in a average time of 0.035 seconds for the control move linear MPC scheme. In this case too BNMPC ensures good computation. On the other hand, in presence of the hull transient stability compared with the PSS and slightly better pruning operator, the control move computation time was settling time when compared with the linear MPC. well within the sampling period of 0.03 seconds—on average Similar findings can be seen in transient responses in the 0.015 seconds. Similar, findings are observed for Scenario II. generator terminal voltage from Fig. 6. Fig. 7 shows the Finally, to study the scalability of our BNMPC scheme control signal delivered to the generator. We note that PSS against the linear MPC scheme, we vary the prediction had a large oscillating damping before settling. On the other horizon N from 3 to 7. An increase in the prediction hand, the BNMPC and linear MPC control moves had small horizon results in an increase in number of decision variables for the optimization problem (3)-(6). Fig. 11 shows the resulting average computational times for the solution of an 1.05 PSS optimization problem. In all cases, BNMPC was found to 1.04 BNMPC LPMC be slower than its counter part, linear MPC, as expected. 1.03 1.02

However, in both cases the average computational time rise 1.01 was observed to be almost linear with the prediction horizon 1 varying from 3 to 7. 0.99 0.98 Generator terminal voltage (pu) 0.97

V. CONCLUSIONS 0.96

0.95 2 3 4 5 6 7 8 In this work a nonlinear model predictive control (NMPC) Time (sec) scheme was presented. The specific highlight of our NMPC Fig. 6. Generator terminal voltage under a 100 ms short-circuit fault scheme was an improved branch-and-prune type Bernstein (Scenario I). global optimization procedure to solve the optimization prob- lems at each sampling instant. This NMPC scheme holds good potential for power systems and other applications, because it uses hull pruning procedure to handle constraints efficiently in the optimization problems at each sampling 0.15 PSS BNMPC instant. Further, such NMPC scheme also benefits from 0.1 LMPC the Bernstein algorithm due to its ability to locate correct 0.05 globally optimal solutions with any desired accuracy, and quickly enough for solving online optimization problems. 0 Control input (pu) The scalability of our NMPC scheme for a varying prediction −0.05 horizon and the computational comparison with respect to −0.1 the linear MPC scheme were also found to be satisfactory.

2 3 4 5 6 7 8 In summary, this paper provides further evidence that the Time (sec) Bernstein algorithm is an effective tool for NMPC. Fig. 7. Control signals under a 100 ms short-circuit fault (Scenario I).

0.2 PSS 0.15 BNMPC LMPC 0.1

0.05 0.2

PSS 0 0.15 BNMPC LMPC −0.05 Rotor angle (pu) 0.1 −0.1 0.05 −0.15

0

−0.2 Rotor angle (pu) 2 3 4 5 6 7 8 Time (sec) −0.05

Fig. 4. Generator rotor angle response under a 100 ms short circuit fault −0.1 (Scenario I). Pm = 0.9 Pm = 0.8548 Pm = 1.0258 −0.15 1 2 3 4 5 6 7 8 Time (sec) Fig. 8. Generator rotor angle response with changes in mechanical power input (Scenario II). −3 x 10 3 PSS BNMPC 2 LMPC

1

0

1.04

−1 PSS 1.03 BNMPC Rotor speed deviation (pu) LMPC

−2 1.02

1.01 −3 2 3 4 5 6 7 8 Time (sec) 1

Fig. 5. Generator rotor speed response under a 100 ms short circuit fault 0.99

(Scenario I). Generator terminal voltage (pu) 0.98

0.97 Pm = 0.9 Pm = 0.8548 Pm = 1.0258

0.96 1 2 3 4 5 6 7 8 Time (sec) Fig. 9. Generator terminal voltage response with changes in mechanical power input (Scenario II). [7] M. Diehl, H. J. Ferreau, and N. Haverbeke, Efficient numerical meth-

NMPC with YALMIP BMIBNB solver ods for nonlinear MPC and moving horizon estimation. In: L. Magni, 0.2 D. M. Raimondo, and F. Allgower¨ (Eds.), Nonlinear Model Predictive 0.1 Control. Springer: Lecture Notes in Control and Information Sciences, Time (sec) 0 pp. 391-417, 2009. 0 50 100 150 200 250 300 Samples [8] J. D. Hedengren, R. A. Shishavana, K. M. Powell, and T. F. Edgar, 0.06 “Nonlinear modeling, estimation and predictive control in APMonitor,” BNMPC without pruning Computers and Chemical Engineering, vol. 70, no. 5, pp. 133–148, 0.04 2014.

Time (sec) 0.02 [9] S. Gros, M. Zanon, R. Quirynen, A. Bemporad, and M. Diehl, “From 0 50 100 150 200 250 300 linear to nonlinear MPC: bridging the gap via the real-time iteration,” Samples 0.04 International Journal of Control, pp. 1–19, 2016. BNMPC with pruning [10] Inga J. Wolf and W. Marquardt, “Fast NMPC schemes for regulatory 0.02 and economic NMPC− A review,” Journal of Process Control, vol. 44, pp. 162–183, 2016. Time (sec) 0 0 50 100 150 200 250 300 [11] L. Biegler, Efficient solution of dynamic optimization and NMPC Samples −3 problems. In: F. Allgower¨ and A. Zheng (Eds.), Nonlinear Model x 10 6 Predictive Control. Springer Basel AG, pp. 219-243, 2000. LMPC with quadprog solver [12] X. Wang, V. Mahalec, and F. Qian, “Globally optimal nonlinear model 4 predictive control based on multi-parametric disaggregation,” Journal

Time (sec) 2 of Process Control, vol. 57, pp. 1–13, 2017. 0 50 100 150 200 250 300 [13] B. V. Patil, J. Maciejowski, and K. V. Ling, “Nonlinear model Samples predictive control based on Bernstein global optimization with appli- cation to a nonlinear CSTR,” IEEE Proceedings of European Control Fig. 10. Comparison of the computation time needed for a solution of an Conference (ECC), pp. 471–476, 2016. optimization problem (in MPC scheme) at each sampling instant: YALMIP [14] B. V. Patil, J. Maciejowski, and K. V. Ling, “Nonlinear model global optimization solver BMIBNB, Bernstein algorithm (with and without predictive control based on improved Bernstein global optimization pruning operator), and linear MPC (Scenario I). Sampling time is 30 ms. algorithm with application to power systems,” 20th IFAC World Congress, July 9-14, Toulouse, 2017. [15] H. Ratschek and J. Rokne, New computer methods for global opti- mization. Chichester, England: Ellis Horwood Publishers, 1988. [16] P. Kundur, Power system stability and control, 1nd edition. New York:

0.09 McGraw-Hill Education, 1994.

LMPC [17] J. Lofberg, “YALMIP: a toolbox for modeling and optimization 0.08 BNMPC in MATLAB,” IEEE International Symposium on computer Aided 0.07 Control Systems Design, pp. 282–289, 2004. [18] B. V. Patil, P. S. V. Nataraj, and S. Bhartiya, “Global optimization 0.06 of mixed- nonlinear (polynomial) programming problems: the 0.05 Bernstein polynomial approach,” Computing, vol. 94, no. 2-4, pp. 325– 343, 2012. 0.04 [19] J. Garloff, “The Bernstein algorithm,” Interval Computations, vol. 2, 0.03 per MPC iterration (sec) pp. 154–168, 1993. Average computational time

0.02 [20] E. R. Hansen and G. W. Walster, Global optimization using interval analysis, 2nd edition. New York: Marcel Dekker, 2005. 0.01 [21] The Mathworks Inc., MATLAB version 8.3 (R2014a), Natick, MA,

0 2014. 3 4 5 6 7 Prediction horizin (N) Fig. 11. Comparison of the average computation time for a solution of an optimization problem (in MPC scheme) at each sampling instant for varying prediction horizon (N): linear MPC (LMPC) and Bernstein algorithm based NMPC (BNMPC) (Scenario I).

REFERENCES

[1] J. M. Maciejowski, Predicitve control with constraints. UK, Harlow: Prentice Hall, 2002. [2] E. F. Camacho and C. Bordons, Model predictive control, 2nd ed. London: Springer-Verlag, 2004. [3] Y. Wan and J. Zhao, “Extended backstepping method for single- machine infinite-bus power systems with SMES,” IEEE Transactions on Control Systems Technology, vol. 21, no. 3, pp. 915–923, 2013. [4] S. S. Kaddah, K. M. Abo-Al-Ez, and T. F. Megahed, “Application of nonlinear model predictive control based on swarm optimization in power systems optimal operation with wind resources,” Electric Power Systems Research, vol. 143, pp. 415–430, 2017. [5] F. Martinsen, L. T. Biegler, and B. A. Fossa, “A new optimization algorithm with application to nonlinear MPC,” Journal of Process Control, vol. 14, no. 8, pp. 853–865, 2004. [6] R. Findeisen, F. Allgower,¨ and L. Biegler. Assessment and future directions of nonlinear model predictive control, Lecture Notes in Control and Information Sciences: Springer-Verlag, 2007.