direct_data_driven_mpc.nonlinear_data_driven_mpc_controller.NonlinearDataDrivenMPCController#

class NonlinearDataDrivenMPCController[source]#

A class that implements a Data-Driven Model Predictive Control (MPC) controller for nonlinear systems. The implementation is based on research by J. Berberich et al., as described in [2].

Attributes:
  • n (int) – The estimated order of the system.

  • m (int) – The number of control inputs.

  • p (int) – The number of system outputs.

  • u (numpy.ndarray) – The input trajectory applied to the system.

  • y (numpy.ndarray) – The system’s output response to u.

  • du (numpy.ndarray) – The input increment trajectory for a controller that uses input increments (ext_out_incr_in = True).

  • N (int) – The length of the initial input (u) and output (y) trajectories.

  • L (int) – The prediction horizon length.

  • Q (numpy.ndarray) – The output weighting matrix for the MPC formulation.

  • R (numpy.ndarray) – The input weighting matrix for the MPC formulation.

  • S (numpy.ndarray) – The output setpoint weighting matrix for the MPC formulation.

  • y_r (numpy.ndarray) – The system output setpoint.

  • lamb_alpha (float) – The ridge regularization weight for alpha.

  • lamb_sigma (float) – The ridge regularization weight for sigma.

  • U (numpy.ndarray) – An array of shape (m, 2) containing the bounds for the m predicted inputs. Each row specifies the [min, max] bounds for a single input.

  • Us (numpy.ndarray) – An array of shape (m, 2) containing the bounds for the m predicted input setpoints. Us must be a subset of U. Each row specifies the [min, max] bounds for a single input.

  • alpha_reg_type (AlphaRegType) – The alpha regularization type for the Nonlinear Data-Driven MPC formulation.

  • lamb_alpha_s (float) – The ridge regularization weight for alpha_s for a controller that uses an approximation of alpha_Lin^sr(D_t) for the regularization of alpha.

  • lamb_sigma_s (float) – The ridge regularization weight for sigma_s for a controller that uses an approximation of alpha_Lin^sr(D_t) for the regularization of alpha.

  • ext_out_incr_in (bool) – The controller structure:

    • If True, the controller uses an extended output representation (y_ext[k] = [y[k], u[k]]) and input increments (u[k] = u[k-1] + du[k-1]).

    • If False, the controller operates as a standard controller with direct control inputs and without system state extensions.

    Defaults to False.

  • update_cost_threshold (float) – The tracking cost value threshold. Online input-output data updates are disabled when the tracking cost value is less than this value.

  • n_mpc_step (int) – The number of consecutive applications of the optimal input for an n-Step Data-Driven MPC Scheme (multi-step).

  • HLn1_u (numpy.ndarray) – The Hankel matrix constructed from the input data u (or du if the controller uses an extended output representation and input increments).

  • HLn1_y (numpy.ndarray) – The Hankel matrix constructed from the output data y.

  • alpha (cvxpy.expressions.variable.Variable) – The optimization variable for alpha.

  • ubar (cvxpy.expressions.variable.Variable) – The predicted control input variable.

  • ybar (cvxpy.expressions.variable.Variable) – The predicted system output variable.

  • u_s (cvxpy.expressions.variable.Variable) – The predicted equilibrium input variable.

  • y_s (cvxpy.expressions.variable.Variable) – The predicted equilibrium output variable.

  • sigma (cvxpy.expressions.variable.Variable) – The optimization variable for sigma.

  • sigma_ubar (Vstack | None) – A CVXPY Vstack object that stacks the sigma values corresponding to the input. Defined only if the controller uses an extended output representation.

  • u_s_tiled (cvxpy.atoms.affine.vstack.Vstack) – A CVXPY Vstack object that stacks the predicted input setpoint variables for use in the cost function formulation.

  • y_s_tiled (cvxpy.atoms.affine.vstack.Vstack) – A CVXPY Vstack object that stacks the predicted output setpoint variables for use in the cost function formulation.

  • alpha_s (cp.Variable | None) – The optimization variable for alpha_s. Defined only if alpha is regularized with respect to an approximation of alpha_Lin^sr(D_t).

  • sigma_s (cp.Variable | None) – The optimization variable for sigma_s. Defined only if alpha is regularized with respect to an approximation of alpha_Lin^sr(D_t).

  • sigma_s_ubar (Vstack | None) – A CVXPY Vstack object that stacks the sigma_s values corresponding to the input. Defined only if the controller uses an extended output representation and if alpha is regularized with respect to an approximation of alpha_Lin^sr(D_t).

  • dynamics_constraint (list[cp.Constraint]) – The system dynamics constraints for a Data-Driven MPC formulation.

  • internal_state_constraint (list[cp.Constraint]) – The internal state constraints for a Data-Driven MPC formulation.

  • terminal_constraint (list[cp.Constraint]) – The terminal state constraints for a Data-Driven MPC formulation.

  • input_constraints (list[cp.Constraint]) – The input constraints for a Data-Driven MPC formulation.

  • constraints (list[cp.Constraint]) – The combined constraints for the Data-Driven MPC formulation.

  • cost (cvxpy.expressions.expression.Expression) – The cost function for the Data-Driven MPC formulation.

  • problem (cvxpy.problems.problem.Problem) – The quadratic programming problem for the Data-Driven MPC.

  • optimal_u (numpy.ndarray) – The optimal control input derived from the Data-Driven MPC solution.

  • optimal_du (np.ndarray | None) – The optimal control input increments derived from the Data-Driven MPC solution. Defined only for controllers with an extended output representation and input increments.

  • prev_alpha_val (np.ndarray | None) – The previous value of alpha used for when alpha is regularized with respect to the previous optimal alpha value. Defined only if alpha is regularized with respect to its previous optimal alpha value.

  • ones_NLn (numpy.ndarray) – A vector of ones of shape (1, N - L - n).

  • ones_Ln1 (numpy.ndarray) – A vector of ones of shape (L + n + 1, 1).

  • ones_n1 (numpy.ndarray) – A vector of ones of shape (n + 1, 1).

  • U_const_low (numpy.ndarray) – A tiled lower bound for the input trajectory constraints over the prediction horizon.

  • U_const_up (numpy.ndarray) – A tiled upper bound for the input trajectory constraints over the prediction horizon.

  • Us_const_low (numpy.ndarray) – The lower bound for the equilibrium input constraints.

  • Us_const_up (numpy.ndarray) – The upper bound for the equilibrium input constraints.

