SCL  1.0
Standard Control Library : Control, dynamics, physics, and simulation
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends Macros Groups Pages
taoDNode.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 _taoDNode_h
27 #define _taoDNode_h
28 
29 #include "taoTypes.h"
30 
32 class taoJoint;
33 class deVector3;
34 class deVector6;
35 class deFrame;
36 class deMatrix3;
37 
46 class taoDNode
47 {
48 public:
49  taoDNode() : _abNode(NULL), _propagate(1),
51  _id(-1), _isFixed(0), _cor(0), _cofg(0), _cofv(0), _cofs(0), _cofd(0) {}
52 
53  virtual ~taoDNode() {}
54 
55  virtual void sync(deFrame* local) = 0;
57 
60  virtual deInt isRoot() { return (getDParent() == NULL); }
62 
65  virtual deInt isParentRoot() { return (isRoot() || getDParent()->isRoot()); }
66 
67  virtual taoJoint* getJointList() = 0;
68  virtual taoJoint const * getJointList() const = 0;
69 
71  virtual taoArticulatedBodyLink* getABNode() { return _abNode; }
73  virtual void setABNode(taoArticulatedBodyLink* node) { _abNode = node; }
74 
76 
79  virtual deInt getPropagate() { return _propagate; }
80  virtual void setPropagate(deInt p) { _propagate = p; } // YYY
81 
82  virtual deVector6* velocity() = 0;
83  virtual deVector6* acceleration() = 0;
84 
86  virtual deFrame* frameHome() = 0;
88  virtual deFrame* frameLocal() = 0;
90  //virtual deFrame* frameGlobal() = 0;
92  virtual deFloat* mass() = 0;
94  virtual deVector3* center() = 0;
95  virtual deVector3 const * center() const = 0;
97  virtual deMatrix3* inertia() = 0;
99  virtual deVector6* force() = 0;
100  virtual void zeroForce() = 0;
101  virtual void addForce(const deVector6* f) = 0;
102 
103  virtual void updateFrame() = 0;
104  virtual void integrate(deFloat dt) = 0;
105 
107  virtual taoDNode* getDParent() = 0;
108  virtual taoDNode const * getDParent() const = 0;
109  virtual void setDChild(taoDNode* n) = 0;
111  virtual taoDNode* getDChild() = 0;
112  virtual taoDNode const* getDChild() const = 0;
114  virtual taoDNode* getDSibling() = 0;
115  virtual taoDNode const* getDSibling() const = 0;
116 
117 private:
118  taoArticulatedBodyLink* _abNode;
119  deInt _propagate;
120 
121  /* *********************************************
122  * Moved here from taoDNode
123  * ********************************************* */
124 public:
126 
130  virtual deFrame* frameGlobal() = 0;
131  virtual deFrame const * frameGlobal() const = 0;
133 
139  virtual void getFrameGraphics(deFrame* Fg) = 0;
140 
141  virtual void setID(const deInt id) { _id = id; }
142  virtual deInt getID() const { return _id; }
143 
144  virtual void setIsFixed(const deInt f) { _isFixed = f; }
145  virtual deInt getIsFixed() { return _isFixed; }
146 
147  virtual deFloat getCOR() { return _cor; }
148  virtual deFloat getCOF_grip() { return _cofg; }
149  virtual deFloat getCOF_viscous() { return _cofv; }
150  virtual deFloat getCOF_static() { return _cofs; }
151  virtual deFloat getCOF_dynamic() { return _cofd; }
152 
154  virtual void setCOR(deFloat c) { _cor = c; }
160  virtual void setCOF_grip(deFloat c) { _cofg = c; }
163  virtual void setCOF_viscous(deFloat c) { _cofv = c; }
165  virtual void setCOF_static(deFloat c) { _cofs = c; }
167  virtual void setCOF_dynamic(deFloat c) { _cofd = c; }
168 
169  virtual deFloat effectiveMass(const deVector3* Pie, const deVector3* Ui) { return 0; }
170  virtual void linearVelocity(deVector3* Vie, const deVector3* Pie) {}
171  virtual void linearAcceleration(deVector3* Aie, const deVector3* Pie) {}
173 
182  virtual void impulse(const deVector3* Pie, const deVector3* Yie) {}
184 
190  virtual void impulseDist(const deVector3* Pie, const deVector3* Yie) {}
192 
202  virtual void force(const deVector3* Pie, const deVector3* Fie) {}
204 
215  virtual deInt impact1(const deVector3* Pie, const deVector3* Ui, const deFloat cor2, const deFloat cofg2);
217 
224  virtual deInt impact2(taoDNode* ni, const deVector3* Pie, const deVector3* Ui,
225  taoDNode* nj, const deVector3* Pje, const deVector3* Uj);
227 
234  virtual deInt penetration1(const deVector3* Pie, const deVector3* Ui, const deVector3* pdist, const deFloat dt);
235 
236  std::string name_;
237 
238 private:
239  deInt _id;
240  deInt _isFixed;
241 
242  deFloat _cor;
243  deFloat _cofg;
244  deFloat _cofv;
245  deFloat _cofs;
246  deFloat _cofd;
247 
248  deInt _Impact1(const deVector3* Pie, const deVector3* Ui, const deVector3* V, const deFloat m, const deFloat vp, const deFloat vm, const deFloat cofg2);
249  void _Friction(const deVector3* Pie, const deVector3* Ui, const deVector3* Ut, const deFloat vtmag, const deFloat m);
250 };
251 
252 #endif // _taoDNode_h
virtual void getFrameGraphics(deFrame *Fg)=0
global frame for graphics display
3x1 vector classThis is a C++ wrapper class of deVector3f.
Definition: TaoDeVector3.h:32
virtual void impulseDist(const deVector3 *Pie, const deVector3 *Yie)
computes new position given pseudo impulse
Definition: taoDNode.h:190
virtual taoDNode * getDChild()=0
virtual deInt impact2(taoDNode *ni, const deVector3 *Pie, const deVector3 *Ui, taoDNode *nj, const deVector3 *Pje, const deVector3 *Uj)
This method computes impulse/force and changes velocity/friction between two colliding nodes...
Definition: taoDNode.cpp:39
virtual deInt isParentRoot()
indicates if parent of this node is root
Definition: taoDNode.h:65
virtual void force(const deVector3 *Pie, const deVector3 *Fie)
computes new force given force
Definition: taoDNode.h:202
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 deInt getPropagate()
indicates if dynamics of node should be included for control
Definition: taoDNode.h:79
virtual deFrame * frameLocal()=0
virtual void setCOF_grip(deFloat c)
cofg : coefficient of grip friction when v != 0 and y != 0 : f_g = - sign(v_t) * cofg * y_n ...
Definition: taoDNode.h:161
virtual deMatrix3 * inertia()=0
virtual void setCOR(deFloat c)
coefficient of restitution
Definition: taoDNode.h:154
virtual void setCOF_dynamic(deFloat c)
cofd : coefficient of dynamic friction when v != 0 : f_d = - sign(v_t) * cofd * f_n ...
Definition: taoDNode.h:167
virtual void setCOF_static(deFloat c)
cofs : coefficient of static friction when v == 0 and a != 0 : f_s = - sign(a_t) * cofs * f_n ...
Definition: taoDNode.h:165
virtual deVector3 * center()=0
Transformation class using quaternionThis class consists of a quaternion for rotation and a vector fo...
Definition: TaoDeFrame.h:36
taoDNode()
Definition: taoDNode.h:49
virtual deFrame * frameHome()=0
virtual deInt isRoot()
indicates if this node is root
Definition: taoDNode.h:60
virtual taoArticulatedBodyLink * getABNode()
gets _abNode
Definition: taoDNode.h:71
virtual void impulse(const deVector3 *Pie, const deVector3 *Yie)
computes new velocity given impulse
Definition: taoDNode.h:182
virtual deInt impact1(const deVector3 *Pie, const deVector3 *Ui, const deFloat cor2, const deFloat cofg2)
computes new velocity and force given pos, vel, acc
Definition: taoDNode.cpp:86
virtual taoDNode * getDParent()=0
Base joint class for articulated bodyThis provides a joint for articulated body dynamics.
Definition: taoJoint.h:45
virtual taoDNode * getDSibling()=0
virtual deInt penetration1(const deVector3 *Pie, const deVector3 *Ui, const deVector3 *pdist, const deFloat dt)
This method computes impulse and changes position/orientation using impulseDist().
Definition: taoDNode.cpp:172
virtual void setABNode(taoArticulatedBodyLink *node)
sets _abNode
Definition: taoDNode.h:73
3x3 matrix classThis is a C++ wrapper class of deMatrix3f.
Definition: TaoDeMatrix3.h:33
virtual deFrame * frameGlobal()=0
global frame for the dynamics computation
virtual deFloat * mass()=0
virtual deVector6 * force()=0
virtual void setCOF_viscous(deFloat c)
cofv : coefficient of viscous friction when v != 0 : f_v = - v_t * cofv
Definition: taoDNode.h:163