taoABDynamics Class Reference
[Dynamics]

Articulated body dynamics class

This class provides inverse and forward dynamics for articulated body. More...

#include <taoABDynamics.h>

List of all members.

Static Public Member Functions

static void updateLocalXTreeOut (taoDNode *root)
 updates local transforms in the subtree with root
static void resetInertiaTreeOut (taoDNode *root)
 resets inertias in the subtree with root
static void resetFlagTreeOut (taoDNode *root)
 resets flags in the subtree with root
static void forwardDynamics (taoDNode *root, const deVector3 *gravity)
 computes forward dynamics of the subtree with root under gravity
static void inverseDynamics (taoDNode *root, const deVector3 *gravity)
 computes inverse dynamics of the subtree with root under gravity
static void forwardDynamicsImpulse (taoDNode *contact, const deVector3 *point, const deVector3 *impulse, const deInt dist)
 computes velocity changes given impulse
static void globalJacobianOut (taoDNode *root)
 computes global Jacobina matrices
static void opSpaceInertiaMatrixOut (taoDNode *root, const deMatrix6 *Oah=NULL)
 computes inverse operational space inertia matrix for each node: diagonal terms: Omega_i_i
static void biasAccelerationOut (taoDNode *root, const deVector6 *Hh=NULL)
static void compute_Jg_Omega_H (taoDNode *root, const deMatrix6 *Oah=NULL, const deVector6 *Hh=NULL)
static deFloat effectiveMassInv (taoDNode *node, const deVector3 *point, const deVector3 *dir)
static void opSpaceInvDynamics (taoDNode *opNode, deVector6 *ddXn)
static void add2Tau_JgT_F (taoDNode *node, const deVector6 *Fg)
static deFloat potentialEnergy (taoDNode *root, const deVector3 *gravity)
 computes the potential energy of the subtree with root under gravity
static deFloat kineticEnergy (taoDNode *root, const deVector6 *Vh=NULL)
 computes the kinetic energy of the subtree with root under gravity
static void resetInertia (taoDNode *node)
 resets inertia of node


Detailed Description

Articulated body dynamics class

This class provides inverse and forward dynamics for articulated body.


Member Function Documentation

void taoABDynamics::add2Tau_JgT_F taoDNode node,
const deVector6 Fg
[static]
 

void taoABDynamics::biasAccelerationOut taoDNode root,
const deVector6 Hh = NULL
[static]
 

void taoABDynamics::compute_Jg_Omega_H taoDNode root,
const deMatrix6 Oah = NULL,
const deVector6 Hh = NULL
[static]
 

deFloat taoABDynamics::effectiveMassInv taoDNode node,
const deVector3 point,
const deVector3 dir
[static]
 

void taoABDynamics::forwardDynamics taoDNode root,
const 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 taoABDynamics::forwardDynamicsImpulse taoDNode contact,
const deVector3 point,
const deVector3 impulse,
const deInt  dist
[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 taoABDynamics::globalJacobianOut taoDNode root  )  [static]
 

computes global Jacobina matrices

Precondition:
q
Postcondition:
Jg

void taoABDynamics::inverseDynamics taoDNode root,
const 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 taoABDynamics::kineticEnergy taoDNode root,
const deVector6 Vh = NULL
[static]
 

computes the kinetic energy of the subtree with root under gravity

Parameters:
Vh spatial velocity vector of root
Returns:
the total kinetic energy

void taoABDynamics::opSpaceInertiaMatrixOut taoDNode root,
const deMatrix6 Oah = NULL
[static]
 

computes inverse operational space inertia matrix for each node: diagonal terms: Omega_i_i

Precondition:
S, Dinv, L
Postcondition:
Omega

void taoABDynamics::opSpaceInvDynamics taoDNode opNode,
deVector6 ddXn
[static]
 

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

computes the potential energy of the subtree with root under gravity

Returns:
the total potential energy

void taoABDynamics::resetFlagTreeOut taoDNode root  )  [static]
 

resets flags in the subtree with root

void taoABDynamics::resetInertia taoDNode node  )  [static]
 

resets inertia of node

void taoABDynamics::resetInertiaTreeOut taoDNode root  )  [static]
 

resets inertias in the subtree with root

void taoABDynamics::updateLocalXTreeOut taoDNode root  )  [static]
 

updates local transforms in the subtree with root


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