|
DUECA/DUSIME
|
Rigid body dynamics function, calculates derivative of a rigid body, given sum of moments and forces and the acting gravity field. More...
#include <RigidBody.hxx>
Public Member Functions | |
| RigidBody (double mass, double Jxx, double Jyy, double Jzz, double Jxy, double Jxz, double Jyz, int extrastates=0) | |
| Simple constructor for a rigid body dynamics module. | |
| ~RigidBody () | |
| Destructor. | |
| void | initialize (double x, double y, double z, double u, double v, double w, double phi, double theta, double psi, double p, double q, double r) |
| Initialize a state vector x. | |
| void | derivative (VectorE &xd, double unused=0.0) |
| Obtain and calculate the derivative, given sum of forces and moments and the gravitational field acting on the body. | |
| template<class V > | |
| void | derivative (V &xd, double unused=0.0) |
| Obtain and calculate the derivative, given sum of forces and moments and the gravitational field acting on the body. | |
| void | specific (Vector &sp) |
| Calculate specific forces and moments, forces stored in elements 0, 1, and 2, moments in elements 3, 4 and 6. | |
| void | zeroForces () |
| Initialize sum of forces on the body to zero. | |
| void | applyBodyForce (const Vector3 &Fb, const Vector3 &point) |
| Apply a force expressed in body coordinates. | |
| void | applyInertialForce (const Vector &Fi, const Vector &point) |
| Apply a force expressed in inertial coordinates, at a specific body point, give in body coordinates. | |
| void | applyBodyMoment (const Vector &M) |
| Apply a moment expressed in body coordinates. | |
| void | changeState (const Vector &dx) |
| Change the state vector by a quantity dx. | |
| void | addInertialGravity (const Vector &g) |
| Add a gravitational field; 3 element vector, gravitation expressed in the inertial system. | |
| void | setState (const Vector &newx) |
| Put in a new state vector. | |
| void | changeMass (const double dm) |
| Add to the mass of the body. | |
| void | setMass (const double newm) |
| Set a new mass. | |
| void | output () |
| Calculate auxiliary outputs, V, \(\alpha\), \(\beta\), \(\phi\), \(\theta\) and \(\Psi\). | |
| const Vector & | X () const |
| Obtain the state, 13 elements. | |
| const double | V () const |
| Obtain speed. | |
| const double | alpha () const |
| Obtain alpha. | |
| const double | beta () const |
| Obtain beta. | |
| const double | getMass () const |
| Get current mass. | |
| const double | phi () const |
| Get euler angle phi. | |
| const double | theta () const |
| Get euler angle theta. | |
| const double | psi () const |
| Get euler angle psi. | |
| const Matrix3 & | A () |
| Get the transformation matrix, for transforming a vector in earth coordinates to one in the body's coordinate system. | |
Protected Attributes | |
| Vector | x |
| State vector. | |
Rigid body dynamics function, calculates derivative of a rigid body, given sum of moments and forces and the acting gravity field.
The contents of the state vector are:
u, v, w, x, y, z, p, q, r, l1, l2, l3, L
Note that the RigidBody class only calculates the derivatives. If you want to integrate the equations of motion, you need an integration routine. Two templated integration functions are available, integrate_euler() and integrate_rungekutta().
The normal procedure would be to create a class that derives from the RigidBody class. You can also indicate that a number of additional state variables is needed, the RigidBody class will make these available to you, from index 13 onward.
The normal "work cycle" would be to call RigidBody::zeroForces(), which zeroes forces and gravity applied to the body, then repeatedly call RigidBody::applyBodyForce(), RigidBody::applyInertialForce(), RigidBody::applyBodyMoment() RigidBody::addInertialGravity() as needed, until all forces (drag, lift, wheel forces, thrusters, whatever) and all gravitational effects have been applied.
Then call RigidBody::derivative() to obtain the derivative.
RigidBody::specific(), RigidBody::X() and RigidBody::phi(), RigidBody::theta(), RigidBody::psi() can be used to get your outputs.
| RigidBody::RigidBody | ( | double | mass, |
| double | Jxx, | ||
| double | Jyy, | ||
| double | Jzz, | ||
| double | Jxy, | ||
| double | Jxz, | ||
| double | Jyz, | ||
| int | extrastates = 0 ) |
Simple constructor for a rigid body dynamics module.
Note that motion is always described around center of mass.
| mass | mass of the object |
| Jxx | Moment of inertia around x axis |
| Jyy | Moment of inertia around y axis |
| Jzz | Moment of inertia around z axis |
| Jxy | Inertia cross product x and y |
| Jxz | Inertia cross product x and z |
| Jyz | Inertia cross product y and z |
| extrastates | Number of additional states needed by derived classes. |
| void RigidBody::initialize | ( | double | x, |
| double | y, | ||
| double | z, | ||
| double | u, | ||
| double | v, | ||
| double | w, | ||
| double | phi, | ||
| double | theta, | ||
| double | psi, | ||
| double | p, | ||
| double | q, | ||
| double | r ) |
Initialize a state vector x.
Remember that x has 13 elements, due to the use of a quaternion representation.
| x | Carthesian position, x direction |
| y | Carthesian position, y direction |
| z | Carthesian position, z direction |
| u | Velocity, along body x axis |
| v | Velocity, along body y axis |
| w | Velocity, along body z axis |
| phi | Euler angle phi |
| theta | Euler angle theta |
| psi | Euler angle psi |
| p | Rotational velocity, along body x axis |
| q | Rotational velocity, along body y axis |
| r | Rotational velocity, along body z axis |
| void RigidBody::derivative | ( | VectorE & | xd, |
| double | unused = 0.0 ) |
Obtain and calculate the derivative, given sum of forces and moments and the gravitational field acting on the body.
| xd | Resultant derivative vector |
| unused | Unused variable, for compatibility with integration functions. |
Obtain and calculate the derivative, given sum of forces and moments and the gravitational field acting on the body.
| V | Vector type |
| xd | Resultant derivative vector |
| unused | Unused variable, for compatibility with integration functions. |
| void RigidBody::specific | ( | Vector & | sp | ) |
Calculate specific forces and moments, forces stored in elements 0, 1, and 2, moments in elements 3, 4 and 6.
Forces and moments calculated in body coordinates.
| sp | Vector with 6 elements, for result. |
| void RigidBody::zeroForces | ( | ) |
Initialize sum of forces on the body to zero.
Call before applying a new set of forces and moments.
Apply a force expressed in body coordinates.
at a specific body point.
| void RigidBody::setState | ( | const Vector & | newx | ) |
Put in a new state vector.
Note that you need a 13-element vector
|
inline |
Get the transformation matrix, for transforming a vector in earth coordinates to one in the body's coordinate system.
Note that for the reverse translation, you need the transpose of this matrix. Example:
|
protected |
State vector.
Contents: u, v, w, x, y, z, then p, q, r, l1, l2, l3, L. After this, thus from state 13 onwards, the state vector contains states for derived classes.