References

[2] J. Berberich, J. Köhler, M. A. Müller and F. Allgöwer, “Linear Tracking MPC for Nonlinear Systems—Part II: The Data-Driven Case,” in IEEE Transactions on Automatic Control, vol. 67, no. 9, pp. 4406-4421, Sept. 2022, doi: 10.1109/TAC.2022.3166851.

__init__(n: int, m: int, p: int, u: ndarray, y: ndarray, L: int, Q: ndarray, R: ndarray, S: ndarray, y_r: ndarray, lamb_alpha: float, lamb_sigma: float, U: ndarray, Us: ndarray, alpha_reg_type: AlphaRegType = AlphaRegType.ZERO, lamb_alpha_s: float | None = None, lamb_sigma_s: float | None = None, ext_out_incr_in: bool = False, update_cost_threshold: float | None = None, n_mpc_step: int = 1)[source]#

Initialize a Direct Nonlinear Data-Driven MPC with specified system model parameters, an initial input-output data trajectory measured from the system, and Nonlinear Data-Driven MPC parameters.

Note

The input data u used to excite the system to get the initial output data must be persistently exciting of order (L + n + 1), as defined in the Data-Driven MPC formulation in [2].

Parameters:
  • n (int) – The estimated order of the system.

  • m (int) – The number of control inputs.

  • p (int) – The number of system outputs.

  • u (numpy.ndarray) – A persistently exciting input sequence.

  • y (numpy.ndarray) – The system’s output response to u.

  • L (int) – The prediction horizon length.

  • Q (numpy.ndarray) – The output weighting matrix for the MPC formulation.

  • R (numpy.ndarray) – The input weighting matrix for the MPC formulation.

  • S (numpy.ndarray) – The output setpoint weighting matrix for the MPC formulation.

  • y_r (numpy.ndarray) – The system output setpoint.

  • lamb_alpha (float) – The ridge regularization weight for alpha.

  • lamb_sigma (float) – The ridge regularization weight for sigma.

  • U (numpy.ndarray) – An array of shape (m, 2) containing the bounds for the m predicted inputs. Each row specifies the [min, max] bounds for a single input.

  • Us (numpy.ndarray) – An array of shape (m, 2) containing the bounds for the m predicted input setpoints. Us must be a subset of U. Each row specifies the [min, max] bounds for a single input.

  • alpha_reg_type (AlphaRegType) – The alpha regularization type for the Nonlinear Data-Driven MPC formulation.

  • lamb_alpha_s (float | None) – The ridge regularization weight for alpha_s for a controller that uses an approximation of alpha_Lin^sr(D_t) for the regularization of alpha.

  • lamb_sigma_s (float | None) – The ridge regularization weight for sigma_s for a controller that uses an approximation of alpha_Lin^sr(D_t) for the regularization of alpha.

  • ext_out_incr_in (bool) –

    The controller structure:

    • If True, the controller uses an extended output representation (y_ext[k] = [y[k], u[k]]) and input increments (u[k] = u[k-1] + du[k-1]).

    • If False, the controller operates as a standard controller with direct control inputs and without system state extensions.

    Defaults to False.

  • update_cost_threshold (float | None) – The tracking cost value threshold. Online input-output data updates are disabled when the tracking cost value is less than this value. If None, input-output data is always updated online. Defaults to None.

  • n_mpc_step (int) – The number of consecutive applications of the optimal input for an n-Step Data-Driven MPC Scheme (multi-step). Defaults to 1.

