GCOP
1.0
|
#include <system.h>
Public Types | |
typedef Matrix< double, _nx, 1 > | Vectornd |
typedef Matrix< double, _nu, 1 > | Vectorcd |
typedef Matrix< double, _np, 1 > | Vectormd |
typedef Matrix< double, _nx, _nx > | Matrixnd |
typedef Matrix< double, _nx, _nu > | Matrixncd |
typedef Matrix< double, _nu, _nx > | Matrixcnd |
typedef Matrix< double, _nu, _nu > | Matrixcd |
typedef Matrix< double, _np, _np > | Matrixmd |
typedef Matrix< double, _nx, _np > | Matrixnmd |
typedef Matrix< double, _np, _nx > | Matrixmnd |
Public Member Functions | |
System (Manifold< T, _nx > &X, int nu=0, int np=0) | |
virtual double | Step (T &xb, double t, const T &xa, const Vectorcd &u, double h, const Vectormd *p=0, Matrixnd *A=0, Matrixncd *B=0, Matrixnmd *C=0) |
virtual double | Step (T &xb, double t, const T &xa, const Vectorcd &u, double h, const Vectornd &w, const Vectormd *p, Matrixnd *A=0, Matrixncd *B=0, Matrixnmd *C=0, Matrixnd *D=0) |
virtual double | Step (T &xb, const Vectorcd &u, double h, const Vectormd *p=0, Matrixnd *A=0, Matrixncd *B=0, Matrixnmd *C=0) |
virtual double | Step (const Vectorcd &u, double h, const Vectormd *p=0, Matrixnd *A=0, Matrixncd *B=0, Matrixnmd *C=0) |
virtual double | Step (T &xb, const Vectorcd &u, double h, const Vectornd &w, const Vectormd *p=0, Matrixnd *A=0, Matrixncd *B=0, Matrixnmd *C=0, Matrixnd *D=0) |
virtual bool | Reset (const T &x, double t=0) |
virtual void | Rec (T &x, double h) |
virtual void | print (const T &x) const |
virtual bool | Noise (Matrixnd &Q, double t, const T &x, const Vectorcd &u, double dt, const Vectormd *p=0) |
virtual bool | NoiseMatrix (Matrixnd &Q, double t, const T &x, const Vectorcd &u, double h, const Vectormd *p=0) |
virtual void | StateAndControlsToFlat (VectorXd &y, const T &x, const Vectorcd &u) |
virtual void | FlatToStateAndControls (T &x, Vectorcd &u, const std::vector< VectorXd > &y) |
Public Attributes | |
Manifold< T, _nx > & | X |
state manifold | |
Rn< _nu > | U |
control Euclidean manifold | |
Rn< _np > | P |
parameter Euclidean manifold | |
int | np |
Number of Parameters. | |
bool | internalState |
for some systems (in particular using Bullet) time-stepping is performed using the internal state rather than passing xa and t before each update. Thus in the Step() function xa and t are ignored and instead the internal (x, t) are used. This is false by default. | |
bool | affineNoise |
whether the noise w enters the dynamics in an affine way, i.e. as x = f(t, x, u, p) + H(t, x, u, p)*w | |
T | x |
Internal State of the system. | |
double | t |
Internal time of the system. |
Control system interface for dynamic systems on manifolds. Defines the discrete dynamics and any structural/inertial system parameters such as body dimensions, mass matrices, etc...
Subclasses should provide implementation for the time-stepping Step function and optionally for process noise evolution
Authors: Marin Kobilarov marin(at)jhu.edu Gowtham Garimella
typedef Matrix<double, _nu, _nu> gcop::System< T, _nx, _nu, _np >::Matrixcd |
Reimplemented in gcop::Body3d< c >, gcop::Body3d< 4 >, and gcop::System_extstep< T, _nx, _nu, _np >.
typedef Matrix<double, _nu, _nx> gcop::System< T, _nx, _nu, _np >::Matrixcnd |
Reimplemented in gcop::System_extstep< T, _nx, _nu, _np >.
typedef Matrix<double, _np, _np> gcop::System< T, _nx, _nu, _np >::Matrixmd |
Reimplemented in gcop::System_extstep< T, _nx, _nu, _np >.
typedef Matrix<double, _np, _nx> gcop::System< T, _nx, _nu, _np >::Matrixmnd |
Reimplemented in gcop::System_extstep< T, _nx, _nu, _np >.
typedef Matrix<double, _nx, _nu> gcop::System< T, _nx, _nu, _np >::Matrixncd |
Reimplemented in gcop::System_extstep< T, _nx, _nu, _np >.
typedef Matrix<double, _nx, _nx> gcop::System< T, _nx, _nu, _np >::Matrixnd |
Reimplemented in gcop::System_extstep< T, _nx, _nu, _np >.
typedef Matrix<double, _nx, _np> gcop::System< T, _nx, _nu, _np >::Matrixnmd |
Reimplemented in gcop::System_extstep< T, _nx, _nu, _np >.
typedef Matrix<double, _nu, 1> gcop::System< T, _nx, _nu, _np >::Vectorcd |
Reimplemented in gcop::Body2d< c >, gcop::Body3d< c >, gcop::Body3d< 4 >, and gcop::System_extstep< T, _nx, _nu, _np >.
typedef Matrix<double, _np, 1> gcop::System< T, _nx, _nu, _np >::Vectormd |
Reimplemented in gcop::System_extstep< T, _nx, _nu, _np >.
typedef Matrix<double, _nx, 1> gcop::System< T, _nx, _nu, _np >::Vectornd |
Reimplemented in gcop::System_extstep< T, _nx, _nu, _np >.
gcop::System< T, _nx, _nu, _np >::System | ( | Manifold< T, _nx > & | X, |
int | nu = 0 , |
||
int | np = 0 |
||
) |
A system evolving on a state manifold manifold X with nu inputs and np parameters
X | state manifold |
nu | number of control inputs |
np | number of parameters |
nw | number of noise parameters |
void gcop::System< T, _nx, _nu, _np >::FlatToStateAndControls | ( | T & | x, |
Vectorcd & | u, | ||
const std::vector< VectorXd > & | y | ||
) | [virtual] |
Convert flat outputs and derivatives of flat outputs to the state and controls of the system.
y | given flat outputs and derivatives of flat outputs |
x | generated state |
u | generated controls |
bool gcop::System< T, _nx, _nu, _np >::Noise | ( | Matrixnd & | Q, |
double | t, | ||
const T & | x, | ||
const Vectorcd & | u, | ||
double | dt, | ||
const Vectormd * | p = 0 |
||
) | [virtual] |
For filtering purposes, it is often necessary to provide a discrete-time process noise covariance Q, typically used in linear error propagation according to P = A*P*A' + Q
Q | discrete-time process noise covariance |
t | start time |
x | start state |
u | control |
dt | time-step |
p | parameter (optional) |
bool gcop::System< T, _nx, _nu, _np >::NoiseMatrix | ( | Matrixnd & | Q, |
double | t, | ||
const T & | x, | ||
const Vectorcd & | u, | ||
double | h, | ||
const Vectormd * | p = 0 |
||
) | [virtual] |
Noise in the system is modeled as x[i+1] = f(xi,ui,ti,p) + noisematrix(xi,ui,ti,p)*wi This function provides the necessary noise coefficient matrix
Q | provides the noise matrix |
t | current time |
x | current state |
u | current control |
h | time-step |
p | parameter (optional) |
virtual void gcop::System< T, _nx, _nu, _np >::print | ( | const T & | x | ) | const [inline, virtual] |
General print function to print the state
Reimplemented in gcop::Mbs.
virtual void gcop::System< T, _nx, _nu, _np >::Rec | ( | T & | x, |
double | h | ||
) | [inline, virtual] |
Reconstruct the full state. Some states contain redundant parameters for efficiency and it is useful to reconstruct them to maintain a consisten state.
x | state |
h | time-step |
Reimplemented in gcop::Mbs.
bool gcop::System< T, _nx, _nu, _np >::Reset | ( | const T & | x, |
double | t = 0 |
||
) | [virtual] |
Resets the internal state of the system to one specified
x | State to reset to |
t | time to reset to (optional) |
Reimplemented in gcop::System_extstep< T, _nx, _nu, _np >.
void gcop::System< T, _nx, _nu, _np >::StateAndControlsToFlat | ( | VectorXd & | y, |
const T & | x, | ||
const Vectorcd & | u | ||
) | [virtual] |
Convert a system state and controls to flat outputs for the system.
y | the generated flat outputs |
x | given state |
u | given controls |
double gcop::System< T, _nx, _nu, _np >::Step | ( | T & | xb, |
double | t, | ||
const T & | xa, | ||
const Vectorcd & | u, | ||
double | h, | ||
const Vectormd * | p = 0 , |
||
Matrixnd * | A = 0 , |
||
Matrixncd * | B = 0 , |
||
Matrixnmd * | C = 0 |
||
) | [virtual] |
Discrete dynamics update. The function computes the next system state xb given current state xa and applied forces u
xb | resulting state |
t | current time |
xa | current state |
u | current control |
h | step size |
p | static parameters (optional) |
A | jacobian w.r.t. x (optional) |
B | jacobian w.r.t. u (optional) |
C | jacobian w.r.t. p (optional) |
double gcop::System< T, _nx, _nu, _np >::Step | ( | T & | xb, |
double | t, | ||
const T & | xa, | ||
const Vectorcd & | u, | ||
double | h, | ||
const Vectornd & | w, | ||
const Vectormd * | p, | ||
Matrixnd * | A = 0 , |
||
Matrixncd * | B = 0 , |
||
Matrixnmd * | C = 0 , |
||
Matrixnd * | D = 0 |
||
) | [virtual] |
This is the master (the most general) Step function performing a discrete dynamics update. The function computes the next system state xb given current state xa, time t, applied forces u, parameters p, and noise w. This function calls the deterministic Step function as well as the NoiseMatrix function and combines the output to update the state: xb = f(t, xa, u, p) + H(t, xa, u, p)*w
xb | resulting state |
t | current time |
xa | current state |
u | current control |
h | step size |
p | static parameters (optional, set to 0 to ignore) |
w | noise |
A | jacobian w.r.t. x (optional) |
B | jacobian w.r.t. u (optional) |
C | jacobian w.r.t. p (optional) |
D | jacobian w.r.t. w (optional) |
double gcop::System< T, _nx, _nu, _np >::Step | ( | T & | xb, |
const Vectorcd & | u, | ||
double | h, | ||
const Vectormd * | p = 0 , |
||
Matrixnd * | A = 0 , |
||
Matrixncd * | B = 0 , |
||
Matrixnmd * | C = 0 |
||
) | [virtual] |
Discrete Dynamics Update. This function computes the next state xb using the internal input state x_int and applied forces u
xb | resulting state |
t | current time |
u | current control |
h | step size |
p | static parameters (optional) |
A | jacobian w.r.t. x (optional) |
B | jacobian w.r.t. u (optional) |
C | jacobian w.r.t. p (optional) |
Reimplemented in gcop::System_extstep< T, _nx, _nu, _np >.
double gcop::System< T, _nx, _nu, _np >::Step | ( | const Vectorcd & | u, |
double | h, | ||
const Vectormd * | p = 0 , |
||
Matrixnd * | A = 0 , |
||
Matrixncd * | B = 0 , |
||
Matrixnmd * | C = 0 |
||
) | [virtual] |
Discrete Dynamics update of internal state and no output
t | current time |
u | current control |
h | step size |
p | static parameters (optional) |
A | jacobian w.r.t. x (optional) |
B | jacobian w.r.t. u (optional) |
C | jacobian w.r.t. p (optional) |
Reimplemented in gcop::System_extstep< T, _nx, _nu, _np >.
double gcop::System< T, _nx, _nu, _np >::Step | ( | T & | xb, |
const Vectorcd & | u, | ||
double | h, | ||
const Vectornd & | w, | ||
const Vectormd * | p = 0 , |
||
Matrixnd * | A = 0 , |
||
Matrixncd * | B = 0 , |
||
Matrixnmd * | C = 0 , |
||
Matrixnd * | D = 0 |
||
) | [virtual] |
A version of most general step function with noise and internal state
xb | resulting state |
u | current control |
h | step size |
w | noise of same size as state |
p | static parameters (optional) |
A | jacobian w.r.t. x (optional) |
B | jacobian w.r.t. u (optional) |
C | jacobian w.r.t. p (optional) |
D | jacobian w.r.t w (optional) |
bool gcop::System< T, _nx, _nu, _np >::affineNoise |
whether the noise w enters the dynamics in an affine way, i.e. as x = f(t, x, u, p) + H(t, x, u, p)*w
bool gcop::System< T, _nx, _nu, _np >::internalState |
for some systems (in particular using Bullet) time-stepping is performed using the internal state rather than passing xa and t before each update. Thus in the Step() function xa and t are ignored and instead the internal (x, t) are used. This is false by default.
int gcop::System< T, _nx, _nu, _np >::np |
Number of Parameters.
Rn<_np> gcop::System< T, _nx, _nu, _np >::P |
parameter Euclidean manifold
Referenced by gcop::LqSensorCost< T, _nx, _nu, _np, _ng, Tz, _nz >::LqSensorCost(), gcop::LsSensorCost< T, _nx, _nu, _np, _ng, Tz, _nz >::LsSensorCost(), and gcop::MultiCost< T, _nx, _nu, _np >::MultiCost().
double gcop::System< T, _nx, _nu, _np >::t |
Internal time of the system.
Referenced by gcop::Bulletrccar1::reset(), gcop::System_extstep< T, _nx, _nu, _np >::Reset(), gcop::Bulletrccar::Reset(), gcop::System_extstep< T, _nx, _nu, _np >::Step(), gcop::Bulletrccar::Step(), and gcop::Bulletrccar1::Step1().
Rn<_nu> gcop::System< T, _nx, _nu, _np >::U |
control Euclidean manifold
Referenced by gcop::Bulletrccar::Bulletrccar(), gcop::Bulletrccar1::Bulletrccar1(), gcop::Ddp< T, nx, nu, np >::Ddp(), gcop::Docp< T, nx, nu, np >::Docp(), gcop::LqCost< T, _nx, _nu, _np, _ng >::LqCost(), gcop::MultiCost< T, _nx, _nu, _np >::MultiCost(), gcop::PDdp< T, n, c, np >::PDdp(), gcop::Rccar::Rccar(), gcop::Rccar1::Rccar1(), gcop::SDdp< T, nx, nu, np >::SDdp(), and gcop::SystemCe< T, n, c, np, ntp, Tc >::SystemCe().
Manifold<T, _nx>& gcop::System< T, _nx, _nu, _np >::X |
state manifold
Referenced by gcop::ConstraintCost< T, _nx, _nu, _np, _ng >::ConstraintCost(), gcop::ControllerTparam< Tx, nx, nu, np, _ntp, Tc >::ControllerTparam(), gcop::Ddp< T, nx, nu, np >::Ddp(), gcop::Docp< T, nx, nu, np >::Docp(), gcop::Doep< T, nx, nu, np, Tz, nz, T1, nx1 >::Doep(), gcop::KalmanPredictor< T, _nx, _nu, _np >::KalmanPredictor(), gcop::LqCost< T, _nx, _nu, _np, _ng >::LqCost(), gcop::LqSensorCost< T, _nx, _nu, _np, _ng, Tz, _nz >::LqSensorCost(), gcop::MultiCost< T, _nx, _nu, _np >::MultiCost(), gcop::PDdp< T, n, c, np >::PDdp(), gcop::SDdp< T, nx, nu, np >::SDdp(), gcop::UnscentedCorrector< T, _nx, _nu, _np, Tz, _nz >::UnscentedCorrector(), and gcop::UnscentedPredictor< T, _nx, _nu, _np >::UnscentedPredictor().
T gcop::System< T, _nx, _nu, _np >::x |
Internal State of the system.
Referenced by gcop::Rccar::FlatToStateAndControls(), gcop::Bulletrccar1::reset(), gcop::System_extstep< T, _nx, _nu, _np >::Reset(), gcop::Bulletrccar::Reset(), gcop::Bulletrccar::setinitialstate(), gcop::System_extstep< T, _nx, _nu, _np >::Step(), gcop::Bulletrccar::Step(), and gcop::Bulletrccar1::Step1().