DOF Class Reference

A single degree of freedom in a robot. More...

#include <dof.h>

Inheritance diagram for DOF:
Inheritance graph
[legend]

List of all members.

Public Types

enum  Type { RIGID, BREAKAWAY, COMPLIANT }

Public Member Functions

virtual bool accumulateMove (double q1, double *jointVals, int *stoppedJoints)=0
void addToTrajectory (double *traj, int numPts)
virtual void buildDynamicCouplingConstraints (std::map< Body *, int > &islandIndices, int numBodies, double *Nu, double *eps, int &ncn)=0
 Computes the dynamic constraints that ensure that the coupling of this DOF is respected.
virtual void buildDynamicLimitConstraints (std::map< Body *, int > &islandIndices, int numBodies, double *H, double *g, int &hcn)=0
 Computes the dynamic constraints that prevent this DOF from exceeding its range.
virtual void callController (double timeStep)
 Does the bookkeeping and calls an appropriate controller to set the force on the DOF.
virtual bool computeStaticJointTorques (double *jointTorques, double dofForce=-1)=0
 DOF (const DOF *original)
 This copy constructor only copies some of the fields; use with care.
 DOF ()
 Initializes everything to zero.
virtual bool dynamicsProgress ()
 Returns true if this DOF is still progrssing towards its dynamic target.
double getActualVelocity () const
double getDefaultVelocity () const
double getDesiredForce () const
double getDesiredPos () const
double getDesiredVelocity () const
int getDOFNum () const
float getDraggerScale () const
double getExtForce () const
double getForce () const
virtual void getJointValues (double *jointVals) const =0
double getMax () const
double getMaxAccel () const
double getMaxForce () const
double getMin () const
virtual int getNumCouplingConstraints ()=0
 Returns the number of dynamic coupling constraints this DOF needs.
virtual int getNumLimitConstraints ()=0
 Returns the number of limit constraints that this DOF needs.
virtual double getSaveVal () const
 Get a value of this DOF that is later used to restore the state.
double getSetPoint () const
virtual double getStaticRatio (Joint *j) const =0
virtual Type getType () const =0
 Returns the type of this DOF.
double getVal () const
virtual void initDOF (Robot *myRobot, const std::list< Joint * > &jList)
 Initializes a DOF based on a list of joints it controls.
virtual double PDPositionController (double timeStep)
 Calls the PD controller which will set the appropriate force on this DOF.
virtual bool readFromStream (QTextStream &stream)
virtual bool readParametersFromXml (const TiXmlElement *root)
virtual void reset ()=0
 Resets the DOF. This is a fairly abstract concept, see implementations for details.
void setDefaultVelocity (double v)
void setDesiredPos (double p)
void setDesiredVelocity (double v)
virtual void setForce (double f)=0
void setTrajectory (double *traj, int numPts)
virtual void updateFromJointValues (const double *jointVals=NULL)=0
void updateMinMax ()
 Sets the max and min vals of the DOF from the smallest range of the joint limits.
void updateSetPoint ()
virtual void updateVal (double q1)=0
virtual bool writeToStream (QTextStream &stream)
virtual ~DOF ()
 Stub destructor.

Protected Attributes

double actualVelocity
int currTrajPt
 Index of the current set point within the trajectory vector.
double defaultVelocity
double desiredq
 The desired value.
double desiredVelocity
int dofNum
 The number of this DOF within the robot definition.
double draggerScale
 How large we want the UI dragger for this DOF to be.
double extForce
 The sum of external forces acting on the this DOF.
double force
 The current force acting on this DOF.
std::list< Joint * > jointList
 List of robot joints that are connected to this DOF.
double Kp
 Proportional gain used for PD controller.
double Kv
 Derivative gain used for PD controller.
double maxAccel
double maxForce
 The maximum force this DOF can exert.
double maxq
 Tha maximum allowable value.
double mDynStartTime
 The world time when the current desired trajectory was set.
std::list< double > mErrorHistory
 The dynamics error over the last dynamics steps; most recent is first.
std::list< double > mForceHistory
 The force applied to this dof over the last step.
int mHistoryMaxSize
 The max number of error values remembered.
double minq
 The minimum allowable value.
std::list< double > mPositionHistory
 The position of this dof over the last steps.
std::list< double > mVelocityHistory
 The velocity of the dof over the last steps.
Robotowner
 The robot that this DOF is a part of.
double q
 The current value of this DOF.
double setPoint
 The current trajectory set point.
