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

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

#include <taoDynamics.h>

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 More...
 
static void invDynamics (taoDNode *root, const deVector3 *gravity)
 computes inverse dynamics of the subtree with root under gravity More...
 
static void fwdDynamics (taoDNode *root, const deVector3 *gravity)
 computes forward dynamics of the subtree with root under gravity More...
 
static void computeA (taoDNode *root, const deInt dof, deFloat *A)
 computes Joint Space Inertia Matrix, A of size dof x dof More...
 
static void computeAinv (taoDNode *root, const deInt dof, deFloat *Ainv)
 computes Joint Space Inertia Matrix Inverse, Ainv (dof x dof) More...
 
static void computeB (taoDNode *root, const deInt dof, deFloat *B)
 computes Coriolis and centrifugal forces, B (dof x 1) More...
 
static void computeG (taoDNode *root, deVector3 *gravity, const deInt dof, deFloat *G)
 computes gravitational forces, G (dof x 1) under gravity More...
 
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) More...
 
static int computeDOF (taoDNode *obj)
 find dof : degrees of freedom More...
 
static void impulse (taoDNode *contactNode, const deVector3 *contactPoint, const deVector3 *impulseVector)
 computes velocity changes given impulse More...
 
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)
 

Private Types

enum  flagType { TAO_DDQ, TAO_DQ, TAO_TAU }
 

Static Private Member Functions

static void _Read (taoDNode *root, deFloat *v, flagType type)
 
static void _Write (taoDNode *root, deFloat *v, flagType type)
 

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
JJacobian 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::fwdDynamics ( 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 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
pointexpressed 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::initialize ( taoDNode root)
static

Edited 2013-08-21 : Samir Menon smeno.nosp@m.n@st.nosp@m.anfor.nosp@m.d.ed.nosp@m.u

void taoDynamics::invDynamics ( 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
void taoDynamics::reset ( taoDNode root)
static
Remarks
calls r->sync(r->frameHome())

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