Robot Class Reference

Base class for all robots which are collections of links connected by moveable joints. More...

#include <robot.h>

Inheritance diagram for Robot:
Inheritance graph
[legend]

List of all members.

Signals

void configurationChanged ()
 This signal informs that dof values have changed.
void moveDOFStepTaken (int numCols, bool &stopRequest)
 Emitted by moveDOFToCOntacts each time a step is taken.
void userInteractionEnd ()
 This signal is the complement of userInteractionStart().
void userInteractionStart ()
 This signal informs that user has begun interaction by clicking on a robot handler.

Public Member Functions

void applyJointPassiveInternalWrenches ()
 Applies internal joint forces (if any), such as friction or joint springs.
void attachRobot (Robot *r, int chainNum, const transf &offsetTr)
 Attaches another robot to the end of a chain of this robot.
void breakContacts ()
 Breaks all the contacts on this robot.
virtual void buildDOFCouplingConstraints (std::map< Body *, int > &islandIndices, int numBodies, double *Nu, double *eps, int &ncn)
 Builds dynamic constraints for all the coupled dof's of this robot.
virtual void buildDOFLimitConstraints (std::map< Body *, int > &islandIndices, int numBodies, double *H, double *g, int &hcn)
 Builds dynamic dof limit constraints for all the dof's of this robot.
bool checkDOFPath (double *desiredVals, double desiredStep)
 Checks if the path between current and a desired posture is free of collisions.
bool checkDOFVals (double *dofVals) const
 Returns true if all specified dof vals are within their respective legal ranges.
bool checkSetDOFVals (double *dofVals) const
 Clamps the given dofVals to be within their respective legal ranges.
virtual void cloneFrom (Robot *original)
 Makes this robot into a clone of the original.
bool contactSlip ()
 Returns true if any of the contacts on the fingers are slipping during dynamics.
virtual bool contactsPreventMotion (const transf &motion) const
 Returns true of contacts on the palm, a link or a parent robot prevent given motion.
void detachRobot (Robot *r)
 Detaches a previously attached robot.
virtual void DOFController (double timeStep)
 Calls the DOF controllers which set dof forces based on current and desired posture.
bool dynamicAutograspComplete ()
 Attempt to check if the dynamic autograsp is complete.
void emitConfigChange ()
 Emits the configuration changed signal.
void emitUserInteractionEnd ()
 Emits the user interaction ended signal.
void emitUserInteractionStart ()
 Emits the user interaction start signal.
void forceDOFVal (int dofNum, double val)
 Sets the given DOF to the given value and updates the link poses. Collisions are NOT checked.
void forceDOFVals (double *dofVals)
 Sets the values of the DOF's to the values in the array dofVals. Collisions are NOT checked.
virtual void fwdKinematics (double *dofVals, std::vector< transf > &trVec, int chainNum)
 Computes the transform of all links in a chain for a given set of dof vals.
void generateCartesianTrajectory (const transf &startTr, const transf &endTr, std::vector< transf > &traj, double startVel, double endVel=0.0, double timeNeeded=-1.0)
 Computes a trajectory that interpolates linearly between a start and end poses.
void getAllAttachedRobots (std::vector< Robot * > &robotVec)
 Returns a vector of all robots attached to this one.
void getAllLinks (std::vector< DynamicBody * > &allLinkVec)
 Returns a vector of all links associated with this robot.
double getApproachDistance (Body *object, double maxDist)
 Tells us how far along the approach direction a given object is, within a certain limit.
transf getApproachTran () const
 Returns the pre-defined approach direction for this robot.
LinkgetBase () const
 Return a pointer to the base link of this robot.
RobotgetBaseRobot ()
 Given a chain or tree of connected robots, returns a pointer to the root or base robot.
int getBirdNumber ()
 Returns the number of the bird that this robot is connected to.
KinematicChaingetChain (int i) const
 Returns a pointer to the cnumber of kinematic chains in this robot.
std::list< Contact * > getContacts (Body *body=NULL)
 Returns all the contacts on this robot against a given body.
double getDefaultRotVel () const
 Returns the default rotational velocity (rad/sec) for the robot.
double getDefaultTranslVel () const
 Returns the default translational velocity (mm/sec) for the robot.
DOFgetDOF (int i) const
 Returns a pointer to the i-th DOF.
float getDOFDraggerScale (int i) const
 Returns the scale of the i-th DOF dragger.
void getDOFVals (double *dofVals) const
 Returns the current values of all of the DOF's of the robot.
EigenGraspInterfacegetEigenGrasps ()
 Returns the eigengrasps of this robot.
const EigenGraspInterfacegetEigenGrasps () const
 Returns the eigengrasps of this robot.
FlockTransfgetFlockTran ()
 Returns the class that keeps track of flock transforms for this robot.
const FlockTransfgetFlockTran () const
 Returns the transform that indicates where the flock sensor is mounted on this robot.
GloveInterfacegetGloveInterface ()
 Returns the class that interfaces between the CyberGlove and this robot.
LinkgetMountPiece () const
 Returns a point to the mountpiece link (NULL if none exists).
int getNumChains () const
 Returns the number of kinematic chains in this robot.
int getNumContacts (Body *body=NULL)
 Returns the total number of contacts on this robot against a given body.
int getNumDOF () const
 Returns the number of degrees of freedom for this robot.
int getNumJoints () const
 Returns the number of joints in this robot, as set when robot was loaded.
int getNumLinks () const
 Return the number of links for this robot (including palm and mount piece).
int getNumVirtualContacts ()
 Returns the total number of virtual contacts on this robot.
RobotgetParent ()
 Returns a pointer to the parent robot (whose chain this robot is connected to).
int getParentChainNum ()
 Returns the index of the chain that this robot is connected to.
bool getRenderGeometry () const
 Returns whether the automatic render flag is set.
transf const & getTran () const
const transfgetTranToParentEnd ()
LinkimportMountPiece (QString filename)
 Loads a mount piece from a file, if this robot is atatched to another.
virtual int invKinematics (const transf &endTran, double *dofVals, int chainNum)
 Computes the dofvals that achieve a desired end pose for a chain.
double jointLimitDist () const
 Returns the closest distance between a joint value and its limit.
int loadContactData (QString filename)
 Looks for and loads virtual contact data from a given file.
int loadEigenData (QString filename)
 Looks for and loads eigengrasp information from a given file.
