26 #ifndef _taoDynamics_h
27 #define _taoDynamics_h
49 static void updateTransformation(
taoDNode* root);
51 static void integrate(
taoDNode* root, deFloat dt);
127 static void resetMass(
taoDNode* node,
const deFloat mass);
130 static deFloat kineticEnergy(
taoDNode* root);
133 typedef enum {TAO_DDQ, TAO_DQ, TAO_TAU} flagType;
134 static void _Read(
taoDNode* root, deFloat* v, flagType type);
135 static void _Write(
taoDNode* root, deFloat* v, flagType type);
138 #endif // _taoDynamics_h
3x1 vector classThis is a C++ wrapper class of deVector3f.
Definition: TaoDeVector3.h:32
articulated body dynamicsThis class provides various dynamics computations for articulated body...
Definition: taoDynamics.h:41
static void impulse(taoDNode *contactNode, const deVector3 *contactPoint, const deVector3 *impulseVector)
computes velocity changes given impulse
Definition: taoDynamics.cpp:95
6x1 vector classThis class consists of two 3x1 vectors.
Definition: TaoDeVector6.h:33
abstract node class for articulated bodyA dynamics node = {Articulated Body Link + Set of associated ...
Definition: taoDNode.h:46
static void computeOpSpaceInertiaMatrixInv(taoDNode *root, const deFloat *J, const deInt row, const deInt dof, const deFloat *Ainv, deFloat *Linv)
compute the operational Space Inertia Matrix Inverse, Linv (row x row)
Definition: taoDynamics.cpp:231
static void reset(taoDNode *root)
Definition: taoDynamics.cpp:50
static void globalJacobian(taoDNode *root)
computes global Jacobina matrices
Definition: taoDynamics.cpp:71
static void computeG(taoDNode *root, deVector3 *gravity, const deInt dof, deFloat *G)
computes gravitational forces, G (dof x 1) under gravity
Definition: taoDynamics.cpp:151
static void computeA(taoDNode *root, const deInt dof, deFloat *A)
computes Joint Space Inertia Matrix, A of size dof x dof
Definition: taoDynamics.cpp:263
static int computeDOF(taoDNode *obj)
find dof : degrees of freedom
Definition: taoDynamics.cpp:134
static void invDynamics(taoDNode *root, const deVector3 *gravity)
computes inverse dynamics of the subtree with root under gravity
Definition: taoDynamics.cpp:76
static void initialize(taoDNode *root)
Definition: taoDynamics.cpp:42
static void computeAinv(taoDNode *root, const deInt dof, deFloat *Ainv)
computes Joint Space Inertia Matrix Inverse, Ainv (dof x dof)
Definition: taoDynamics.cpp:311
static void fwdDynamics(taoDNode *root, const deVector3 *gravity)
computes forward dynamics of the subtree with root under gravity
Definition: taoDynamics.cpp:87
static void computeB(taoDNode *root, const deInt dof, deFloat *B)
computes Coriolis and centrifugal forces, B (dof x 1)
Definition: taoDynamics.cpp:196