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

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

#include <algebraic_riccati_continuous.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 isNumericallyStable (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)
 Determine if solving the riccati equation seems to be numerically 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 continuous-time algebraic Riccati equation. More...
 

Static Protected Member Functions

static bool hasNegativeRealPart (const Eigen::Ref< const Eigen::MatrixXd > &block)
 Predicate for Schur block ordering (see solveRiccatiHamiltonianSchur()) More...
 
static bool hasRealPartsCloseToZero (const Eigen::Ref< const Eigen::MatrixXd > &matrix)
 Check if the real parts of the provided matrix are close to zero. More...
 
static bool solveRiccatiHamiltonianSchur (const Eigen::MatrixXd &H, Eigen::MatrixXd &X)
 Solve Hamiltonian via Schur method. More...
 

Detailed Description

Methods for dealing with continuous-time algebraic Riccati equations.

The continuous-time algebraic Riccati equation is given by

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

$ A $ and $ B $ must be stabilizable.

The resulting gain matrix is given by

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

See also
AlgebraicRiccatiDiscrete 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 determines 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_continuous.h.

Member Function Documentation

◆ hasNegativeRealPart()

static bool corbo::AlgebraicRiccatiContinuous::hasNegativeRealPart ( const Eigen::Ref< const Eigen::MatrixXd > &  block)
inlinestaticprotected

Predicate for Schur block ordering (see solveRiccatiHamiltonianSchur())

Definition at line 153 of file algebraic_riccati_continuous.h.

◆ hasRealPartsCloseToZero()

bool corbo::AlgebraicRiccatiContinuous::hasRealPartsCloseToZero ( const Eigen::Ref< const Eigen::MatrixXd > &  matrix)
staticprotected

Check if the real parts of the provided matrix are close to zero.

Definition at line 103 of file algebraic_riccati_continuous.cpp.

◆ isClosedLoopStable()

bool corbo::AlgebraicRiccatiContinuous::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 exhibit only negative real parts. This method returns true if $ A - B G $ has only eigenvalues with negative real parts. 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 180 of file algebraic_riccati_continuous.cpp.

◆ isNumericallyStable()

bool corbo::AlgebraicRiccatiContinuous::isNumericallyStable ( 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 
)
static

Determine if solving the riccati equation seems to be numerically stable.

However, it is not guaranteed...

This method checks the real parts of the egienvalues of the Hamiltonian are close to the imaginary axis. If yet, numerically stability is likely to be not satisfactory (also see Matlabs care solver).

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
Returns
true if the problem seems to be numerically stable

Definition at line 196 of file algebraic_riccati_continuous.cpp.

◆ solve()

bool corbo::AlgebraicRiccatiContinuous::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 continuous-time algebraic Riccati equation.

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

$ A $ and $ B $ must be stabilizable (all unstable modes are controllable). In addition, the associated Hamiltonian matrix must have no eigenvalue on the imaginary axis. Sufficient conditions: R > 0.

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

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 G = R^{-1} B^T X 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_continuous.cpp.

◆ solveRiccatiHamiltonianSchur()

bool corbo::AlgebraicRiccatiContinuous::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 having a negative real part precede other one. 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 72 of file algebraic_riccati_continuous.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