CompliantDOF Class Reference

#include <dof.h>

Inheritance diagram for CompliantDOF:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual bool accumulateMove (double q1, double *jointVals, int *stoppedJoints)
 Distal joints are unaffected by proximal joints.
virtual void buildDynamicCouplingConstraints (std::map< Body *, int > &, int, double *, double *, int &)
 No dynamic coupling constraints, all joint forces are set explicitly.
virtual void buildDynamicLimitConstraints (std::map< Body *, int > &islandIndices, int numBodies, double *H, double *g, int &hcn)
 Computes one constraint for each joint that exceeds it range.
 CompliantDOF (CompliantDOF *original)
 CompliantDOF ()
virtual bool computeStaticJointTorques (double *jointTorques, double dofForce=-1)
 Takes joint springs and coupling ratios into account.
virtual bool dynamicsProgress ()
 Returns true if this DOF is still progrssing towards its dynamic target.
virtual void getJointValues (double *jointVals) const
 Returns the values as if no contact were present and links were free.
virtual int getNumCouplingConstraints ()
 No dynamic coupling constraints, all joint forces are set explicitly.
virtual int getNumLimitConstraints ()
 One constraint for each joint that exceeds it range.
virtual double getStaticRatio (Joint *j) const
 Static ratio depends on both coupling ratio and joint spring ratio.
Type getType () const
 Returns the type of this DOF.
virtual void initDOF (Robot *myRobot, const std::list< Joint * > &jList)
 Makes sure all the joints have spring stiffness defined.
virtual double PDPositionController (double timeStep)
 A simple stub for now, always applying max force.
virtual void reset ()
 This DOF is stateless, nothing to reset.
virtual void setForce (double f)
 Explicitly sets force to all joints in the DOF.
virtual void updateFromJointValues (const double *jointVals=NULL)
 This can not always work, as states can be ambigous.
virtual void updateVal (double q1)
 Nothing to keep track of here.

Private Member Functions

double smoothProfileController (double timeStep)
 Attempts to create a smooth profile directly from current and target positions.

Detailed Description

The compliant DOF is modeled after the Harvard Hand. It assumes compliant joints coupled through tendon actuation. As in the Breakaway DOF, if a proximal joint is stopped, distal joints continue to close. However, there is no breakaway mechanism, to joints that are stopped due to contact are always connected to the DOF.

Definition at line 377 of file dof.h.


Constructor & Destructor Documentation

CompliantDOF::CompliantDOF (  )  [inline]

Definition at line 383 of file dof.h.

CompliantDOF::CompliantDOF ( CompliantDOF original  )  [inline]

Definition at line 384 of file dof.h.


Member Function Documentation

bool CompliantDOF::accumulateMove ( double  q1,
double *  jointVals,
int *  stoppedJoints 
) [virtual]

Distal joints are unaffected by proximal joints.

Proximal joints do not affect distal joints, in any direction of movement.

Implements DOF.

Definition at line 796 of file dof.cpp.

virtual void CompliantDOF::buildDynamicCouplingConstraints ( std::map< Body *, int > &  ,
int  ,
double *  ,
double *  ,
int &   
) [inline, virtual]

No dynamic coupling constraints, all joint forces are set explicitly.

Implements DOF.

Definition at line 409 of file dof.h.

void CompliantDOF::buildDynamicLimitConstraints ( std::map< Body *, int > &  islandIndices,
int  numBodies,
double *  H,
double *  g,
int &  hcn 
) [virtual]

Computes one constraint for each joint that exceeds it range.

One constraint for each joint that has exceeded its legal range. For now this duplicates code from the regular DOF, so everything should probably move someplace else.

Implements DOF.

Definition at line 939 of file dof.cpp.

bool CompliantDOF::computeStaticJointTorques ( double *  jointTorques,
double  dofForce = -1 
) [virtual]

Takes joint springs and coupling ratios into account.

We use a linear spring model w. stiffness k for any joint. First we apply the spring force to each joint. Then we say that the dof force must be enough to balance the largest spring force we have found. Therefore, we then apply that dof force to all joints.

Implements DOF.

Definition at line 831 of file dof.cpp.

bool CompliantDOF::dynamicsProgress (  )  [virtual]

Returns true if this DOF is still progrssing towards its dynamic target.

Simply looks at the change in position of this dof. Since it is hard-coded to always apply the max force, no motion always means no progress.

Reimplemented from DOF.

Definition at line 1040 of file dof.cpp.

void CompliantDOF::getJointValues ( double *  jointVals  )  const [virtual]

Returns the values as if no contact were present and links were free.

Implements DOF.

Definition at line 764 of file dof.cpp.

virtual int CompliantDOF::getNumCouplingConstraints (  )  [inline, virtual]

No dynamic coupling constraints, all joint forces are set explicitly.

Implements DOF.

Definition at line 407 of file dof.h.

int CompliantDOF::getNumLimitConstraints (  )  [virtual]

One constraint for each joint that exceeds it range.

We will use one limit constraint for each joint that exceeds is very close to or outside its legal range.

Implements DOF.

Definition at line 923 of file dof.cpp.

double CompliantDOF::getStaticRatio ( Joint j  )  const [virtual]

Static ratio depends on both coupling ratio and joint spring ratio.

Implements DOF.

Definition at line 745 of file dof.cpp.

Type CompliantDOF::getType (  )  const [inline, virtual]

Returns the type of this DOF.

Implements DOF.

Definition at line 385 of file dof.h.

void CompliantDOF::initDOF ( Robot myRobot,
const std::list< Joint * > &  jList 
) [virtual]

Makes sure all the joints have spring stiffness defined.

Reimplemented from DOF.

Definition at line 733 of file dof.cpp.

double CompliantDOF::PDPositionController ( double  timeStep  )  [virtual]

A simple stub for now, always applying max force.

A stub for now. Always applies max force no matter what. For now, the simulation of the Harvard Hand behaves reasonably like this, but in the future this should be fixed.

Reimplemented from DOF.

Definition at line 1028 of file dof.cpp.

virtual void CompliantDOF::reset (  )  [inline, virtual]

This DOF is stateless, nothing to reset.

Implements DOF.

Definition at line 403 of file dof.h.

void CompliantDOF::setForce ( double  f  )  [virtual]

Explicitly sets force to all joints in the DOF.

Implements DOF.

Definition at line 979 of file dof.cpp.

double CompliantDOF::smoothProfileController ( double  timeStep  )  [private]

Attempts to create a smooth profile directly from current and target positions.

Tries to build up the force slowly looking at the time elapsed since the last reset. This is something of a hack, but it's the best I could come up with to avoid jerking the hand around.

Definition at line 1064 of file dof.cpp.

void CompliantDOF::updateFromJointValues ( const double *  jointVals = NULL  )  [virtual]

This can not always work, as states can be ambigous.

Make the assumption that the joint that's most flexed gives the value of the DOF. This doesn't always work. In general, due to the nature of this DOF and the fact that it is implemented as stateless, link positions can be ambiguous, so this function only provides a best effort but no guarantee.

Implements DOF.

Definition at line 778 of file dof.cpp.

virtual void CompliantDOF::updateVal ( double  q1  )  [inline, virtual]

Nothing to keep track of here.

Implements DOF.

Definition at line 395 of file dof.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