51 _id(-1), _isFixed(0), _cor(0), _cofg(0), _cofv(0), _cofs(0), _cofd(0) {}
55 virtual void sync(
deFrame* local) = 0;
67 virtual taoJoint* getJointList() = 0;
68 virtual taoJoint const * getJointList()
const = 0;
80 virtual void setPropagate(deInt p) { _propagate = p; }
92 virtual deFloat*
mass() = 0;
100 virtual void zeroForce() = 0;
101 virtual void addForce(
const deVector6* f) = 0;
103 virtual void updateFrame() = 0;
104 virtual void integrate(deFloat dt) = 0;
109 virtual void setDChild(
taoDNode* n) = 0;
141 virtual void setID(
const deInt
id) { _id = id; }
142 virtual deInt getID()
const {
return _id; }
144 virtual void setIsFixed(
const deInt f) { _isFixed = f; }
145 virtual deInt getIsFixed() {
return _isFixed; }
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; }
154 virtual void setCOR(deFloat c) { _cor = c; }
169 virtual deFloat effectiveMass(
const deVector3* Pie,
const deVector3* Ui) {
return 0; }
248 deInt _Impact1(
const deVector3* Pie,
const deVector3* Ui,
const deVector3* V,
const deFloat m,
const deFloat vp,
const deFloat vm,
const deFloat cofg2);
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
Articulated body node classThis class provides node for articulated body.
Definition: taoArticulatedBodyLink.hpp:40
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