DynamicBody Class Reference

The superclass for all bodies that take part in the dynamics. More...

#include <body.h>

Inheritance diagram for DynamicBody:
Inheritance graph
[legend]

List of all members.

Public Member Functions

void addExtWrench (double *extW)
 Adds an external wrench expressed in world coordinates.
void addForce (vec3 force)
 Adds a pure force expressed in world coordinates.
void addForceAtPos (vec3 force, position pos)
 Adds the wrench resulting from a force applied at some location on the object in world coords.
void addForceAtRelPos (vec3 force, position pos)
 Adds the wrench resulting from a force applied at some location on the object in body coords.
void addRelTorque (vec3 torque)
 Adds a torque expressed in body coordinates.
void addTorque (vec3 torque)
 Adds an external torque expressed in world coordinates.
bool axesShown () const
void clearState ()
 Clears the state stack.
void cloneFrom (const DynamicBody *newBody)
 Clones another dynamic body.
void computeDefaultMassProp (position &cog, double *I)
 Attempts to compute mass and inertia matrix based only on geometry.
double computeDefaultMaxRadius ()
 Attempts to compute the max radius based only on geometry.
 DynamicBody (const Body &b, double m)
 Creates a dynamic body from a static one.
 DynamicBody (World *w, const char *name=0)
 An empty dynamic body with no meaningful properties.
bool dynamicsComputed () const
bool dynContactForcesShown () const
void fix ()
 Makes this body fixed for dynamic simulations.
const double * getAccel ()
position const & getCoG () const
virtual DynJointgetDynJoint ()
double * getExtWrenchAcc ()
const transfgetFixedTran () const
const double * getInertia () const
 Returns a pointer to the body's 3x3 inertia tensor (stored as an array).
SoSeparator * getIVWorstCase () const
double getMass () const
double getMaxRadius () const
const double * getPos ()
const double * getVelocity ()
bool isDynamic () const
bool isFixed () const
virtual int loadFromXml (const TiXmlElement *root, QString rootPath)
 Also looks for properties specific to the dynamic body.
void markState ()
 Saves the current state in a one-slot-only location.
bool popState ()
 Pops and sets the current state from the stack.
void pushState ()
 Saves the current state on the stack.
void resetDynamics ()
 Initializes dynamic parameters after copy constructor or load method.
void resetDynamicsFlag ()
void resetExtWrenchAcc ()
 Clears the external wrench accumulator.
void returnToMarkedState ()
 Returns to previously saved state.
virtual int saveToXml (QTextStream &xml)
 Saves the DynamicBody information to an XML structure.
void setAccel (double *new_a)
void setBounds (vec3 minBounds, vec3 maxBounds)
void setCoG (const position &newCoG)
 Sets the center of gravity and reinitializes the state vector to match it.
void setDefaultDynamicParameters ()
 Computes and sets the default center of gravity and inertia matrix.
virtual void setDefaultViewingParameters ()
 Hides the axes by default.
void setDynamicsFlag ()
virtual void setDynJoint (DynJoint *dj)
 Connects a dynamic joint (usually a fixed one) to this body.
void setInertiaMatrix (const double *newI)
 Sets the inertia matrix from newI.
void setMass (double m)
void setMaxRadius (double maxRad)
 Sets the maximum radius of the object, used for scaling and grasp computations.
bool setPos (const double *new_q)
virtual int setTran (transf const &newTr)
 Also updates the dynamic state of the body.
void setUseDynamics (bool dyn)
void setVelocity (double *new_v)
void showAxes (bool on)
void showDynContactForces (bool on)
void unfix ()
 Allows this body to move in dynamic simulations.
virtual ~DynamicBody ()

Static Public Attributes

static double defaultMass = 300.0

Protected Member Functions

void compFaceIntegrals (FACE &f, int A, int B, int C)
 Used for computing mass properties if not supplied in file.
