00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023 #ifndef _taoABDynamics_h
00024 #define _taoABDynamics_h
00025
00026 #include "taoTypes.h"
00027
00028 class taoDNode;
00029 class deMatrix3;
00030 class deMatrix6;
00031 class deVector3;
00032 class deVector6;
00033 class deFrame;
00034 class taoABDynamicsData;
00035 class taoABDynamicsData2;
00036
00037
00038
00045 class taoABDynamics
00046 {
00047 public:
00049 static void updateLocalXTreeOut(taoDNode* root);
00051 static void resetInertiaTreeOut(taoDNode* root);
00053 static void resetFlagTreeOut(taoDNode* root);
00055
00059 static void forwardDynamics(taoDNode* root, const deVector3* gravity);
00061
00065 static void inverseDynamics(taoDNode* root, const deVector3* gravity);
00066
00068
00075 static void forwardDynamicsImpulse(taoDNode* contact, const deVector3* point, const deVector3* impulse, const deInt dist);
00077
00081 static void globalJacobianOut(taoDNode* root);
00083
00087 static void opSpaceInertiaMatrixOut(taoDNode* root, const deMatrix6* Oah = NULL);
00088 static void biasAccelerationOut(taoDNode* root, const deVector6* Hh = NULL);
00089 static void compute_Jg_Omega_H(taoDNode* root, const deMatrix6* Oah = NULL, const deVector6* Hh = NULL);
00090 static deFloat effectiveMassInv(taoDNode* node, const deVector3* point, const deVector3* dir);
00091
00092
00093 static void opSpaceInvDynamics(taoDNode* opNode, deVector6* ddXn);
00094
00095 static void add2Tau_JgT_F(taoDNode* node, const deVector6* Fg);
00096
00098
00101 static deFloat potentialEnergy(taoDNode* root, const deVector3* gravity);
00103
00107 static deFloat kineticEnergy(taoDNode* root, const deVector6* Vh = NULL);
00109 static void resetInertia(taoDNode* node);
00110
00111 private:
00112 static void _forwardDynamicsOutIn(taoDNode* root, taoABDynamicsData* datah, deVector6* Pah, const deVector6* Vh);
00113 static void _inverseDynamicsOutIn(taoDNode* root, taoABDynamicsData2* datah, deVector6* Fh, const deVector6* Vh, const deVector6* Ah);
00114 static void _accelerationTreeOut(taoDNode* root, const deVector6* Ah);
00115 static void _articulatedImpulsePathIn(taoDNode* contact, const deInt dist);
00116 static void _velocityDeltaTreeOut(taoDNode* root, const deVector6* dVh, const deVector6* Vh, const deInt dist);
00117 static void _plusEq_Jg_ddQ(taoDNode* node, deVector6* A);
00118 };
00119
00120
00121
00122 #endif // _taoABDynamics_h
00123