node class for articulated body dynamicsThis implements taoDNode for articulated body dynamics.
More...
#include <taoNode.h>
|
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.
|
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 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...
|
|
std::string | name_ |
|
node class for articulated body dynamics
This implements taoDNode for articulated body dynamics.
- See Also
- taoCNode, taoDNode, taoDynamics
virtual void taoNode::addForce |
( |
const deVector6 * |
f | ) |
|
|
inlinevirtual |
- Returns
- center of gravity in local frame
Implements taoDNode.
computes new force given force
This method replaces the accumulated force with the given 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 from taoDNode.
virtual deFrame* taoNode::frameGlobal |
( |
| ) |
|
|
inlinevirtual |
global frame for the dynamics computation
- Note
- for taoNodeRB, this is the center of mass frame.
-
for taoNode, this is the same frame getFrameGraphics()
Implements taoDNode.
virtual deFrame* taoNode::frameHome |
( |
| ) |
|
|
inlinevirtual |
virtual deFrame* taoNode::frameLocal |
( |
| ) |
|
|
inlinevirtual |
virtual taoDNode* taoNode::getDChild |
( |
| ) |
|
|
inlinevirtual |
- Returns
- first child node
Implements taoDNode.
virtual taoDNode* taoNode::getDParent |
( |
| ) |
|
|
inlinevirtual |
virtual taoDNode* taoNode::getDSibling |
( |
| ) |
|
|
inlinevirtual |
- Returns
- next sibling node
Implements taoDNode.
virtual void taoNode::getFrameGraphics |
( |
deFrame * |
Fg | ) |
|
|
inlinevirtual |
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
-
Fg | is filled with the frame info for graphics sync. |
Implements taoDNode.
virtual deInt taoDNode::getPropagate |
( |
| ) |
|
|
inlinevirtualinherited |
indicates if dynamics of node should be included for control
- Return values
-
1 | to propagate dynamics of node for control |
0 | not to propagate dynamics of node for control |
deInt taoDNode::impact1 |
( |
const deVector3 * |
Pie, |
|
|
const deVector3 * |
Ui, |
|
|
const deFloat |
cor2, |
|
|
const deFloat |
cofg2 |
|
) |
| |
|
virtualinherited |
computes new velocity and force given pos, vel, acc
- 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.
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
computes new velocity given impulse
This method changes velocity instantaneously by applying the given impulse.
- 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 from taoDNode.
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 from taoDNode.
- Returns
- inertia tensor at the origin of local frame
Implements taoDNode.
virtual deInt taoDNode::isParentRoot |
( |
| ) |
|
|
inlinevirtualinherited |
indicates if parent of this node is root
- Return values
-
1 | parent this node is root |
0 | parent this node in not root |
virtual deInt taoDNode::isRoot |
( |
| ) |
|
|
inlinevirtualinherited |
indicates if this node is root
- Return values
-
1 | this node is root |
0 | this node in not root |
virtual deFloat* taoNode::mass |
( |
| ) |
|
|
inlinevirtual |
- Returns
- global frame
-
mass
Implements taoDNode.
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::setCOF_dynamic |
( |
deFloat |
c | ) |
|
|
inlinevirtualinherited |
cofd
: coefficient of dynamic friction when v != 0
: f_d = - sign(v_t) * cofd
* f_n
virtual void taoDNode::setCOF_grip |
( |
deFloat |
c | ) |
|
|
inlinevirtualinherited |
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 | ) |
|
|
inlinevirtualinherited |
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 | ) |
|
|
inlinevirtualinherited |
cofv
: coefficient of viscous friction when v != 0
: f_v = - v_t * cofv
virtual void taoDNode::setCOR |
( |
deFloat |
c | ) |
|
|
inlinevirtualinherited |
coefficient of restitution
void taoNode::updateFrame |
( |
| ) |
|
|
virtual |
This function updates two frames. parent_T_node (_frameLocal), and origin_T_node (_frameGlobal)
Implements taoDNode.
The documentation for this class was generated from the following files:
- /home/samir/Code/control/scl.git/src/scl/dynamics/tao/tao/dynamics/taoNode.h
- /home/samir/Code/control/scl.git/src/scl/dynamics/tao/tao/dynamics/taoNode.cpp