std::vector< double > trajectory
 A vector of set points.

Friends

class Robot

Detailed Description

A single degree of freedom in a robot.

The best way to think about a DOF is as a motor, connected to one or multiple joints by some transmission type. It is the only way that an external user has at his disposal to change the joint positions of a robot. A single DOF must be connected to at least one joint, but can be connected to multiple joints as well. Currently though each joint can only be connected to a single DOF.

Each DOF has a value associated with it (which usually translates directly to a joint angle), limits on that value, a velocity, and a generalized force acting on it. The simplest type of DOF has a 1-to-1 relationship with a joint and can be considered as a motor that only affects that joint. In this case, the DOF value will be equal to the joint value, and the dof limits equal to the joint limits.

More complex DOF's are connected to multiple joints. In this case, depending on how the connection is done, different DOF's behave differently. This is the reason for having a hierarchy of different DOF types. The main difference is what happens when a joint from one DOF is stopped due to contact: how are the other joints of the same DOF affected? See implementations of the DOF interface for details.

In static mode, the desired value of the DOF can be set directly, and then the DOF itself will tell you what joint values result from that value. In dynamics, the only way to go is to apply a force to a DOF and let the dynamic engine compute body motions in response. The DOF can also simulate controllers to create desired joint motion, although simulating better DOF controllers would be needed.

Definition at line 71 of file dof.h.


Member Enumeration Documentation

enum DOF::Type
Enumerator:
RIGID 
BREAKAWAY 
COMPLIANT 

Definition at line 75 of file dof.h.


Constructor & Destructor Documentation

DOF::DOF (  ) 

Initializes everything to zero.

Definition at line 40 of file dof.cpp.

DOF::DOF ( const DOF original  ) 

This copy constructor only copies some of the fields; use with care.

This copy constructor only copies the paramters of the DOF, but none of its dynamic state or the joints or robot. Use initDOF(), like you would with a regularly contructed DOF, to assign joints to it.

Definition at line 51 of file dof.cpp.

virtual DOF::~DOF (  )  [inline, virtual]

Stub destructor.

Definition at line 156 of file dof.h.


Member Function Documentation

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

Computes the values of the joints controlled by this DOF for the case where the DOF value was set to q1. The vector jointVals lists all the joints of the owning robot, but this function only affects the values for those joints controlled by this DOF. stoppedJoints is a binary vector that has information about what joints are stopped (presumably due to some contact). The DOF can take that into account. This vector also has an entry for each joint in the owning robot.

Implemented in RigidDOF, BreakAwayDOF, and CompliantDOF.

void DOF::addToTrajectory ( double *  traj,
int  numPts 
)

Adds numPts values to the current trajectory.

Definition at line 154 of file dof.cpp.

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

Computes the dynamic constraints that ensure that the coupling of this DOF is respected.

Implemented in RigidDOF, and CompliantDOF.

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

Computes the dynamic constraints that prevent this DOF from exceeding its range.

Implemented in RigidDOF, and CompliantDOF.

void DOF::callController ( double  timeStep  )  [virtual]

Does the bookkeeping and calls an appropriate controller to set the force on the DOF.

This wraps the controller call so we can have different types of DOF's call different controllers if we want to.

Definition at line 166 of file dof.cpp.

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

Computes the static forces that are applied at each joint for a given level of DOF force If dofForce is negative, it computes instead the joint forces that have to be applied just to keep the joints in the given position. This is relevant in the case of coupled and compliant dof's.

Implemented in RigidDOF, BreakAwayDOF, and CompliantDOF.

bool DOF::dynamicsProgress (  )  [virtual]

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

Not implemented for the general case. This is a more difficult feature than originally thought. What is a good test of whether dynamic progress has stopped?

Reimplemented in CompliantDOF.

Definition at line 242 of file dof.cpp.

double DOF::getActualVelocity (  )  const [inline]

Returns the actual velocity.

Definition at line 239 of file dof.h.

double DOF::getDefaultVelocity (  )  const [inline]

Returns the default velocity.

Definition at line 237 of file dof.h.

double DOF::getDesiredForce (  )  const [inline]

Returns the desired (target) level of force to be applied to this DOF

Definition at line 245 of file dof.h.

double DOF::getDesiredPos (  )  const [inline]

Definition at line 255 of file dof.h.

double DOF::getDesiredVelocity (  )  const [inline]

Returns the desired velocity.

Definition at line 235 of file dof.h.

int DOF::getDOFNum (  )  const [inline]

