SCL  1.0
Standard Control Library : Control, dynamics, physics, and simulation
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends Macros Groups Pages
taoDynamics.h
1 /* Copyright (c) 2005 Arachi, Inc. and Stanford University. All rights reserved.
2  *
3  * Permission is hereby granted, free of charge, to any person obtaining
4  * a copy of this software and associated documentation files (the
5  * "Software"), to deal in the Software without restriction, including
6  * without limitation the rights to use, copy, modify, merge, publish,
7  * distribute, sublicense, and/or sell copies of the Software, and to
8  * permit persons to whom the Software is furnished to do so, subject
9  * to the following conditions:
10  *
11  * The above copyright notice and this permission notice shall be included
12  * in all copies or substantial portions of the Software.
13  *
14  * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
15  * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
16  * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT.
17  * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY
18  * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT,
19  * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE
20  * SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
21  */
22 
26 #ifndef _taoDynamics_h
27 #define _taoDynamics_h
28 
29 #include "taoTypes.h"
30 
31 class taoDNode;
32 class deVector3;
33 class deVector6;
34 
42 {
43 public:
44  static void initialize(taoDNode* root);
48  static void reset(taoDNode* root);
49  static void updateTransformation(taoDNode* root);
50 
51  static void integrate(taoDNode* root, deFloat dt);
52 
54 
58  static void globalJacobian(taoDNode* root);
59 
61 
65  static void invDynamics(taoDNode* root, const deVector3* gravity);
67 
71  static void fwdDynamics(taoDNode* root, const deVector3* gravity);
72 
73 
75 
95  static void computeA(taoDNode* root, const deInt dof, deFloat* A);
97  static void computeAinv(taoDNode* root, const deInt dof, deFloat* Ainv);
99  static void computeB(taoDNode* root, const deInt dof, deFloat* B);
101  static void computeG(taoDNode* root, deVector3* gravity, const deInt dof, deFloat* G);
102 
104 
111  static void computeOpSpaceInertiaMatrixInv(taoDNode* root, const deFloat* J, const deInt row, const deInt dof, const deFloat* Ainv, deFloat* Linv);
112 
114  static int computeDOF(taoDNode* obj);
115 
117 
124  static void impulse(taoDNode* contactNode, const deVector3* contactPoint, const deVector3* impulseVector);
125  static void impulseDist(taoDNode* contactNode, const deVector3* contactPoint, const deVector3* impulseVector);
126  static void force(taoDNode* contactNode, const deVector3* contactPoint, const deVector3* forceVector);
127  static void resetMass(taoDNode* node, const deFloat mass);
128 
129  static deFloat potentialEnergy(taoDNode* root, const deVector3* gravity);
130  static deFloat kineticEnergy(taoDNode* root);
131 
132 private:
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);
136 };
137 
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