In file /home/blah/darwin2k/src/dyno/mechanism/dyno.h:

class link

The link class represents rigid bodies, either freely-moving or part of a mechanism.

Inheritance:


Public Fields

[more] State variables
[more] Mass properties
[more] Joint/mechanism relations
[more] Lists
[more] Dynamics-related members
[more] Miscellaneous members

Public Methods

[more] link(void)
constructor
[more] ~link(void)
destructor
[more] Geometry-related methods
[more] Dynamics and force/moment
[more] Coordinate transformation
[more] convenience functions


Inherited from synObject:

Public Fields

ostatic int staticClassID
oint objectID
oint verboseLevel

Public Methods

ovirtual const char* className(void) const
ovirtual synObject* copy(void) const
ovirtual int isOfType(int typeNum, int derivedOk)
ostatic int setStaticClassID(void)
ovirtual 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.
o State variables

otriple x
the world-space location of the link's center of mass

oquaternion Q
the orientation of the link

omatrix r
the orientation of the link as a 3x3 rotation matrix; corresponds to Q

otriple v
the current velocity of the link's center of mass

otriple omega
the current angular velocity of the link

o Mass properties

omatrix Ibody
the body-space inertia matrix for the link

omatrix IbodyInv
the inverse of Ibody

otriple com
the link's center-of-mass, in link coordinates

omatrix I
the link's world-space inertia matrix

omatrix Iinv
the inverse of the link's world-space inertia matrix

odouble mass
the mass of the link

o Joint/mechanism relations

otmatrix toParent
a matrix converting from the link's coordinate system to its parent's

oint idx
the index of the link in the mechanism's list of links

olink* parent
the parent link

ojoint* parentJoint
the joint connecting the link to its parent; NULL if the link is a root

omechanism* mech
the mechanism of which the link is a part

o Lists

optrList* children
list of child links

optrList* parts
list of parts composing the link

optrList* joints
list of joints (including parentJoint) connected to the link

optrList* mpolyList
mpolys representing the physical form of the link

optrList* bpolyList
mpolys used for collision detection

optrList* dpolyList
mpolys used for display

optrList* msegs
a list of ownerSegments for the link

optrList* frecs
linkForceRecords

o Dynamics-related members

osvTripleResult* FS
the sum of inertial forces and forces applied to child links

osvTripleResult* NS
the sum of inertial moments and moments applied to child links

osvTripleResult* vcDotS
the acceleration of the link's center of mass

osvTripleResult* vDotS
the acceleration of the link's parent joint

osvTripleResult* omegaDotS
the angular acceleration of the link

otriple inertialGunk
other terms that don't depend on acceleration

o Miscellaneous members

oconst char* name
an optional name for the link; may be NULL

ocdBody* cdb
an object used for collision detection

o link(void)
constructor

o ~link(void)
destructor

o Geometry-related methods

oint addMPoly(mpoly* mp, mpolyType whichType = DEFAULT)
adds an mpoly of the indicated type; normally called by an assembly

oint 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

oint processPolyGeometry(void)
computes surface normals and inertial properties

o Dynamics and force/moment
methods

oinline 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.

oinline 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.)

oinline 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.

oinline 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.

oinline triple getFext(void) const
returns the resultant of external forces applied to the link

oinline triple getNext(void) const
returns the resultant of external moments applied to the link

oint computeConnectionForces(void)
computes internal forces at each connection between parts

oint printDynamics(int printValue) const
prints the dynamic equations for the link

ovoid printDynamicsFlags(void) const
prints the flags for s-val dynamic equations

o Coordinate transformation

ovoid getOriginPose(tmatrix &m)
returns the pose of the link's origin in m

oinline triple T(const triple &pt)
transforms pt from link to world coordinates

oinline triple Tinv(const triple &pt)
transforms pt from world to link coordinates

oinline triple Tdot(const triple &pt)
returns the world-space velocity of the point (which is in link coords)

oinline triple Tdir(const triple &dir)
transforms a direction vector from link to world coordinates

o convenience functions

oinline int numParts(void) const
returns the number of parts

oinline int numChildren(void) const
returns the number of children

oinline int numJoints(void) const
returns the number of joints

oinline int numSegments(void) const
returns the number of segments

oinline int numPolys(void) const
returns the number of mpolys

oinline part* getPart(int i)
returns the i'th part

oinline joint* getJoint(int i)
returns the i'th joint

oinline link* getChild(int i)
returns the i'th child link

oinline mpoly* getMPoly(int i)
returns the i'th mpoly

oinline mpoly* getBPoly(int i)
returns the i'th bounding poly

oinline mpoly* getDPoly(int i)
returns the i'th display poly

oinline 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++.