SCL  1.0
Standard Control Library : Control, dynamics, physics, and simulation
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends Macros Groups Pages
Public Member Functions | Private Attributes | List of all members
taoDNode Class Referenceabstract

abstract node class for articulated bodyA dynamics node = {Articulated Body Link + Set of associated Joints}. More...

#include <taoDNode.h>

Inheritance diagram for taoDNode:
Inheritance graph
[legend]
Collaboration diagram for taoDNode:
Collaboration graph
[legend]

Public Member Functions

 taoDNode ()
 
virtual void sync (deFrame *local)=0
 
virtual deInt isRoot ()
 indicates if this node is root More...
 
virtual deInt isParentRoot ()
 indicates if parent of this node is root More...
 
virtual taoJointgetJointList ()=0
 
virtual taoJoint const * getJointList () const =0
 
virtual taoArticulatedBodyLinkgetABNode ()
 gets _abNode More...
 
virtual void setABNode (taoArticulatedBodyLink *node)
 sets _abNode More...
 
virtual deInt getPropagate ()
 indicates if dynamics of node should be included for control More...
 
virtual void setPropagate (deInt p)
 
virtual deVector6velocity ()=0
 
virtual deVector6acceleration ()=0
 
virtual deFrameframeHome ()=0
 
virtual deFrameframeLocal ()=0
 
virtual deFloat * mass ()=0
 
virtual deVector3center ()=0
 
virtual deVector3 const * center () const =0
 
virtual deMatrix3inertia ()=0
 
virtual deVector6force ()=0
 
virtual void zeroForce ()=0
 
virtual void addForce (const deVector6 *f)=0
 
virtual void updateFrame ()=0
 
virtual void integrate (deFloat dt)=0
 
virtual taoDNodegetDParent ()=0
 
virtual taoDNode const * getDParent () const =0
 
virtual void setDChild (taoDNode *n)=0
 
virtual taoDNodegetDChild ()=0
 
virtual taoDNode const * getDChild () const =0
 
virtual taoDNodegetDSibling ()=0
 
virtual taoDNode const * getDSibling () const =0
 
virtual deFrameframeGlobal ()=0
 global frame for the dynamics computation More...
 
virtual deFrame const * frameGlobal () const =0
 
virtual void getFrameGraphics (deFrame *Fg)=0
 global frame for graphics display More...
 
virtual void setID (const deInt id)
 
virtual deInt getID () const
 
virtual void setIsFixed (const deInt f)
 
virtual deInt getIsFixed ()
 
virtual deFloat getCOR ()
 
virtual deFloat getCOF_grip ()
 
virtual deFloat getCOF_viscous ()
 
virtual deFloat getCOF_static ()
 
virtual deFloat getCOF_dynamic ()
 
virtual void setCOR (deFloat c)
 coefficient of restitution More...
 

Private Attributes

taoArticulatedBodyLink_abNode
 
deInt _propagate
 

Coefficients of friction

where v is velocity, a is acceleration, y is impulse, and f is force at the contact point.

Note
: (*)_n and (*)_t indicate the normal and tangential components of (*) respectively.
deInt _id
 
deInt _isFixed
 
deFloat _cor
 
deFloat _cofg
 
deFloat _cofv
 
deFloat _cofs
 
deFloat _cofd
 
std::string name_
 
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 More...
 
virtual void setCOF_viscous (deFloat c)
 cofv : coefficient of viscous friction when v != 0 : f_v = - v_t * cofv More...
 
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 More...
 
virtual void setCOF_dynamic (deFloat c)
 cofd : coefficient of dynamic friction when v != 0 : f_d = - sign(v_t) * cofd * f_n More...
 
virtual deFloat effectiveMass (const deVector3 *Pie, const deVector3 *Ui)
 
virtual void linearVelocity (deVector3 *Vie, const deVector3 *Pie)
 
virtual void linearAcceleration (deVector3 *Aie, const deVector3 *Pie)
 
virtual void impulse (const deVector3 *Pie, const deVector3 *Yie)
 computes new velocity given impulse More...
 
