taoDynamics Class Reference
[Dynamics]

articulated body dynamics

This class provides various dynamics computations for articulated body. More...

#include <taoDynamics.h>

List of all members.

Static Public Member Functions

static void initialize (taoDNode *root)
static void reset (taoDNode *root)
static void updateTransformation (taoDNode *root)
static void integrate (taoDNode *root, deFloat dt)
static void globalJacobian (taoDNode *root)
 computes global Jacobina matrices
static void invDynamics (taoDNode *root, deVector3 *gravity)
 computes inverse dynamics of the subtree with root under gravity
static void fwdDynamics (taoDNode *root, deVector3 *gravity)
 computes forward dynamics of the subtree with root under gravity
static void computeA (taoDNode *root, const deInt dof, deFloat *A)
 computes Joint Space Inertia Matrix, A of size dof x dof
static void computeAinv (taoDNode *root, const deInt dof, deFloat *Ainv)
 computes Joint Space Inertia Matrix Inverse, Ainv (dof x dof)
static void computeB (taoDNode *root, const deInt dof, deFloat *B)
 computes Coriolis and centrifugal forces, B (dof x 1)
static void computeG (taoDNode *root, deVector3 *gravity, const deInt dof, deFloat *G)
 computes gravitational forces, G (dof x 1) under gravity
static void computeOpSpaceInertiaMatrixInv (taoDNode *root, const deFloat *J, const deInt row, const deInt dof, const deFloat *Ainv, deFloat *Linv)
 compute the operational Space Inertia Matrix Inverse, Linv (row x row)
static int computeDOF (taoDNode *obj)
 find dof : degrees of freedom
static void impulse (taoDNode *contactNode, const deVector3 *contactPoint, const deVector3 *impulseVector)
 computes velocity changes given impulse
static void impulseDist (taoDNode *contactNode, const deVector3 *contactPoint, const deVector3 *impulseVector)
static void force (taoDNode *contactNode, const deVector3 *contactPoint, const deVector3 *forceVector)
static void resetMass (taoDNode *node, const deFloat mass)
static deFloat potentialEnergy (taoDNode *root, const deVector3 *gravity)
static deFloat kineticEnergy (taoDNode *root)


Detailed Description

articulated body dynamics

This class provides various dynamics computations for articulated body.


Member Function Documentation

void taoDynamics::computeA taoDNode root,
const deInt  dof,
deFloat A
[static]
 

computes Joint Space Inertia Matrix, A of size dof x dof

assuming current configuration/velocity

Remarks:
tau = A * ddq + b + g

ddq = Ainv * (tau - b - g)

************* output

A = joint space inertia matrix

B = centrifugal / Coriolis force

G = gravity

Ainv = inverse of mass matrix

************* Usage

{

fwdDynamics(root, gravity);

int dof = computeDOF(root);

deFloat A[dof * dof]

deFloat B[dof], G[dof]

computeA(root, gravity, dof, A);

computeB(root, gravity, dof, B);

computeG(root, gravity, dof, G);

computeAinv(root, gravity, dof, Ainv);

}

void taoDynamics::computeAinv taoDNode root,
const deInt  dof,
deFloat Ainv
[static]
 

computes Joint Space Inertia Matrix Inverse, Ainv (dof x dof)

void taoDynamics::computeB taoDNode root,
const deInt  dof,
deFloat B
[static]
 

computes Coriolis and centrifugal forces, B (dof x 1)

deInt taoDynamics::computeDOF taoDNode obj  )  [static]
 

find dof : degrees of freedom

void taoDynamics::computeG taoDNode root,
deVector3 gravity,
const deInt  dof,
deFloat G
[static]
 

computes gravitational forces, G (dof x 1) under gravity

void taoDynamics::computeOpSpaceInertiaMatrixInv taoDNode root,
const deFloat J,
const deInt  row,
const deInt  dof,
const deFloat Ainv,
deFloat Linv
[static]
 

compute the operational Space Inertia Matrix Inverse, Linv (row x row)

Parameters:
J Jacobian matrix of the operational points (row x dof)
Ainv (dof x dof)
Linv (row x row) = J Ainv J^T
Remarks:
effective mass in the direction of u can be found: m_u = 1 (u^T Linv u)

void taoDynamics::force taoDNode contactNode,
const deVector3 contactPoint,
const deVector3 forceVector
[static]
 

void taoDynamics::fwdDynamics taoDNode root,
deVector3 gravity
[static]
 

computes forward dynamics of the subtree with root under gravity

Precondition:
q, dq, tau should be given
Postcondition:
ddq is acceleration

void taoDynamics::globalJacobian taoDNode root  )  [static]
 

computes global Jacobina matrices

Precondition:
q
Postcondition:
Jg

void taoDynamics::impulse taoDNode contactNode,
const deVector3 contactPoint,
const deVector3 impulseVector
[static]
 

computes velocity changes given impulse

Parameters:
point expressed in local frame
Remarks:
use this methods after forwardDynamicsConifgInit
Precondition:
tau (impulse) is given only to the contact at local point with impulse
Postcondition:
ddq (velocity change) are computed for all nodes, V, dQ are also changed

void taoDynamics::impulseDist taoDNode contactNode,
const deVector3 contactPoint,
const deVector3 impulseVector
[static]
 

void taoDynamics::initialize taoDNode root  )  [static]
 

void taoDynamics::integrate taoDNode root,
deFloat  dt
[static]
 

void taoDynamics::invDynamics taoDNode root,
deVector3 gravity
[static]
 

computes inverse dynamics of the subtree with root under gravity

Precondition:
q, dq, ddq should be given, Fext
Postcondition:
tau is computed torque

deFloat taoDynamics::kineticEnergy taoDNode root  )  [static]
 

deFloat taoDynamics::potentialEnergy taoDNode root,
const deVector3 gravity
[static]
 

void taoDynamics::reset taoDNode root  )  [static]
 

Remarks:
calls r->sync(r->frameHome())

void taoDynamics::resetMass taoDNode node,
const deFloat  mass
[static]
 

void taoDynamics::updateTransformation taoDNode root  )  [static]
 


The documentation for this class was generated from the following files:
Generated on Sun Apr 9 22:12:45 2006 for TAO by  doxygen 1.4.6-NO