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

class joint

joint - a connection between links.

Inheritance:


Public Fields

[more]link* l0
the two links connected by the joint.
[more]tmatrix xform
l1->pose = l0->pose*xform
[more]jointType type
the type of joint
[more]mechanism* mech
the mechanism to which the joint belongs
[more]tmatrix bframe0
the coordinate frame on l0
[more]tmatrix bframe1
the coordinate frame on l1
[more]svalCreationCallback svCallback
a callback for creating specialized dynamic equations
[more]triple origin
the origin of the joint
[more]triple* axis
an array of triples, one per DOF, indicating the joint axes
[more]int sense
the sense of the joint; 1 = normal, 0 = swapped frames
[more]char* limits
when allocated, limit[i] indicates whether the ith DOF has limits
[more]vector min
joint limits; min(i) and max(i) determine the range of the i'th DOF when limits[i] = 1, and are ignored otherwise
[more]vector pos
the current position of each DOF
[more]vector vel
the current velocity of each DOF
[more]vector vtol
a velocity tolerance for each DOF; velocity < vtol considered to be 0
[more]vector prevVel
the previous velocity of each DOF; reserved
[more]int checkSignChanges
determines whether velocity zero crossings should be detected.
[more] dynamic properties.
[more] bookkeeping members - these should not be changed by users
[more] dynamic equations

Public Methods

[more]virtual const double* getCoefficients(int i)
returns the dynamic equation coefficients for the i'th DOF
[more]inline virtual int dim(void) const
returns dimension (or number of DOFs) of the joint
[more]inline virtual int isJoint(void)
returns 1 for joints, 0 for connectors
[more]virtual int setLock(int jdim, int newStatus)
locks or unlocks the indicated DOF
[more]inline virtual int isLocked(int jdim) const
returns 1 if the indicated DOF is locked, or 0 if not
[more]virtual const char* typeName(void) const
returns a string containing name the joint's type
[more]inline int useLimits(int i)
returns 1 if the indicated DOF has limits
[more]int enforceLimits(int &modified)
kinematically enforces joint limits.
[more]virtual int computeJacobian(const triple &worldPt, matrix &J, int rowOffset, int columnOffset)
computes the joint's effect on the given world point
[more]virtual int computeAppliedForce(int jdim, double jointForce, int whichLink, triple &f, triple &n, triple &pt)
Computes the force, torque, and point of application for a joint-space force.
[more]inline int hasSignChanges(void) const
returns 1 if any DOFs have changed velocity
[more]virtual void printDynamics(int printValue) const
prints the dynamic equations.
[more]inline double& torque(int jdim)
returns the torque of the indicated DOF, taken from mech->T
[more]inline double torque(int jdim) const
returns the torque of the indicated DOF, taken from mech->T
[more]inline double& acc(int jdim)
returns the torque of the indicated DOF, taken from mech->T
[more]inline double acc(int jdim) const
returns the torque of the indicated DOF, taken from mech->T
[more]inline void saveSignState(void)
copies vel to prevVel, enabling checking for zero crossings

Public Members

[more]enum jointType
indicates joint type:
  • FIXED - the two links are rigidly attached.


Inherited from connection:

Public Fields

osynObject* owner
oint id
oconnector* c0
otriple fc
otriple nc


Documentation

joint - a connection between links. Links in a mechanism are connected by joints. Joints are usually movable, so that links may move relative to one others; however, to allow mechanism to split and joint without breaking individual links, a fixed joint can also be used to attach two links.

Joints are a subclass of connection, and are significantly more complex: they can create dynamic equations arising from their motion; can compute the relative pose between links based on the joint position variables; contain compute a jacobian, transforming joint to cartesian velocity; and have properties such as dry friction, viscous friction, and inertia for each degree of freedom, used for computing the equations of motion for a mechanism.

Joints may have any number of degrees of freedom (DOFs), but the number of DOFs cannot change over time. (Well, it can, but I won't guaruntee things will work right.) There are several built-in joint types: fixed, prismatic, revolute, planar, and other. (Naturally, 'other' joints don't do a whole lot right now.) Prismatic joints cause a translation along the joint's z axis, while revolute joints cause a rotation about z. planar joints rotate about z and translate along x and y, while fixed joints do nothing at all. joints may have limits along each degree of freedom, as indicated by the limits[], min, and max members.

Many members of the joint class are exposed for use by user programs; however, most of these should not actually be changed by users.

As with connections, the new operator should always be used to create joints and the joints will be deleted by one of the parts they're connected to, so the user doesn't need to retain a pointer to the joint for memory management purposes.

oenum jointType
indicates joint type:

olink* l0
the two links connected by the joint. l0 is the parent of l1; l1 is connected to l0 by l1->parentJoint, which is this.

otmatrix xform
l1->pose = l0->pose*xform

ojointType type
the type of joint

omechanism* mech
the mechanism to which the joint belongs