References

[2] J. Berberich, J. Köhler, M. A. Müller and F. Allgöwer, “Linear Tracking MPC for Nonlinear Systems—Part II: The Data-Driven Case,” in IEEE Transactions on Automatic Control, vol. 67, no. 9, pp. 4406-4421, Sept. 2022, doi: 10.1109/TAC.2022.3166851.

evaluate_input_persistent_excitation() None[source]#

Evaluate whether the input data is persistently exciting of order (L + n + 1).

This method first verifies that the length of the elements in the input data matches the number of inputs of the system. Then, it evaluates the rank of the Hankel matrix induced by the input sequence to determine if the input sequence is persistently exciting of order (L + n + 1), as described in Definition 1 [2].

Raises:

ValueError – If the length of the elements in the data sequence does not match the number of inputs of the system, or if the input data is not persistently exciting of order (L + n + 1).

References

[2]: See class-level docstring for full reference details.

check_prediction_horizon_length() None[source]#

Check if the prediction horizon length, L, satisfies the MPC system design, as described in [2].

Raises:

ValueError – If the prediction horizon L is less than the required threshold based on the controller type.

References

[2]: See class-level docstring for full reference details.

check_weighting_matrices_dimensions() None[source]#

Check if the dimensions of the output (Q), input (R), and setpoint (S) weighting matrices are correct for an MPC formulation based on their order.

Raises:

ValueError – If the dimensions of the Q, R, or S matrices are incorrect.

initialize_data_driven_mpc() None[source]#

Initialize the Data-Driven MPC controller.

This method performs the following tasks:

  1. Constructs Hankel matrices from the initial input-output trajectory data (u, y). These matrices are used for the data-driven characterization of the unknown system, as defined by the system dynamic constraints in the Nonlinear Data-Driven MPC formulation of [2].

  2. Defines the optimization variables for the Data-Driven MPC problem.

  3. Defines the constraints for the MPC problem, which include the system dynamics, internal state, terminal state, and input constraints.

  4. Defines the cost function for the MPC problem.

  5. Formulates the MPC problem as a Quadratic Programming (QP) problem.

  6. Solves the initialized MPC problem to ensure the formulation is valid and retrieve the optimal control input for the initial setup.

This initialization process ensures that all necessary components for the Data-Driven MPC are correctly defined and that the MPC problem is solvable with the provided initial data.

References

[2]: See class-level docstring for full reference details.

update_and_solve_data_driven_mpc(warm_start: bool = False) None[source]#