virtual void impulseDist (const deVector3 *Pie, const deVector3 *Yie)
 computes new position given pseudo impulse More...
 
virtual void force (const deVector3 *Pie, const deVector3 *Fie)
 computes new force given force More...
 
virtual deInt impact1 (const deVector3 *Pie, const deVector3 *Ui, const deFloat cor2, const deFloat cofg2)
 computes new velocity and force given pos, vel, acc More...
 
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, ni and nj. More...
 
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(). More...
 
deInt _Impact1 (const deVector3 *Pie, const deVector3 *Ui, const deVector3 *V, const deFloat m, const deFloat vp, const deFloat vm, const deFloat cofg2)
 
void _Friction (const deVector3 *Pie, const deVector3 *Ui, const deVector3 *Ut, const deFloat vtmag, const deFloat m)
 

Detailed Description

abstract node class for articulated body

A dynamics node = {Articulated Body Link + Set of associated Joints}.

This class should be used as a base class and implemented accordingly.

Constructor & Destructor Documentation

taoDNode::taoDNode ( )
inline

Copied from CNode

Member Function Documentation

virtual deVector3* taoDNode::center ( )
pure virtual
Returns
center of gravity in local frame

Implemented in taoNodeRoot, and taoNode.

virtual deVector6* taoDNode::force ( )
pure virtual
Return values
fextaccumulate all external forces

Implemented in taoNodeRoot, and taoNode.

virtual void taoDNode::force ( const deVector3 Pie,
const deVector3 Fie 
)
inlinevirtual

computes new force given force

This method replaces the accumulated force with the given force.

Remarks
replaces the internal force with a new force
Precondition
A, F
Postcondition
F
  • Pie - contact point expressed in local frame.
  • Fie - force at the contact point expressed in local frame.
    Note
    this method replaces the internal force in the node.

Reimplemented in taoNode.

virtual deFrame* taoDNode::frameGlobal ( )
pure virtual

global frame for the dynamics computation

Note
for taoNodeRB, this is the center of mass frame.
for taoNode, this is the same frame getFrameGraphics()

Implemented in taoNodeRoot, and taoNode.

virtual deFrame* taoDNode::frameHome ( )
pure virtual
Returns
home frame

Implemented in taoNodeRoot, and taoNode.

virtual deFrame* taoDNode::frameLocal ( )
pure virtual
Returns
local frame

Implemented in taoNodeRoot, and taoNode.

virtual taoArticulatedBodyLink* taoDNode::getABNode ( )
inlinevirtual

gets _abNode

virtual taoDNode* taoDNode::getDChild ( )
pure virtual
Returns
first child node

Implemented in taoNodeRoot, and taoNode.

virtual taoDNode* taoDNode::getDParent ( )
pure virtual
Returns
parent node

Implemented in taoNodeRoot, and taoNode.

virtual taoDNode* taoDNode::getDSibling ( )
pure virtual
Returns
next sibling node

Implemented in taoNodeRoot, and taoNode.

virtual void taoDNode::getFrameGraphics ( deFrame Fg)
pure virtual

global frame for graphics display

Note
for taoNodeRB, this is the graphics origin frame without the offset.
for taoNodeRB, setFrameGraphics() should be used to set this frame.
for taoNode, this is the same frame as frameGlobal()
Return values
Fgis filled with the frame info for graphics sync.

Implemented in taoNodeRoot, and taoNode.

virtual deInt taoDNode::getPropagate ( )
inlinevirtual

indicates if dynamics of node should be included for control

Return values
1to propagate dynamics of node for control
0not to propagate dynamics of node for control
deInt taoDNode::impact1 ( const deVector3 Pie,
const deVector3 Ui,
const deFloat  cor2,
const deFloat  cofg2 
)
virtual

computes new velocity and force given pos, vel, acc

Remarks
do not use ddQ after this call, replaces the internal force to the new force
Precondition
T, Q, V, dQ, A
Postcondition
V, dQ, F
  • Pie - contact point expressed in local frame.
  • Ui - unit contact direction vector expressed in local frame (outward normal vector)
  • cor2 - coefficient of restitution of the other collision node.
  • cof2 - coefficient of grip friction of the other collision node.
    Note
    this method is assuming a node is colliding with a non-moving node.
