26 #ifndef _taoABDynamics_h
27 #define _taoABDynamics_h
118 static void _articulatedImpulsePathIn(
taoDNode* contact,
const deInt dist);
125 #endif // _taoABDynamics_h
static void resetFlagTreeOut(taoDNode *root)
resets flags in the subtree with root
Definition: taoABDynamics.cpp:73
3x1 vector classThis is a C++ wrapper class of deVector3f.
Definition: TaoDeVector3.h:32
static void resetInertia(taoDNode *node)
resets inertia of node
Definition: taoABDynamics.cpp:60
static void opSpaceInertiaMatrixOut(taoDNode *root, const deMatrix6 *Oah=NULL)
computes inverse operational space inertia matrix for each node: diagonal terms: Omega_i_i ...
Definition: taoABDynamics.cpp:81
static void updateLocalXTreeOut(taoDNode *root)
updates local transforms in the subtree with root
Definition: taoABDynamics.cpp:52
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 deFloat potentialEnergy(taoDNode *root, const deVector3 *gravity)
computes the potential energy of the subtree with root under gravity
Definition: taoABDynamics.cpp:379
static void resetInertiaTreeOut(taoDNode *root)
resets inertias in the subtree with root
Definition: taoABDynamics.cpp:65
static void forwardDynamics(taoDNode *root, const deVector3 *gravity)
computes forward dynamics of the subtree with root under gravity
Definition: taoABDynamics.cpp:256
static void forwardDynamicsImpulse(taoDNode *contact, const deVector3 *point, const deVector3 *impulse, const deInt dist)
computes velocity changes given impulse
Definition: taoABDynamics.cpp:274
Transformation class using quaternionThis class consists of a quaternion for rotation and a vector fo...
Definition: TaoDeFrame.h:36
6x6 matrix classThis class consists of four 3x3 matrices.
Definition: TaoDeMatrix6.h:33
static void globalJacobianOut(taoDNode *root)
computes global Jacobina matrices
Definition: taoABDynamics.cpp:91
Definition: taoABDynamics.cpp:43
static deFloat kineticEnergy(taoDNode *root, const deVector6 *Vh=NULL)
computes the kinetic energy of the subtree with root under gravity
Definition: taoABDynamics.cpp:391
3x3 matrix classThis is a C++ wrapper class of deMatrix3f.
Definition: TaoDeMatrix3.h:33
Definition: taoABDynamics.cpp:35
Articulated body dynamics classThis class provides inverse and forward dynamics for articulated body...
Definition: taoABDynamics.h:48
static void inverseDynamics(taoDNode *root, const deVector3 *gravity)
computes inverse dynamics of the subtree with root under gravity
Definition: taoABDynamics.cpp:266