void compProjectionIntegrals (FACE &f, int A, int B)
 Used for computing mass properties if not supplied in file.
int computeDefaultInertiaMatrix (std::vector< Triangle > &triangles, double *defaultI)
 Uses Brian Mirtich's code to compute cog and inertia matrix based on geometry.
void init ()
 Initializes an empty dynamic body, common to all constructors.

Protected Attributes

double a [6]
 Dynamic acceleration, in mm/sec^2.
vec3 bbox_max
 Corners of the box bounding the possible world positions of the object.
vec3 bbox_min
position CoG
 Center of gravity position (in millimeters).
bool dynamicsComputedFlag
 Tells us if the motion for this body has been computed at the current time step.
DynJointdynJoint
 Points to the dynamic joint connecting this body to its parent.
double extWrenchAcc [6]
 Accumulates external wrenches in world coordinates applied to this body.
bool fixed
 Is this body fixed in the world frame?
transf fixedTran
 World pose a fixed body should maintain.
double I [9]
 The inertia tensor of this body; remember to multiply by mass to get the actual inertia.
double markedQ [7]
 A single saved position state.
double markedV [6]
 A single saved velocity state.
double mass
 Mass of the body (in grams).
double maxRadius
 Maximum radius of the body from the center of gravity (in millimeters).
double q [7]
 Dynamic pose (translation in mm and quaternion).
std::list< double * > qStack
 Stack for saved position states.
bool showAx
 Flag determining whether axes should be shown (origin at COG).
bool showDynCF
 Flag determining whether dynamic contact forces for this body should be drawn.
double v [6]
 Dynamic velocity, in mm/sec.
std::list< double * > vStack
 Stack for saved velocity states.

Private Attributes

double Fa
 face integrals used in mass properties computations
double Faa
double Faaa
double Faab
double Fb
double Fbb
double Fbbb
double Fbbc
double Fc
double Fcc
double Fcca
double Fccc
double P1
 projection integrals used in mass properties computations
double Pa
double Paa
double Paaa
double Paab
double Pab
double Pabb
double Pb
double Pbb
double Pbbb
bool useDynamics
 Is this body affected by dynamics?

Detailed Description

The superclass for all bodies that take part in the dynamics.

A dynamic body adds mass parameters to the generic body description. It also includes the state variables q and v, which encode the position and velocity of the body at the current time step of the dynamics.

Definition at line 351 of file body.h.


Constructor & Destructor Documentation

DynamicBody::DynamicBody ( World w,
const char *  name = 0 
)

An empty dynamic body with no meaningful properties.

Constructs an empty DynamicBody. Use load() to initialize this class from a model file, or cloneFrom to initialize from a different dynamic body.

Definition at line 1290 of file body.cpp.

DynamicBody::DynamicBody ( const Body b,
double  m 
)

Creates a dynamic body from a static one.

Creates a dynamic body from the basic body b. Computes the mass properties automatically assuming a mass of m and uniform mass distribution.

Definition at line 1300 of file body.cpp.

DynamicBody::~DynamicBody (  )  [virtual]

If there is a dynamic joint connected to this body, it is deleted before the body is destroyed.

Definition at line 1242 of file body.cpp.


Member Function Documentation

void DynamicBody::addExtWrench ( double *  extW  ) 

Adds an external wrench expressed in world coordinates.

Adds extW to the external wrench accumulator.

Definition at line 1890 of file body.cpp.

void DynamicBody::addForce ( vec3  force  ) 

Adds a pure force expressed in world coordinates.

Adds a force expressed in world coordinates, to the external force accumulator for this body.

Definition at line 1904 of file body.cpp.

void DynamicBody::addForceAtPos ( vec3  force,
position  pos 
)

Adds the wrench resulting from a force applied at some location on the object in world coords.

Adds a force expressed in world coordinates at a position also expressed world coordinates. This force and the computed torque are added to the external force accumulator for this body.

