Static Public Member Functions | Static Protected Member Functions | List of all members
corbo::AlgebraicRiccatiDiscrete Class Reference

Methods for dealing with discrete-time algebraic Riccati equations. More...

#include <algebraic_riccati_discrete.h>

Static Public Member Functions

static bool isClosedLoopStable (const Eigen::Ref< const Eigen::MatrixXd > &A, const Eigen::Ref< const Eigen::MatrixXd > &B, const Eigen::Ref< const Eigen::MatrixXd > &G)
 Determine if the closed-loop system is stable. More...
 
static bool solve (const Eigen::Ref< const Eigen::MatrixXd > &A, const Eigen::Ref< const Eigen::MatrixXd > &B, const Eigen::Ref< const Eigen::MatrixXd > &Q, const Eigen::Ref< const Eigen::MatrixXd > &R, Eigen::MatrixXd &X, Eigen::MatrixXd *G=nullptr)
 Solve discrete-time algebraic Riccati equation. More...
 

Static Protected Member Functions

static bool isInsideUnitCircle (const Eigen::Ref< const Eigen::MatrixXd > &block)
 
static bool solveRiccatiHamiltonianSchur (const Eigen::MatrixXd &H, Eigen::MatrixXd &X)
 Solve Hamiltonian via Schur method. More...
 

Detailed Description

Methods for dealing with discrete-time algebraic Riccati equations.

The discrete-time algebraic Riccati equation is given by

\[ A^T X A - X - A^T X B ( B^T X B + R )^{-1} B^T X A + Q = 0 \]

$ A $ and $ B $ must be stabilizable.

The resulting gain matrix is given by

\[ G = (B^T X B R)^{-1} B^T X A \]

See also
AlgebraicRiccatiContinuous LyapunovDiscrete LyapunovContinuous SylvesterContinuous SylvesterDiscrete
Author
Christoph Rösmann (chris.nosp@m.toph.nosp@m..roes.nosp@m.mann.nosp@m.@tu-d.nosp@m.ortm.nosp@m.und.d.nosp@m.e)
Todo:

Add a method that determiens if sufficient conditions hold and that (A,B) is stabilizable.

Add support for the more generalized Riccati equation (augmented by matrix S and E) E.g. Hamiltonian for augmentation with S: http://web.dcsc.tudelft.nl/~cscherer/books/thesis.pdf

Definition at line 58 of file algebraic_riccati_discrete.h.

Member Function Documentation

◆ isClosedLoopStable()

bool corbo::AlgebraicRiccatiDiscrete::isClosedLoopStable ( const Eigen::Ref< const Eigen::MatrixXd > &  A,
const Eigen::Ref< const Eigen::MatrixXd > &  B,
const Eigen::Ref< const Eigen::MatrixXd > &  G 
)
static

Determine if the closed-loop system is stable.

The closed-loop system is stable if the closed-loop eigenvalues are within the unit circle. This method returns true if $ A - B G $ has only eigenvalues within the unit circle. Hereby, G denotes the gain matrix obtained from solve().

Parameters
[in]AOpen-loop system matrix [n x n]
[in]BInput matrix [n x m]
[in]GFeedback gain matrix according to the solution of the algebraic Riccati equation [m x n]
Returns
true if the closed-loop system is stable, false otherwise.

Definition at line 102 of file algebraic_riccati_discrete.cpp.

◆ isInsideUnitCircle()

static bool corbo::AlgebraicRiccatiDiscrete::isInsideUnitCircle ( const Eigen::Ref< const Eigen::MatrixXd > &  block)
inlinestaticprotected

Definition at line 132 of file algebraic_riccati_discrete.h.

◆ solve()

bool corbo::AlgebraicRiccatiDiscrete::solve ( const Eigen::Ref< const Eigen::MatrixXd > &  A,
const Eigen::Ref< const Eigen::MatrixXd > &  B,
const Eigen::Ref< const Eigen::MatrixXd > &  Q,
const Eigen::Ref< const Eigen::MatrixXd > &  R,
Eigen::MatrixXd &  X,
Eigen::MatrixXd *  G = nullptr 
)
static

Solve discrete-time algebraic Riccati equation.

Solve $ A^T X A - X - A^T X B ( B^T X B + R )^{-1} B^T X A + Q = 0 $ w.r.t. $ X $.

$ A $ and $ B $ must be stabilizable (all eigenvalues of A outside the unit circle must be controllable). In addition, the associated symplectic pencil must have no eigenvalue on the unit circle. Sufficient conditions: R > 0.

Also, $ A $ must be invertible for this implementation.

This method optionally returns the gain matrix $ G = (B^T X B + R)^{-1} B^T X A $.

Warning
Input matrix sizes are checked only in debug mode and occuring issues immediately break execution
Parameters
[in]A[n x n] matrix
[in]B[n x m] matrix
[in]Q[n x n] matrix
[in]R[m x m] matrix
[out]XSolution of the algebraic Riccati equation with size [n x n] (must not be preallocated).
[out]GGain matrix with size [m x n] (optional)
Returns
true if a finite solution is found, false otherwise (but no NaN checking is performend on X, use X.allFinite()).

Definition at line 40 of file algebraic_riccati_discrete.cpp.

◆ solveRiccatiHamiltonianSchur()

bool corbo::AlgebraicRiccatiDiscrete::solveRiccatiHamiltonianSchur ( const Eigen::MatrixXd &  H,
Eigen::MatrixXd &  X 
)
staticprotected

Solve Hamiltonian via Schur method.

The Hamiltonian constructed in solve() is solved via the Schur decomposition. The Real Schur form of A is reordered such that blocks on the diagonal with eigenvalues contained in the unit circle. The corresponding column in the orthogonal transformation matrix U spans the invariant subspace: [U1 U2]^T. The solution of the Riccati equation is then obtained by

\[ X = U_2 U_1^{-1} \]

The implementation is based on [1].

[1] A. J. Laub. "A Schur method for solving algebraic Riccati equations", IEEE Conference on Decision and Control, 1978.

Parameters
[in]HHamiltonian matrix of the Riccati equation [square]
[out]XResuling solution: symmetric matrix with size(H).
Returns
true if solving was successful (but no NaN checking is performend on X, use X.allFinite()).

Definition at line 71 of file algebraic_riccati_discrete.cpp.


The documentation for this class was generated from the following files:


control_box_rst
Author(s): Christoph Rösmann
autogenerated on Mon Feb 28 2022 22:08:02