Update the Data-Driven MPC optimization parameters, solve the problem, and store the optimal control input.

This method performs the following tasks:

  1. Constructs Hankel matrices using the latest measured input-output data. If the tracking cost value from the previous solution is small enough (less than update_cost_threshold), omits this step and the previously defined matrices are used.

  2. Updates the MPC optimization parameters to use the latest input-output measurements. Additionally, it updates the value of alpha_Lin^sr(D_t) if alpha is not regularized with respect to zero.

    Note: The value of alpha_Lin^sr(D_t) is computed during the optimization parameter update.

  3. Solves the MPC problem and stores the resulting optimal control input.

  4. Stores the optimal value of alpha if alpha is regularized with respect to its previous optimal value (see Section V of [2]).

  5. Toggles online data updates based on the current tracking cost value.

References

[2]: See class-level docstring for full reference details.

define_optimization_variables() None[source]#

Define the optimization variables for the Data-Driven MPC controller.

This method defines data-driven MPC optimization variables as described in the Nonlinear Data-Driven MPC formulation in [2].

Note

This method initializes attributes that define the MPC optimization variables for the controller. Additional attributes are initialized if the MPC controller uses an extended output representation and input increments or if the alpha regularization type is APPROXIMATED.

References

[2]: See class-level docstring for full reference details.

define_optimization_parameters() None[source]#

Define MPC optimization parameters that are updated at every step iteration.

This method initializes the following MPC parameters:

  • Output setpoint: y_r_param.

  • Hankel matrices: HLn1_u_param and HLn1_y_param.

  • Past inputs and outputs: u_past_param and y_past_param.

  • Past input increments: du_past_param (if applicable).

  • Computed value of alpha_Lin^sr(D_t): alpha_sr_Lin_D_param (if alpha is not regularized with respect to zero).

The value of y_r_param is initialized to y_r.

These parameters are updated at each MPC iteration, except for y_r_param, which must be manually updated when setting a new controller setpoint.

Using CVXPY Parameter objects allows efficient updates without the need of reformulating the MPC problem at every step.

update_optimization_parameters() None[source]#

Update MPC optimization parameters.

This method updates the MPC optimization parameters using the most recent input-output measurement data.

Additionally, it updates the computed alpha_Lin^sr(D_t) value based on the alpha regularization type:

  • alpha_reg_type == AlphaRegType.APPROXIMATED: Computes alpha_Lin^sr(D_t) solving Equation (23) of [2] and updates its value.

  • alpha_reg_type == AlphaRegType.PREVIOUS: Updates alpha_Lin^sr(D_t) with the previous optimal value of alpha.

References

[2]: See class-level docstring for full reference details.

define_mpc_constraints() None[source]#

Define the constraints for the Data-Driven MPC formulation.

This method defines the following constraints, as described in the Nonlinear Data-Driven MPC formulation in [2]:

  • System dynamics: Ensures input-output predictions are possible trajectories of the system based on a data-driven characterization of all its input-output trajectories. Defined by Equation (22b).

  • Internal state: Ensures predictions align with the internal state of the system’s trajectory. This constrains the first n input-output predictions to match the past n input-output measurements of the system, guaranteeing that the predictions consider the initial state of the system. Defined by Equation (22c).

  • Terminal state: Aims to stabilize the internal state of the system so it aligns with the steady-state that corresponds to the input-output equilibrium pair (predicted equilibrium setpoints u_s, y_s) in any minimal realization (last n input-output predictions, as considered in [2]). Defined by Equation (22d).

  • Input: Constrains both the equilibrium input (predicted input setpoint u_s) and the input trajectory (ubar). Defined by Equation (22e).

Note

This method initializes the dynamics_constraints, internal_state_constraints, terminal_constraints, input_constraints, and constraints attributes to define the MPC constraints based on the MPC controller type.

References

[2]: See class-level docstring for full reference details.

define_system_dynamic_constraints() list[Constraint][source]#

Define the system dynamic constraints for the Data-Driven MPC formulation.

These constraints use a data-driven characterization of all the input-output trajectories of a system, as defined by Theorem 1 [2], to ensure predictions are possible system trajectories. This is analogous to the system dynamics constraints in a typical MPC formulation.