Returns the number of this DOF within the robot definition.

Definition at line 228 of file dof.h.

float DOF::getDraggerScale (  )  const [inline]

Returns the dragger scale for this DOF

Definition at line 251 of file dof.h.

double DOF::getExtForce (  )  const [inline]

Returns the sum of all external forces applied to this DOF

Definition at line 249 of file dof.h.

double DOF::getForce (  )  const [inline]

Returns the current force acting on the DOF.

Definition at line 243 of file dof.h.

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

Gets the values of the joints for the current position of the DOF. Does no checking whatsoever

Implemented in RigidDOF, BreakAwayDOF, and CompliantDOF.

double DOF::getMax (  )  const [inline]

Returns the maximum allowable value.

Definition at line 230 of file dof.h.

double DOF::getMaxAccel (  )  const [inline]

Returns the max. acceleration

Definition at line 241 of file dof.h.

double DOF::getMaxForce (  )  const [inline]

Returns the maximum force that can be applied by this DOF (think torque limit).

Definition at line 247 of file dof.h.

double DOF::getMin (  )  const [inline]

Returns the minimum allowable value.

Definition at line 232 of file dof.h.

virtual int DOF::getNumCouplingConstraints (  )  [pure virtual]

Returns the number of dynamic coupling constraints this DOF needs.

Implemented in RigidDOF, and CompliantDOF.

virtual int DOF::getNumLimitConstraints (  )  [pure virtual]

Returns the number of limit constraints that this DOF needs.

Implemented in RigidDOF, and CompliantDOF.

virtual double DOF::getSaveVal (  )  const [inline, virtual]

Get a value of this DOF that is later used to restore the state.

See Robot::storeDOFVals(...) for more details on why this was needed.

Reimplemented in BreakAwayDOF.

Definition at line 226 of file dof.h.

double DOF::getSetPoint (  )  const [inline]

Returns the current trajectory set point.

Definition at line 254 of file dof.h.

virtual double DOF::getStaticRatio ( Joint j  )  const [pure virtual]

Returns the ratio of joint j to this dof when static computations are performed

Implemented in RigidDOF, and CompliantDOF.

virtual Type DOF::getType (  )  const [pure virtual]

Returns the type of this DOF.

Implemented in RigidDOF, BreakAwayDOF, and CompliantDOF.

double DOF::getVal (  )  const [inline]

Returns the current value.

Definition at line 223 of file dof.h.

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

Initializes a DOF based on a list of joints it controls.

Initializes a DOF by giving it the owning robot myRobot, and the list of joints connected to this DOF, jList. Also sets the max and min vals of the DOF from the smallest range of the joint limits.

Reimplemented in BreakAwayDOF, and CompliantDOF.

Definition at line 83 of file dof.cpp.

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

Calls the PD controller which will set the appropriate force on this DOF.

Updates the error between the current DOF value and its setpoint and uses this along with the rate of change of the error (first-order approx) to compute a force that should be applied to the DOF to correct the error. The gains for this controller are read from the robot configuration file.

Reimplemented in CompliantDOF.

Definition at line 215 of file dof.cpp.

bool DOF::readFromStream ( QTextStream &  stream  )  [virtual]

Reads the state of this DOF from a stream