Definition at line 1948 of file body.cpp.

void DynamicBody::addForceAtRelPos ( vec3  force,
position  pos 
)

Adds the wrench resulting from a force applied at some location on the object in body coords.

Adds a force expressed in body coordinates at a position also expressed body coordinates. This force and the computed torque are added to the external force accumulator for this body.

Definition at line 1971 of file body.cpp.

void DynamicBody::addRelTorque ( vec3  torque  ) 

Adds a torque expressed in body coordinates.

Definition at line 1930 of file body.cpp.

void DynamicBody::addTorque ( vec3  torque  ) 

Adds an external torque expressed in world coordinates.

Adds a torque expressed in world coordinates, to the external force accumulator for this body.

Definition at line 1917 of file body.cpp.

bool DynamicBody::axesShown (  )  const [inline]

Returns whether axes are drawn for this body

Definition at line 520 of file body.h.

void DynamicBody::clearState (  ) 

Clears the state stack.

Definition at line 2081 of file body.cpp.

void DynamicBody::cloneFrom ( const DynamicBody original  ) 

Clones another dynamic body.

Clones another dynamic body; all dynamic paramters are copied over.

Definition at line 1318 of file body.cpp.

void DynamicBody::compFaceIntegrals ( FACE f,
int  A,
int  B,
int  C 
) [protected]

Used for computing mass properties if not supplied in file.

Support routine for computing body mass properties. This code is adapted from code written by Brian Mirtich.

Definition at line 1554 of file body.cpp.

void DynamicBody::compProjectionIntegrals ( FACE f,
int  A,
int  B 
) [protected]

Used for computing mass properties if not supplied in file.

Support routine for computing body mass properties. This code is adapted from code written by Brian Mirtich.

Definition at line 1493 of file body.cpp.

int DynamicBody::computeDefaultInertiaMatrix ( std::vector< Triangle > &  triangles,
double *  defaultI 
) [protected]

Uses Brian Mirtich's code to compute cog and inertia matrix based on geometry.

Helper function that uses code by Brian Mirtich to compute the center of gravity and the inertia matrix for a list of triangles. Returns FAILURE if the computation fails, and some degenerate values are returned.

Definition at line 1592 of file body.cpp.

void DynamicBody::computeDefaultMassProp ( position defaultCoG,
double *  defaultI 
)

Attempts to compute mass and inertia matrix based only on geometry.

Given a list of the body vertices, and the number of triangles, this computes the center of gravity and inertia matrix by assuming a uniform mass distribution.

Definition at line 1827 of file body.cpp.

double DynamicBody::computeDefaultMaxRadius (  ) 

Attempts to compute the max radius based only on geometry.

Definition at line 1473 of file body.cpp.

bool DynamicBody::dynamicsComputed (  )  const [inline]

Returns whether the dynamics have been computed for this body during the current dynamics iteration.

See also:
setDynamicsFlag()
resetDynamicsFlag()

Definition at line 537 of file body.h.

bool DynamicBody::dynContactForcesShown (  )  const [inline]

Returns whether dynamic contact forces should be drawn for this body

Definition at line 523 of file body.h.

void DynamicBody::fix (  ) 

Makes this body fixed for dynamic simulations.

Fixes the body so that it does not move during dynamic simulation. This is done by addind a fixed dynamic joint that will constrain all 6 body velocities to 0.

Definition at line 2127 of file body.cpp.

const double* DynamicBody::getAccel (  )  [inline]

Returns a pointer to the body's 6x1 acceleration vector (simple first order approximation).

Definition at line 492 of file body.h.

position const& DynamicBody::getCoG (  )  const [inline]

Returns the center of gravity position.

Definition at line 473 of file body.h.

virtual DynJoint* DynamicBody::getDynJoint (  )  [inline, virtual]

Returns the dynamic joint connecting this body to its parent or NULL if there is none

Definition at line 517 of file body.h.

