#include <kinematic_model.h>
Public Types | |
enum | { x = 0, y, z } |
enum | { phi = 0, theta, psi } |
enum | { u = 0, v, w, p, q, r } |
Public Member Functions | |
void | init (double depth=0) |
KinematicModel () | |
Default constructor for common use without configuration. | |
const vector3 & | orientation () |
const vector3 & | position () const |
void | reset () |
void | setPosition (const vector3 &pos, const vector3 &rpy) |
void | setPosition (const vector3 &pos, const quaternion &quat) |
void | setTs (double Ts) |
Set the sampling time in seconds. | |
void | step (const vector &nu) |
Protected Attributes | |
vector3 | current |
The external current disturbance in world coordinates. | |
double | dT |
The model sampling step. | |
vector3 | pos |
Position and orientation state. | |
vector3 | pos0 |
The initial position vector. | |
quaternion | quat |
The orientation quaternion. | |
quaternion | quat0 |
The initial quaternion vector. | |
vector3 | rpy |
The internal rpy representation. |
This class implements the kinematics of a 6DOF rigid-body. This model is based on the equations of motion derived in chapter 2 of Guidance and control of Ocean Vehicles by Fossen (1994).
Definition at line 51 of file kinematic_model.h.
anonymous enum |
Definition at line 54 of file kinematic_model.h.
anonymous enum |
Definition at line 55 of file kinematic_model.h.
anonymous enum |
Definition at line 56 of file kinematic_model.h.
Default constructor for common use without configuration.
Definition at line 42 of file kinematic_model.cpp.
void labust::simulation::KinematicModel::init | ( | double | depth = 0 | ) | [inline] |
Initialize the model.
depth | Defaults to zero but can be used to set a neutral depth. |
Definition at line 111 of file kinematic_model.h.
const vector3& labust::simulation::KinematicModel::orientation | ( | ) | [inline] |
Method to get the current model states. This vector returns the model orientation in Euler ZYX in world coordinates.
Definition at line 79 of file kinematic_model.h.
const vector3& labust::simulation::KinematicModel::position | ( | ) | const [inline] |
Method to get the current position. This vector returns the model position in world coordinates.
Definition at line 72 of file kinematic_model.h.
void labust::simulation::KinematicModel::reset | ( | ) | [inline] |
The method restarts the model to initial parameters.
Definition at line 120 of file kinematic_model.h.
void labust::simulation::KinematicModel::setPosition | ( | const vector3 & | pos, |
const vector3 & | rpy | ||
) | [inline] |
The method sets the initial states of the model.
pos | Position in the earth-fixed coordinate frame. |
rpy | Euler ZYX orientation in the earth-fixed coordinate frame. |
Definition at line 90 of file kinematic_model.h.
void labust::simulation::KinematicModel::setPosition | ( | const vector3 & | pos, |
const quaternion & | quat | ||
) | [inline] |
The method sets the initial states of the model.
pos | Position in the earth-fixed coordinate frame. |
quat | Quaternion orientation in the earth-fixed coordinate frame. |
Definition at line 101 of file kinematic_model.h.
void labust::simulation::KinematicModel::setTs | ( | double | Ts | ) | [inline] |
Set the sampling time in seconds.
Definition at line 126 of file kinematic_model.h.
void KinematicModel::step | ( | const vector & | nu | ) |
The method performs one simulation step. The model is propagated in time for one sampling period. To access states after the propagation use the accessor methods.
nu | Vector of linear and angular speeds. |
Definition at line 53 of file kinematic_model.cpp.
vector3 labust::simulation::KinematicModel::current [protected] |
The external current disturbance in world coordinates.
Definition at line 132 of file kinematic_model.h.
double labust::simulation::KinematicModel::dT [protected] |
The model sampling step.
Definition at line 126 of file kinematic_model.h.
vector3 labust::simulation::KinematicModel::pos [protected] |
Position and orientation state.
Definition at line 136 of file kinematic_model.h.
vector3 labust::simulation::KinematicModel::pos0 [protected] |
The initial position vector.
Definition at line 134 of file kinematic_model.h.
quaternion labust::simulation::KinematicModel::quat [protected] |
The orientation quaternion.
Definition at line 140 of file kinematic_model.h.
quaternion labust::simulation::KinematicModel::quat0 [protected] |
The initial quaternion vector.
Definition at line 138 of file kinematic_model.h.
vector3 labust::simulation::KinematicModel::rpy [protected] |
The internal rpy representation.
Definition at line 142 of file kinematic_model.h.