Read in the value (or for more complex dof's the complete state) of this dof from a stream.

Reimplemented in BreakAwayDOF.

Definition at line 281 of file dof.cpp.

bool DOF::readParametersFromXml ( const TiXmlElement root  )  [virtual]

Reads in the force parameters from XML

Reads the parameters (not the value) of this DOF from XML. Used when reading robot configuration files, where we want to define a DOF, not set a particular value.

Reimplemented in BreakAwayDOF.

Definition at line 252 of file dof.cpp.

virtual void DOF::reset (  )  [pure virtual]

Resets the DOF. This is a fairly abstract concept, see implementations for details.

Implemented in RigidDOF, BreakAwayDOF, and CompliantDOF.

void DOF::setDefaultVelocity ( double  v  )  [inline]

Definition at line 259 of file dof.h.

void DOF::setDesiredPos ( double  p  )  [inline]

Definition at line 257 of file dof.h.

void DOF::setDesiredVelocity ( double  v  )  [inline]

Definition at line 258 of file dof.h.

virtual void DOF::setForce ( double  f  )  [pure virtual]

Sets the motor force applied on this DOF

Implemented in RigidDOF, and CompliantDOF.

void DOF::setTrajectory ( double *  traj,
int  numPts 
)

Given an array of DOF values, and the length of the array, this clears the current trajectory and sets the trajectory to the given values.

Definition at line 136 of file dof.cpp.

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

Attempts to compute the value of the DOF based on the values of the controlled joints. jointVals lists the joint values to be used. If NULL, the current joint values as reported by the joints themselves are used

Implemented in RigidDOF, BreakAwayDOF, and CompliantDOF.

void DOF::updateMinMax (  ) 

Sets the max and min vals of the DOF from the smallest range of the joint limits.

Definition at line 92 of file dof.cpp.

void DOF::updateSetPoint (  ) 

If a trajectory exists, this increments the currTrajPt counter, and makes the setPoint the next point of the trajectory. Otherwise, it makes the setPoint the current desired value. The setPoint is used by the PD controller to determine the proper force to apply to this DOF.

Definition at line 119 of file dof.cpp.

virtual void DOF::updateVal ( double  q1  )  [pure virtual]

Informs the dof that the robot has set joint values according to the given DOF value. This typically happens due to some interpolation in joint value space

Implemented in RigidDOF, BreakAwayDOF, and CompliantDOF.

bool DOF::writeToStream ( QTextStream &  stream  )  [virtual]

Writes the state of this DOF to a stream in the format that readFromStream() can read in

Write the value, or the overall state, of this DOF to a stream. Used for saving the posture of a robot, either to a variable or to a file.

Reimplemented in BreakAwayDOF.

Definition at line 271 of file dof.cpp.


Friends And Related Function Documentation

friend class Robot [friend]

Definition at line 72 of file dof.h.


Member Data Documentation

double DOF::actualVelocity [protected]

Definition at line 101 of file dof.h.

int DOF::currTrajPt [protected]

Index of the current set point within the trajectory vector.

Definition at line 141 of file dof.h.

double DOF::defaultVelocity [protected]

Definition at line 100 of file dof.h.

double DOF::desiredq [protected]

The desired value.

Definition at line 94 of file dof.h.

double DOF::desiredVelocity [protected]

Definition at line 99 of file dof.h.

int DOF::dofNum [protected]

The number of this DOF within the robot definition.

Definition at line 82 of file dof.h.

double DOF::draggerScale [protected]

How large we want the UI dragger for this DOF to be.

Definition at line 147 of file dof.h.

double DOF::extForce [protected]

The sum of external forces acting on the this DOF.

Definition at line 111 of file dof.h.

double DOF::force [protected]

The current force acting on this DOF.

Definition at line 105 of file dof.h.

std::list<Joint *> DOF::jointList [protected]

List of robot joints that are connected to this DOF.

Definition at line 144 of file dof.h.

double DOF::Kp [protected]

Proportional gain used for PD controller.

Definition at line 117 of file dof.h.

double DOF::Kv [protected]

Derivative gain used for PD controller.

Definition at line 114 of file dof.h.

double DOF::maxAccel [protected]

Definition at line 102 of file dof.h.

double DOF::maxForce [protected]

The maximum force this DOF can exert.

Definition at line 108 of file dof.h.

double DOF::maxq [protected]

Tha maximum allowable value.

Definition at line 88 of file dof.h.

double DOF::mDynStartTime [protected]

The world time when the current desired trajectory was set.

Definition at line 135 of file dof.h.

std::list<double> DOF::mErrorHistory [protected]

The dynamics error over the last dynamics steps; most recent is first.

Definition at line 120 of file dof.h.

std::list<double> DOF::mForceHistory [protected]

The force applied to this dof over the last step.

Definition at line 129 of file dof.h.

int DOF::mHistoryMaxSize [protected]

The max number of error values remembered.

Definition at line 132 of file dof.h.

double DOF::minq [protected]

The minimum allowable value.

Definition at line 91 of file dof.h.

std::list<double> DOF::mPositionHistory [protected]

The position of this dof over the last steps.

Definition at line 123 of file dof.h.

std::list<double> DOF::mVelocityHistory [protected]

The velocity of the dof over the last steps.

Definition at line 126 of file dof.h.

Robot* DOF::owner [protected]

The robot that this DOF is a part of.

Definition at line 79 of file dof.h.

double DOF::q [protected]

The current value of this DOF.

Definition at line 85 of file dof.h.

double DOF::setPoint [protected]

The current trajectory set point.

Definition at line 97 of file dof.h.

std::vector<double> DOF::trajectory [protected]

A vector of set points.

Definition at line 138 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