double* DynamicBody::getExtWrenchAcc (  )  [inline]

Returns the value of the external wrench accumulator.

Definition at line 574 of file body.h.

const transf& DynamicBody::getFixedTran (  )  const [inline]

Returns the world pose a fixed body should maintain

Definition at line 512 of file body.h.

const double* DynamicBody::getInertia (  )  const [inline]

Returns a pointer to the body's 3x3 inertia tensor (stored as an array).

Definition at line 484 of file body.h.

SoSeparator* DynamicBody::getIVWorstCase (  )  const [inline]

The returns a pointer to the Inventor subgraph containing the worst case indicator

Definition at line 501 of file body.h.

double DynamicBody::getMass (  )  const [inline]

Returns the mass of the body (in grams).

See also:
setMass()

Definition at line 481 of file body.h.

double DynamicBody::getMaxRadius (  )  const [inline]

Returns the max radius of the body.

Definition at line 476 of file body.h.

const double* DynamicBody::getPos (  )  [inline]

Returns a pointer to the body's 7x1 position vector [3x1 translation , 4x1 quaternion]

Definition at line 497 of file body.h.

const double* DynamicBody::getVelocity (  )  [inline]

Returns a pointer to the body's 6x1 velocity vector.

Definition at line 487 of file body.h.

void DynamicBody::init (  )  [protected]

Initializes an empty dynamic body, common to all constructors.

Definition at line 1248 of file body.cpp.

bool DynamicBody::isDynamic (  )  const [inline, virtual]

Returns whether this body is affected by dynamics

See also:
setUseDynamics()

Reimplemented from Body.

Definition at line 509 of file body.h.

bool DynamicBody::isFixed (  )  const [inline]

Returns whether the body is fixed within the world

Definition at line 504 of file body.h.

int DynamicBody::loadFromXml ( const TiXmlElement root,
QString  rootPath 
) [virtual]

Also looks for properties specific to the dynamic body.

Reimplemented from Body.

Definition at line 1328 of file body.cpp.

void DynamicBody::markState (  ) 

Saves the current state in a one-slot-only location.

Save the current dynamic state of the body. May soon be replaced by pushState().

Definition at line 2023 of file body.cpp.

bool DynamicBody::popState (  ) 

Pops and sets the current state from the stack.

Pop the current dynamic state of the body from a local stack.

Definition at line 2059 of file body.cpp.

void DynamicBody::pushState (  ) 

Saves the current state on the stack.

Push the current dynamic state of the body onto a local stack.

Definition at line 2044 of file body.cpp.

void DynamicBody::resetDynamics (  ) 

Initializes dynamic parameters after copy constructor or load method.

