🧠 Optimal Control Theory – An Introduction
“Because the shape of the whole universe is most perfect and, in fact, designed by the wisest Creator, nothing in the world will occur without some maximum or minimum rule.” – Leonhard Euler, 1744
📌 1. Introduction
Optimal Control Theory is concerned with finding control strategies that make a system behave in the best possible way, based on a performance measure.
- Classical Control: Uses input-output models (SISO).
- Modern Control: Uses state variables and matrix theory.
- Calculus of Variations: Foundation for optimization.
⚙️ 1.2 Classical Control
Applied to linear, time-invariant, SISO systems. Design focuses on:
- Time Response: Rise time, peak overshoot, settling time
- Frequency Response: Gain & phase margins, bandwidth
🧮 1.3 Modern Control Theory
- Uses state-space feedback with full state information
- Controller input u(t) computed based on states X(t) and reference r(t)
- Based on matrix theory and multiple model representations
🔄 1.4 Components of a Modern Control System
- Modeling: Uses differential/difference equations (Lagrange function)
- Analysis: Evaluate stability and performance (Lyapunov function)
- Design: Optimize system behavior using performance index J(X)
Key Functions: • Lagrange Function (1788) – Modeling • Lyapunov Function (1892) – Stability • Pontryagin’s H Function (1956) – Optimization
⚖️ 1.5 Optimization
Static Optimization
- Applies to steady-state systems (time-invariant)
- Techniques: Ordinary calculus, Lagrange multipliers, Linear/Nonlinear programming
Dynamic Optimization
- Applies when system variables change over time
- Techniques: Calculus of variations, Pontryagin principle, Dynamic programming
🎯 1.6 Optimal Control Problem
To define an optimal control problem, specify:
- A mathematical model (typically state-space form)
- A performance index J or I
- Boundary conditions and constraints
🏁 Types of Performance Indices
- Time-Optimal Control
- Fuel-Optimal Control
- Minimum Energy Control
- Terminal State Control
- General Optimal Control
Performance Index Forms
- Mayer Problem: Cost depends on terminal state only
- Lagrange Problem: Cost depends on integral over time
- Bolza Problem: Combines terminal and integral costs
✅ Summary: Optimal Control Framework
Solve the problem by modeling the system as: 𝑅 = f(X, u, t)
And define the performance index:
J = φ(X(T)) + ∫₀ᵀ L(X(t), u(t), t) dt
Subject to:
- Initial conditions
- State/control constraints
- Boundary conditions
1.2 Classical Control
Classical or conventional control theory focuses on the analysis and design of single-input single-output (SISO) systems. It is primarily based on the use of Laplace transform methods and block diagram representations to study system behavior in the frequency domain. In a classical feedback control system, the input signal to the plant, denoted by u(t), is generated by processing the error signal e(t) through a compensator or controller. The error signal is the difference between the desired reference input r(t) and the actual output y(t) of the system.
Note: • Only the output of the system is used for feedback; internal state variables are not available. • Classical control is generally applied to linear time-invariant (LTI) systems.
The closed-loop transfer function of a typical classical control system with unity feedback is given by:
Y(s) / R(s) = G(s) / (1 + G(s)H(s)) (1.1)
where:
- Y(s) and R(s) are the Laplace transforms of the output and input, respectively,
- G(s) is the open-loop transfer function,
- H(s) is the transfer function of the feedback path.
If the open-loop system consists of a compensator and a plant, the transfer function G(s) is expressed as:
G(s) = Gc(s) × Gp(s) (1.2)
where:
- Gc(s) is the transfer function of the compensator (controller).
- Gp(s) is the transfer function of the plant (the system to be controlled).
Fig. 1. Classical Control System Configuration
1.3 Modern Control Theory
Modern control theory, also referred to as advanced control, extends classical control to handle more complex systems, especially those with multiple inputs and multiple outputs (MIMO). It is based on the state-variable representation, which models systems using first-order differential equations in the time domain. This approach provides a more complete description of system dynamics and is applicable to linear, nonlinear, time-invariant, and time-varying systems.
State-Space Representation of Linear Time-Invariant (LTI) Systems
The state-space model for an LTI system is given by:
Ẋ(t) = A·X(t) + B·U(t) (1.3)
Y(t) = C·X(t) + D·U(t) (1.4)
Where:
- X(t) – State vector
- U(t) – Input vector
- Y(t) – Output vector
- A – System matrix
- B – Input matrix
- C – Output matrix
- D – Feedthrough (or direct transmission) matrix
State-Space Representation of Nonlinear Systems
For nonlinear systems, the state-space representation becomes
Ẋ(t) = f(X(t), U(t), t) (1.5)
Y(t) = g(X(t), U(t), t) (1.6)
Here, f(·) and g(·) are nonlinear functions that describe the system’s dynamics and output, respectively. This representation enables the use of advanced control techniques such as state feedback, observer design, optimal control, and robust control, making it essential for high-order and complex system analysis and design.
State Feedback in Modern Control Theory
In modern control theory, all state variables are ideally available for feedback. This allows the controller to make accurate and effective decisions. The input u(t) is determined by the controller, which includes an error detector and a compensator, based on the system states X(t) and the reference input r(t), as shown in Fig. 2. This structure supports state feedback control, where each state is multiplied by an appropriate gain to achieve the desired system response — such as improved stability or faster dynamics. Modern control is based on matrix algebra and is well-suited for digital computer implementation and simulations. It provides a flexible and systematic method to model and control multi-input, multi-output (MIMO) systems. It is also important to note that while the state-space model uniquely determines the system’s transfer function, the reverse is not true: a single transfer function can have many valid state-space representations. This allows engineers to choose forms like controllable, observable, or diagonal for convenience in analysis and design. Fig.2. Modern Control System Configuration 1.4. Components of the Modern Control System
Fig. 3. Main Components of Modern Control System
Modeling:
The first step in any control theory approach is to model the system dynamics. This involves formulating the system using differential or difference equations. In many cases, the dynamics are derived using the Lagrangian function.
Analysis:
Once the model is established, the system is analyzed to evaluate its performance—especially its stability. A fundamental tool for this analysis is Lyapunov stability theory, which helps determine whether the system will remain stable under various conditions.
Design:
If the system does not meet the desired performance specifications, the next step is control system design. In optimal control theory, this involves designing a controller that minimizes or maximizes a performance index (commonly denoted as J(X) or I(X)) based on system states.
1.5. Optimization Fig.4. Overview of Optimization Optimization can be broadly classified into static optimization and dynamic optimization.
1. Static Optimization
Static optimization involves controlling a plant under steady-state conditions, where system variables do not change with time. The plant is described by algebraic equations. Techniques used: Ordinary calculus, Lagrange multipliers, linear programming, and nonlinear programming.
2. Dynamic Optimization
Dynamic optimization deals with the control of a plant under dynamic conditions, where system variables change over time. The plant is described by differential or difference equations. Techniques used: Search techniques, dynamic programming, calculus of variations, and Pontryagin’s principle.
1.6 Optimal Control
Objective
The objective of optimal control is to determine a control signal u*(t) that drives the system (plant) in such a way that it:
- Satisfies all physical and operational constraints.
- Minimizes or maximizes a chosen performance index J or I.
Formulation of an Optimal Control Problem
To formulate an optimal control problem, the following components are required:
- Mathematical Model of the Process A detailed description of the physical system to be controlled, usually expressed in state-space form.
- Performance Index A scalar function (typically an integral over time) that quantifies the objective to be optimized—such as energy usage, error, time, or cost.
- Boundary Conditions and Constraints Specifications for initial/final states, along with physical constraints on the system variables and control inputs.
System (Plant) Representation
For optimization purposes, a physical plant is modeled using either linear or nonlinear differential equations. A linear time-invariant (LTI) system is typically described by:
Ẋ(t) = AX(t) + BU(t) (1.3) Y(t) = CX(t) + DU(t) (1.4)
A nonlinear system is generally represented as:
Ẋ(t) = f(X(t), U(t), t) (1.5) Y(t) = g(X(t), U(t), t) (1.6)
Where:
- Ẋ(t) is the state vector
- U(t) is the control input
- Y(t) is the output
- A, B, C, D are system matrices
- f(·), g(·) are nonlinear functions of state, input, and time
Performance Index / Performance Measure (I or J):
1. Classical Control:
Classical control techniques are applied to linear, time-invariant, single-input single-output (SISO) systems. These methods analyze system behavior in both the time and frequency domains.
Time-domain specifications include:
- Rise time
- Settling time
- Peak overshoot
- Steady-state error
Frequency-domain characteristics include:
- Gain margin
- Phase margin
- Bandwidth
Common controllers include PID (Proportional-Integral-Derivative) controllers.
2. Modern Control:
Modern control theory applies to multi-input multi-output (MIMO) systems using state-space representation. It allows feedback using all system state variables. A key objective is optimal control, where the control input drives the system to a desired state or trajectory while optimizing a performance index. Performance index may involve
- Energy consumption
- Time to reach target
- Control effort
Minimizing the performance index I means minimizing the time required to complete the control task.
Minimizing the performance index I means minimizing the time required to complete the control task.
2. Performance Index: Fuel-Optimal Control (Minimum Fuel Problem)
Consider a spacecraft control problem where u(t) represents the thrust produced by the rocket engine. The magnitude of the thrust, |u(t)|, is assumed to be proportional to the rate of fuel consumption.
To minimize the total fuel expenditure, the performance index (PI) is defined as:
I = ∫t₀tf |u(t)| dt (1.8)
This integral represents the total fuel consumed over the time interval from t₀ to tf.
For a multi-input system with m control inputs u1(t), u2(t), …, um(t), the performance index becomes:
I = ∫t₀tf ∑i=1m Ri |ui(t)| dt (1.9)
Where:
- Ri is the weighting factor for the ith control input
- |ui(t)| is the magnitude of the control input
These weighting factors allow for prioritization or penalization of fuel usage across different thrusters or control channels.
3. Performance Index: Energy-Optimal Control (Minimum Energy Problem)
Consider ui(t) as the current in the ith loop of an electric network, and let ri be the resistance of that loop. The total power or rate of energy expenditure at time t is given by:
∑i=1m ui2(t) ri
To minimize the total energy expended over the time interval [t₀, tf], the performance index is defined as:
I = ∫t₀tf ∑i=1m ui2(t) ri dt (1.10)
This expression represents the total energy consumed by the network during the control interval.
In a more general vector-matrix form, the performance index becomes:
I = ∫t₀tf UT(t) R U(t) dt (1.11)
Where:
- U(t) is the control vector containing all inputs ui(t)
- R is a positive definite matrix representing energy weighting factors (e.g., resistances)
This form is commonly used in optimal control, especially in the Linear Quadratic Regulator (LQR) problem to penalize control energy.
Minimizing the performance index I means minimizing the time required to complete the control task.
Minimization of Tracking Error in Optimal Control
In a tracking system, we aim to minimize the deviation of the actual state from the desired trajectory over time. This objective can be achieved by minimizing the integral of the squared tracking error. I = ∫t₀tf XT(t) Q X(t) dt (1.12) Where:
- Xd(t) is the desired state,
- Xa(t) is the actual state,
- X(t) = Xa(t) − Xd(t) is the tracking error,
- Q is a positive semidefinite weighting matrix.
Note: The matrix Q may be time-varying depending on the system requirements. This form is widely used in tracking problems where minimizing the accumulated error over time is essential. 4. Performance Index for Terminal Control System: In a terminal target problem, we are interested in minimizing the error between the desired target position Xd (tf) and the actual target position Xa (tf) at the end of the maneuver or at the final time tf. The terminal (final) error is X(tf) = Xa(tf) – Xd (tf ). Taking care of positive and negative values of error and weighting factors, we structure the cost function as I= X^T (t_f )PX(t_f ) (1.13) which is also called the terminal cost function. Here, P is a positive semi-definite matrix.
4. Performance Index for Terminal Control System
In a terminal control problem, the objective is to minimize the error between the actual and desired system states at the final time tf. Specifically, we are concerned with the difference between the actual terminal state Xa(tf) and the desired terminal state Xd(tf). The terminal error is defined as: X(tf) = Xa(tf) − Xd(tf) To account for both positive and negative errors and apply appropriate weighting, the performance index (also called the terminal cost function) is defined as: I = XT(tf) P X(tf) (1.13) Where:
- X(tf) is the terminal state error
- P is a positive semidefinite weighting matrix
This cost function focuses only on the final state, making it suitable for applications where performance at the endpoint is critical.
5. Performance Index for General Optimal Control System
By combining terminal and tracking objectives, the performance index for a general optimal control problem can be expressed as: I = XT(tf) P X(tf) + ∫t₀tf [XT(t) Q X(t) + UT(t) R U(t)] dt (1.14) Alternatively, in a more general form, it can be written as: I = S(X(tf), tf) + ∫t₀tf F(X(t), U(t), t) dt (1.15) Where:
- X(t) is the state vector
- U(t) is the control input vector
- Q and P are positive semidefinite weighting matrices
- R is a positive definite weighting matrix
- S(X(tf), tf) is the terminal cost function
- F(X(t), U(t), t) is the running (or path) cost function
Note: The matrices Q(t) and R(t) may vary with time depending on the problem requirements. Equation (1.14) is known as the quadratic performance index because it is quadratic in terms of both the states and control inputs. It is widely used in Linear Quadratic Regulator (LQR) and related optimal control problems.
Classification of Optimal Control Problems Based on Performance Index
Optimal control problems are often classified according to the structure of the performance index I. The classification is as follows:
- Mayer Problem:
If the performance index includes only the terminal cost function,
I = S(X(tf), tf)
it is called a Mayer-type problem. - Lagrange Problem:
If the performance index consists only of the integral (running) cost term,
I = ∫t₀tf F(X(t), U(t), t) dt
it is referred to as a Lagrange-type problem. - Bolza Problem:
If the performance index includes both the terminal cost and the integral cost term,
I = S(X(tf), tf) + ∫t₀tf F(X(t), U(t), t) dt
it is known as a Bolza-type problem.
Although various other forms of cost functions can be used depending on performance specifications, the quadratic forms of these indices lead to particularly elegant and tractable solutions in optimal control theory.
Constraints in Optimal Control Problems
In optimal control problems, the control input u(t) and the state vector x(t) may be either unconstrained or constrained, depending on the physical nature of the system.
Unconstrained problems are mathematically simpler and often lead to elegant analytical solutions. However, in practical systems, physical limitations typically impose constraints on both control and state variables.
For example, in systems such as electrical circuits, motors, or rockets, variables like current, voltage, speed, or thrust must lie within specified limits. These constraints are usually expressed as:
Umin ≤ u(t) ≤ Umax, Xmin ≤ x(t) ≤ Xmax (1.16)
Where:
- Umin and Umax: Minimum and maximum allowable control values
- Xmin and Xmax: Minimum and maximum allowable state values
These constraints must be considered in the formulation and solution of realistic optimal control problems.
Formal Statement of an Optimal Control Problem (Linear Time-Invariant System)
Consider the linear time-invariant (LTI) system:
𝑐̇(t) = A X(t) + B U(t), t ∈ [t0, tf] (1.17)
with the initial condition:
X(t0) = X0
Problem: Find the control input U*(t) that minimizes the performance index:
I = XT(tf) P X(tf) + ∫t₀tf [XT(t) Q X(t) + UT(t) R U(t)] dt (1.18)
The corresponding state trajectory generated by U*(t) is denoted X*(t).
Where:
- X(t) ∈ ℝⁿ is the state vector
- U(t) ∈ ℝᵐ is the control vector
- A ∈ ℝⁿˣⁿ and B ∈ ℝⁿˣᵐ are constant system matrices
- P and Q are positive semidefinite weighting matrices (P ≥ 0, Q ≥ 0)
- R is a positive definite weighting matrix (R > 0)
This formulation, which includes both terminal and integral quadratic cost terms, is the standard setup for the Linear Quadratic Regulator (LQR) problem.
Formal Statement of an Optimal Control Problem (Nonlinear System)
Consider a nonlinear dynamic system described by:
𝑐̇(t) = f(X(t), U(t), t), t ∈ [t0, tf] (1.19)
with the initial condition:
X(t0) = X0
Objective:
Find the optimal control U*(t) that generates the optimal state trajectory X*(t) such that the following general performance index is minimized (or maximized):
I = S(X(tf), tf) + ∫t₀tf F(X(t), U(t), t) dt (1.20)
Subject to:
- The nonlinear system dynamics (Equation 1.19)
- Constraints on control and/or state variables:
Umin ≤ U(t) ≤ Umax, Xmin ≤ X(t) ≤ Xmax (1.16)
The final time tf may be fixed or free, and the final (target) state may be fully specified, partially specified, or free, depending on the nature of the problem.
This formulation represents a general nonlinear optimal control problem and encompasses a wide variety of real-world applications.
The entire problem statement is also shown pictorially in Figure 5. Thus,
Fig.5. Formal Representation of Optimal Control