virtual int loadFromXml (const TiXmlElement *root, QString rootPath)
 The main load function that loads all the information from XML.
bool moveDOFToContacts (double *desiredVals, double *desiredSteps, bool stopAtContact, bool renderIt=false)
 The main way to move robot dofs IN STATICS. Checks collisions and finds contacts.
void processCyberGlove ()
 Processes a new reading from the CyberGlove.
virtual QTextStream & readDOFVals (QTextStream &is)
 Reads the values of all dofs from a text stream, then updates posture accordingly.
virtual void restoreState ()
 Restores the previously saved state (if any).
 Robot (World *w, const char *name)
virtual void saveState ()
 Saves the state of the robot (pose and posture). Overwrites any previously saved state.
void setChainEndTrajectory (std::vector< transf > &traj, int chainNum)
 Computes a smooth trajectory so that a given chain goes through a set of poses.
void setDefaultRotVel (double v)
 Sets the default rotational velocity (rad/sec) for the robot.
void setDefaultTranslVel (double v)
 Sets the default translational velocity (mm/sec) for the robot.
void setDesiredDOFVals (double *dofVals)
 The main way to move the robot dofs IN DYNAMICS mode.
void setGlove (CyberGlove *glove)
 Sets the instance of the class which translates CyberGlove informration for this robot.
void setName (QString newName)
 Sets the name of this robot.
void setRenderGeometry (bool s)
 Enables or disables the automatic render when the pose or porture of the robot are changed.
virtual int setTran (transf const &tr)
 Sets the location (pose) of the base of this robot in the world coordinate system.
void setTransparency (float t)
 Sets the transparency of the entire robot to the given value.
void showVirtualContacts (bool on)
 Shows or hides virtual contacts.
bool snapChainToContacts (int chainNum, CollisionReport colReport)
Matrix staticJointTorques (bool useDynamicDofForce)
 Accumulated the total static torques applied at each joint by all dof's.
void storeDOFVals (double *dofVals) const
 Returns the values of the DOFs that can be used to save the current state.
void updateDOFFromJoints (double *jointVals)
 Sets the DOF values based on the current values of the joints.
virtual void updateJointValuesFromDynamics ()
 Computes the joint angles after a dynamic step has been completed.
bool useCyberGlove ()
 Returns true if this robot is controlled by a CyberGlove.
int useIdentityEigenData ()
 Sets the trivial eigengrasp set, where we have 1 eg per dof.
bool usesFlock ()
 Returns true if this robot is connected to a Flock of Birds.
virtual QTextStream & writeDOFVals (QTextStream &os)
 Writes the values of all dofs to a text stream.
virtual ~Robot ()
 Deletes all kinematic chains, the base and mount piece, etc.

Protected Member Functions

void addApproachGeometry ()
 Adds a visual indicator of the pre-specified approach direction for this hand.
void addFlockSensorGeometry ()
 Adds a visual image of the Flock of Birds sensor to the base of the robot.
virtual void getBodyList (std::vector< Body * > *bodies)
 Adds all of the bodies that make up this robot to the given vector.
Matrix getJacobianJointToDOF (int chainNum)
 Gets the Jacobian matrix of Joints w.r.t. DOF.
void getJointValues (double *jointVals) const
 Gets the current joint values from the chains.
virtual bool getJointValuesFromDOF (const double *desireddofVals, double *actualDofVals, double *jointVals, int *stoppedJoints)
 Main function for obtaining joint values from the dofs given desired dof values.
int interpolateJoints (double *initialVals, double *finalVals, CollisionReport *colReport, double *interpolationTime)
 Finds the contact time between a collision and a collision-free posture.
bool jumpDOFToContact (double *desiredVals, int *stoppedJoints, int *numCols=NULL)
 Attempts to set the desired dof values, detecting contacts along the way.
virtual void setJointValues (const double *jointVals)
 Asks all chains to set the given joint values.
virtual void setJointValuesAndUpdate (const double *jointVals)
 Asks all chains to set the given joint values, then update the position of all links.
virtual bool simpleContactsPreventMotion (const transf &motion) const
 Recurses to all chains of this robot and any attached robots.
virtual void simpleSetTran (transf const &tr)
 An internal method called by setTran.
void stopJointsFromLink (Link *link, double *desiredJointVals, int *stoppedJoints)
 Stops all the joints that affect a link that is in contact.
void updateDofVals (double *dofVals)
 Informs the dof's that certain values have been set.

Protected Attributes

transf approachTran
 Pre-specified information on how to best approach an object for grasping.
Linkbase
 A pointer to the base link (or palm) of the robot.
std::vector< KinematicChain * > chainVec
 A vector of pointers to this robot's kinematic chains.
double defaultRotVel
 The default rotational velocity (rad/sec) to use when generating cartesian trajectories.
double defaultTranslVel
 The default translational velocity (mm/sec) to use when generating cartesian trajectories.
double dofUpdateTime
 The simulation time of when the next change of DOF setpoints should occur.
std::vector< DOF * > dofVec
 A vector of pointers to this robot's DOF's.
SoSeparator * IVApproachRoot
 Geometry for the visual model of the approach direction.
SoSeparator * IVFlockRoot
 Geometry for a visual model that shows where the bird is attached to the robot.
int mBirdNumber
 If robot is controlled by Flock of Birds, shows which bird it is attached to.
EigenGraspInterfacemEigenGrasps
 Holds all information about this robot's eigengrasps.
FlockTransf mFlockTran
 The relative tranform used for the Flock of Birds.
GloveInterfacemGloveInterface
 Provides translation between the CyberGlove and this robot's DOFs.
bool mRenderGeometry
 Whether changes to the position / geometry of the robot should trigger a scene graph redraw.
bool mUseCyberGlove
 Shows if this robot is to be controlled via a CyberGlove.
bool mUsesFlock
 Shows if this robot is to be controlled by the Flock of Birds.
int numChains
 The number of kinematic chains (or fingers) this robot has.
int numDOF
 The number of degrees of freedom this robot has.
int numJoints
 The total number of joints of this robot. Set when robot is loaded.
QString savedDOF
 Is used to store the states of the DOF; a stream is convenient as it can pack all dofs.
bool savedState
 Tells us whether the state has been previously saved or not.
transf savedTran
 Is used to save the current transform if we want to restore it later.

Private Attributes