Sets acceleration and velocity to 0 and the 7-dimensional state vector to match the current transform (which includes the position of the center of gravity.

Definition at line 1268 of file body.cpp.

void DynamicBody::resetDynamicsFlag (  )  [inline]

At the end of the dynamics iteration, this is used to reset the dynamicsComputed flag

Definition at line 542 of file body.h.

void DynamicBody::resetExtWrenchAcc (  ) 

Clears the external wrench accumulator.

Resets the external wrench accumulator to 0.

Definition at line 1880 of file body.cpp.

void DynamicBody::returnToMarkedState (  ) 

Returns to previously saved state.

Restore the marked dynamic state of the body. May soon be replaced by popState().

Definition at line 2034 of file body.cpp.

int DynamicBody::saveToXml ( QTextStream &  xml  )  [virtual]

Saves the DynamicBody information to an XML structure.

Reimplemented from Body.

Definition at line 1428 of file body.cpp.

void DynamicBody::setAccel ( double *  new_a  )  [inline]

Sets the current 6x1 acceleration vector

Definition at line 562 of file body.h.

void DynamicBody::setBounds ( vec3  minBounds,
vec3  maxBounds 
) [inline]

Sets the world boundaries for this body. This is so a body can't fall forever.

Definition at line 565 of file body.h.

void DynamicBody::setCoG ( const position newCoG  ) 

Sets the center of gravity and reinitializes the state vector to match it.

Also has to reset dynamics since the current state has to be changed to match the new CoG.

Definition at line 1445 of file body.cpp.

void DynamicBody::setDefaultDynamicParameters (  ) 

Computes and sets the default center of gravity and inertia matrix.

Computes both the center of gravity and the inertia matrix automatically, based on the geometry of the object and then sets them.

Definition at line 1418 of file body.cpp.

void DynamicBody::setDefaultViewingParameters (  )  [virtual]

Hides the axes by default.

Reimplemented from Body.

Reimplemented in GraspableBody.

Definition at line 1846 of file body.cpp.

void DynamicBody::setDynamicsFlag (  )  [inline]

This is called to set the dynamicsComputed flag after the motions for this body have been computed during the current iteration of the dynamics.

Definition at line 547 of file body.h.

void DynamicBody::setDynJoint ( DynJoint dj  )  [virtual]

Connects a dynamic joint (usually a fixed one) to this body.

Sets the dynamic joint connected to this body to dj.

Definition at line 2148 of file body.cpp.

void DynamicBody::setInertiaMatrix ( const double *  newI  ) 

Sets the inertia matrix from newI.

Definition at line 1467 of file body.cpp.

void DynamicBody::setMass ( double  m  )  [inline]

Sets the body's mass in grams to m.

See also:
getMass()

Definition at line 571 of file body.h.

void DynamicBody::setMaxRadius ( double  maxRad  ) 

Sets the maximum radius of the object, used for scaling and grasp computations.

The max radius can be thought of as the largest distance from the center of gravity to the edge of the object.

Definition at line 1460 of file body.cpp.

bool DynamicBody::setPos ( const double *  new_q  ) 

Sets the current 7x1 position vector

Definition at line 1991 of file body.cpp.

int DynamicBody::setTran ( transf const &  tr  )  [virtual]

Also updates the dynamic state of the body.

Calls Body::setTran then updates the dynamic state of the body.

Reimplemented from Body.

Definition at line 2097 of file body.cpp.

void DynamicBody::setUseDynamics ( bool  dyn  )  [inline]

Sets whether this body should be affected by dynamics. Rather than creating a new static body when a body is set to be static, we just set this flag to false. That way if the body is made dynamic again, many\ parameters won't have to be recomputed.

Definition at line 530 of file body.h.

void DynamicBody::setVelocity ( double *  new_v  )  [inline]

Sets the current 6x1 velocity vector [vx vy vz vrx vry vrz]

Definition at line 559 of file body.h.

void DynamicBody::showAxes ( bool  on  ) 

Sets whether axes should be drawn for this body

Changes the state of the Inventor switch node controlling whether the coordinate axes on the body are visible

Definition at line 1857 of file body.cpp.

void DynamicBody::showDynContactForces ( bool  on  ) 

Sets whether dynamic contact forces should be drawn for this body

Sets whether dynamic contact forces should be drawn during dynamic simulation.

Definition at line 1870 of file body.cpp.

void DynamicBody::unfix (  ) 

Allows this body to move in dynamic simulations.

Removes the fixed dynamic joint so the body is free to move again during dynamic simulation.

Definition at line 2138 of file body.cpp.


Member Data Documentation

double DynamicBody::a[6] [protected]

Dynamic acceleration, in mm/sec^2.

Definition at line 392 of file body.h.

Corners of the box bounding the possible world positions of the object.

Definition at line 383 of file body.h.

Definition at line 383 of file body.h.

Center of gravity position (in millimeters).

Definition at line 365 of file body.h.

double DynamicBody::defaultMass = 300.0 [static]

Holds a default mass in case a body file doesn't specify one. The other mass properties can be computed assuming uniform density

Definition at line 612 of file body.h.

Tells us if the motion for this body has been computed at the current time step.

Definition at line 410 of file body.h.

Points to the dynamic joint connecting this body to its parent.

Definition at line 380 of file body.h.

double DynamicBody::extWrenchAcc[6] [protected]

Accumulates external wrenches in world coordinates applied to this body.

Definition at line 413 of file body.h.

double DynamicBody::Fa [private]

face integrals used in mass properties computations

Definition at line 361 of file body.h.

double DynamicBody::Faa [private]

Definition at line 361 of file body.h.

double DynamicBody::Faaa [private]

Definition at line 361 of file body.h.

double DynamicBody::Faab [private]

Definition at line 361 of file body.h.

double DynamicBody::Fb [private]

Definition at line 361 of file body.h.

double DynamicBody::Fbb [private]

Definition at line 361 of file body.h.

double DynamicBody::Fbbb [private]

Definition at line 361 of file body.h.

double DynamicBody::Fbbc [private]

Definition at line 361 of file body.h.

double DynamicBody::Fc [private]

Definition at line 361 of file body.h.

double DynamicBody::Fcc [private]

Definition at line 361 of file body.h.

double DynamicBody::Fcca [private]

Definition at line 361 of file body.h.

double DynamicBody::Fccc [private]

Definition at line 361 of file body.h.

bool DynamicBody::fixed [protected]

Is this body fixed in the world frame?

Definition at line 374 of file body.h.

World pose a fixed body should maintain.

Definition at line 377 of file body.h.

double DynamicBody::I[9] [protected]

The inertia tensor of this body; remember to multiply by mass to get the actual inertia.

Definition at line 407 of file body.h.

double DynamicBody::markedQ[7] [protected]

A single saved position state.

Definition at line 404 of file body.h.

double DynamicBody::markedV[6] [protected]

A single saved velocity state.

Definition at line 402 of file body.h.

double DynamicBody::mass [protected]

Mass of the body (in grams).

Definition at line 371 of file body.h.

double DynamicBody::maxRadius [protected]

Maximum radius of the body from the center of gravity (in millimeters).

Definition at line 368 of file body.h.

double DynamicBody::P1 [private]

projection integrals used in mass properties computations

Definition at line 358 of file body.h.

double DynamicBody::Pa [private]

Definition at line 358 of file body.h.

double DynamicBody::Paa [private]

Definition at line 358 of file body.h.

double DynamicBody::Paaa [private]

Definition at line 358 of file body.h.

double DynamicBody::Paab [private]

Definition at line 358 of file body.h.

double DynamicBody::Pab [private]

Definition at line 358 of file body.h.

double DynamicBody::Pabb [private]

Definition at line 358 of file body.h.

double DynamicBody::Pb [private]

Definition at line 358 of file body.h.

double DynamicBody::Pbb [private]

Definition at line 358 of file body.h.

double DynamicBody::Pbbb [private]

Definition at line 358 of file body.h.

double DynamicBody::q[7] [protected]

Dynamic pose (translation in mm and quaternion).

Definition at line 396 of file body.h.

std::list<double*> DynamicBody::qStack [protected]

Stack for saved position states.

Definition at line 400 of file body.h.

bool DynamicBody::showAx [protected]

Flag determining whether axes should be shown (origin at COG).

Definition at line 386 of file body.h.

bool DynamicBody::showDynCF [protected]

Flag determining whether dynamic contact forces for this body should be drawn.

Definition at line 389 of file body.h.

bool DynamicBody::useDynamics [private]

Is this body affected by dynamics?

Definition at line 355 of file body.h.

double DynamicBody::v[6] [protected]

Dynamic velocity, in mm/sec.

Definition at line 394 of file body.h.

std::list<double*> DynamicBody::vStack [protected]

Stack for saved velocity states.

Definition at line 398 of file body.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


graspit
Author(s):
autogenerated on Wed Jan 25 11:00:20 2012