deInt taoDNode::impact2 ( taoDNode ni,
const deVector3 Pie,
const deVector3 Ui,
taoDNode nj,
const deVector3 Pje,
const deVector3 Uj 
)
virtual

This method computes impulse/force and changes velocity/friction between two colliding nodes, ni and nj.

  • Pie - contact point expressed in frame i : Pie = ^iP_e - ^iP_i
  • Pje - contact point expressed in frame j : Pje = ^jP_e - ^jP_j
  • Ui - unit contact direction vector expressed in frame i : Ui = (^iP_j - ^iP_i)/|^iP_j - ^iP_i|
  • Uj - Ui expressed in frame j
    Note
    this method should be used for two moving nodes.
    Edited 2013-08-21 : Samir Menon smeno.nosp@m.n@st.nosp@m.anfor.nosp@m.d.ed.nosp@m.u
virtual void taoDNode::impulse ( const deVector3 Pie,
const deVector3 Yie 
)
inlinevirtual

computes new velocity given impulse

This method changes velocity instantaneously by applying the given impulse.

Remarks
do not use ddQ after this call
Precondition
T, Q, V, dQ, Y
Postcondition
V, dQ
  • Pie - contact point expressed in local frame.
  • Yie - impulse at the contact point expressed in local frame.

Reimplemented in taoNode.

virtual void taoDNode::impulseDist ( const deVector3 Pie,
const deVector3 Yie 
)
inlinevirtual

computes new position given pseudo impulse

This method changes position and orientation instantaneously by applying the given pseudo impulse.

  • Pie - contact point expressed in local frame.
  • Yie - pseudo impulse at the contact point expressed in local frame.

Reimplemented in taoNode.

virtual deMatrix3* taoDNode::inertia ( )
pure virtual
Returns
inertia tensor at the origin of local frame

Implemented in taoNodeRoot, and taoNode.

virtual deInt taoDNode::isParentRoot ( )
inlinevirtual

indicates if parent of this node is root

Return values
1parent this node is root
0parent this node in not root
virtual deInt taoDNode::isRoot ( )
inlinevirtual

indicates if this node is root

Return values
1this node is root
0this node in not root
virtual deFloat* taoDNode::mass ( )
pure virtual
Returns
global frame
mass

Implemented in taoNodeRoot, and taoNode.

deInt taoDNode::penetration1 ( const deVector3 Pie,
const deVector3 Ui,
const deVector3 pdist,
const deFloat  dt 
)
virtual

This method computes impulse and changes position/orientation using impulseDist().

  • Pie - contact point expressed in local frame.
  • Ui - unit contact direction vector expressed in local frame (outward normal vector).
  • pdist - penetration distance vector : pdist = P_o - P_i
  • dt - integration time step.
    Note
    this method is assuming a node is colliding with a non-moving node.
virtual void taoDNode::setABNode ( taoArticulatedBodyLink node)
inlinevirtual

sets _abNode

virtual void taoDNode::setCOF_dynamic ( deFloat  c)
inlinevirtual

cofd : coefficient of dynamic friction when v != 0 : f_d = - sign(v_t) * cofd * f_n

virtual void taoDNode::setCOF_grip ( deFloat  c)
inlinevirtual

cofg : coefficient of grip friction when v != 0 and y != 0 : f_g = - sign(v_t) * cofg * y_n

virtual void taoDNode::setCOF_static ( deFloat  c)
inlinevirtual

cofs : coefficient of static friction when v == 0 and a != 0 : f_s = - sign(a_t) * cofs * f_n

virtual void taoDNode::setCOF_viscous ( deFloat  c)
inlinevirtual

cofv : coefficient of viscous friction when v != 0 : f_v = - v_t * cofv

virtual void taoDNode::setCOR ( deFloat  c)
inlinevirtual

coefficient of restitution


The documentation for this class was generated from the following files: