00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00030 #ifndef ROBOT_H
00031
00032 #include <vector>
00033 #include <map>
00034 #include <QTextStream>
00035 #include <QString>
00036
00037 #include "collisionStructures.h"
00038 #include "mytools.h"
00039 #include "kinematicChain.h"
00040 #include "dof.h"
00041 #include "worldElement.h"
00042 #include "body.h"
00043 #include "joint.h"
00044
00045 class Grasp;
00046 class GloveInterface;
00047 class CyberGlove;
00048 class EigenGraspInterface;
00049 class Matrix;
00050 class TiXmlElement;
00051
00053
00097 class Robot : public WorldElement {
00098 Q_OBJECT
00099
00100 signals:
00102 void configurationChanged();
00103
00105 void userInteractionStart();
00106
00108 void userInteractionEnd();
00109
00111 void moveDOFStepTaken(int numCols, bool &stopRequest);
00112
00113 private:
00114
00116 Robot *parent;
00118 int parentChainNum;
00120 transf tranToParentEnd;
00122 Link *mountPiece;
00123
00124 protected:
00125
00126
00128 int numChains;
00130 int numDOF;
00132 int numJoints;
00134 std::vector<KinematicChain *> chainVec;
00136 std::vector<DOF *> dofVec;
00138 Link *base;
00139
00140
00142 transf savedTran;
00144 QString savedDOF;
00146 bool savedState;
00147
00149 bool mRenderGeometry;
00150
00151
00153 double dofUpdateTime;
00155 double defaultTranslVel;
00157 double defaultRotVel;
00158
00159
00161 bool mUseCyberGlove;
00163 GloveInterface *mGloveInterface;
00165 bool mUsesFlock;
00167 int mBirdNumber;
00169 SoSeparator *IVFlockRoot;
00171 FlockTransf mFlockTran;
00172
00174 EigenGraspInterface* mEigenGrasps;
00175
00177
00179 transf approachTran;
00181 SoSeparator *IVApproachRoot;
00182
00184 void addFlockSensorGeometry();
00186 void addApproachGeometry();
00187
00189 virtual bool simpleContactsPreventMotion(const transf& motion) const;
00190
00192 inline virtual void simpleSetTran(transf const& tr);
00193
00195 virtual void setJointValues(const double* jointVals);
00197 virtual void setJointValuesAndUpdate(const double* jointVals);
00199 inline void getJointValues(double* jointVals) const;
00201 inline void updateDofVals(double *dofVals);
00203 virtual bool getJointValuesFromDOF(const double *desireddofVals, double *actualDofVals,
00204 double *jointVals, int *stoppedJoints);
00206 Matrix getJacobianJointToDOF(int chainNum);
00207
00209 bool jumpDOFToContact(double *desiredVals, int *stoppedJoints, int *numCols = NULL);
00211 int interpolateJoints(double *initialVals, double *finalVals, CollisionReport *colReport,
00212 double *interpolationTime);
00214 void stopJointsFromLink(Link *link, double *desiredJointVals, int *stoppedJoints);
00215
00217 virtual void getBodyList(std::vector<Body*> *bodies);
00218
00219 friend void KinematicChain::updateLinkPoses();
00220 friend void KinematicChain::attachRobot(Robot *r,const transf &offsetTr);
00221
00222 public:
00223
00226 Robot(World *w,const char *name) : WorldElement(w,name) {
00227 parent=NULL; parentChainNum = -1; mountPiece=NULL;
00228 numChains = numDOF = 0; base = NULL; dofUpdateTime=0.0;
00229 mUseCyberGlove = false; mGloveInterface = NULL; mUsesFlock = false;
00230 mEigenGrasps = NULL; mRenderGeometry = true; savedState = false;
00231 approachTran = transf::IDENTITY;
00232
00233 defaultTranslVel = 50; defaultRotVel = M_PI/4.0;
00234 }
00235
00237 virtual ~Robot();
00238
00239
00240
00242 virtual int loadFromXml(const TiXmlElement* root,QString rootPath);
00243
00245 virtual void cloneFrom(Robot *original);
00246
00247
00248
00250 bool moveDOFToContacts(double *desiredVals, double *desiredSteps, bool stopAtContact,
00251 bool renderIt=false);
00252
00254 virtual int setTran(transf const& tr);
00255
00257 inline void forceDOFVal(int dofNum,double val);
00258
00260 inline void forceDOFVals(double *dofVals);
00261
00262
00263
00265 void setDesiredDOFVals(double *dofVals);
00266
00268 bool contactSlip();
00269
00271 bool dynamicAutograspComplete();
00272
00274 virtual void updateJointValuesFromDynamics();
00275
00277 void applyJointPassiveInternalWrenches();
00278
00280 virtual void DOFController(double timeStep);
00281
00283 virtual void buildDOFCouplingConstraints(std::map<Body*,int> &islandIndices, int numBodies,
00284 double* Nu,double *eps,int &ncn);
00285
00287 virtual void buildDOFLimitConstraints(std::map<Body*,int> &islandIndices, int numBodies,
00288 double* H, double *g, int &hcn);
00289
00290
00291
00294 transf const &getTran() const {return base->getTran();}
00295
00297 virtual void fwdKinematics(double *dofVals,std::vector<transf>& trVec,int chainNum);
00298
00300 virtual int invKinematics(const transf& endTran,double* dofVals, int chainNum);
00301
00303 inline void getDOFVals(double *dofVals) const;
00304
00306 inline void storeDOFVals(double *dofVals) const;
00307
00308
00309
00311 inline bool checkDOFVals(double *dofVals) const;
00312
00314 inline bool checkSetDOFVals(double *dofVals) const;
00315
00317 virtual bool contactsPreventMotion(const transf& motion) const;
00318
00320 bool checkDOFPath(double *desiredVals, double desiredStep);
00321
00323 inline void updateDOFFromJoints(double *jointVals);
00324
00326 inline double jointLimitDist() const;
00327
00328
00329
00331 bool useCyberGlove(){return mUseCyberGlove;}
00332
00334 void setGlove(CyberGlove *glove);
00335
00337 void processCyberGlove();
00338
00340 GloveInterface* getGloveInterface(){return mGloveInterface;}
00341
00343 int getBirdNumber(){return mBirdNumber;}
00344
00346 bool usesFlock(){return mUsesFlock;}
00347
00349 const FlockTransf* getFlockTran() const {return &mFlockTran;}
00350
00352 FlockTransf* getFlockTran(){return &mFlockTran;}
00353
00354
00355
00357 int loadEigenData(QString filename);
00358
00360 int useIdentityEigenData();
00361
00363 const EigenGraspInterface* getEigenGrasps() const {return mEigenGrasps;}
00364
00366 EigenGraspInterface* getEigenGrasps() {return mEigenGrasps;}
00367
00368
00369
00371 virtual QTextStream &readDOFVals(QTextStream &is);
00372
00374 virtual QTextStream &writeDOFVals(QTextStream &os);
00375
00377 virtual void saveState();
00378
00380 virtual void restoreState();
00381
00382
00383
00385 int getNumContacts(Body* body = NULL);
00386
00388 std::list<Contact*> getContacts(Body* body = NULL);
00389
00391 void breakContacts();
00392
00394 int getNumVirtualContacts();
00395
00397 void showVirtualContacts(bool on);
00398
00400 int loadContactData(QString filename);
00401
00402
00403
00405 Robot *getBaseRobot() {if (parent) return parent->getBaseRobot(); return this;}
00406
00408 Robot *getParent() {return parent;}
00409
00411 int getParentChainNum() {return parentChainNum;}
00412
00415 const transf &getTranToParentEnd() {return tranToParentEnd;}
00416
00418 void getAllAttachedRobots(std::vector<Robot *> &robotVec);
00419
00421 void attachRobot(Robot *r,int chainNum,const transf &offsetTr);
00422
00424 void detachRobot(Robot *r);
00425
00427 Link *importMountPiece(QString filename);
00428
00430 Link *getMountPiece() const {return mountPiece;}
00431
00432
00433
00434 bool snapChainToContacts(int chainNum, CollisionReport colReport);
00435
00437 void setName(QString newName);
00438
00440 int getNumLinks() const;
00441
00443 int getNumDOF() const {return numDOF;}
00444
00446 DOF *getDOF(int i) const {return dofVec[i];}
00447
00449 float getDOFDraggerScale(int i) const {return dofVec[i]->getDraggerScale();}
00450
00452 int getNumChains() const {return numChains;}
00453
00455 int getNumJoints() const {return numJoints;}
00456
00458 KinematicChain *getChain(int i) const {return chainVec[i];}
00459
00461 Link *getBase() const {return base;}
00462
00464 void setTransparency(float t);
00465
00467 double getDefaultTranslVel() const {return defaultTranslVel;}
00468
00470 double getDefaultRotVel() const {return defaultRotVel;}
00471
00473 void setDefaultTranslVel(double v) {defaultTranslVel = v;}
00474
00476 void setDefaultRotVel(double v) {defaultRotVel = v;}
00477
00479 void setRenderGeometry(bool s);
00480
00482 bool getRenderGeometry() const {return mRenderGeometry;}
00483
00485 void getAllLinks(std::vector<DynamicBody *> &allLinkVec);
00486
00488 void setChainEndTrajectory(std::vector<transf>& traj,int chainNum);
00489
00491 void generateCartesianTrajectory(const transf &startTr, const transf &endTr,
00492 std::vector<transf> &traj,
00493 double startVel, double endVel=0.0, double timeNeeded=-1.0);
00494
00496 Matrix staticJointTorques(bool useDynamicDofForce);
00497
00499 transf getApproachTran() const {return approachTran;}
00500
00502 double getApproachDistance(Body *object, double maxDist);
00503
00504
00505
00507 void emitConfigChange(){emit configurationChanged();}
00509 void emitUserInteractionStart(){emit userInteractionStart();}
00511 void emitUserInteractionEnd(){emit userInteractionEnd();}
00512 };
00513
00517 void Robot::updateDofVals(double *dofVals)
00518 {
00519 for (int d=0; d<numDOF; d++) {
00520 dofVec[d]->updateVal(dofVals[d]);
00521 }
00522 }
00523
00527 void Robot::getJointValues(double *jointVals) const
00528 {
00529 for (int c=0; c<numChains; c++) {
00530 chainVec[c]->getJointValues(jointVals);
00531 }
00532 }
00533
00537 double Robot::jointLimitDist() const
00538 {
00539 double dist, minDist = 1.0e10;
00540 for (int c=0; c<numChains; c++) {
00541 for (int j=0; j<chainVec[c]->getNumJoints(); j++) {
00542 double val = chainVec[c]->getJoint(j)->getVal();
00543 dist = std::min( chainVec[c]->getJoint(j)->getMax() - val,
00544 val - chainVec[c]->getJoint(j)->getMin() );
00545 minDist = std::min(dist, minDist);
00546 }
00547 }
00548 return minDist;
00549 }
00550
00555 void Robot::simpleSetTran(transf const& tr) {
00556 base->setTran(tr);
00557 if (mountPiece) mountPiece->setTran(tr);
00558 for (int f=0;f<numChains;f++) chainVec[f]->updateLinkPoses();
00559 }
00560
00564 void Robot::getDOFVals(double *dofVals) const {
00565 for (int d=0;d<numDOF;d++) dofVals[d]=dofVec[d]->getVal();
00566 }
00567
00587 void Robot::storeDOFVals(double *dofVals) const {
00588 for (int d=0;d<numDOF;d++) dofVals[d]=dofVec[d]->getSaveVal();
00589 }
00590
00595 void Robot::forceDOFVal(int dofNum,double val) {
00596 double *jointVals = new double[numJoints];
00597 getJointValues(jointVals);
00598 dofVec[dofNum]->reset();
00599 dofVec[dofNum]->accumulateMove(val, jointVals, NULL);
00600 setJointValuesAndUpdate(jointVals);
00601 dofVec[dofNum]->updateVal(val);
00602 delete [] jointVals;
00603 }
00604
00608 void Robot::forceDOFVals(double *dofVals) {
00609 double *jointVals = new double[numJoints];
00610 getJointValues(jointVals);
00611 for (int d=0; d<numDOF; d++) {
00612 dofVec[d]->reset();
00613 dofVec[d]->accumulateMove(dofVals[d], jointVals, NULL);
00614 }
00615 setJointValuesAndUpdate(jointVals);
00616 updateDofVals(dofVals);
00617 delete [] jointVals;
00618 }
00619
00623 void Robot::updateDOFFromJoints(double *jointVals) {
00624 for (int d=0; d<numDOF; d++) {
00625 dofVec[d]->updateFromJointValues(jointVals);
00626 }
00627 }
00628
00630 bool Robot::checkDOFVals(double *dofVals) const {
00631 for (int d=0;d<numDOF;d++) {
00632 if ( dofVals[d] > dofVec[d]->getMax()) return false;
00633 if ( dofVals[d] < dofVec[d]->getMin()) return false;
00634 }
00635 return true;
00636 }
00637
00641 bool Robot::checkSetDOFVals(double *dofVals) const {
00642 bool atLeastOneValid = false;
00643 for (int d=0;d<numDOF;d++) {
00644 if ( dofVals[d] > dofVec[d]->getMax()) {
00645 dofVals[d] = dofVec[d]->getMax();
00646 } else if ( dofVals[d] < dofVec[d]->getMin()) {
00647 dofVals[d] = dofVec[d]->getMin();
00648 }
00649 else atLeastOneValid = true;
00650 }
00651 return atLeastOneValid;
00652 }
00653
00654
00656
00669 class Hand : public Robot {
00670 Q_OBJECT
00671
00672 protected:
00674 Grasp *grasp;
00675
00676 public:
00678 Hand(World *w,const char *name);
00680 virtual ~Hand();
00681
00683 virtual void cloneFrom(Hand *original);
00684
00687 int getNumFingers() const {return numChains;}
00688
00690 KinematicChain *getFinger(int i) const {return chainVec[i];}
00691
00693 Link *getPalm() const {return base;}
00694
00696 Grasp *getGrasp() const {return grasp;}
00697
00699 virtual bool autoGrasp(bool renderIt, double speedFactor = 1.0, bool stopAtContact = false);
00700
00702 virtual bool quickOpen(double speedFactor = 0.1);
00703
00705 virtual bool approachToContact(double moveDist, bool oneStep = true);
00706
00708 virtual bool findInitialContact(double moveDist);
00709 };
00710
00711 #define ROBOT_H
00712 #endif
00713