In file /home/blah/darwin2k/src/dyno/mechanism/dyno.h: The link class represents rigid bodies, either freely-moving or part of a mechanism.
Inheritance:
Public Fields
-
State variables
-
Mass properties
-
Joint/mechanism relations
-
Lists
-
Dynamics-related members
-
Miscellaneous members
Public Methods
-
link(void)
- constructor
-
~link(void)
- destructor
-
Geometry-related methods
-
Dynamics and force/moment
-
Coordinate transformation
-
convenience functions
Public Fields
-
static int staticClassID
-
int objectID
-
int verboseLevel
Public Methods
-
virtual const char* className(void) const
-
virtual synObject* copy(void) const
-
virtual int isOfType(int typeNum, int derivedOk)
-
static int setStaticClassID(void)
-
virtual int classID(void) const
Documentation
The link class represents rigid bodies, either freely-moving or
part of a mechanism. In a mechanism, links are connected by
joints into a tree structure. Closed-chain mechanisms may be
created by adding further constraints between links.
Links are composed of parts, and can compute their inertial properties
from the list of polyhedra (and their densities) in their parts.
The parts in a link are also connected in a tree, and the root part
of the tree shares the same coordinate system as the link.
State variables
triple x
- the world-space location of the link's center of mass
quaternion Q
- the orientation of the link
matrix r
- the orientation of the link as a 3x3 rotation matrix; corresponds to Q
triple v
- the current velocity of the link's center of mass
triple omega
- the current angular velocity of the link
Mass properties
matrix Ibody
- the body-space inertia matrix for the link
matrix IbodyInv
- the inverse of Ibody
triple com
- the link's center-of-mass, in link coordinates
matrix I
- the link's world-space inertia matrix
matrix Iinv
- the inverse of the link's world-space inertia matrix
double mass
- the mass of the link
Joint/mechanism relations
tmatrix toParent
- a matrix converting from the link's coordinate system to its parent's
int idx
- the index of the link in the mechanism's list of links
link* parent
- the parent link
joint* parentJoint
- the joint connecting the link to its parent; NULL if the link is a root
mechanism* mech
- the mechanism of which the link is a part
Lists
ptrList* children
- list of child links
ptrList* parts
- list of parts composing the link
ptrList* joints
- list of joints (including parentJoint) connected to the link
ptrList* mpolyList
- mpolys representing the physical form of the link
ptrList* bpolyList
- mpolys used for collision detection
ptrList* dpolyList
- mpolys used for display
ptrList* msegs
- a list of ownerSegments for the link
ptrList* frecs
- linkForceRecords
Dynamics-related members
svTripleResult* FS
- the sum of inertial forces and forces applied to child links
svTripleResult* NS
- the sum of inertial moments and moments applied to child links
svTripleResult* vcDotS
- the acceleration of the link's center of mass
svTripleResult* vDotS
- the acceleration of the link's parent joint
svTripleResult* omegaDotS
- the angular acceleration of the link
triple inertialGunk
- other terms that don't depend on acceleration
Miscellaneous members
const char* name
- an optional name for the link; may be NULL
cdBody* cdb
- an object used for collision detection
link(void)
- constructor
~link(void)
- destructor
Geometry-related methods
int addMPoly(mpoly* mp, mpolyType whichType = DEFAULT)
- adds an mpoly of the indicated type; normally called by an assembly
int addMPoly(mpoly* mp, const tmatrix &m, mpolyType whichType = DEFAULT)
- adds an mpoly of the indicated type, transforming first
by m; normally called by an assembly Note: this modifies mp
int processPolyGeometry(void)
- computes surface normals and inertial properties
Dynamics and force/moment
- methods
inline linkForceRecord* addForce(const triple &f, const triple &pt, part* p = NULL)
- adds a force applied at the point pt (in world coordinates) to
Fext, and the corresponding moment to Next.
If mech->recordLinkForces is non-zero, then the linkForceRecord
for the force will be returned so that the caller can modify
it. This is mainly useful when computeConnectionForces() will
be used, and can be completely ignored otherwise.
inline linkForceRecord* addForce(const triple &f, part* p = NULL)
- adds a pure force to the link (applied at the COM)
If mech->recordLinkForces is non-zero, then the linkForceRecord
for the force will be returned so that the caller can modify
it. This is mainly useful when computeConnectionForces() will
be used, and can be completely ignored otherwise.
Note that if p is NULL, then multiple linkForceRecords will be
created to distribute the forces among all link parts, proportional
to part mass. (This is an arbitrary distribution; if a more specific
distribution is desired, then use addForce(triple &force, triple &point,
part *p) instead.)
inline linkForceRecord* addForce(const triple &f, const triple &n, const triple &pt, part* p = NULL)
- adds a force applied at the point pt (in world coordinates) to
Fext, and the sum of n and the corresponding moment to Next.
If mech->recordLinkForces is non-zero, then the linkForceRecord
for the force will be returned so that the caller can modify
it. This is mainly useful when computeConnectionForces() will
be used, and can be completely ignored otherwise.
inline linkForceRecord* addMoment(const triple &n, part* p = NULL)
- adds the supplied moment to Next
If mech->recordLinkForces is non-zero, then the linkForceRecord
for the force will be returned so that the caller can modify
it. This is mainly useful when computeConnectionForces() will
be used, and can be completely ignored otherwise.
inline triple getFext(void) const
- returns the resultant of external forces applied to the link
inline triple getNext(void) const
- returns the resultant of external moments applied to the link
int computeConnectionForces(void)
- computes internal forces at each connection between parts
int printDynamics(int printValue) const
- prints the dynamic equations for the link
void printDynamicsFlags(void) const
- prints the flags for s-val dynamic equations
Coordinate transformation
void getOriginPose(tmatrix &m)
- returns the pose of the link's origin in m
inline triple T(const triple &pt)
- transforms pt from link to world coordinates
inline triple Tinv(const triple &pt)
- transforms pt from world to link coordinates
inline triple Tdot(const triple &pt)
- returns the world-space velocity of the point (which is in link coords)
inline triple Tdir(const triple &dir)
- transforms a direction vector from link to world coordinates
convenience functions
inline int numParts(void) const
- returns the number of parts
inline int numChildren(void) const
- returns the number of children
inline int numJoints(void) const
- returns the number of joints
inline int numSegments(void) const
- returns the number of segments
inline int numPolys(void) const
- returns the number of mpolys
inline part* getPart(int i)
- returns the i'th part
inline joint* getJoint(int i)
- returns the i'th joint
inline link* getChild(int i)
- returns the i'th child link
inline mpoly* getMPoly(int i)
- returns the i'th mpoly
inline mpoly* getBPoly(int i)
- returns the i'th bounding poly
inline mpoly* getDPoly(int i)
- returns the i'th display poly
inline ownerSegment* getOwnerSegment(int i)
- returns the i'th owner segment
- This class has no child classes.
- Friends:
- joint
mechanism
assembly
dynamicSystem
Alphabetic index HTML hierarchy of classes or Java
This page was generated with the help of DOC++.