otmatrix bframe0
the coordinate frame on l0

otmatrix bframe1
the coordinate frame on l1

osvalCreationCallback svCallback
a callback for creating specialized dynamic equations

otriple origin
the origin of the joint

otriple* axis
an array of triples, one per DOF, indicating the joint axes

oint sense
the sense of the joint; 1 = normal, 0 = swapped frames

ochar* limits
when allocated, limit[i] indicates whether the ith DOF has limits

ovector min
joint limits; min(i) and max(i) determine the range of the i'th DOF when limits[i] = 1, and are ignored otherwise

ovector pos
the current position of each DOF

ovector vel
the current velocity of each DOF

ovector vtol
a velocity tolerance for each DOF; velocity < vtol considered to be 0

ovector prevVel
the previous velocity of each DOF; reserved

oint checkSignChanges
determines whether velocity zero crossings should be detected. This is useful for improving stability when velocity-proportional joint torques are being applied.

o dynamic properties.
These variables are incorporated into a joint's dynamic equations, and thus must be set before createEquations() is called. For reference, createEquations() is called by mechanism::createEquations(), which in turn is called (eventually) by dynamicSystem::stepForward. So, make sure these variables are set before taking the first simulation time step.

ovector inertia
the actuator inertia for each DOF; < 0 -> disabled. affects joint torque by adding inertia(i)*acceleration(i).

ovector dryFriction
dry (sliding) friction; < 0 -> disabled. the dry frictional force for the i'th DOF is dryFriction(i)*sgn(vel(i)).

ovector viscousFriction
viscous friction; < 0 -> disabled. the viscous frictional force for the i'th DOF is viscousFriction(i)*vel(i).

ovector friction
summed dry + viscous friction; used internally

o bookkeeping members - these should not be changed by users

oint offset
starting offset in dyn. eqns

oint idx
position in mechanism's list of joints

oint ownerIdx
index for owner's use

ochar matrixCurrent
indicates whether the joint's matrix is updated

o dynamic equations
don't mess with these unless you really know what you're doing or are interested in wacky results.

osvScalarResult** torqueS
an array of svals for joint torque equations. the coefficients of torqueS[i] go into the (i+offset) row of the mechanism's M and V matrices, respectively.

osvScalar** accS
an array of svals for joint acceleration variables. accS[i] represents the (i+offset) entry in the mechanism's acceleration vector.

osvTripleResult* f
the force applied by the joint, from l0 to l1

osvTripleResult* n
the moment applied by the joint, from l0 to l1

otriple p
vector from previous joint origin to this one

otriple pc
vector from the joint origin to l1's com

otriple vDotTerms
various inertial terms for vDot

otriple omegaDotTerms
various inertial terms for omegaDot

otriple vcDotTerms
various inertial terms for vcDot

ovirtual const double* getCoefficients(int i)
returns the dynamic equation coefficients for the i'th DOF

oinline virtual int dim(void) const
returns dimension (or number of DOFs) of the joint

oinline virtual int isJoint(void)
returns 1 for joints, 0 for connectors

ovirtual int setLock(int jdim, int newStatus)
locks or unlocks the indicated DOF

oinline virtual int isLocked(int jdim) const
returns 1 if the indicated DOF is locked, or 0 if not

ovirtual const char* typeName(void) const
returns a string containing name the joint's type

oinline int useLimits(int i)
returns 1 if the indicated DOF has limits

oint enforceLimits(int &modified)
kinematically enforces joint limits. This method should only be used with kinematic simulation. Returns the number of DOFs that were modified in 'modified'

ovirtual int computeJacobian(const triple &worldPt, matrix &J, int rowOffset, int columnOffset)
computes the joint's effect on the given world point

ovirtual int computeAppliedForce(int jdim, double jointForce, int whichLink, triple &f, triple &n, triple &pt)
Computes the force, torque, and point of application for a joint-space force. jdim is the dimension of the joint along which jointForce is applied, while whichLink indicates which link of the joint the user is interested in. The force applied by the joint is returned in f, the moment in n, and the point of application in pt.

oinline int hasSignChanges(void) const
returns 1 if any DOFs have changed velocity

ovirtual void printDynamics(int printValue) const
prints the dynamic equations. if printValue is 1, then the equations' numeric values will be printed; otherwise, more symbolic information is displayed

oinline double& torque(int jdim)
returns the torque of the indicated DOF, taken from mech->T

oinline double torque(int jdim) const
returns the torque of the indicated DOF, taken from mech->T

oinline double& acc(int jdim)
returns the torque of the indicated DOF, taken from mech->T

oinline double acc(int jdim) const
returns the torque of the indicated DOF, taken from mech->T

oinline void saveSignState(void)
copies vel to prevVel, enabling checking for zero crossings


This class has no child classes.
Friends:
link
mechanism
dynamicSystem
assembly

Alphabetic index HTML hierarchy of classes or Java



This page was generated with the help of DOC++.