SCL  1.0
Standard Control Library : Control, dynamics, physics, and simulation
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends Macros Groups Pages
taoNode.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 _taoNode_h
27 #define _taoNode_h
28 
29 #include "taoDNode.h"
30 #include <tao/matrix/TaoDeMath.h>
31 
32 class taoWorld;
33 class taoControl;
34 
42 class taoNode : public taoDNode
43 {
44 public:
45  taoNode();
46  taoNode(taoDNode* parent, deFrame const * home);
47  virtual ~taoNode();
48 
49  virtual void sync(deFrame* local);
50 
51  virtual taoJoint* getJointList() { return _jointList; }
52  virtual taoJoint const * getJointList() const { return _jointList; }
53 
57  virtual deVector6* velocity();
61  virtual deVector6* acceleration();
62  virtual void getFrameGraphics(deFrame* Tog) { *Tog = *frameGlobal(); }
63 
64  virtual deFrame* frameHome() { return &_frameHome; }
65  virtual deFrame* frameLocal() { return &_frameLocal; }
66  virtual deFrame* frameGlobal() { return &_frameGlobal; }
67  virtual deFrame const * frameGlobal() const { return &_frameGlobal; }
68  virtual deFloat* mass() { return &_mass; }
69  virtual deVector3* center() { return &_center; }
70  virtual deVector3 const * center() const { return &_center; }
71  virtual deMatrix3* inertia() { return &_inertia; }
75  virtual deVector6* force() { return &_Fext; }
76  virtual void zeroForce() { _Fext.zero(); }
80  virtual void addForce(const deVector6* f) { _Fext += *f; }
81 
83  virtual void updateFrame();
84  virtual void integrate(deFloat dt);
85 
86  virtual void setDParent(taoDNode* n) { _parent = n; }
87  virtual taoDNode* getDParent() { return _parent; }
88  virtual taoDNode const * getDParent() const { return _parent; }
89  virtual void setDChild(taoDNode* n) { _child = (taoNode*)n; }
90  virtual taoDNode* getDChild() { return _child; }
91  virtual taoDNode const* getDChild() const { return _child; }
92  virtual void setDSibling(taoDNode* n) { _sibling = (taoNode*)n; }
93  virtual taoDNode* getDSibling() { return _sibling; }
94  virtual taoDNode const* getDSibling() const { return _sibling; }
95 
96  virtual void addJoint(taoJoint* joint);
97  virtual void addABNode();
98 
99  virtual void unlink();
100  virtual void link(taoDNode* parent, deFrame const * home);
101 
102  virtual void deleteJointABNode();
103 
108  virtual void linearVelocity(deVector3* Vie, const deVector3* Pie);
113  virtual void linearAcceleration(deVector3* Aie, const deVector3* Pie);
114  // XXX
115  //virtual deFloat effectiveMass(const deVector3* Pie, const deVector3* Ui);
116  virtual void impulse(const deVector3* Pie, const deVector3* Yie);
117  virtual void impulseDist(const deVector3* Pie, const deVector3* Yie);
118  virtual void force(const deVector3* Pie, const deVector3* Fie);
119 
120 private:
121  deFrame _frameHome;
122  deFrame _frameLocal;
123  deFrame _frameGlobal;
124 
125  deVector3 _center;
126  deFloat _mass;
127  deMatrix3 _inertia;
128 
129  deVector6 _Fext;
130 
131  taoDNode* _parent;
132  taoNode* _child;
133  taoNode* _sibling;
134 
135  taoJoint* _jointList;
136 
137  void _Initialize();
138 };
139 
147 class taoNodeRoot : public taoDNode
148 {
149 public:
150  taoNodeRoot(deFrame const & global);
151 
152  virtual ~taoNodeRoot();
153 
154  virtual void sync(deFrame* local) { _frameGlobal = *local; }
155 
156  virtual taoJoint* getJointList() { return NULL; }
157  virtual taoJoint const * getJointList() const { return NULL; }
158 
159  virtual deVector6* velocity();
160  virtual deVector6* acceleration();
161  virtual void getFrameGraphics(deFrame* Tog) { *Tog = *frameGlobal(); }
162 
163  virtual deFrame* frameHome() { return &_frameGlobal; }
164  virtual deFrame* frameLocal() { return &_frameGlobal; }
165  virtual deFrame* frameGlobal() { return &_frameGlobal; }
166  virtual deFrame const * frameGlobal() const { return &_frameGlobal; }
167  virtual deFloat* mass() { return &_zero; } // YYY
168  virtual deVector3* center() { return NULL; }
169  virtual deVector3 const * center() const { return NULL; }
170  virtual deMatrix3* inertia() { return NULL; }
171  virtual deVector6* force() { return NULL; }
172  virtual void zeroForce() {}
173  virtual void addForce(const deVector6* f) {}
174 
175  virtual void updateFrame() {}
176  virtual void integrate(deFloat dt) {}
177 
178  virtual taoDNode* getDParent() { return NULL; }
179  virtual taoDNode const * getDParent() const { return NULL; }
180  virtual void setDChild(taoDNode* n) { _child = (taoNode*)n; }
181  virtual taoDNode* getDChild() { return _child; }
182  virtual taoDNode const* getDChild() const { return _child; }
183  virtual taoDNode* getDSibling() { return NULL; }
184  virtual taoDNode const* getDSibling() const { return NULL; }
185 
186  void setNext(taoNodeRoot* r) { _next = r; }
187  taoNodeRoot* getNext() { return _next; }
188 
189  void setGroup(taoWorld* g) { _group = g; }
190  taoWorld* getGroup() { return _group; }
191 
192  void setController(taoControl* c) { _controller = c; }
193  taoControl* getController() { return _controller; }
194 
198  virtual void sync();
199 
200 private:
201  deFloat _zero; // YYY
202  deFrame _frameGlobal;
203 
204  taoWorld* _group;
205  taoControl* _controller;
206 
207  taoNode* _child;
208 
209  taoNodeRoot* _next;
210 
211  void _DeleteNodeTree(taoDNode* r);
212  void _SyncNodeTree(taoDNode* r);
213 };
214 
215 #endif // _taoNode_h
virtual taoDNode * getDChild()
Definition: taoNode.h:181
3x1 vector classThis is a C++ wrapper class of deVector3f.
Definition: TaoDeVector3.h:32
virtual deFrame * frameGlobal()
global frame for the dynamics computation
Definition: taoNode.h:165
node class for articulated body dynamicsThis implements taoDNode for articulated body dynamics...
Definition: taoNode.h:42
virtual deMatrix3 * inertia()
Definition: taoNode.h:170
virtual void impulseDist(const deVector3 *Pie, const deVector3 *Yie)
computes new position given pseudo impulse
Definition: taoNode.cpp:232
virtual void sync()
Definition: taoNode.cpp:286
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
virtual void addForce(const deVector6 *f)
Definition: taoNode.h:80
virtual void linearAcceleration(deVector3 *Aie, const deVector3 *Pie)
Definition: taoNode.cpp:211
root node class for articulated body dynamicsThis implements taoDNode for root node of a articulated ...
Definition: taoNode.h:147
virtual void updateFrame()
Definition: taoNode.cpp:102
virtual deVector6 * velocity()
Definition: taoNode.cpp:31
virtual taoDNode * getDParent()
Definition: taoNode.h:178
virtual deFrame * frameHome()
Definition: taoNode.h:64
virtual deFrame * frameHome()
Definition: taoNode.h:163
virtual deFrame * frameLocal()
Definition: taoNode.h:65
container class to hold dynamics charactersA group is a container object for dynamics characters...
Definition: taoWorld.h:45
DE_MATH_API void zero()
this = zero vector
Definition: TaoDeVector6Inl.h:36
virtual deVector6 * force()
Definition: taoNode.h:75
virtual taoDNode * getDParent()
Definition: taoNode.h:87
virtual deVector6 * force()
Definition: taoNode.h:171
Transformation class using quaternionThis class consists of a quaternion for rotation and a vector fo...
Definition: TaoDeFrame.h:36
virtual deFrame * frameGlobal()
global frame for the dynamics computation
Definition: taoNode.h:66
virtual deVector3 * center()
Definition: taoNode.h:168
virtual void getFrameGraphics(deFrame *Tog)
global frame for graphics display
Definition: taoNode.h:161
virtual taoDNode * getDChild()
Definition: taoNode.h:90
virtual deFloat * mass()
Definition: taoNode.h:167
virtual deVector6 * acceleration()
Definition: taoNode.cpp:36
Base joint class for articulated bodyThis provides a joint for articulated body dynamics.
Definition: taoJoint.h:45
virtual taoDNode * getDSibling()
Definition: taoNode.h:183
virtual void getFrameGraphics(deFrame *Tog)
global frame for graphics display
Definition: taoNode.h:62
virtual taoDNode * getDSibling()
Definition: taoNode.h:93
virtual void impulse(const deVector3 *Pie, const deVector3 *Yie)
computes new velocity given impulse
Definition: taoNode.cpp:227
virtual deMatrix3 * inertia()
Definition: taoNode.h:71
virtual deVector3 * center()
Definition: taoNode.h:69
3x3 matrix classThis is a C++ wrapper class of deMatrix3f.
Definition: TaoDeMatrix3.h:33
virtual deFloat * mass()
Definition: taoNode.h:68
virtual deFrame * frameLocal()
Definition: taoNode.h:164
virtual void linearVelocity(deVector3 *Vie, const deVector3 *Pie)
Definition: taoNode.cpp:205