LinkmountPiece
 A pointer to an optional mount piece link.
Robotparent
 Points to a parent robot that this robot is attached to.
int parentChainNum
 Records which chain of the parent robot this robot is attached to.
transf tranToParentEnd
 The inverse of the offset transform from parent chain end to this robot's base.

Friends

void KinematicChain::attachRobot (Robot *r, const transf &offsetTr)
void KinematicChain::updateLinkPoses ()

Detailed Description

Base class for all robots which are collections of links connected by moveable joints.

A robot is collection of link bodies orgainized around a base link. Connected to the base link may be 1 or more kinematic chains of links and joints. When a robot is attached to another robot an additional mount piece that connects to the base of the child robot may also be defined. The structure of a robot is defined in a text configuration file [see user documentation] that is parsed by the load method.

Each robot has a collection of DOF's (degrees of freedom) that are linked to the individual joints of a kinematic chain. In general, a robot can not set its joints directly. All joint motion has to be obtained from the DOF's then set using the kinematic chains. In general, we will refer to the position of the robot's base in world coordinate systems as the robot's "pose" while the value of the joints (and implicitly the DOF's) is the robot's "posture".

To set the robot pose, think of it as a general WorldElement; nothing complicated here. Posture is more involved, and depends on whether you are in static or dynamic mode.

In static mode, you can have the robot move to some desired *DOF* values. The DOF's will then compute appropriate joint values, and the robot will have the chains execute those. The settings come in two flavors:

moveDOFToContacts(...) will perform the move in small steps and detect contacts along the way. It is guaranteed to leave your robot in a legal configuration, and detect all contacts that occur.

forceDOFVals(...) will force the final joint values and perform no collision detection. Therefore, it might leave the robot in inter-penetration with some other object.

If dynamics are on, then new desired DOF positions are set with a call to setDesiredDOFVals, and a number of intermediate set points are generated for each joint that will ensure a smooth velocity and acceleration profile. Built in PD DOF controllers use gains specified in the robot configuration file to apply approriate forces to each joint to correct error between the current joint position and the current set point.

If a linear cartesian moves are desired, a trajectory generator can smoothly interpolate between the desired poses by creating a number of intermediate poses. The inverse kinematics for each of these positions is computed and and the resulting joint positions are used as set points for the PD controllers.

Definition at line 97 of file robot.h.


Constructor & Destructor Documentation

Robot::Robot ( World w,
const char *  name 
) [inline]

Simply initializes an empty robot within world w. The load method must be called to read a configuration file and give structure to the robot.

Definition at line 226 of file robot.h.

Robot::~Robot (  )  [virtual]

Deletes all kinematic chains, the base and mount piece, etc.

Removes the base and mountpiece from the world, and deletes the kinematic chains and DOFs. If this robot is connected to a parent robot, it detaches itself.

Definition at line 71 of file robot.cpp.


Member Function Documentation

void Robot::addApproachGeometry (  )  [protected]

Adds a visual indicator of the pre-specified approach direction for this hand.

Adds an arrow that shows the pre-defined approach direction for this robot. The arrow is rooted at the origin of the approach direction and points in the z direction of mApproachTran

Definition at line 525 of file robot.cpp.

void Robot::addFlockSensorGeometry (  )  [protected]

Adds a visual image of the Flock of Birds sensor to the base of the robot.

Adds a visual marker that shows where on the robot the Flock of Birds sensor is mounted. Uses the mounting information stored in the mFlockTran, which is usually pre-defined in the robot file

Definition at line 551 of file robot.cpp.

void Robot::applyJointPassiveInternalWrenches (  ) 

Applies internal joint forces (if any), such as friction or joint springs.

Applies joint friction forces as a pair of equal and opposite forces to links connected at each joint. Frictional forces resist the direction of motion of the joint and uses a viscous friction model with the coefficients defined in the robot configuration file.

Also applies other passive forces, such as spring forces for compliant joints. Spring coefficients are also read from config file.

Definition at line 2063 of file robot.cpp.

void Robot::attachRobot ( Robot r,
int  chainNum,
const transf offsetTr 
)

Attaches another robot to the end of a chain of this robot.

Given a pointer to a robot, the number of the chain on this robot to connect the new robot to, and the offset transform between the chain end and the base of the new robot, this will attach the new robot to this robot's chain end.

Also disables collision between the link of this robot that the other robot is attached to and the base of the other robot as well as the mount piece.

Definition at line 709 of file robot.cpp.

void Robot::breakContacts (  ) 

Breaks all the contacts on this robot.

Breaks all the contacts formed on the links or the base of this robot

Definition at line 1012 of file robot.cpp.

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

Builds dynamic constraints for all the coupled dof's of this robot.

Transparently goes to each DOF and asks them to build the coupling constraints however they want. See the corresponding DOF functions and users manual for dynamics for details.

Definition at line 2090 of file robot.cpp.

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

Builds dynamic dof limit constraints for all the dof's of this robot.

Transparently goes to each DOF and asks them to build the limit constraints however they want. See the corresponding DOF functions and users manual for dynamics for details.

Definition at line 2077 of file robot.cpp.

bool Robot::checkDOFPath ( double *  desiredVals,
double  desiredStep 
)

Checks if the path between current and a desired posture is free of collisions.

This function checks if the path to the desired vals is legal. Breaks down motion into steps and does each step. As soon as any collision is detected, it returns false. Duplicates a lot of the functionality of moveDOFToContacts. This is not a very good implementation and should probably be cleaned up in the future.

Definition at line 1654 of file robot.cpp.

bool Robot::checkDOFVals ( double *  dofVals  )  const [inline]

Returns true if all specified dof vals are within their respective legal ranges.

Returns true if all the dof values in dofVals are within their limits

Definition at line 630 of file robot.h.

bool Robot::checkSetDOFVals ( double *  dofVals  )  const [inline]

Clamps the given dofVals to be within their respective legal ranges.

Clamps the dof values in dofVals to be within the dof limits. Returns true if at least one the values in dofVals was within its limit before clamping

Definition at line 641 of file robot.h.

void Robot::cloneFrom ( Robot original  )  [virtual]

Makes this robot into a clone of the original.

This robot becomes a "clone" of another robot, specified in original. This means that the new robot has its own kinematic structure, DOF's, etc but its links share the geometry of the original robot. See the clone function in the Body class for details on how that works.

This is generally used for multi-threading, if you want to do spread the computations done on a robot to multiple cores. You then create multiple clones of your robot and pass one to each thread. See the threading documentation in the collision detection classes for details.

Definition at line 416 of file robot.cpp.

void Robot::configurationChanged (  )  [signal]

This signal informs that dof values have changed.

Definition at line 89 of file moc_robot.cpp.

bool Robot::contactSlip (  ) 

Returns true if any of the contacts on the fingers are slipping during dynamics.

Looks at dynamics LCP parameters to determine if any of the contacts are slipping during dynamic simulation. Does not do a great job at it, as this turned out to be a much trickier problem than expected.

Definition at line 2167 of file robot.cpp.

bool Robot::contactsPreventMotion ( const transf motion  )  const [virtual]

Returns true of contacts on the palm, a link or a parent robot prevent given motion.

Examines all of the contacts on every link of this robot, and each child robot connected to this one, to determine if the desired motion can be performed. It also performs the inverse kinematics of the parent robot to see if any of those link motions will be prevented by contacts on those links. The motion is expressed with respect to the base frame of the robot. This is only used when dynamics are off.

Implements WorldElement.

Definition at line 970 of file robot.cpp.

void Robot::detachRobot ( Robot r  ) 

Detaches a previously attached robot.

The detaches the robot pointed to by r from this robot so that they may move independently.

Definition at line 729 of file robot.cpp.

void Robot::DOFController ( double  timeStep  )  [virtual]

Calls the DOF controllers which set dof forces based on current and desired posture.

If the current simulation time is past the DOF setpoint update time this updates the DOF set points. Then the PD position controller for each DOF computes the control force for the DOF given the length of the current timestep.

Reimplemented in HumanHand, and Pincer.

Definition at line 2106 of file robot.cpp.

bool Robot::dynamicAutograspComplete (  ) 

Attempt to check if the dynamic autograsp is complete.

A specialized function that attempts to see if the autograsp has completed, when executed dynamically. Does not do a great job at it, as this turned out to be a much trickier problem than expected.

Definition at line 2127 of file robot.cpp.

void Robot::emitConfigChange (  )  [inline]

Emits the configuration changed signal.

Definition at line 507 of file robot.h.

void Robot::emitUserInteractionEnd (  )  [inline]

Emits the user interaction ended signal.

Definition at line 511 of file robot.h.

void Robot::emitUserInteractionStart (  )  [inline]

Emits the user interaction start signal.

Definition at line 509 of file robot.h.

void Robot::forceDOFVal ( int  dofNum,
double  val 
) [inline]

Sets the given DOF to the given value and updates the link poses. Collisions are NOT checked.

Forces a single dof to assume a current value. Gets the appropriate joint values from the dofs, then forces the joints to that position and updates the posture. Does NOT check for collisions

Definition at line 595 of file robot.h.

void Robot::forceDOFVals ( double *  dofVals  )  [inline]

Sets the values of the DOF's to the values in the array dofVals. Collisions are NOT checked.

Sets the values of the dofs of this robot to the values in the array dofVals. Then it updates the link poses, but collisions are NOT checked.

Definition at line 608 of file robot.h.

void Robot::fwdKinematics ( double *  dofVals,
std::vector< transf > &  trVec,
int  chainNum 
) [virtual]

Computes the transform of all links in a chain for a given set of dof vals.

Given an array of DOF values equal in length to the number of DOFs in this robot, and the chain number for which the kinematics should be computed, this will return a vector of transforms corresponding to the pose of each link in the chain.

Definition at line 744 of file robot.cpp.

void Robot::generateCartesianTrajectory ( const transf startTr,
const transf endTr,
std::vector< transf > &  traj,
double  startVel,
double  endVel = 0.0,
double  timeNeeded = -1.0 
)

Computes a trajectory that interpolates linearly between a start and end poses.

Given a start and end pose, this creates a number of intermediate poses that linearly interpolate between the two in cartesian space. The start and end velocities of the end effector default to 0 but can be changed. If the time needed for the move is not set, the trajectory will have an average velocity equal to the defaultTranVel and defaultRotVel. The number of poses generated is determined by the amount of time needed for the move divided by the default dyanmic time step length.

Definition at line 1973 of file robot.cpp.

void Robot::getAllAttachedRobots ( std::vector< Robot * > &  robotVec  ) 

Returns a vector of all robots attached to this one.

Returns a pointer to this robot and recursively, all child robots connected to this one

Definition at line 687 of file robot.cpp.

void Robot::getAllLinks ( std::vector< DynamicBody * > &  allLinkVec  ) 

Returns a vector of all links associated with this robot.

Returns a vector of all links associated with this robot including all links in all chains, the base, and the mountpiece.

Definition at line 668 of file robot.cpp.

double Robot::getApproachDistance ( Body object,
double  maxDist 
)

Tells us how far along the approach direction a given object is, within a certain limit.

Tells us how far along the pre-specified approach distance a certain object is. Since the approach direction might never intersect the given body, it also needs a cap telling is how far to look. This cap is maxDist. Therefore, a return value of maxDist might mean that the object is never hit by moving along the approach direction.

Definition at line 1737 of file robot.cpp.

transf Robot::getApproachTran (  )  const [inline]

Returns the pre-defined approach direction for this robot.

Definition at line 499 of file robot.h.

Link* Robot::getBase (  )  const [inline]

Return a pointer to the base link of this robot.

Definition at line 461 of file robot.h.

Robot* Robot::getBaseRobot (  )  [inline]

Given a chain or tree of connected robots, returns a pointer to the root or base robot.

Definition at line 405 of file robot.h.

int Robot::getBirdNumber (  )  [inline]

Returns the number of the bird that this robot is connected to.

Definition at line 343 of file robot.h.

void Robot::getBodyList ( std::vector< Body * > *  bodies  )  [protected, virtual]

Adds all of the bodies that make up this robot to the given vector.

Adds all the bodies associated with this robot (links, base, mountpiece, attached robots) to the given vector of bodies.

Implements WorldElement.

Definition at line 647 of file robot.cpp.

KinematicChain* Robot::getChain ( int  i  )  const [inline]

Returns a pointer to the cnumber of kinematic chains in this robot.

Definition at line 458 of file robot.h.

std::list< Contact * > Robot::getContacts ( Body body = NULL  ) 

Returns all the contacts on this robot against a given body.

Returns the list of contacts on this robot against the Body body, including contacts on all robot links and the palm. If body is NULL it returns all the contacts on this robot regardless of who they are against.

Definition at line 1108 of file robot.cpp.

double Robot::getDefaultRotVel (  )  const [inline]

Returns the default rotational velocity (rad/sec) for the robot.

Definition at line 470 of file robot.h.

double Robot::getDefaultTranslVel (  )  const [inline]

Returns the default translational velocity (mm/sec) for the robot.

Definition at line 467 of file robot.h.

DOF* Robot::getDOF ( int  i  )  const [inline]

Returns a pointer to the i-th DOF.

Definition at line 446 of file robot.h.

float Robot::getDOFDraggerScale ( int  i  )  const [inline]

Returns the scale of the i-th DOF dragger.

Definition at line 449 of file robot.h.

void Robot::getDOFVals ( double *  dofVals  )  const [inline]

Returns the current values of all of the DOF's of the robot.

dofVals should point to a double array with a length at least equal to the number of DOF's of this robot.

Definition at line 564 of file robot.h.

EigenGraspInterface* Robot::getEigenGrasps (  )  [inline]

Returns the eigengrasps of this robot.

Definition at line 366 of file robot.h.

const EigenGraspInterface* Robot::getEigenGrasps (  )  const [inline]

Returns the eigengrasps of this robot.

Definition at line 363 of file robot.h.

FlockTransf* Robot::getFlockTran (  )  [inline]

Returns the class that keeps track of flock transforms for this robot.

Definition at line 352 of file robot.h.

const FlockTransf* Robot::getFlockTran (  )  const [inline]

Returns the transform that indicates where the flock sensor is mounted on this robot.

Definition at line 349 of file robot.h.

GloveInterface* Robot::getGloveInterface (  )  [inline]

Returns the class that interfaces between the CyberGlove and this robot.

Definition at line 340 of file robot.h.

Matrix Robot::getJacobianJointToDOF ( int  chainNum  )  [protected]

Gets the Jacobian matrix of Joints w.r.t. DOF.

Definition at line 2364 of file robot.cpp.

void Robot::getJointValues ( double *  jointVals  )  const [inline, protected]

Gets the current joint values from the chains.

Gets the current joint values in jointVals. It is expected that this vector is of size equal to the number of joints of this robot.

Definition at line 527 of file robot.h.

bool Robot::getJointValuesFromDOF ( const double *  desiredDofVals,
double *  actualDofVals,
double *  jointVals,
int *  stoppedJoints 
) [protected, virtual]

Main function for obtaining joint values from the dofs given desired dof values.

One of the main functions for moving DOF's in statics. Given a set of desiredDofVals, this will ask the DOF's what values should be given to the joints. The vector stoppedJoints contains information about which joints have been stopped due to contacts. On exit, jointVals will contain the needed joint values, and actualDofVals will contain the DOF values that were actually set (which might be different from desireDofVals because contacts might prevent the desired motion.

The main reason for this implementation is that different types of DOF's react different to contacts and implement coupling in their own differnt way.

Returns true if at least on the joints of the robot is still moving, or if contacts prevent all motion, limits have been reached and no more movement is possible.

Definition at line 1363 of file robot.cpp.

Link* Robot::getMountPiece (  )  const [inline]

Returns a point to the mountpiece link (NULL if none exists).

Definition at line 430 of file robot.h.

int Robot::getNumChains (  )  const [inline]

Returns the number of kinematic chains in this robot.

Definition at line 452 of file robot.h.

int Robot::getNumContacts ( Body body = NULL  ) 

Returns the total number of contacts on this robot against a given body.

Returns the total number of contacts on this robot, including all links and the palm. If body is NULL it returns the total number of contacts on this robot regardless of who they are against.

Definition at line 1094 of file robot.cpp.

int Robot::getNumDOF (  )  const [inline]

Returns the number of degrees of freedom for this robot.

Definition at line 443 of file robot.h.

int Robot::getNumJoints (  )  const [inline]

Returns the number of joints in this robot, as set when robot was loaded.

Definition at line 455 of file robot.h.

int Robot::getNumLinks (  )  const

Return the number of links for this robot (including palm and mount piece).

Returns the total number of links of this robot, including the palm and the mount piece (if any).

Definition at line 1078 of file robot.cpp.

int Robot::getNumVirtualContacts (  ) 

Returns the total number of virtual contacts on this robot.

Returns the total number of virtual contacts on this robot, including all links and the palm.

Definition at line 1124 of file robot.cpp.

Robot* Robot::getParent (  )  [inline]

Returns a pointer to the parent robot (whose chain this robot is connected to).

Definition at line 408 of file robot.h.

int Robot::getParentChainNum (  )  [inline]

Returns the index of the chain that this robot is connected to.

Definition at line 411 of file robot.h.

bool Robot::getRenderGeometry (  )  const [inline]

Returns whether the automatic render flag is set.

Definition at line 482 of file robot.h.

transf const& Robot::getTran (  )  const [inline, virtual]

Return the transform which describes the world pose of the robot base frame with respect to the world coordinate system.

Implements WorldElement.

Definition at line 294 of file robot.h.

const transf& Robot::getTranToParentEnd (  )  [inline]

Returns the transform from the base of this robot to end frame of the parent's kinematic chain that this robot is connected to.

Definition at line 415 of file robot.h.

Link * Robot::importMountPiece ( QString  filename  ) 

Loads a mount piece from a file, if this robot is atatched to another.

Given the body filename of a mountpiece, this will load it into the world and connect it to the base of this robot.

Definition at line 629 of file robot.cpp.

int Robot::interpolateJoints ( double *  initialVals,
double *  finalVals,
CollisionReport colReport,
double *  interpolationTime 
) [protected]

Finds the contact time between a collision and a collision-free posture.

This is one of the core function used for moving the DOF's of a robot in statics. Its purpose is to solve a collision: given an initial set of joint values, which should be collision-free, and a set of final joint values that result in a collision, it will interpolate between the two to find the initial moment of contact (where the bodies are not inter-penetrating, but are separated by less then the contat threshold.

In order to be efficient, it only checks the bodies that are given in the colReport. If other bodies are also colliding at any point during the interpolation, this function will never know about it.

Returns 0 if the interpolation fails (usually because the starting configuration is also in collision, or 1 if its succeeds. In case of success, interpolationTime will hold the interpolation coefficient that resulted in the original contact.

Definition at line 1274 of file robot.cpp.

int Robot::invKinematics ( const transf targetPos,
double *  dofVals,
int  chainNum 
) [virtual]

Computes the dofvals that achieve a desired end pose for a chain.

Given a transform for the end pose of a particular kinematic chain, this will compute the DOF values corresponding to that pose. It will use an iterative approximation technique. In this method, the jacobian is based on each dofs rather than the joint angles

Reimplemented in Puma560.

Definition at line 761 of file robot.cpp.

double Robot::jointLimitDist (  )  const [inline]

Returns the closest distance between a joint value and its limit.

Returns the closest distance between a joint value and its limit; positive if the joint is inside its legal range and negative if it's outside

Definition at line 537 of file robot.h.

bool Robot::jumpDOFToContact ( double *  desiredVals,
int *  stoppedJoints,
int *  numCols = NULL 
) [protected]

Attempts to set the desired dof values, detecting contacts along the way.

The core of the robot DOF movement in statics. Given a set of desiredVals for the DOF's, it will set the DOF's to that value. If the result is free of contact, we are done. If the result is in collision, it will interpolate to find the exact moment of contact and set the DOF's at that value. stoppedJoints marks any joints that can not move (presumably due to some contact discovered earlier). Returns the number of collisions found (and resolved) in numCols.

After completing the move, it will also mark all the new contacts that have appeared due to the move. It will also mark as stopped the joints of the links that are now in contact, by setting the appropriate bits in stoppedJoints.

In theory, this function should always leave the robot in a legal state, with no inter-penetrations.

Returns true if the move had been performed successfully. Returns false if either no motion was performed because all dofs are already at the desired values, or contacts prevent all motion. Also returns false if there is an error in the interpolation.

A final note of warning: this rather involved way of doing this was dictated by multiple problems: always avoid leaving the robot in an illegal state; allow different dof's to react to stopped joints in their own way; don't compute contacts more often then you have to (it's expensive); make sure the dof's move together, and not one by one; handle the case where the collision detection engine finds a collision, but fails to detect a contact after it's solved (happens very rarely, but it does); etc. In general, this whole process is more complicated than it appears at first. We would love a general and robust solution to this, but tread carefully here.

Definition at line 1442 of file robot.cpp.

int Robot::loadContactData ( QString  filename  ) 

Looks for and loads virtual contact data from a given file.

Loads all the virtual contacts specified in the file filename

Definition at line 368 of file robot.cpp.

int Robot::loadEigenData ( QString  filename  ) 

Looks for and loads eigengrasp information from a given file.

Loads the eigengrasp information from the file filename.

Definition at line 353 of file robot.cpp.

int Robot::loadFromXml ( const TiXmlElement root,
QString  rootPath 
) [virtual]

The main load function that loads all the information from XML.

Loads the robot information from an XML node, which is asumed to be the root of a hierarchy containing all the relevant information. The rootPath is considered the reference path for other files which are referenced in the XML. One exception are the link files which are assumed to be placed in rootPath/iv

Reimplemented in Barrett, HumanHand, M7, M7Tool, McGrip, Pr2Gripper, Robonaut, and Shadow.

Definition at line 96 of file robot.cpp.

void Robot::moveDOFStepTaken ( int  numCols,
bool &  stopRequest 
) [signal]

Emitted by moveDOFToCOntacts each time a step is taken.

Definition at line 107 of file moc_robot.cpp.

bool Robot::moveDOFToContacts ( double *  desiredVals,
double *  desiredSteps,
bool  stopAtContact,
bool  renderIt = false 
)

The main way to move robot dofs IN STATICS. Checks collisions and finds contacts.

This is the only interface for the user to perform robot DOF movement in statics. The desired dof vals are specified in desiredVals, which should be of size equal to the number of dofs of this robot.

The most important aspect is that the motion can be broken down in small steps, to make sure that no collisions are missed along the way by "jumping through" an obstacle. The other important aspect is that, when a contact is found and a DOF is stopped, the other DOF's can continue to move.

desiredSteps holds the size of the desired steps for each DOF. We usually use 10 degrees for rotational DOFs and 50*ContactTHRESHOLD for translational DOF's. You can use WorldElement::ONE_STEP if no stepping is to be performed. If desiredSteps is NULL it has the same effect as setting all entried to ONE_STEP.

If stopAtContact is true, all movement ends as soon as the first contact is detected. If not, movement proceeds until all DOF's have either reached the desired value, reached their limit, or have been stopped due to contact.

Works by breaking down the motion in small time steps and uses the internal forceDOFTo function repeatedly for each step.Returns true if the joints were moved; if no movement was possible from the beginning, it returns false.

Note that the desired steps are treated as absolute values; this function will automatically choose the right sign for the steps based on the direction of movement. In the past, the sign of the desired step used to matter, so some functions inside GraspIt still check for that themselves; that should no be necessary anymore.

Definition at line 1557 of file robot.cpp.

void Robot::processCyberGlove (  ) 

Processes a new reading from the CyberGlove.

Sets the values of the DOF's based on the information from the mGloveInterface, which has presumably processed a new batch of raw information from a real CyberGlove

Definition at line 605 of file robot.cpp.

QTextStream & Robot::readDOFVals ( QTextStream &  is  )  [virtual]

Reads the values of all dofs from a text stream, then updates posture accordingly.

Reads DOF values from a text stream (usually from a saved world file or an internally saved state) and sets them

Definition at line 1197 of file robot.cpp.

void Robot::restoreState (  )  [virtual]

Restores the previously saved state (if any).

Restores the previously saved state of this robot. If no state has been saved since the last restore, is prints out a warning, but does not die in pain.

Definition at line 1178 of file robot.cpp.

void Robot::saveState (  )  [virtual]

Saves the state of the robot (pose and posture). Overwrites any previously saved state.

Saves the current state of the robot, which can be restored later. Overwrites any previously saved state. Maybe at some point we will unify this with the stack of dynamic states which can hold any number of states for a body.

Definition at line 1164 of file robot.cpp.

void Robot::setChainEndTrajectory ( std::vector< transf > &  traj,
int  chainNum 
)

Computes a smooth trajectory so that a given chain goes through a set of poses.

Given a kinematic chain number and a vector of chain end poses, this computes the inverse kinematics for each pose, and computes a smooth trajectory for each DOF to reach each pose.

Definition at line 1935 of file robot.cpp.

void Robot::setDefaultRotVel ( double  v  )  [inline]

Sets the default rotational velocity (rad/sec) for the robot.

Definition at line 476 of file robot.h.

void Robot::setDefaultTranslVel ( double  v  )  [inline]

Sets the default translational velocity (mm/sec) for the robot.

Definition at line 473 of file robot.h.

void Robot::setDesiredDOFVals ( double *  dofVals  ) 

The main way to move the robot dofs IN DYNAMICS mode.

This is the main function for moving the robot DOF's in dynamics. All the user can do is set the desired dof vals. This function will compute a smooth trajectory for each joint so that each has a smooth acceleration and velocity profile. The intermediate values become the setpoints for each joint controller.

After that, we rely on the simulation world to run each dynamic time step and call the robot's dof controllers which will set dof dynamic forces based on the desired dof values. The next dynamic time step will then move the links based on the forces applied by the dof's.

In practice, the dof controllers are tricky and I've never been able to make them very robust. They work reasonably well, but not in all cases.

Definition at line 1877 of file robot.cpp.

void Robot::setGlove ( CyberGlove *  glove  ) 

Sets the instance of the class which translates CyberGlove informration for this robot.

Tells the robot which CyberGlove the raw sensor data is coming from. The robot does not process raw data directly, just passes it to the mGloveInterface which hodsl calibration and DOF mapping between a raw Glove and this particular robot

Definition at line 591 of file robot.cpp.

void Robot::setJointValues ( const double *  jointVals  )  [protected, virtual]

Asks all chains to set the given joint values.

Asks the chains to set the new joint values in jointVals. It is expected that this vector is of size equal to the number of joints of this robot. Does NOT ask the chains to also update the poses of the links.

Definition at line 1236 of file robot.cpp.

void Robot::setJointValuesAndUpdate ( const double *  jointVals  )  [protected, virtual]

Asks all chains to set the given joint values, then update the position of all links.

Asks the chains to set the new joint values in jointVals. It is expected that this vector is of size equal to the number of joints of this robot. Also asks the chains to also update the poses of the links.

Reimplemented in Pr2Gripper2010.

Definition at line 1248 of file robot.cpp.

void Robot::setName ( QString  newName  )  [virtual]

Sets the name of this robot.

Sets the name newName for the robot, as well as derived names of the form newName_chain::_link# for the links and newName_base for the base.

Reimplemented from WorldElement.

Definition at line 509 of file robot.cpp.

void Robot::setRenderGeometry ( bool  s  ) 

Enables or disables the automatic render when the pose or porture of the robot are changed.

This can be used to disable / enable the automatic render requests from this robot. If this is disabled, changes to the robot pose or posture should not trigger an automatic render request through Coin. The robot however is still part of the scene graph, so whenever a render request comes from someplace else, the robot is rendered in its most current state. See also the option in the World class to completely remove a robot from the scene graph.

Definition at line 1032 of file robot.cpp.

int Robot::setTran ( transf const &  tr  )  [virtual]

Sets the location (pose) of the base of this robot in the world coordinate system.

This attempt to set the pose of the robot base to tr. It does not check for collisions, but it will check the inverse kinematics of a parent robot (if it exists) to determine whether the move is valid. If it is valid the DOF's of the parent are set, and this robot and all of its children are moved.

Implements WorldElement.

Definition at line 1057 of file robot.cpp.

void Robot::setTransparency ( float  t  ) 

Sets the transparency of the entire robot to the given value.

Sets the transparency of all the links that make up this robot, as well as the base

Definition at line 495 of file robot.cpp.

void Robot::showVirtualContacts ( bool  on  ) 

Shows or hides virtual contacts.

Shows or hides the virtual contact on this robot (which can be shown as thin red cylinders). They are usually hidden so they don't trigger a redraw when not wanted, although we now have a better mechanism for that using setRenderGeometry on the entire robot

Definition at line 1141 of file robot.cpp.

bool Robot::simpleContactsPreventMotion ( const transf motion  )  const [protected, virtual]

Recurses to all chains of this robot and any attached robots.

This is an internal method called by contactsPreventMotion. Given a motion transform for an entire robot that is defined with respect to the base frame of the robot, it recursively checks all of the kinematic chains of the robot and any robots connected to them to determine if any contacts will prevent the motion.

Definition at line 935 of file robot.cpp.

void Robot::simpleSetTran ( transf const &  tr  )  [inline, protected, virtual]

An internal method called by setTran.

Sets the transform of the base link, the mount piece (if it exists), and tells each kinematic chain to update the link poses, which also updates the pose of each attached robot.

Definition at line 555 of file robot.h.

bool Robot::snapChainToContacts ( int  chainNum,
CollisionReport  colReport 
)

This function snaps a kinematic chain out of collision with an object and into contact - if possible. It moves the chain "out" (in the opposite direction of autograsp) a little bit. If this is a valid position, it interpolates between it and the original collision position to find the moment of contact.

Definition at line 1779 of file robot.cpp.

Matrix Robot::staticJointTorques ( bool  useDynamicDofForce  ) 

Accumulated the total static torques applied at each joint by all dof's.

Returns the static torques on all the joints of this robot. This is relevant for underactuated compliant hands only, should be zero in all other cases. See the CompliantDOF class for details.

If is set, the static joint torques are computed using the dynamic force currently set by each DOF. If not, the minimum values for balancing the system are computed. This is somewhat hacky as this is done in statics, not dynamics, but we needed a way of computing static joint torques for some pre-specified level of DOF force.

Definition at line 1715 of file robot.cpp.

void Robot::stopJointsFromLink ( Link link,
double *  desiredJointVals,
int *  stoppedJoints 
) [protected]

Stops all the joints that affect a link that is in contact.

A utility function for the main static DOF movement functions. Given a link that is stopped (presumably due to some contact) it will mark all the joints that affect that link as stopped. This is done by setting the a bit in the entry that correspinds to a given joint in the vector stoppedJoints. stoppedJoints is assumed to be large enough for all the joints in the robot.

Definition at line 1330 of file robot.cpp.

void Robot::storeDOFVals ( double *  dofVals  )  const [inline]

Returns the values of the DOFs that can be used to save the current state.

The values of the DOFs that can be used for saving the current state are not always the current values of the DOF's. This in not ideal, but was necessary in the case of tha Barrett hand: when saving the current state, more often we want the *breakaway* value of the DOF rather than its current value.

Neither solution is ideal:

  • if we later restore the state using the current value of the DOF, we have lost breakaway information and that might result in a collision
  • if we do it using the breakaway value, we will lose some contacts on the distal link. However, these can usually be recovered using an autoGrasp(...).

The correct way is to use writeDOFVals(...) and readDOFVals(...) which save the entire state of the DOFs, including all breakaway information. However, those functions work with QStrings, while we needed to save the state as one value per DOF for external reasons. Hence the need for this hack-ish function.

Definition at line 587 of file robot.h.

void Robot::updateDOFFromJoints ( double *  jointVals  )  [inline]

Sets the DOF values based on the current values of the joints.

Asks each dof to update its value based on the joint values supplied in jointVals

Definition at line 623 of file robot.h.

void Robot::updateDofVals ( double *  dofVals  )  [inline, protected]

Informs the dof's that certain values have been set.

Informs the dofs of their new values in dofVals. Simply passes through to the similar function of each dof

Definition at line 517 of file robot.h.

void Robot::updateJointValuesFromDynamics (  )  [virtual]

Computes the joint angles after a dynamic step has been completed.

This is only called when dynamics is on. It updates the joint values of the dynamic joints. It is important that this be called after each dynamic movement because other function then look at joint->getVal() for many different reasons.

Definition at line 2030 of file robot.cpp.

bool Robot::useCyberGlove (  )  [inline]

Returns true if this robot is controlled by a CyberGlove.

Definition at line 331 of file robot.h.

int Robot::useIdentityEigenData (  ) 

Sets the trivial eigengrasp set, where we have 1 eg per dof.

Sets the robot to use the trivial eigengrasps set, where each eigengrasp corresponds to a single DOF with an amplitude of 1.0. In this case, there is no difference between seting EG's and using DOF's directly.

Definition at line 578 of file robot.cpp.

void Robot::userInteractionEnd (  )  [signal]

This signal is the complement of userInteractionStart().

Definition at line 101 of file moc_robot.cpp.

void Robot::userInteractionStart (  )  [signal]

This signal informs that user has begun interaction by clicking on a robot handler.

Definition at line 95 of file moc_robot.cpp.

bool Robot::usesFlock (  )  [inline]

Returns true if this robot is connected to a Flock of Birds.

Definition at line 346 of file robot.h.

QTextStream & Robot::writeDOFVals ( QTextStream &  os  )  [virtual]

Writes the values of all dofs to a text stream.

Writes DOF values to a text stream (usually a world save file or the internally saved state)

Definition at line 1221 of file robot.cpp.


Friends And Related Function Documentation

void KinematicChain::attachRobot ( Robot r,
const transf offsetTr 
) [friend]
void KinematicChain::updateLinkPoses (  )  [friend]

Member Data Documentation

Pre-specified information on how to best approach an object for grasping.

This transform sets the origin and the z axis to match the best approach direction for this hand

Definition at line 179 of file robot.h.

Link* Robot::base [protected]

A pointer to the base link (or palm) of the robot.

Definition at line 138 of file robot.h.

std::vector<KinematicChain *> Robot::chainVec [protected]

A vector of pointers to this robot's kinematic chains.

Definition at line 134 of file robot.h.

double Robot::defaultRotVel [protected]

The default rotational velocity (rad/sec) to use when generating cartesian trajectories.

Definition at line 157 of file robot.h.

double Robot::defaultTranslVel [protected]

The default translational velocity (mm/sec) to use when generating cartesian trajectories.

Definition at line 155 of file robot.h.

double Robot::dofUpdateTime [protected]

The simulation time of when the next change of DOF setpoints should occur.

Definition at line 153 of file robot.h.

std::vector<DOF *> Robot::dofVec [protected]

A vector of pointers to this robot's DOF's.

Definition at line 136 of file robot.h.

SoSeparator* Robot::IVApproachRoot [protected]

Geometry for the visual model of the approach direction.

Definition at line 181 of file robot.h.

SoSeparator* Robot::IVFlockRoot [protected]

Geometry for a visual model that shows where the bird is attached to the robot.

Definition at line 169 of file robot.h.

int Robot::mBirdNumber [protected]

If robot is controlled by Flock of Birds, shows which bird it is attached to.

Definition at line 167 of file robot.h.

Holds all information about this robot's eigengrasps.

Definition at line 174 of file robot.h.

The relative tranform used for the Flock of Birds.

Definition at line 171 of file robot.h.

Provides translation between the CyberGlove and this robot's DOFs.

Definition at line 163 of file robot.h.

Link* Robot::mountPiece [private]

A pointer to an optional mount piece link.

Definition at line 122 of file robot.h.

bool Robot::mRenderGeometry [protected]

Whether changes to the position / geometry of the robot should trigger a scene graph redraw.

Definition at line 149 of file robot.h.

bool Robot::mUseCyberGlove [protected]

Shows if this robot is to be controlled via a CyberGlove.

Definition at line 161 of file robot.h.

bool Robot::mUsesFlock [protected]

Shows if this robot is to be controlled by the Flock of Birds.

Definition at line 165 of file robot.h.

int Robot::numChains [protected]

The number of kinematic chains (or fingers) this robot has.

Definition at line 128 of file robot.h.

int Robot::numDOF [protected]

The number of degrees of freedom this robot has.

Definition at line 130 of file robot.h.

int Robot::numJoints [protected]

The total number of joints of this robot. Set when robot is loaded.

Definition at line 132 of file robot.h.

Robot* Robot::parent [private]

Points to a parent robot that this robot is attached to.

Definition at line 116 of file robot.h.

int Robot::parentChainNum [private]

Records which chain of the parent robot this robot is attached to.

Definition at line 118 of file robot.h.

QString Robot::savedDOF [protected]

Is used to store the states of the DOF; a stream is convenient as it can pack all dofs.

Definition at line 144 of file robot.h.

bool Robot::savedState [protected]

Tells us whether the state has been previously saved or not.

Definition at line 146 of file robot.h.

transf Robot::savedTran [protected]

Is used to save the current transform if we want to restore it later.

Definition at line 142 of file robot.h.

The inverse of the offset transform from parent chain end to this robot's base.

Definition at line 120 of file robot.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:24 2012