DynJoint Class Reference

The parent class for each of the joint modules used in the dynamics. More...

#include <dynJoint.h>

Inheritance diagram for DynJoint:
Inheritance graph
[legend]

List of all members.

Public Types

enum  DynamicJointT {
  FIXED, REVOLUTE, UNIVERSAL, BALL,
  PRISMATIC
}

Public Member Functions

virtual void buildConstraints (double *Nu, double *eps, int numBodies, std::map< Body *, int > &islandIndices, int &ncn)
 DynJoint (DynamicBody *pLink, DynamicBody *nLink, const transf &pFrame, const transf &nFrame)
virtual void getConstraints (char *c)=0
 Fills in a array of binary chars showing what constraints are enforced by this joint.
DynamicBodygetNextLink () const
virtual transf getNextTrans ()=0
virtual int getNumConstraints ()=0
DynamicBodygetPrevLink () const
virtual transf getPrevTrans ()=0
virtual DynamicJointT getType ()=0
 Returns the type of this dynamic joint.
void jacobian (transf toTarget, Matrix *J, bool worldCoords)
 Computes the 6x6 Jacobian of this joint wrt to a point.
virtual void updateValues ()=0

Protected Attributes

transf nextFrame
 The position and orientation of the end frame of the succeeding link.
DynamicBodynextLink
 The link succeeding this joint in the kinematic chain.
transf prevFrame
 The position and orientation of the end frame of the preceding link.
DynamicBodyprevLink
 The link preceding this joint in the kinematic chain, could be NULL if joint is connected to the world space.

Detailed Description

The parent class for each of the joint modules used in the dynamics.

A dynamic joint is different from a regular Joint in that it is not restricted to a single degree of freedom of motion. A regular Joint defines a single rotation, around 1 axis, or a single translation. In contrast, a dynamic joint can alow motion along anything between 0 and 6 of the degrees of freedom that are possible between two bodies in general. The 6 degrees of freedom that are possible between two bodies are rotations around the 3 axes and translations around the 3 axes. Note that here we use the term "degree of freedom" with a different meaning that in the context of a robot DOF. Think of the DynJoint as a "generalized Joint".

The simplest dynamic joint is the fixed one: is prohibits motion along all 6 possible dof's. A revolute joints only allows one rotation around one axis, and fixes the other 5 dofs. A universall joint allows two rotations, a ball joint three, etc.

In GraspIt, dynamic joints are usually made up of the regular joints that they correspond to. For example, a revolute dynamic joint will correspond to a single regular Joint in the robot. A universall dynamic joint correspdonds to two regular joints, one for each axis of rotation, etc. In the future, it would be nice to remove this dual notion of regular joint / dynamic joint, but that would also mean getting away from defining robots in the D-H notation.

The DynJoint has two main responsabilities: to assemble its own constraints for the dynamic engine, and to update the values of the regular joints it corresponds to after a dynamic step has been taken.

Definition at line 69 of file dynJoint.h.


Member Enumeration Documentation

Enumerator:
FIXED 
REVOLUTE 
UNIVERSAL 
BALL 
PRISMATIC 

Definition at line 71 of file dynJoint.h.


Constructor & Destructor Documentation

DynJoint::DynJoint ( DynamicBody pLink,
DynamicBody nLink,
const transf pFrame,
const transf nFrame 
) [inline]

Initializes the class with pointers and transfroms of the two links connected to this joint.

Definition at line 92 of file dynJoint.h.


Member Function Documentation

void DynJoint::buildConstraints ( double *  Nu,
double *  eps,
int  numBodies,
std::map< Body *, int > &  islandIndices,
int &  ncn 
) [virtual]

Creates the dynamic constraints for this joint. Nu is the joint constraint matrix, eps is the constraint error.

Fills in the constraint columns in the joint constraint matrix Nu . It also computes the generalized position error between the two links or between the one link and the world coordinates it should be fixed to. The errors are copied into the corresponding elements of the eps vector. Nu^T * v = eps.

numBodies are the number of bodies in this dynamic island, and islandIndices is a vector that maps a body to the index of that body within the vector of bodies for this dynamic island. This allows us to compute the starting row numbers for the links connected to this joint. ncn is a counter that holds the current constraint number, thus the current column to use.

Reimplemented in FixedDynJoint.

Definition at line 53 of file dynJoint.cpp.

virtual void DynJoint::getConstraints ( char *  c  )  [pure virtual]

Fills in a array of binary chars showing what constraints are enforced by this joint.

Implemented in FixedDynJoint, RevoluteDynJoint, UniversalDynJoint, and BallDynJoint.

DynamicBody* DynJoint::getNextLink (  )  const [inline]

Returns a pointer to the succeeding link

Definition at line 121 of file dynJoint.h.

virtual transf DynJoint::getNextTrans (  )  [pure virtual]

Returns the transform from the next link to the coordinate system of this joint

Implemented in FixedDynJoint, RevoluteDynJoint, UniversalDynJoint, and BallDynJoint.

virtual int DynJoint::getNumConstraints (  )  [pure virtual]

Returns the number of constrained DOF's for this joint.

Implemented in FixedDynJoint, RevoluteDynJoint, UniversalDynJoint, and BallDynJoint.

DynamicBody* DynJoint::getPrevLink (  )  const [inline]

Returns a pointer to the preceding link

Definition at line 118 of file dynJoint.h.

virtual transf DynJoint::getPrevTrans (  )  [pure virtual]

Returns the transform from the previous link to the coordinate system of this joint

Implemented in FixedDynJoint, RevoluteDynJoint, UniversalDynJoint, and BallDynJoint.

virtual DynamicJointT DynJoint::getType (  )  [pure virtual]

Returns the type of this dynamic joint.

Implemented in FixedDynJoint, RevoluteDynJoint, UniversalDynJoint, and BallDynJoint.

void DynJoint::jacobian ( transf  toTarget,
Matrix J,
bool  worldCoords 
)

Computes the 6x6 Jacobian of this joint wrt to a point.

Given a point that has world transform toTarget, this computes the 6x6 Jacobian of this joint relative to that point. The Jacobian is either expressed in global world coordinates or in the local coordinates of the target.

Definition at line 153 of file dynJoint.cpp.

virtual void DynJoint::updateValues (  )  [pure virtual]

Update the joint values from the current position of the connected links.

Implemented in FixedDynJoint, RevoluteDynJoint, UniversalDynJoint, and BallDynJoint.


Member Data Documentation

The position and orientation of the end frame of the succeeding link.

Definition at line 84 of file dynJoint.h.

The link succeeding this joint in the kinematic chain.

Definition at line 78 of file dynJoint.h.

The position and orientation of the end frame of the preceding link.

Definition at line 81 of file dynJoint.h.

The link preceding this joint in the kinematic chain, could be NULL if joint is connected to the world space.

Definition at line 75 of file dynJoint.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