GCOP
1.0
|
#include <body3d.h>
Public Member Functions | |
Body3d () | |
Body3d (const Vector3d &ds, double m) | |
Body3d (const Vector3d &ds, double m, const Vector3d &J) | |
virtual | ~Body3d () |
virtual double | Step (Body3dState &xb, double t, const Body3dState &xa, const Vectorcd &u, double h, const VectorXd *p=0, Matrix12d *A=0, Matrix12xcd *B=0, Matrix12Xd *C=0) |
virtual bool | NoiseMatrix (Matrix12d &Q, double t, const Body3dState &x, const Vectorcd &u, double h, const VectorXd *p=0) |
double | SympStep (double t, Body3dState &xb, const Body3dState &xa, const Vectorcd &u, double h, const VectorXd *p=0, Matrix12d *A=0, Matrix12xcd *B=0, Matrix12Xd *C=0) |
double | EulerStep (double t, Body3dState &xb, const Body3dState &xa, const Vectorcd &u, double h, const VectorXd *p=0, Matrix12d *A=0, Matrix12xcd *B=0, Matrix12Xd *C=0) |
void | ID (Vector6d &f, double t, const Body3dState &xb, const Body3dState &xa, const Vectorcd &u, double h) |
void | StateAndControlsToFlat (VectorXd &y, const Body3dState &x, const Vectorcd &u) |
void | FlatToStateAndControls (Body3dState &x, Vectorcd &u, const std::vector< VectorXd > &y) |
Static Public Member Functions | |
static void | Compute (Vector3d &J, double m, const Vector3d &ds) |
static void | Compute (Vector6d &I, double m, const Vector3d &ds) |
Public Attributes | |
Vector3d | ds |
body dimensions | |
double | m |
mass | |
Vector3d | J |
3x1 principal moments of inertia | |
Vector6d | I |
6x1 spatial inertia matrix | |
Vector6d | Ii |
6x1 spatial inertia matrix inverse | |
Vector3d | Dw |
linear rotational damping terms | |
Vector3d | Dv |
linear translational damping terms | |
Vector3d | fp |
constant position force in spatial frame (e.g. due to gravity) | |
Matrix6xcd | Bu |
control input transformation | |
bool | symp |
symplectic? | |
string | name |
Unique name of the body. | |
double | sw |
process noise: standard deviation in torque (zero by default) | |
double | sv |
process noise: standard deviation in force (zero by default) | |
Protected Types | |
typedef Matrix< double, c, 1 > | Vectorcd |
typedef Matrix< double, c, c > | Matrixcd |
typedef Matrix< double, 6, c > | Matrix6xcd |
typedef Matrix< double, 12, c > | Matrix12xcd |
typedef Matrix< double, 12, Dynamic > | Matrix12Xd |
A single rigid body system
Note: damping is currently supported only by Euler's method
Author: Marin Kobilarov marin(at)jhu.edu
typedef Matrix<double, 12, c> gcop::Body3d< c >::Matrix12xcd [protected] |
typedef Matrix<double, 12, Dynamic> gcop::Body3d< c >::Matrix12Xd [protected] |
typedef Matrix<double, 6, c> gcop::Body3d< c >::Matrix6xcd [protected] |
typedef Matrix<double, c, c> gcop::Body3d< c >::Matrixcd [protected] |
Reimplemented from gcop::System< Body3dState, 12, c >.
typedef Matrix<double, c, 1> gcop::Body3d< c >::Vectorcd [protected] |
Reimplemented from gcop::System< Body3dState, 12, c >.
gcop::Body3d< c >::Body3d | ( | ) |
gcop::Body3d< c >::Body3d | ( | const Vector3d & | ds, |
double | m | ||
) |
References gcop::Body3d< c >::Compute(), gcop::Body3d< c >::I, and gcop::Body3d< c >::J.
gcop::Body3d< c >::Body3d | ( | const Vector3d & | ds, |
double | m, | ||
const Vector3d & | J | ||
) |
gcop::Body3d< c >::~Body3d | ( | ) | [virtual] |
void gcop::Body3d< c >::Compute | ( | Vector3d & | J, |
double | m, | ||
const Vector3d & | ds | ||
) | [static] |
Compute moments of inertia J given mass m and dimensions ds
J | moments of inertia (3x1 vector) |
m | mass |
ds | dimensions (assume a rectangular body) |
Referenced by gcop::Body3d< c >::Body3d().
void gcop::Body3d< c >::Compute | ( | Vector6d & | I, |
double | m, | ||
const Vector3d & | ds | ||
) | [static] |
Compute moments of inertia tensor I given mass m and dimensions ds
J | moments of inertia (6x1 vector) |
m | mass |
ds | dimensions (assume a rectangular body) |
double gcop::Body3d< c >::EulerStep | ( | double | t, |
Body3dState & | xb, | ||
const Body3dState & | xa, | ||
const Vectorcd & | u, | ||
double | h, | ||
const VectorXd * | p = 0 , |
||
Matrix12d * | A = 0 , |
||
Matrix12xcd * | B = 0 , |
||
Matrix12Xd * | C = 0 |
||
) |
References gcop::SO3::Ad(), gcop::SO3::cay(), gcop::SO3::dcay(), gcop::SO3::hat(), and gcop::SO3::Instance().
void gcop::Body3d< c >::FlatToStateAndControls | ( | Body3dState & | x, |
Vectorcd & | u, | ||
const std::vector< VectorXd > & | y | ||
) |
References gcop::SO3::Instance().
void gcop::Body3d< c >::ID | ( | Vector6d & | f, |
double | t, | ||
const Body3dState & | xb, | ||
const Body3dState & | xa, | ||
const Vectorcd & | u, | ||
double | h | ||
) |
Inverse dynamics
f | inverse dynamics vector |
t | time |
xb | end state |
xa | start state |
u | control |
h | time-step |
bool gcop::Body3d< c >::NoiseMatrix | ( | Matrix12d & | Q, |
double | t, | ||
const Body3dState & | x, | ||
const Vectorcd & | u, | ||
double | h, | ||
const VectorXd * | p = 0 |
||
) | [virtual] |
void gcop::Body3d< c >::StateAndControlsToFlat | ( | VectorXd & | y, |
const Body3dState & | x, | ||
const Vectorcd & | u | ||
) |
References gcop::SO3::Instance(), gcop::SO3::pitch(), gcop::SO3::roll(), and gcop::SO3::yaw().
double gcop::Body3d< c >::Step | ( | Body3dState & | xb, |
double | t, | ||
const Body3dState & | xa, | ||
const Vectorcd & | u, | ||
double | h, | ||
const VectorXd * | p = 0 , |
||
Matrix12d * | A = 0 , |
||
Matrix12xcd * | B = 0 , |
||
Matrix12Xd * | C = 0 |
||
) | [virtual] |
Referenced by gcop::Body3dTrack::Add(), and gcop::Body3dTrack::Add2().
double gcop::Body3d< c >::SympStep | ( | double | t, |
Body3dState & | xb, | ||
const Body3dState & | xa, | ||
const Vectorcd & | u, | ||
double | h, | ||
const VectorXd * | p = 0 , |
||
Matrix12d * | A = 0 , |
||
Matrix12xcd * | B = 0 , |
||
Matrix12Xd * | C = 0 |
||
) |
Matrix6xcd gcop::Body3d< c >::Bu |
control input transformation
Vector3d gcop::Body3d< c >::ds |
body dimensions
Referenced by gcop::Body3d< c >::Body3d().
Vector3d gcop::Body3d< c >::Dv |
linear translational damping terms
Vector3d gcop::Body3d< c >::Dw |
linear rotational damping terms
Vector3d gcop::Body3d< c >::fp |
constant position force in spatial frame (e.g. due to gravity)
Vector6d gcop::Body3d< c >::I |
6x1 spatial inertia matrix
Referenced by gcop::Body3d< c >::Body3d().
Vector6d gcop::Body3d< c >::Ii |
6x1 spatial inertia matrix inverse
Vector3d gcop::Body3d< c >::J |
3x1 principal moments of inertia
Referenced by gcop::Body3d< c >::Body3d().
double gcop::Body3d< c >::m |
mass
Referenced by gcop::Body3d< c >::Body3d().
string gcop::Body3d< c >::name |
Unique name of the body.
double gcop::Body3d< c >::sv |
process noise: standard deviation in force (zero by default)
double gcop::Body3d< c >::sw |
process noise: standard deviation in torque (zero by default)
bool gcop::Body3d< c >::symp |
symplectic?