These constraints are defined according to Equation (22b) of [2].

Returns:

list[cp.Constraint] – A list containing the CVXPY system dynamic constraints for the Data-Driven MPC controller, corresponding to the specified MPC controller type.

References

[2]: See class-level docstring for full reference details.

define_internal_state_constraints() list[Constraint][source]#

Define the internal state constraints for the Data-Driven MPC formulation.

These constraints ensure predictions align with the internal state of the system’s trajectory. This way, the first n input-output predictions are constrained to match the past n input-output measurements of the system, guaranteeing that the predictions consider the initial state of the system.

These constraints are defined according to Equation (22c) of [2].

Returns:

list[cp.Constraint] – A list containing the CVXPY internal state constraints for the Data-Driven MPC controller.

Note

It is essential to update the system’s input-output measurements, u, y, and du, at each MPC iteration.

References

[2]: See class-level docstring for full reference details.

define_terminal_state_constraints() list[Constraint][source]#

Define the terminal state constraints for the Data-Driven MPC formulation.

These constraints aim to stabilize the internal state of the system so it aligns with the steady-state that corresponds to the input-output pair (predicted equilibrium setpoints u_s, y_s) in any minimal realization, specifically the last n input-output predictions, as considered in [2].

These constraints are defined according to Equation (22d) of [2].

Returns:

list[cp.Constraint] – A list containing the CVXPY terminal state constraints for the Data-Driven MPC controller.

References

[2]: See class-level docstring for full reference details.

define_input_constraints() list[Constraint][source]#

Define the input constraints for the Data-Driven MPC formulation.

These constraints are defined according to Equation (22e) of [2].

Returns:

list[cp.Constraint] – A list containing the CVXPY input constraints for the Data-Driven MPC controller.

define_cost_function() None[source]#

Define the cost function for the Data-Driven MPC formulation.

This method defines the MPC cost function as described in the Nonlinear Data-Driven MPC formulation in Section IV of [2]. The value of alpha_Lin^sr(D_t) is computed during the cost function definition.

Note

This method initializes the cost attribute to define the MPC cost function.

References

[2]: See class-level docstring for full reference details.

define_mpc_problem() None[source]#

Define the optimization problem for the Data-Driven MPC formulation.

Note

This method initializes the problem attribute to define the MPC problem of the Data-Driven MPC controller, which is formulated as a Quadratic Programming (QP) problem. It assumes that the cost (objective function) and constraints attributes have already been defined.

solve_mpc_problem(warm_start: bool = False) str[source]#

Solve the optimization problem for the Data-Driven MPC formulation.

Returns:

str – The status of the optimization problem after attempting to solve it (e.g., “optimal”, “optimal_inaccurate”, “infeasible”, “unbounded”).

Note

This method assumes that the MPC problem has already been defined. It solves the problem and updates the problem attribute with the solution status.

get_problem_solve_status() str[source]#

Get the solve status of the optimization problem of the Data-Driven MPC formulation.

Returns:

str – The status of the optimization problem after attempting to solve it (e.g., “optimal”, “optimal_inaccurate”, “infeasible”, “unbounded”).

get_optimal_cost_value() float[source]#

Get the cost value corresponding to the solved optimization problem of the Data-Driven MPC formulation.

Returns:

float – The optimal cost value of the solved MPC optimization problem.

get_optimal_control_input() ndarray[source]#

Retrieve and store either the optimal control input or the optimal control input increments from the MPC solution.

Returns:

np.ndarray – The predicted optimal control input from time step 0 to L. If the controller uses an extended output representation and input increments, returns the predicted optimal control input increments instead.

Raises:

ValueError – If the MPC problem solution status was not “optimal” or “optimal_inaccurate”.

Note

This method should be called after the MPC problem has been solved. It stores the predicted optimal control input in the optimal_u attribute, or the predicted optimal control input increments in the optimal_du attribute if the controller uses an extended output representation and input increments.

get_optimal_control_input_at_step(n_step: int = 0) ndarray[source]#

Get the optimal control input (u) from the MPC solution corresponding to a specified time step in the prediction horizon [0, L].

