Classic Riccati recursive formula for optimal control in a LQ problem.
More...
#include <optimalControl.h>
|
| Riccati (const yarp::sig::Matrix &_A, const yarp::sig::Matrix &_B, const yarp::sig::Matrix &_V, const yarp::sig::Matrix &_P, const yarp::sig::Matrix &_VN, bool verb=false) |
| Constructor, with initialization of algebraic Riccati equation.
|
|
yarp::sig::Matrix | L (int step) |
| Get stored L_i matrix; call this function only after solveRiccati()
|
|
yarp::sig::Matrix | T (int step) |
| Get stored T_i matrix; call this function only after solveRiccati()
|
|
void | setProblemData (const yarp::sig::Matrix &_A, const yarp::sig::Matrix &_B, const yarp::sig::Matrix &_V, const yarp::sig::Matrix &_P, const yarp::sig::Matrix &_VN) |
| Initialization of algebraic Riccati equation.
|
|
void | solveRiccati (int steps) |
| Solve recursively discrete algebraic Riccati equation (DARE) and stores matrices Ti and Li, where i=0:N-1 is the time index.
|
|
yarp::sig::Vector | doLQcontrol (int step, const yarp::sig::Vector &x) |
| Compute the LQ feedback control, in the form: ret= - L(i) * x.
|
|
void | doLQcontrol (int step, const yarp::sig::Vector &x, yarp::sig::Vector &ret) |
| Compute the LQ feedback control, in the form: u= - L(i) * x.
|
|
void | setVerbose (bool verb=true) |
| Enable or disable verbose feedback (that is, printing additional information)
|
|
|
yarp::sig::Matrix | A |
|
yarp::sig::Matrix | At |
|
yarp::sig::Matrix | B |
|
yarp::sig::Matrix | Bt |
|
yarp::sig::Matrix | V |
|
yarp::sig::Matrix | VN |
|
yarp::sig::Matrix | P |
|
yarp::sig::Matrix | TN |
|
yarp::sig::Matrix | lastT |
|
yarp::sig::Matrix * | Ti |
|
yarp::sig::Matrix * | Li |
|
yarp::sig::Vector | x |
|
size_t | n |
|
size_t | m |
|
int | N |
|
bool | verbose |
|
Classic Riccati recursive formula for optimal control in a LQ problem.
Definition at line 79 of file optimalControl.h.
◆ Riccati()
Riccati::Riccati |
( |
const yarp::sig::Matrix & |
_A, |
|
|
const yarp::sig::Matrix & |
_B, |
|
|
const yarp::sig::Matrix & |
_V, |
|
|
const yarp::sig::Matrix & |
_P, |
|
|
const yarp::sig::Matrix & |
_VN, |
|
|
bool |
verb = false |
|
) |
| |
Constructor, with initialization of algebraic Riccati equation.
- Parameters
-
_A | State transition matrix |
_B | Control matrix |
_V | State cost matrix |
_P | Control cost matrix |
_VN | Final state cost matrix |
Definition at line 26 of file optimalControl.cpp.
◆ doLQcontrol() [1/2]
yarp::sig::Vector iCub::ctrl::Riccati::doLQcontrol |
( |
int |
step, |
|
|
const yarp::sig::Vector & |
x |
|
) |
| |
Compute the LQ feedback control, in the form: ret= - L(i) * x.
- Parameters
-
step | The time index i |
x | The state vector |
◆ doLQcontrol() [2/2]
void iCub::ctrl::Riccati::doLQcontrol |
( |
int |
step, |
|
|
const yarp::sig::Vector & |
x, |
|
|
yarp::sig::Vector & |
ret |
|
) |
| |
Compute the LQ feedback control, in the form: u= - L(i) * x.
- Parameters
-
step | The time index i |
x | The state vector |
ret | The control vector |
◆ L()
Matrix Riccati::L |
( |
int |
step | ) |
|
◆ setProblemData()
void Riccati::setProblemData |
( |
const yarp::sig::Matrix & |
_A, |
|
|
const yarp::sig::Matrix & |
_B, |
|
|
const yarp::sig::Matrix & |
_V, |
|
|
const yarp::sig::Matrix & |
_P, |
|
|
const yarp::sig::Matrix & |
_VN |
|
) |
| |
Initialization of algebraic Riccati equation.
- Parameters
-
_A | State transition matrix |
_B | Control matrix |
_V | State cost matrix |
_P | Control cost matrix |
_VN | Final state cost matrix |
Definition at line 94 of file optimalControl.cpp.
◆ setVerbose()
void Riccati::setVerbose |
( |
bool |
verb = true | ) |
|
Enable or disable verbose feedback (that is, printing additional information)
- Parameters
-
verb | Flag for verbose mode |
Definition at line 49 of file optimalControl.cpp.
◆ solveRiccati()
void Riccati::solveRiccati |
( |
int |
steps | ) |
|
Solve recursively discrete algebraic Riccati equation (DARE) and stores matrices Ti and Li, where i=0:N-1 is the time index.
- Parameters
-
steps | The number N of steps of the finite horizon controller |
Definition at line 113 of file optimalControl.cpp.
◆ T()
Matrix Riccati::T |
( |
int |
step | ) |
|
yarp::sig::Matrix iCub::ctrl::Riccati::A |
|
protected |
◆ At
yarp::sig::Matrix iCub::ctrl::Riccati::At |
|
protected |
yarp::sig::Matrix iCub::ctrl::Riccati::B |
|
protected |
◆ Bt
yarp::sig::Matrix iCub::ctrl::Riccati::Bt |
|
protected |
◆ lastT
yarp::sig::Matrix iCub::ctrl::Riccati::lastT |
|
protected |
◆ Li
yarp::sig::Matrix* iCub::ctrl::Riccati::Li |
|
protected |
size_t iCub::ctrl::Riccati::m |
|
protected |
size_t iCub::ctrl::Riccati::n |
|
protected |
int iCub::ctrl::Riccati::N |
|
protected |
yarp::sig::Matrix iCub::ctrl::Riccati::P |
|
protected |
◆ Ti
yarp::sig::Matrix* iCub::ctrl::Riccati::Ti |
|
protected |
◆ TN
yarp::sig::Matrix iCub::ctrl::Riccati::TN |
|
protected |
yarp::sig::Matrix iCub::ctrl::Riccati::V |
|
protected |
◆ verbose
bool iCub::ctrl::Riccati::verbose |
|
protected |
◆ VN
yarp::sig::Matrix iCub::ctrl::Riccati::VN |
|
protected |
yarp::sig::Vector iCub::ctrl::Riccati::x |
|
protected |
The documentation for this class was generated from the following files: