The superclass for all bodies that take part in the dynamics. More...
#include <body.h>
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 DynJoint * | getDynJoint () |
double * | getExtWrenchAcc () |
const transf & | getFixedTran () 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. | |
DynJoint * | dynJoint |
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? |
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.
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.
DynamicBody::DynamicBody | ( | const Body & | b, | |
double | m | |||
) |
DynamicBody::~DynamicBody | ( | ) | [virtual] |
void DynamicBody::addExtWrench | ( | double * | extW | ) |
void DynamicBody::addForce | ( | vec3 | force | ) |
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.
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.
void DynamicBody::addRelTorque | ( | vec3 | torque | ) |
void DynamicBody::addTorque | ( | vec3 | torque | ) |
bool DynamicBody::axesShown | ( | ) | const [inline] |
void DynamicBody::cloneFrom | ( | const DynamicBody * | original | ) |
void DynamicBody::compFaceIntegrals | ( | FACE & | f, | |
int | A, | |||
int | B, | |||
int | C | |||
) | [protected] |
void DynamicBody::compProjectionIntegrals | ( | FACE & | f, | |
int | A, | |||
int | B | |||
) | [protected] |
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.
void DynamicBody::computeDefaultMassProp | ( | position & | defaultCoG, | |
double * | defaultI | |||
) |
double DynamicBody::computeDefaultMaxRadius | ( | ) |
bool DynamicBody::dynamicsComputed | ( | ) | const [inline] |
Returns whether the dynamics have been computed for this body during the current dynamics iteration.
bool DynamicBody::dynContactForcesShown | ( | ) | const [inline] |
void DynamicBody::fix | ( | ) |
const double* DynamicBody::getAccel | ( | ) | [inline] |
position const& DynamicBody::getCoG | ( | ) | const [inline] |
virtual DynJoint* DynamicBody::getDynJoint | ( | ) | [inline, virtual] |
double* DynamicBody::getExtWrenchAcc | ( | ) | [inline] |
const transf& DynamicBody::getFixedTran | ( | ) | const [inline] |
const double* DynamicBody::getInertia | ( | ) | const [inline] |
SoSeparator* DynamicBody::getIVWorstCase | ( | ) | const [inline] |
double DynamicBody::getMass | ( | ) | const [inline] |
double DynamicBody::getMaxRadius | ( | ) | const [inline] |
const double* DynamicBody::getPos | ( | ) | [inline] |
const double* DynamicBody::getVelocity | ( | ) | [inline] |
void DynamicBody::init | ( | ) | [protected] |
bool DynamicBody::isDynamic | ( | ) | const [inline, virtual] |
Returns whether this body is affected by dynamics
Reimplemented from Body.
bool DynamicBody::isFixed | ( | ) | const [inline] |
int DynamicBody::loadFromXml | ( | const TiXmlElement * | root, | |
QString | rootPath | |||
) | [virtual] |
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().
bool DynamicBody::popState | ( | ) |
void DynamicBody::pushState | ( | ) |
void DynamicBody::resetDynamics | ( | ) |
void DynamicBody::resetDynamicsFlag | ( | ) | [inline] |
void DynamicBody::resetExtWrenchAcc | ( | ) |
void DynamicBody::returnToMarkedState | ( | ) |
Returns to previously saved state.
Restore the marked dynamic state of the body. May soon be replaced by popState().
int DynamicBody::saveToXml | ( | QTextStream & | xml | ) | [virtual] |
Saves the DynamicBody information to an XML structure.
Reimplemented from Body.
void DynamicBody::setAccel | ( | double * | new_a | ) | [inline] |
void DynamicBody::setCoG | ( | const position & | newCoG | ) |
void DynamicBody::setDefaultDynamicParameters | ( | ) |
void DynamicBody::setDefaultViewingParameters | ( | ) | [virtual] |
void DynamicBody::setDynamicsFlag | ( | ) | [inline] |
void DynamicBody::setDynJoint | ( | DynJoint * | dj | ) | [virtual] |
void DynamicBody::setInertiaMatrix | ( | const double * | newI | ) |
void DynamicBody::setMass | ( | double | m | ) | [inline] |
void DynamicBody::setMaxRadius | ( | double | maxRad | ) |
bool DynamicBody::setPos | ( | const double * | new_q | ) |
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.
void DynamicBody::setUseDynamics | ( | bool | dyn | ) | [inline] |
void DynamicBody::setVelocity | ( | double * | new_v | ) | [inline] |
void DynamicBody::showAxes | ( | bool | on | ) |
void DynamicBody::showDynContactForces | ( | bool | on | ) |
void DynamicBody::unfix | ( | ) |
double DynamicBody::a[6] [protected] |
vec3 DynamicBody::bbox_max [protected] |
vec3 DynamicBody::bbox_min [protected] |
position DynamicBody::CoG [protected] |
double DynamicBody::defaultMass = 300.0 [static] |
bool DynamicBody::dynamicsComputedFlag [protected] |
DynJoint* DynamicBody::dynJoint [protected] |
double DynamicBody::extWrenchAcc[6] [protected] |
double DynamicBody::Fa [private] |
double DynamicBody::Faa [private] |
double DynamicBody::Faaa [private] |
double DynamicBody::Faab [private] |
double DynamicBody::Fb [private] |
double DynamicBody::Fbb [private] |
double DynamicBody::Fbbb [private] |
double DynamicBody::Fbbc [private] |
double DynamicBody::Fc [private] |
double DynamicBody::Fcc [private] |
double DynamicBody::Fcca [private] |
double DynamicBody::Fccc [private] |
bool DynamicBody::fixed [protected] |
transf DynamicBody::fixedTran [protected] |
double DynamicBody::I[9] [protected] |
double DynamicBody::markedQ[7] [protected] |
double DynamicBody::markedV[6] [protected] |
double DynamicBody::mass [protected] |
double DynamicBody::maxRadius [protected] |
double DynamicBody::P1 [private] |
double DynamicBody::Pa [private] |
double DynamicBody::Paa [private] |
double DynamicBody::Paaa [private] |
double DynamicBody::Paab [private] |
double DynamicBody::Pab [private] |
double DynamicBody::Pabb [private] |
double DynamicBody::Pb [private] |
double DynamicBody::Pbb [private] |
double DynamicBody::Pbbb [private] |
double DynamicBody::q[7] [protected] |
std::list<double*> DynamicBody::qStack [protected] |
bool DynamicBody::showAx [protected] |
bool DynamicBody::showDynCF [protected] |
bool DynamicBody::useDynamics [private] |
double DynamicBody::v[6] [protected] |
std::list<double*> DynamicBody::vStack [protected] |