Parameters:

n_step (int) – The time step of the optimal control input to retrieve. It must be within the range [0, L].

Returns:

np.ndarray – An array containing the optimal control input for the specified prediction time step.

Note

This method assumes that the optimal control input from the MPC solution has been stored in the optimal_u attribute. For a controller that uses an extended output representation and input increments, the last du value should contain the optimal control input increment computed from the previous MPC solution (optimal_du[:m]).

Raises:

ValueError – If n_step is not within the range [0, L].

store_previous_alpha_value() None[source]#

Store the previous optimal value of alpha for regularization in subsequent MPC iterations.

get_du_value_at_step(n_step: int = 0) ndarray | None[source]#

Get the optimal control input increment (du) from the MPC solution corresponding to a specified time step in the prediction horizon [0, L].

Parameters:

n_step (int) – The time step of the optimal control input to retrieve. It must be within the range [0, L].

Returns:

np.ndarray | None – An array containing the optimal control input increment for the specified prediction time step if the controller uses an extended output representation and input increments. Otherwise, returns None.

Note

This method assumes that the optimal_du attribute contains the optimal control input increments from the MPC solution.

store_input_output_measurement(u_current: ndarray, y_current: ndarray, du_current: ndarray | None = None) None[source]#

Store an input-output measurement pair for the current time step in the input-output storage variables. If the controller uses an extended output representation and input increments, the input increment corresponding to the current input measurement is also stored.

This method updates the input-output storage variables u, y and du by shifting the arrays and replacing the oldest measurements with the current ones.

Parameters:
  • u_current (numpy.ndarray) – The control input (u[k]) for the current time step, expected to match the dimensions of prior inputs.

  • y_current (numpy.ndarray) – The measured system output for the current time step, expected to match the dimensions of prior outputs. This output should correspond to the system’s response to u_current, as both represent a trajectory of the system.

  • du_current (np.ndarray | None) – The control input increment (du[k] = u[k+1] - u[k]) for the current time step, expected to match the dimensions of prior inputs.

Raises:

ValueError – If u_current, y_current, or du_current do not match the expected dimensions.

Note

This method updates the u, y, and du arrays.

References

[2]: See class-level docstring for full reference details.

set_input_output_data(u: ndarray, y: ndarray) None[source]#

Set the variables for the current input-output measurements.

This method assigns the provided input-output measurements to the arrays storing the current input-output measurements, u and y.

Parameters:
  • u (numpy.ndarray) – An array containing the current measured control input. Expected to have a shape of (N, m), where ‘N’ is the trajectory length and ‘m’ is the dimension of the input.

  • y (numpy.ndarray) – An array containing the current measured system output. Expected to have a shape of (N, p) where ‘N’ is the trajectory length and ‘p’ is the dimension of the output.

Raises:

ValueError – If u or y do not have correct dimensions.

Note

This method sets the values of the u and y attributes with the provided new input-output data.

set_output_setpoint(y_r: ndarray) None[source]#

Set the system output setpoint of the Data-Driven MPC controller.

Parameters:

y_r (numpy.ndarray) – The setpoint for system outputs.

Raises:

ValueError – If y_r does not have the expected dimensions.

Note

This method sets the values of the y_r attribute with the provided new setpoint and updates the value of y_r_param to update the data-driven MPC controller setpoint.

define_alpha_sr_Lin_Dt_prob() None[source]#

Define a Quadratic Programming (QP) problem for computing an approximation of alpha_Lin^sr(D_t) using the latest input-output system measurements for the current iteration. The QP formulation is based on Equation (23) of [2].

References

[2]: See class-level docstring for full reference details.

solve_alpha_sr_Lin_Dt() ndarray[source]#

Compute the approximation of alpha_Lin^sr(D_t) using the latest input-output system measurements for the current iteration.

Returns:

np.ndarray – The computed approximation of alpha_Lin^sr(D_t).

Raises:

ValueError – If the QP solver fails to converge to an optimal solution.

Note

This method assumes that the Quadratic Programming (QP) problem for computing the approximation of alpha_Lin^sr(D_t) (alpha_sr_Lin_Dt_prob) has already been defined.