Base class for all robots which are collections of links connected by moveable joints. More...
#include <robot.h>
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. | |
Link * | getBase () const |
Return a pointer to the base link of this robot. | |
Robot * | getBaseRobot () |
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. | |
KinematicChain * | getChain (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. | |
DOF * | getDOF (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. | |
EigenGraspInterface * | getEigenGrasps () |
Returns the eigengrasps of this robot. | |
const EigenGraspInterface * | getEigenGrasps () const |
Returns the eigengrasps of this robot. | |
FlockTransf * | getFlockTran () |
Returns the class that keeps track of flock transforms for this robot. | |
const FlockTransf * | getFlockTran () const |
Returns the transform that indicates where the flock sensor is mounted on this robot. | |
GloveInterface * | getGloveInterface () |
Returns the class that interfaces between the CyberGlove and this robot. | |
Link * | getMountPiece () 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. | |
Robot * | getParent () |
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 transf & | getTranToParentEnd () |
Link * | importMountPiece (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. | |
Link * | base |
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. | |
EigenGraspInterface * | mEigenGrasps |
Holds all information about this robot's eigengrasps. | |
FlockTransf | mFlockTran |
The relative tranform used for the Flock of Birds. | |
GloveInterface * | mGloveInterface |
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 | |
Link * | mountPiece |
A pointer to an optional mount piece link. | |
Robot * | parent |
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 () |
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.
Robot::Robot | ( | World * | w, | |
const char * | name | |||
) | [inline] |
Robot::~Robot | ( | ) | [virtual] |
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
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
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.
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.
void Robot::breakContacts | ( | ) |
void Robot::buildDOFCouplingConstraints | ( | std::map< Body *, int > & | islandIndices, | |
int | numBodies, | |||
double * | Nu, | |||
double * | eps, | |||
int & | ncn | |||
) | [virtual] |
void Robot::buildDOFLimitConstraints | ( | std::map< Body *, int > & | islandIndices, | |
int | numBodies, | |||
double * | H, | |||
double * | g, | |||
int & | hcn | |||
) | [virtual] |
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.
bool Robot::checkDOFVals | ( | double * | dofVals | ) | const [inline] |
bool Robot::checkSetDOFVals | ( | double * | dofVals | ) | const [inline] |
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.
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.
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.
void Robot::detachRobot | ( | Robot * | r | ) |
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.
bool Robot::dynamicAutograspComplete | ( | ) |
void Robot::emitConfigChange | ( | ) | [inline] |
void Robot::emitUserInteractionEnd | ( | ) | [inline] |
void Robot::emitUserInteractionStart | ( | ) | [inline] |
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
void Robot::forceDOFVals | ( | double * | dofVals | ) | [inline] |
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.
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.
void Robot::getAllAttachedRobots | ( | std::vector< Robot * > & | robotVec | ) |
void Robot::getAllLinks | ( | std::vector< DynamicBody * > & | allLinkVec | ) |
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.
transf Robot::getApproachTran | ( | ) | const [inline] |
Link* Robot::getBase | ( | ) | const [inline] |
Robot* Robot::getBaseRobot | ( | ) | [inline] |
int Robot::getBirdNumber | ( | ) | [inline] |
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.
KinematicChain* Robot::getChain | ( | int | i | ) | const [inline] |
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.
double Robot::getDefaultRotVel | ( | ) | const [inline] |
double Robot::getDefaultTranslVel | ( | ) | const [inline] |
DOF* Robot::getDOF | ( | int | i | ) | const [inline] |
float Robot::getDOFDraggerScale | ( | int | i | ) | const [inline] |
void Robot::getDOFVals | ( | double * | dofVals | ) | const [inline] |
EigenGraspInterface* Robot::getEigenGrasps | ( | ) | [inline] |
const EigenGraspInterface* Robot::getEigenGrasps | ( | ) | const [inline] |
FlockTransf* Robot::getFlockTran | ( | ) | [inline] |
const FlockTransf* Robot::getFlockTran | ( | ) | const [inline] |
GloveInterface* Robot::getGloveInterface | ( | ) | [inline] |
Matrix Robot::getJacobianJointToDOF | ( | int | chainNum | ) | [protected] |
void Robot::getJointValues | ( | double * | jointVals | ) | const [inline, protected] |
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.
Link* Robot::getMountPiece | ( | ) | const [inline] |
int Robot::getNumChains | ( | ) | const [inline] |
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.
int Robot::getNumDOF | ( | ) | const [inline] |
int Robot::getNumJoints | ( | ) | const [inline] |
int Robot::getNumLinks | ( | ) | const |
int Robot::getNumVirtualContacts | ( | ) |
Robot* Robot::getParent | ( | ) | [inline] |
int Robot::getParentChainNum | ( | ) | [inline] |
bool Robot::getRenderGeometry | ( | ) | const [inline] |
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.
const transf& Robot::getTranToParentEnd | ( | ) | [inline] |
Link * Robot::importMountPiece | ( | QString | filename | ) |
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.
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.
double Robot::jointLimitDist | ( | ) | const [inline] |
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.
int Robot::loadContactData | ( | QString | filename | ) |
int Robot::loadEigenData | ( | QString | filename | ) |
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.
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.
void Robot::processCyberGlove | ( | ) |
QTextStream & Robot::readDOFVals | ( | QTextStream & | is | ) | [virtual] |
void Robot::restoreState | ( | ) | [virtual] |
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.
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.
void Robot::setDefaultRotVel | ( | double | v | ) | [inline] |
void Robot::setDefaultTranslVel | ( | double | v | ) | [inline] |
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.
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
void Robot::setJointValues | ( | const double * | jointVals | ) | [protected, virtual] |
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.
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.
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.
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.
void Robot::setTransparency | ( | float | t | ) |
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
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.
void Robot::simpleSetTran | ( | transf const & | tr | ) | [inline, protected, virtual] |
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.
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.
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.
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:
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.
void Robot::updateDOFFromJoints | ( | double * | jointVals | ) | [inline] |
void Robot::updateDofVals | ( | double * | dofVals | ) | [inline, protected] |
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.
bool Robot::useCyberGlove | ( | ) | [inline] |
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.
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] |
QTextStream & Robot::writeDOFVals | ( | QTextStream & | os | ) | [virtual] |
void KinematicChain::updateLinkPoses | ( | ) | [friend] |
transf Robot::approachTran [protected] |
Link* Robot::base [protected] |
std::vector<KinematicChain *> Robot::chainVec [protected] |
double Robot::defaultRotVel [protected] |
double Robot::defaultTranslVel [protected] |
double Robot::dofUpdateTime [protected] |
std::vector<DOF *> Robot::dofVec [protected] |
SoSeparator* Robot::IVApproachRoot [protected] |
SoSeparator* Robot::IVFlockRoot [protected] |
int Robot::mBirdNumber [protected] |
EigenGraspInterface* Robot::mEigenGrasps [protected] |
FlockTransf Robot::mFlockTran [protected] |
GloveInterface* Robot::mGloveInterface [protected] |
Link* Robot::mountPiece [private] |
bool Robot::mRenderGeometry [protected] |
bool Robot::mUseCyberGlove [protected] |
bool Robot::mUsesFlock [protected] |
int Robot::numChains [protected] |
int Robot::numDOF [protected] |
int Robot::numJoints [protected] |
Robot* Robot::parent [private] |
int Robot::parentChainNum [private] |
QString Robot::savedDOF [protected] |
bool Robot::savedState [protected] |
transf Robot::savedTran [protected] |
transf Robot::tranToParentEnd [private] |