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
00029 #include <iomanip>
00030 #include <QFile>
00031 #include <QTextStream>
00032
00033
00034 #include "SoArrow.h"
00035 #include <Inventor/nodes/SoCube.h>
00036
00037 #include "bBox.h"
00038 #include "mytools.h"
00039 #include "matvecIO.h"
00040 #include "robot.h"
00041 #include "joint.h"
00042 #include "dynJoint.h"
00043 #include "world.h"
00044 #include "grasp.h"
00045 #include "graspitGUI.h"
00046 #include "ivmgr.h"
00047 #include "dynamics.h"
00048 #include "gloveInterface.h"
00049 #include "eigenGrasp.h"
00050 #include "matrix.h"
00051 #include "tinyxml.h"
00052
00053 #ifdef USE_DMALLOC
00054 #include "dmalloc.h"
00055 #endif
00056
00057
00058 #include "debug.h"
00059
00060 #define PROF_ENABLED
00061 #include "profiling.h"
00062
00063 PROF_DECLARE(MOVE_DOF);
00064
00065 const double Robot::AUTO_GRASP_TIME_STEP = 0.01;
00066
00071 Robot::~Robot()
00072 {
00073 for (int i=0;i<numChains;i++) {
00074 if (chainVec[i]) delete chainVec[i];
00075 }
00076 for (int i=0;i<numDOF;i++) {
00077 if (dofVec[i]) delete dofVec[i];
00078 }
00079 if (base) myWorld->destroyElement(base);
00080 if (mountPiece) myWorld->destroyElement(mountPiece);
00081 if (parent) parent->detachRobot(this);
00082 if (mGloveInterface) delete mGloveInterface;
00083 if (mEigenGrasps) delete mEigenGrasps;
00084
00085 std::cout << "Deleted robot: " << name() <<std::endl;
00086 }
00087
00095 int
00096 Robot::loadFromXml(const TiXmlElement* root,QString rootPath)
00097 {
00098 QString robotName = root->Attribute("type");
00099 if(robotName.isNull()){
00100 QTWARNING("Robot Name undefined");
00101 return FAILURE;
00102 }
00103 const TiXmlElement* element = findXmlElement(root,"palm");
00104 QString valueStr;
00105 QString ivdir = rootPath + "iv/";
00106
00107 DBGA("Creating base...\n");
00108 if(element){
00109 valueStr = element->GetText();
00110 valueStr = valueStr.stripWhiteSpace();
00111 base = new Link(this,-1,-1,myWorld,(QString(name())+"Base").latin1());
00112 if (!base || base->load(ivdir+valueStr)==FAILURE) {
00113 if (base) delete base;
00114 base = NULL;
00115 DBGA("Failed to load base");
00116 return FAILURE;
00117 }
00118 base->addToIvc();
00119
00120
00121 IVRoot = new SoSeparator;
00122 IVRoot->addChild(base->getIVRoot());
00123 }
00124 else{
00125 QTWARNING("Base not found");
00126 return FAILURE;
00127 }
00128 std::list<const TiXmlElement*> elementList = findAllXmlElements(root, "dof");
00129 numDOF = countXmlElements(root, "dof");
00130 if (numDOF < 1) {
00131 DBGA("Wrong number of DOFs specified: " << numDOF);
00132 return FAILURE;
00133 }
00134 DBGA("Setting up " << numDOF << " degrees of freedom...");
00135 dofVec.resize(numDOF, NULL);
00136
00137
00138 std::list<const TiXmlElement*>::iterator p = elementList.begin();
00139 int f=0;
00140 while(p!=elementList.end()){
00141 valueStr = (*p)->Attribute("type");
00142 if(valueStr.isNull()){
00143 QTWARNING("DOF Type not found");
00144 return FAILURE;
00145 }
00146 QString dofType = valueStr.stripWhiteSpace();
00147 if(dofType == "r")
00148 dofVec[f] = new RigidDOF();
00149 else if(dofType == "b")
00150 dofVec[f] = new BreakAwayDOF();
00151 else if(dofType == "c")
00152 dofVec[f] = new CompliantDOF();
00153 else {
00154 DBGA("Unknown DOF Type requested: " << dofType.toStdString() << " for DOF " << f);
00155 return FAILURE;
00156 }
00157 dofVec[f]->dofNum = f;
00158 if (!dofVec[f]->readParametersFromXml(*p)) {
00159 DBGA("Failed to read DOF " << f );
00160 return FAILURE;
00161 }
00162 p++;
00163 f++;
00164 }
00165
00166
00167 numChains = countXmlElements(root,"chain");
00168 if (numChains < 1) {
00169 DBGA("Wrong number of chains");
00170 return FAILURE;
00171 }
00172 DBGA("Creating " << numChains << " kinematic chains (fingers)...");
00173 chainVec.resize(numChains, NULL);
00174
00175
00176 numJoints = 0;
00177 f = 0;
00178 elementList = findAllXmlElements(root, "chain");
00179 p = elementList.begin();
00180 while(p!=elementList.end()){
00181 fprintf(stderr, "Chain %d: ",f);
00182 chainVec[f] = new KinematicChain(this,f, numJoints);
00183 if (chainVec[f]->initChainFromXml((*p),ivdir)==FAILURE) {
00184 DBGA("Failed to read chain " << f);
00185 return FAILURE;
00186 }
00187 numJoints += chainVec[f]->getNumJoints();
00188 p++;
00189 f++;
00190 }
00191
00192
00193 std::list<Joint *>jointList;
00194 for (int d=0; d<numDOF; d++) {
00195 jointList.clear();
00196 for (int f=0; f<numChains; f++) {
00197 for (int j=0; j<chainVec[f]->getNumJoints(); j++) {
00198 if (chainVec[f]->getJoint(j)->getDOFNum() == d) {
00199 jointList.push_back(chainVec[f]->getJoint(j));
00200 }
00201 }
00202 }
00203 dofVec[d]->initDOF(this,jointList);
00204 }
00205
00206
00207 getBase()->fix();
00208 for (int i=0; i<getNumDOF(); i++) {
00209 getDOF(i)->setDesiredPos( getDOF(i)->getVal() );
00210 }
00211
00212
00213
00214
00215 approachTran = transf::IDENTITY;
00216 element = findXmlElement(root,"approachDirection");
00217 if(element){
00218 const TiXmlElement* tmp = findXmlElement(element,"referenceLocation");
00219 if(!tmp){
00220 DBGA("Failed to read approach direction");
00221 return FAILURE;
00222 }
00223 valueStr = tmp->GetText();
00224 valueStr = valueStr.simplifyWhiteSpace().stripWhiteSpace();
00225 QStringList l = QStringList::split(' ', valueStr);
00226 if(l.count()!=3){
00227 DBGA("Invalid approach direction input");
00228 return FAILURE;
00229 }
00230 bool ok1, ok2, ok3;
00231 float locX, locY, locZ;
00232 locX = l[0].toFloat(&ok1);
00233 locY = l[1].toFloat(&ok2);
00234 locZ = l[2].toFloat(&ok3);
00235 if(!ok1 || !ok2 || !ok3){
00236 DBGA("Invalid approach direction input");
00237 return FAILURE;
00238 }
00239 vec3 aPt = vec3(locX, locY, locZ);
00240
00241 tmp = findXmlElement(element,"direction");
00242 if(!tmp){
00243 DBGA("Failed to read approach direction");
00244 return FAILURE;
00245 }
00246 valueStr = tmp->GetText();
00247 valueStr = valueStr.simplifyWhiteSpace().stripWhiteSpace();
00248 l = QStringList::split(' ', valueStr);
00249 if(l.count()!=3){
00250 DBGA("Invalid approach direction input");
00251 return FAILURE;
00252 }
00253 locX = l[0].toFloat(&ok1);
00254 locY = l[1].toFloat(&ok2);
00255 locZ = l[2].toFloat(&ok3);
00256 if(!ok1 || !ok2 || !ok3){
00257 DBGA("Invalid approach direction input");
00258 return FAILURE;
00259 }
00260 vec3 zdir = vec3(locX, locY, locZ);
00261 zdir = normalise(zdir);
00262
00263 vec3 xdir;
00264 if ( fabs(zdir % vec3(1,0,0)) > 0.9 ) xdir = vec3(0,1,0);
00265 else xdir = vec3(1,0,0);
00266 vec3 ydir = zdir * xdir;
00267 xdir = ydir * zdir;
00268
00269 mat3 r(xdir, ydir, zdir);
00270 approachTran.set(r, aPt);
00271 }
00272 addApproachGeometry();
00273
00274
00275 mEigenGrasps = new EigenGraspInterface(this);
00276 bool eigenLoaded = false;
00277 element = findXmlElement(root,"eigenGrasps");
00278 if(element) {
00279 valueStr = element->GetText();
00280 valueStr = valueStr.stripWhiteSpace();
00281 QString eigenFile = rootPath + valueStr;
00282 if (loadEigenData(eigenFile)==SUCCESS) {
00283 DBGA("Using eigengrasps from file: " << valueStr.latin1());
00284 eigenLoaded = true;
00285 }
00286 }
00287 if (!eigenLoaded) {
00288 mEigenGrasps->setTrivial();
00289 DBGA("Using identity eigengrasps");
00290 }
00291
00292
00293 element = findXmlElement(root,"virtualContacts");
00294 if(element){
00295 valueStr = element->GetText();
00296 valueStr = valueStr.stripWhiteSpace();
00297 QString contactFile = rootPath + valueStr;
00298 if (loadContactData(contactFile)==SUCCESS) {
00299 DBGA("Loaded virtual contacts from file " << valueStr.latin1());
00300 showVirtualContacts(true);
00301 } else {
00302 DBGA("Failed to load virtual contacts from file " << valueStr.latin1());
00303 }
00304 }
00305
00306
00307 mUseCyberGlove = false;
00308 element = findXmlElement(root,"cyberGlove");
00309 if(element){
00310 valueStr = element->GetText();
00311 valueStr = valueStr.stripWhiteSpace();
00312 mGloveInterface = new GloveInterface(this);
00313 QString calibFile = rootPath + valueStr;
00314 if (!mGloveInterface->loadCalibration(calibFile.latin1())) {
00315 DBGA("Failed to load glove calibration file " << calibFile.latin1());
00316 delete mGloveInterface; mGloveInterface = NULL;
00317 mUseCyberGlove = false;
00318 } else {
00319 DBGA("Cyberglove calibration loaded from " << calibFile.latin1());
00320 mUseCyberGlove = true;
00321 }
00322 }
00323
00324
00325 element = findXmlElement(root,"flockOfBirds");
00326 if(element){
00327 QString birdNumber = element->Attribute("number");
00328 if(birdNumber.isNull()){
00329 DBGA("There was a problem reading the Flock of Birds data in the configuration file");
00330 return FAILURE;
00331 }
00332 birdNumber = birdNumber.stripWhiteSpace();
00333 mBirdNumber = birdNumber.toInt();
00334 transf sensorTrans;
00335 const TiXmlElement* tmp = findXmlElement(element,"transform");
00336 if(!getTransform(tmp, sensorTrans)){
00337 DBGA("There was a problem reading the Flock of Birds data in the configuration file");
00338 return FAILURE;
00339 }
00340 mFlockTran.identity();
00341 mFlockTran.setMount(sensorTrans);
00342 mUsesFlock = true;
00343 DBGA("Robot using Flock of Birds sensor " << mBirdNumber);
00344 }
00345 if (mUsesFlock) {
00346 addFlockSensorGeometry();
00347 }
00348 return SUCCESS;
00349 }
00350
00352 int
00353 Robot::loadEigenData(QString filename)
00354 {
00355 if ( !mEigenGrasps->readFromFile(filename.latin1()) ) {
00356 DBGA("Unable to load eigenGrasp file " << filename.latin1());
00357 return FAILURE;
00358 }
00359 QString name = filename.section('/',-1,-1);
00360 name = name.section('.',0,0);
00361 mEigenGrasps->setName(name);
00362 return SUCCESS;
00363 }
00364
00367 int
00368 Robot::loadContactData(QString filename)
00369 {
00370 FILE *fp = fopen(filename.latin1(), "r");
00371 if (!fp) {
00372 DBGA("Could not open contact file " << filename.latin1());
00373 return FAILURE;
00374 }
00375
00376 char robotName[500];
00377 ;
00378 if(fscanf(fp,"%s",robotName) <= 0)
00379 {
00380 DBGA("Robot::loadContactData - failed to read robot name");
00381 return 0;
00382 }
00383
00384 int numContacts;
00385 if( fscanf(fp,"%d",&numContacts) <= 0){
00386 DBGA("Robot::loadContactData - failed to read number of contacts");
00387 return -1;
00388 }
00389
00390 for (int i=0; i<numContacts; i++) {
00391 VirtualContact* newContact = new VirtualContact();
00392 newContact->readFromFile(fp);
00393 int f = newContact->getFingerNum();
00394 int l = newContact->getLinkNum();
00395 if ( f >= 0) {
00396 if ( f>=getNumChains() || l>=getChain(f)->getNumLinks()) {
00397 DBGA("Virtual contact error, chain " << f << " link " << l << " does not exist");
00398 delete newContact;
00399 continue;
00400 }
00401 newContact->setBody( getChain(f)->getLink(l) );
00402 getChain(f)->getLink(l)->addVirtualContact( newContact );
00403 }
00404 else {
00405 newContact->setBody( getBase() );
00406 getBase()->addVirtualContact(newContact);
00407 }
00408 newContact->computeWrenches(false,false);
00409 }
00410 fclose(fp);
00411 return SUCCESS;
00412 }
00413
00424 void
00425 Robot::cloneFrom(Robot *original)
00426 {
00427 myName = original->getName() + QString(" clone");
00428
00429
00430 if (base) delete base;
00431 base = new Link(this,-1,-1,myWorld,(QString(name())+"Base").latin1());
00432 base->cloneFrom( original->getBase() );
00433
00434 IVRoot = new SoSeparator;
00435 IVRoot->addChild(base->getIVRoot());
00436
00437 numDOF = original->getNumDOF();
00438 dofVec.resize(numDOF, NULL);
00439 for (int f=0; f<numDOF; f++) {
00440 switch(original->getDOF(f)->getType()) {
00441 case DOF::RIGID:
00442 dofVec[f] = new RigidDOF( (RigidDOF*)(original->getDOF(f)) );
00443 break;
00444 case DOF::BREAKAWAY:
00445 dofVec[f] = new BreakAwayDOF( (BreakAwayDOF*)(original->getDOF(f)) );
00446 break;
00447 case DOF::COMPLIANT:
00448 dofVec[f] = new CompliantDOF( (CompliantDOF*)(original->getDOF(f)) );
00449 break;
00450 default:
00451 DBGA("ERROR: Unknown DOF type in original!");
00452 assert(0);
00453 }
00454 }
00455
00456 numChains = original->getNumChains();
00457 chainVec.resize(numChains, NULL);
00458 numJoints = 0;
00459 for (int f=0; f<numChains; f++) {
00460 chainVec[f] = new KinematicChain(this,f,numJoints);
00461 chainVec[f]->cloneFrom( original->getChain(f) );
00462 numJoints += chainVec[f]->getNumJoints();
00463 }
00464 assert (numJoints == original->getNumJoints() );
00465
00466 std::list<Joint *>jointList;
00467 for (int d=0; d<numDOF; d++) {
00468 jointList.clear();
00469 for (int f=0; f<numChains; f++) {
00470 for (int j=0; j<chainVec[f]->getNumJoints(); j++) {
00471 if (chainVec[f]->getJoint(j)->getDOFNum() == d) {
00472 jointList.push_back(chainVec[f]->getJoint(j));
00473 }
00474 }
00475 }
00476 dofVec[d]->initDOF(this,jointList);
00477 }
00478
00479 base->setTran(transf::IDENTITY);
00480
00481 getBase()->fix();
00482 for (int i=0; i<getNumDOF(); i++) {
00483 getDOF(i)->setDesiredPos( getDOF(i)->getVal() );
00484 }
00485
00486 setRenderGeometry( original->getRenderGeometry() );
00487
00488
00489 approachTran = original->getApproachTran();
00490 addApproachGeometry();
00491
00492
00493 mEigenGrasps = new EigenGraspInterface(original->getEigenGrasps());
00494
00495
00496 mGloveInterface = NULL;
00497 this->mUseCyberGlove = false;
00498 }
00499
00503 void
00504 Robot::setTransparency(float t)
00505 {
00506 base->setTransparency(t);
00507 for (int i=0; i<getNumChains(); i++) {
00508 for (int l=0; l<getChain(i)->getNumLinks(); l++) {
00509 getChain(i)->getLink(l)->setTransparency(t);
00510 }
00511 }
00512 }
00513
00517 void
00518 Robot::setName(QString newName)
00519 {
00520 WorldElement::setName(newName);
00521 for (int c=0; c<getNumChains(); c++) {
00522 for (int l=0; l<getChain(c)->getNumLinks(); l++){
00523 getChain(c)->getLink(l)->setName( newName + QString("_chain%1_link%2").arg(c).arg(l) );
00524 }
00525 }
00526 if (base) base->setName(newName + QString("_base"));
00527 }
00528
00533 void
00534 Robot::addApproachGeometry()
00535 {
00536 IVApproachRoot = new SoSeparator();
00537
00538 SoTransform *t1 = new SoTransform();
00539 approachTran.toSoTransform(t1);
00540 IVApproachRoot->addChild(t1);
00541
00542 SoArrow *arrow = new SoArrow;
00543 arrow->height = 14;
00544 arrow->cylRadius = (float)1.25;
00545 arrow->coneRadius = (float)2.6;
00546 arrow->coneHeight = (float)5.5;
00547 SoTransform *arrowTran = new SoTransform();
00548 arrowTran->rotation.setValue(SbVec3f(1,0,0),(float)(M_PI/2.0));
00549 IVApproachRoot->addChild(arrowTran);
00550 IVApproachRoot->addChild(arrow);
00551
00552 getBase()->getIVRoot()->addChild(IVApproachRoot);
00553 }
00554
00559 void
00560 Robot::addFlockSensorGeometry()
00561 {
00562 IVFlockRoot = new SoSeparator();
00563 SoTransform *t = new SoTransform();
00564 mFlockTran.getMount().toSoTransform( t );
00565 IVFlockRoot->addChild(t);
00566 SoCube *cube = new SoCube();
00567 cube->width = 30;
00568 cube->height = 20;
00569 cube->depth = 4;
00570 IVFlockRoot->addChild(cube);
00571 SoCube *smallCube = new SoCube();
00572 smallCube->width = 10;
00573 smallCube->height = 20;
00574 smallCube->depth = 6;
00575 SoTransform *t2 = new SoTransform();
00576 t2->translation.setValue(10,0,-5);
00577 IVFlockRoot->addChild(t2);
00578 IVFlockRoot->addChild(smallCube);
00579 getBase()->getIVRoot()->addChild(IVFlockRoot);
00580 }
00581
00586 int
00587 Robot::useIdentityEigenData()
00588 {
00589 if (!mEigenGrasps->setTrivial()) {
00590 QTWARNING("Error setting Identity EigenGrasps");
00591 return FAILURE;
00592 }
00593 return SUCCESS;
00594 }
00595
00600 void Robot::setGlove(CyberGlove *glove)
00601 {
00602 if (!mGloveInterface) {
00603 mUseCyberGlove = false;
00604 return;
00605 }
00606 mGloveInterface->setGlove(glove);
00607 }
00608
00613 void
00614 Robot::processCyberGlove()
00615 {
00616 int i;
00617 double *desiredVals = new double[getNumDOF()];
00618 for (i=0; i<getNumDOF(); i++) {
00619 if ( mGloveInterface->isDOFControlled(i) ) {
00620 desiredVals[i] = mGloveInterface->getDOFValue(i);
00621 if ( desiredVals[i] < getDOF(i)->getMin() ) desiredVals[i] = getDOF(i)->getMin();
00622 if ( desiredVals[i] > getDOF(i)->getMax() ) desiredVals[i] = getDOF(i)->getMax();
00623 }
00624 else {
00625 desiredVals[i] = getDOF(i)->getVal();
00626 }
00627 }
00628 moveDOFToContacts(desiredVals, NULL, false);
00629 emitConfigChange();
00630 delete [] desiredVals;
00631 }
00632
00637 Link *
00638 Robot::importMountPiece(QString filename)
00639 {
00640 QString mountName = QString(name())+"_mount";
00641 mountPiece = new Link(this,-1,-1,myWorld,mountName.latin1());
00642 if (mountPiece->load(filename)==FAILURE){
00643 delete mountPiece; mountPiece = NULL; return NULL;
00644 }
00645 mountPiece->addToIvc();
00646 IVRoot->addChild(mountPiece->getIVRoot());
00647 mountPiece->setTran(base->getTran());
00648 base->setDynJoint(new FixedDynJoint(mountPiece,base));
00649 return mountPiece;
00650 }
00651
00655 void
00656 Robot::getBodyList(std::vector<Body*> *bodies)
00657 {
00658 if (base) bodies->push_back(base);
00659 if (mountPiece) bodies->push_back(mountPiece);
00660 for (int c=0; c<numChains; c++) {
00661 for (int l=0; l<chainVec[c]->getNumLinks(); l++) {
00662 bodies->push_back(chainVec[c]->getLink(l));
00663 }
00664 }
00665 for (int c=0; c<numChains; c++) {
00666 for (int i=0; i<chainVec[c]->getNumAttachedRobots(); i++) {
00667 chainVec[c]->getAttachedRobot(i)->getBodyList(bodies);
00668 }
00669 }
00670 }
00671
00676 void
00677 Robot::getAllLinks(std::vector<DynamicBody *> &allLinkVec)
00678 {
00679 int c,l,i;
00680 if (base) allLinkVec.push_back(base);
00681 if (mountPiece) allLinkVec.push_back(mountPiece);
00682
00683 for (c=0;c<numChains;c++)
00684 for (l=0;l<chainVec[c]->getNumLinks();l++)
00685 allLinkVec.push_back(chainVec[c]->getLink(l));
00686 for (c=0;c<numChains;c++)
00687 for (i=0;i<chainVec[c]->getNumAttachedRobots();i++)
00688 chainVec[c]->getAttachedRobot(i)->getAllLinks(allLinkVec);
00689 }
00690
00695 void
00696 Robot::getAllAttachedRobots(std::vector<Robot *> &robotVec)
00697 {
00698 robotVec.push_back(this);
00699 for (int c=0;c<numChains;c++) {
00700 for (int i=0;i<chainVec[c]->getNumAttachedRobots();i++) {
00701 chainVec[c]->getAttachedRobot(i)->getAllAttachedRobots(robotVec);
00702 }
00703 }
00704 }
00705
00706
00717 void
00718 Robot::attachRobot(Robot *r,int chainNum,const transf &offsetTr)
00719 {
00720 r->parent = this;
00721 r->parentChainNum = chainNum;
00722 r->tranToParentEnd = offsetTr.inverse();
00723 chainVec[chainNum]->attachRobot(r,offsetTr);
00724
00725 Link *lastLink = chainVec[chainNum]->getLink(chainVec[chainNum]->getNumLinks()-1);
00726 myWorld->toggleCollisions(false, lastLink, r->getBase());
00727 if (r->getMountPiece()) {
00728 myWorld->toggleCollisions(false, lastLink, r->getMountPiece());
00729 }
00730 }
00731
00732
00737 void
00738 Robot::detachRobot(Robot *r)
00739 {
00740 DBGA("Detaching Robot " << r->getName().latin1() << " from " << getName().latin1());
00741 r->parent = NULL;
00742 chainVec[r->parentChainNum]->detachRobot(r);
00743 }
00744
00745
00752 void
00753 Robot::fwdKinematics(double* dofVals,std::vector<transf>& trVec,int chainNum)
00754 {
00755 double *jointVals = new double[numJoints];
00756 getJointValues(jointVals);
00757 for (int d=0; d<numDOF; d++) {
00758 dofVec[d]->accumulateMove(dofVals[d], jointVals, NULL);
00759 }
00760 chainVec[chainNum]->fwdKinematics(jointVals,trVec);
00761 delete [] jointVals;
00762 }
00763
00769 int
00770 Robot::invKinematics(const transf& targetPos, double* dofVals, int chainNum)
00771 {
00772
00773
00774 double factor = 0, epsilon = 0.0001, upperBound = 0.2;
00775 const int safeGuardUpperBound = 200;
00776 Matrix deltaPR(6,1);
00777 deltaPR.setAllElements(1.0);
00778 Matrix deltaDOF(numDOF, 1);
00779 std::vector<double> currentDOFVals(numDOF);
00780
00781 for(int i = 0; i < numDOF; ++i){
00782
00783 currentDOFVals[i] = dofVec[i]->getVal();
00784
00785 dofVals[i] = dofVec[i]->getVal();
00786 }
00787
00788 std::vector<transf> fwdK;
00789 fwdK.resize(chainVec[chainNum]->getNumLinks(), transf::IDENTITY);
00790 transf currentPos;
00791
00792
00793
00794
00795 fwdKinematics(¤tDOFVals[0], fwdK, chainNum);
00796 currentPos = fwdK[chainVec[chainNum]->getNumLinks() - 1];
00797
00798 DBGP("from: " << currentPos.translation().x() << " " <<
00799 currentPos.translation().y() << " " <<
00800 currentPos.translation().z() << " " <<
00801 currentPos.rotation().w << " " <<
00802 currentPos.rotation().x << " " <<
00803 currentPos.rotation().y << " " <<
00804 currentPos.rotation().z);
00805
00806 DBGP("to: " << targetPos.translation().x() << " " <<
00807 targetPos.translation().y() << " " <<
00808 targetPos.translation().z() << " " <<
00809 targetPos.rotation().w << " " <<
00810 targetPos.rotation().x << " " <<
00811 targetPos.rotation().y << " " <<
00812 targetPos.rotation().z);
00813
00814 int safeguard = 0;
00815 while(++safeguard < safeGuardUpperBound){
00816
00817
00818 fwdKinematics(¤tDOFVals[0], fwdK, chainNum);
00819 currentPos = fwdK[chainVec[chainNum]->getNumLinks() - 1];
00820
00821 vec3 dtLocation, dtOrientation;
00822 dtLocation = targetPos.translation() - currentPos.translation();
00823
00824 vec3 v1, v2;
00825 mat3 m1, m2;
00826 currentPos.rotation().ToRotationMatrix(m1);
00827 targetPos.rotation().ToRotationMatrix(m2);
00828
00829 v1 = vec3(m1.element(0,0), m1.element(0,1), m1.element(0,2));
00830 v2 = vec3(m2.element(0,0), m2.element(0,1), m2.element(0,2));
00831 dtOrientation = v1 * v2;
00832 v1 = vec3(m1.element(1,0), m1.element(1,1), m1.element(1,2));
00833 v2 = vec3(m2.element(1,0), m2.element(1,1), m2.element(1,2));
00834 dtOrientation += v1 * v2;
00835 v1 = vec3(m1.element(2,0), m1.element(2,1), m1.element(2,2));
00836 v2 = vec3(m2.element(2,0), m2.element(2,1), m2.element(2,2));
00837 dtOrientation += v1 * v2;
00838 dtOrientation *= 0.5;
00839
00840 deltaPR.elem(0,0) = dtLocation[0];
00841 deltaPR.elem(1,0) = dtLocation[1];
00842 deltaPR.elem(2,0) = dtLocation[2];
00843 deltaPR.elem(3,0) = dtOrientation[0];
00844 deltaPR.elem(4,0) = dtOrientation[1];
00845 deltaPR.elem(5,0) = dtOrientation[2];
00846
00847 Matrix m = chainVec[chainNum]->actuatedJacobian(chainVec[chainNum]->linkJacobian(true));
00848 Matrix jointJacobian = m.getSubMatrix(m.rows() - 6, 0, 6, chainVec[chainNum]->getNumJoints());
00849 Matrix jointToDOFJacobian = getJacobianJointToDOF(chainNum);
00850 Matrix DOFJacobian = Matrix(jointJacobian.rows(), jointToDOFJacobian.cols());
00851 matrixMultiply(jointJacobian, jointToDOFJacobian, DOFJacobian);
00852
00853
00854
00855
00856
00857
00858
00859
00860
00861
00862
00863
00864
00865
00866
00867
00868 underDeterminedSolveQR(DOFJacobian, deltaPR, deltaDOF);
00869
00870
00871
00872
00873
00874
00875
00876
00877
00878 for(int i = 0; i < numDOF; ++i){
00879
00880 currentDOFVals[i] += deltaDOF.elem(i,0);
00881
00882 currentDOFVals[i] -= (int)(currentDOFVals[i]/(2*M_PI)) * 2 * M_PI;
00883 }
00884
00885
00886 factor = -1.0;
00887 for(int i = 0; i < deltaDOF.cols(); ++i){
00888 factor = factor > fabs(deltaDOF.elem(i,0)) ? factor : fabs(deltaDOF.elem(i,0));
00889 }
00890
00891
00892 if(factor < epsilon){
00893 for(int k = 0; k < numDOF; ++k){
00894
00895
00896 if(fabs(dofVals[k] - currentDOFVals[k]) > upperBound){
00897 std::cout << "exceeds the upper bound at DOF: " << k << " , jumping to another pose\n";
00898 return FAILURE;
00899 }
00900 dofVals[k] = currentDOFVals[k];
00901 }
00902 break;
00903 }
00904 }
00905
00906 for(int i = 0; i < numChains; ++i){
00907 for(int j = 0; j < chainVec[i]->getNumJoints(); ++j){
00908 double jnt = dofVals[chainVec[i]->getJoint(j)->getDOFNum()] *
00909 chainVec[i]->getJoint(j)->getCouplingRatio();
00910 if(jnt > chainVec[i]->getJoint(j)->getMax() ||
00911 jnt < chainVec[i]->getJoint(j)->getMin()){
00912 std::cout << "inverse kinematics in invalid joint value: " << i << "th chain, " << j << "th joint\n";
00913 return FAILURE;
00914 }
00915 }
00916 }
00917
00918 if(safeguard >= safeGuardUpperBound){
00919 std::cout << "safeguard hit\n";
00920 return FAILURE;
00921 }
00922
00923
00924
00925
00926
00927
00928
00929
00930
00931
00932
00933 return SUCCESS;
00934 }
00935
00943 bool
00944 Robot::simpleContactsPreventMotion(const transf& motion) const
00945 {
00946 transf linkMotion;
00947 transf baseToLink;
00948
00949 for (int i=0;i<numChains;i++) {
00950 for (int j=0; j<chainVec[i]->getNumLinks();j++) {
00951 if (chainVec[i]->getLink(j)->getNumContacts()) {
00952 baseToLink = chainVec[i]->getLink(j)->getTran() * base->getTran().inverse();
00953 linkMotion = baseToLink * motion * baseToLink.inverse();
00954 if (chainVec[i]->getLink(j)->externalContactsPreventMotion(linkMotion))
00955 return true;
00956 }
00957 }
00958
00959 for (int j=0;j<chainVec[i]->getNumAttachedRobots();j++) {
00960 baseToLink = chainVec[i]->getAttachedRobot(j)->getBase()->getTran() * base->getTran().inverse();
00961 linkMotion = baseToLink * motion * baseToLink.inverse();
00962 if (chainVec[i]->getAttachedRobot(j)->simpleContactsPreventMotion(linkMotion))
00963 return true;
00964 }
00965 }
00966 return false;
00967 }
00968
00969
00978 bool
00979 Robot::contactsPreventMotion(const transf& motion) const
00980 {
00981 int l;
00982 transf linkMotion;
00983
00984
00985 if (base->externalContactsPreventMotion(motion)) return true;
00986 if (mountPiece && mountPiece->contactsPreventMotion(motion)) return true;
00987
00988
00989 if (simpleContactsPreventMotion(motion)) return true;
00990
00991
00992
00993 if (parent) {
00994 transf newTran = tranToParentEnd*motion*base->getTran();
00995 KinematicChain *chain = parent->getChain(parentChainNum);
00996 std::vector<transf> parentTrVec(chain->getNumLinks());
00997 double *dofVals = new double[parent->getNumDOF()];
00998
00999 if (parent->invKinematics(newTran,dofVals,parentChainNum)==FAILURE){
01000 delete [] dofVals;
01001 return true;
01002 }
01003
01004 parent->fwdKinematics(dofVals,parentTrVec,parentChainNum);
01005 delete [] dofVals;
01006
01007 for (l=0;l<chain->getNumLinks();l++) {
01008 if (chain->getLink(l)->getNumContacts()) {
01009 linkMotion = parentTrVec[l] * chain->getLink(l)->getTran().inverse();
01010 if (chain->getLink(l)->contactsPreventMotion(linkMotion)) {
01011 return true;
01012 }
01013 }
01014 }
01015 }
01016 return false;
01017 }
01018
01020 void
01021 Robot::breakContacts()
01022 {
01023 for (int f=0; f<getNumChains(); f++) {
01024 for (int l=0; l<getChain(f)->getNumLinks(); l++) {
01025 getChain(f)->getLink(l)->breakContacts();
01026 }
01027 }
01028 base->breakContacts();
01029 if (mountPiece) mountPiece->breakContacts();
01030 }
01031
01032
01040 void
01041 Robot::setRenderGeometry(bool s)
01042 {
01043 mRenderGeometry = s;
01044 if (parent) parent->setRenderGeometry(s);
01045 for (int c=0; c<numChains; c++) {
01046 for (int j=0; j<chainVec[c]->getNumAttachedRobots(); j++) {
01047 chainVec[c]->getAttachedRobot(j)->setRenderGeometry(s);
01048 }
01049 }
01050 for (int f=0; f<getNumChains(); f++) {
01051 for (int l=0; l<getChain(f)->getNumLinks(); l++) {
01052 getChain(f)->getLink(l)->setRenderGeometry(s);
01053 }
01054 }
01055 base->setRenderGeometry(s);
01056 if (mountPiece) mountPiece->setRenderGeometry(s);
01057 }
01058
01065 int
01066 Robot::setTran(const transf& tr)
01067 {
01068 if (parent) {
01069 double *dofVals = new double[parent->getNumDOF()];
01070 transf parentBaseToEnd = tranToParentEnd*tr;
01071 if (parent->invKinematics(parentBaseToEnd,dofVals,parentChainNum)==FAILURE) {
01072 delete [] dofVals;
01073 return FAILURE;
01074 }
01075 parent->forceDOFVals(dofVals);
01076 delete [] dofVals;
01077 } else {
01078 simpleSetTran(tr);
01079 }
01080 return SUCCESS;
01081 }
01082
01086 int
01087 Robot::getNumLinks() const
01088 {
01089 int links=0;
01090 for (int k=0; k<getNumChains(); k++) {
01091 links += chainVec[k]->getNumLinks();
01092 }
01093 links++;
01094 if (mountPiece) links++;
01095 return links;
01096 }
01097
01102 int
01103 Robot::getNumContacts(Body *body)
01104 {
01105 int c = getBase()->getNumContacts(body);
01106 for (int f=0; f<getNumChains(); f++) {
01107 c += getChain(f)->getNumContacts(body);
01108 }
01109 return c;
01110 }
01111
01116 std::list<Contact*>
01117 Robot::getContacts(Body* body)
01118 {
01119 std::list<Contact*> contacts;
01120 std::list<Contact*> chainContacts = getBase()->getContacts(body);
01121 contacts.insert(contacts.end(),chainContacts.begin(), chainContacts.end());
01122 for (int f=0; f<getNumChains(); f++) {
01123 chainContacts = getChain(f)->getContacts(body);
01124 contacts.insert(contacts.end(),chainContacts.begin(), chainContacts.end());
01125 }
01126 return contacts;
01127 }
01128
01132 int
01133 Robot::getNumVirtualContacts()
01134 {
01135 int c = getBase()->getNumVirtualContacts();
01136 for (int f=0; f<getNumChains(); f++) {
01137 for (int l=0; l<getChain(f)->getNumLinks(); l++) {
01138 c += getChain(f)->getLink(l)->getNumVirtualContacts();
01139 }
01140 }
01141 return c;
01142 }
01143
01149 void
01150 Robot::showVirtualContacts(bool on)
01151 {
01152 int s; bool b;
01153 if (on) s = 1;
01154 else s = 2;
01155 b = getBase()->frictionConesShown();
01156 getBase()->showFrictionCones(b, s);
01157 for (int f=0; f<getNumChains(); f++) {
01158 for (int l=0; l<getChain(f)->getNumLinks(); l++) {
01159 b = getChain(f)->getLink(l)->frictionConesShown();
01160 getChain(f)->getLink(l)->showFrictionCones( b, s );
01161 }
01162 }
01163 }
01164
01165
01166
01172 void
01173 Robot::saveState()
01174 {
01175 savedTran = getTran();
01176 savedDOF.clear();
01177 QTextStream stream(&savedDOF,QIODevice::ReadWrite);
01178 writeDOFVals(stream);
01179 savedState = true;
01180 }
01181
01186 void
01187 Robot::restoreState()
01188 {
01189 if (!savedState) {
01190 DBGA("Warning: hand state not saved!");
01191 if (savedDOF.size()==0) {
01192 DBGA("Saved DOF data absent; can not restore");
01193 return;
01194 }
01195 }
01196 savedState = false;
01197 setTran( savedTran );
01198 QTextStream stream(&savedDOF,QIODevice::ReadOnly);
01199 readDOFVals(stream);
01200 }
01201
01205 QTextStream&
01206 Robot::readDOFVals(QTextStream &is)
01207 {
01208 for (int d=0; d<numDOF; d++) {
01209 if (!dofVec[d]->readFromStream(is)) {
01210 DBGA("Failed to read DOF " << d << " from stream");
01211 return is;
01212 }
01213 }
01214
01215
01216
01217 double *jointVals = new double[numJoints];
01218 for (int d=0; d<numDOF; d++) {
01219 dofVec[d]->getJointValues(jointVals);
01220 }
01221 setJointValuesAndUpdate(jointVals);
01222 delete [] jointVals;
01223 return is;
01224 }
01225
01229 QTextStream&
01230 Robot::writeDOFVals(QTextStream &os)
01231 {
01232 for (int d=0; d<numDOF; d++) {
01233 dofVec[d]->writeToStream(os);
01234 os << " ";
01235 }
01236 return os;
01237 }
01238
01239
01240
01245 void Robot::setJointValues(const double* jointVals)
01246 {
01247 for (int c=0; c<numChains; c++) {
01248 chainVec[c]->setJointValues(jointVals);
01249 }
01250 }
01251
01257 void Robot::setJointValuesAndUpdate(const double* jointVals)
01258 {
01259 for (int c=0; c<numChains; c++) {
01260 chainVec[c]->setJointValues(jointVals);
01261 chainVec[c]->updateLinkPoses();
01262 }
01263 }
01264
01265
01282 int
01283 Robot::interpolateJoints(double *initialVals, double *finalVals,
01284 CollisionReport *colReport, double *interpolationTime)
01285 {
01286 double *currentVals = new double[ getNumJoints() ];
01287 double minDist,t = 0.0,deltat = 1.0;
01288 while (deltat > 1.0e-20 && t >= 0) {
01289
01290 DBGP("DOF joint interpolation cycle")
01291 deltat *= 0.5;
01292 for (int j=0; j<getNumJoints(); j++) {
01293 currentVals[j] = t*finalVals[j] + (1.0-t)*initialVals[j];
01294 }
01295 setJointValuesAndUpdate(currentVals);
01296
01297 minDist = 1.0e10;
01298 for (int i=0; i<(int)colReport->size(); i++) {
01299 minDist = MIN(minDist,myWorld->getDist( (*colReport)[i].first, (*colReport)[i].second));
01300 if ( minDist <= 0 ) {
01301 t -= deltat;
01302 break;
01303 }
01304 }
01305 if (minDist > 0) {
01306 if (minDist < 0.5 * Contact::THRESHOLD) break;
01307 t += deltat;
01308 }
01309 }
01310
01311 int retVal;
01312 if (deltat < 1.0e-20 || t < 0) {
01313 #ifdef GRASPITDBG
01314 std::cerr << "t: " << t << " d: " << deltat << std::endl;
01315 std::cerr << "I am " << getName().latin1() << std::endl;
01316 for (int i=0; i<(int)colReport->size(); i++) {
01317 std::cerr << (*colReport)[i].first->getName().latin1()<<" -- "
01318 << (*colReport)[i].second->getName().latin1() << std::endl;
01319 }
01320 std::cerr << "min dist: " << minDist << std::endl << std::endl;
01321 #endif
01322 DBGA("Robot joint interpolation error");
01323 retVal = 0;
01324 } else {
01325 DBGP("Interpolation to t=" << t << " (deltat=" << deltat << ")");
01326 retVal = 1;
01327 }
01328 delete [] currentVals;
01329 *interpolationTime = t;
01330 return retVal;
01331 }
01332
01339 void Robot::stopJointsFromLink(Link *link, double *desiredJointVals, int *stoppedJoints)
01340 {
01341 if (link->getChainNum()<0) return;
01342 KinematicChain *chain = chainVec[link->getChainNum()];
01343 for (int j=chain->getLastJoint( link->getLinkNum() ); j>=0; j--) {
01344 int jnum = chain->getJoint(j)->getNum();
01345 if (desiredJointVals[jnum] > chain->getJoint(j)->getVal()) {
01346
01347 stoppedJoints[jnum] |= 1;
01348 } else if (desiredJointVals[jnum] < chain->getJoint(j)->getVal()){
01349
01350 stoppedJoints[jnum] |= 2;
01351 }
01352 }
01353 }
01354
01371 bool
01372 Robot::getJointValuesFromDOF(const double *desiredDofVals, double *actualDofVals,
01373 double *jointVals, int *stoppedJoints)
01374 {
01375 bool done,moving;
01376 std::vector<transf> newLinkTran;
01377 DBGP("Getting joint movement from DOFs");
01378 do {
01379 moving = false; done = true;
01380 getJointValues(jointVals);
01381
01382 for (int d=0;d<numDOF;d++){
01383
01384
01385 if (dofVec[d]->accumulateMove(desiredDofVals[d], jointVals,stoppedJoints)) {
01386 moving = true;
01387 actualDofVals[d] = desiredDofVals[d];
01388 DBGP("DOF " << d << " is moving");
01389 } else {
01390 actualDofVals[d] = dofVec[d]->getVal();
01391 }
01392 }
01393 if (!moving) {
01394 DBGP("No DOF movement; done.");
01395 break;
01396 }
01397
01398 for (int c = 0; c < getNumChains(); c++) {
01399 KinematicChain *chain = getChain(c);
01400 newLinkTran.resize(chain->getNumLinks(), transf::IDENTITY);
01401 chain->infinitesimalMotion(jointVals, newLinkTran);
01402 for (int l=0; l<chain->getNumLinks(); l++){
01403 Link *link = chain->getLink(l);
01404 transf motion = newLinkTran[l];
01405 if ( link->contactsPreventMotion(motion) ) {
01406 DBGP("Chain " << link->getChainNum() << " link " << link->getLinkNum() << " is blocked.");
01407
01408 stopJointsFromLink(link, jointVals, stoppedJoints);
01409 done = false;
01410
01411
01412 break;
01413 }
01414 }
01415 }
01416 if (done) {
01417 DBGP("All movement OK; done.");
01418 }
01419 } while (!done);
01420 return moving;
01421 }
01422
01450 bool
01451 Robot::jumpDOFToContact(double *desiredVals, int *stoppedJoints, int *numCols)
01452 {
01453 CollisionReport colReport, lateContacts;
01454
01455
01456 double *newDofVals = new double[ getNumDOF() ];
01457 double *initialDofVals = new double [ getNumDOF() ];
01458 getDOFVals(initialDofVals);
01459
01460 double *newJointVals = new double[ getNumJoints() ];
01461 double *initialJointVals = new double[ getNumJoints() ];
01462 getJointValues(initialJointVals);
01463
01464 if (!getJointValuesFromDOF(desiredVals, newDofVals, newJointVals, stoppedJoints)) {
01465 DBGP("No movement of DOFs; forceDOFTo returning false");
01466 if (numCols) *numCols = 0;
01467 delete [] initialJointVals; delete [] newJointVals;
01468 delete [] initialDofVals; delete [] newDofVals;
01469 return false;
01470 }
01471
01472
01473
01474 std::vector<Body*> interestList;
01475 for (int c=0; c<numChains; c++) {
01476 for (int l=0; l<chainVec[c]->getNumLinks(); l++) {
01477 int j = chainVec[c]->getLastJoint(l);
01478 if ( !stoppedJoints[ chainVec[c]->getJoint(j)->getNum() ] ) {
01479 interestList.push_back( chainVec[c]->getLink(l) );
01480 }
01481 }
01482 }
01483
01484 setJointValuesAndUpdate(newJointVals);
01485 bool interpolationError = false;
01486 double interpolationTime;
01487 while (1) {
01488 myWorld->getCollisionReport(&colReport, &interestList);
01489
01490 if (colReport.empty()) break;
01491
01492
01493 getJointValues(newJointVals);
01494 if (!interpolateJoints(initialJointVals, newJointVals, &colReport, &interpolationTime)) {
01495 DBGA("Interpolation failed!");
01496 interpolationError = true;
01497 break;
01498 }
01499
01500 lateContacts.clear();
01501 for (int i=0;i<(int)colReport.size();i++) {
01502 lateContacts.push_back( colReport[i] );
01503 DBGP("Contact: " << colReport[i].first->getName().latin1() << "--" <<
01504 colReport[i].second->getName().latin1());
01505 }
01506 for (int d=0; d<numDOF; d++) {
01507 DBGP("Dof " << d << "initial " << initialDofVals[d] << " new " << newDofVals[d]);
01508 newDofVals[d] = newDofVals[d] * interpolationTime +
01509 initialDofVals[d] * ( 1.0 - interpolationTime);
01510 DBGP("Interpolated: " << newDofVals[d]);
01511 }
01512 }
01513
01514 if (!interpolationError) {
01515 DBGP("ForceDOFTo done");
01516 myWorld->findContacts(lateContacts);
01517 for (int i=0; i<(int)lateContacts.size(); i++) {
01518 if (lateContacts[i].first->getOwner()==this) {
01519 stopJointsFromLink( (Link*)lateContacts[i].first, newJointVals, stoppedJoints);
01520 }
01521 if (lateContacts[i].second->getOwner()==this) {
01522 stopJointsFromLink( (Link*)lateContacts[i].second, newJointVals, stoppedJoints);
01523 }
01524 }
01525 updateDofVals(newDofVals);
01526 if (numCols) *numCols = (int)lateContacts.size();
01527 }
01528
01529 delete [] initialDofVals; delete [] newDofVals;
01530 delete [] initialJointVals; delete [] newJointVals;
01531
01532 if (!interpolationError) return true;
01533 else return false;
01534 }
01535
01536
01565 bool
01566 Robot::moveDOFToContacts(double *desiredVals, double *desiredSteps, bool stopAtContact, bool renderIt)
01567 {
01568
01569
01570 PROF_TIMER_FUNC(MOVE_DOF);
01571
01572 int i,d;
01573 CollisionReport result;
01574
01575 double *stepSize= new double[numDOF];
01576 double *currVals = new double[numDOF];
01577 double *newVals = new double[numDOF];
01578
01579 for (i=0;i<numDOF;i++) {
01580 if (!desiredSteps || desiredSteps[i] == WorldElement::ONE_STEP ) {
01581 stepSize[i] = desiredVals[i] - dofVec[i]->getVal();
01582 } else if (desiredSteps[i]!=0.0) {
01583
01584 double factor = 1.0;
01585 if (desiredVals[i] < dofVec[i]->getVal()) factor = -1.0;
01586 stepSize[i] = factor * fabs(desiredSteps[i]);
01587 } else {
01588 stepSize[i] = 0.0;
01589 desiredVals[i] = dofVec[i]->getVal();
01590 }
01591 DBGP("from " << dofVec[i]->getVal() << " to " << desiredVals[i] << " in " << stepSize[i] << " steps");
01592 }
01593
01594
01595
01596 int *stoppedJoints = new int[numJoints];
01597 for (int j=0; j<numJoints; j++) {
01598 stoppedJoints[j] = 0;
01599 }
01600
01601
01602 int numCols,itercount = 0;
01603 bool moved = false;
01604 do {
01605 itercount++;
01606 DBGP("Move to contact cycle");
01607 getDOFVals(currVals);
01608 for (d=0;d<numDOF;d++) {
01609 newVals[d] = currVals[d] + stepSize[d];
01610 DBGP(" Current value (a): " << currVals[d] << "; new value: " << newVals[d] <<
01611 "; step size: " << stepSize[d]);
01612 if (stepSize[d] > 0 && newVals[d] > desiredVals[d])
01613 newVals[d] = desiredVals[d];
01614 else if (stepSize[d] < 0 && newVals[d] < desiredVals[d])
01615 newVals[d] = desiredVals[d];
01616 DBGP(" Current value (b): " << currVals[d] << "; new value: " << newVals[d]);
01617 }
01618
01619
01620 if (!jumpDOFToContact(newVals, stoppedJoints, &numCols)){
01621 DBGP("ForceDOFTo reports no movement is possible");
01622 break;
01623 }
01624 moved = true;
01625 bool stopRequest = false;
01626
01627 emit moveDOFStepTaken(numCols, stopRequest);
01628 if (stopRequest) {
01629 DBGP("Receiver of movement signal requests early exit");
01630 break;
01631 }
01632
01633 if (stopAtContact && numCols != 0) {
01634 DBGP("Stopping at first contact");
01635 break;
01636 }
01637 if (itercount > 500) {
01638 DBGA("MoveDOF failsafe hit");
01639 break;
01640 }
01641 if (renderIt && (itercount%25==0) && graspItGUI && graspItGUI->getIVmgr()->getWorld()==myWorld) {
01642 graspItGUI->getIVmgr()->getViewer()->render();
01643 }
01644 } while (1);
01645
01646
01647
01648
01649 delete [] currVals;
01650 delete [] newVals;
01651 delete [] stepSize;
01652 delete [] stoppedJoints;
01653 return moved;
01654 }
01655
01662 bool
01663 Robot::checkDOFPath(double *desiredVals, double desiredStep)
01664 {
01665 int d;
01666 bool done, success = true;
01667
01668 double *stepSize= new double[numDOF];
01669 double *currVals = new double[numDOF];
01670 double *newVals = new double[numDOF];
01671
01672 for (d=0;d<numDOF;d++) {
01673 if (desiredStep == WorldElement::ONE_STEP )
01674 stepSize[d] = desiredVals[d] - dofVec[d]->getVal();
01675 else if ( desiredVals[d] >= dofVec[d]->getVal() )
01676 stepSize[d] = desiredStep;
01677 else stepSize[d] = - desiredStep;
01678 }
01679
01680 do {
01681 DBGP("Move to contact cycle")
01682 getDOFVals(currVals);
01683 for (d=0;d<numDOF;d++) {
01684 newVals[d] = currVals[d] + stepSize[d];
01685 if (stepSize[d] > 0 && newVals[d] > desiredVals[d])
01686 newVals[d] = desiredVals[d];
01687 else if (stepSize[d] < 0 && newVals[d] < desiredVals[d])
01688 newVals[d] = desiredVals[d];
01689 }
01690
01691 forceDOFVals(newVals);
01692
01693 if ( !myWorld->noCollision() ) {
01694 success = false;
01695 break;
01696 }
01697
01698 done = true;
01699 for (d=0;d<numDOF;d++) {
01700 if (newVals[d] != desiredVals[d]) done = false;
01701 }
01702
01703 } while (!done);
01704
01705 delete [] currVals;
01706 delete [] newVals;
01707 delete [] stepSize;
01708 return success;
01709 }
01710
01711
01712
01723 Matrix
01724 Robot::staticJointTorques(bool useDynamicDofForce)
01725 {
01726 std::vector<double> jointTorques(getNumJoints(), 0.0);
01727 for (int d=0; d<numDOF; d++) {
01728 double dofForce = -1;
01729 if (useDynamicDofForce) {
01730 dofForce = dofVec[d]->getForce();
01731 }
01732 dofVec[d]->computeStaticJointTorques(&jointTorques[0], dofForce);
01733 }
01734 return Matrix(&jointTorques[0], getNumJoints(), 1, true);
01735 }
01736
01737
01738
01745 double
01746 Robot::getApproachDistance(Body *object, double maxDist)
01747 {
01748 position p0 = position(0,0,0) * getApproachTran() * getTran();
01749 position p = p0;
01750 vec3 app = vec3(0,0,1) * getApproachTran() * getTran();
01751 bool done = false;
01752 double totalDist = 0;
01753 vec3 direction;
01754 int loops = 0;
01755 while (!done) {
01756 loops++;
01757
01758 direction = myWorld->pointDistanceToBody(p, object);
01759
01760
01761 position pc = p; pc+=direction;
01762
01763 if ( normalise(pc-p0) % app > 0.86 ) {
01764 done = true;
01765 }
01766
01767 double d = direction.len();
01768 totalDist += d;
01769 p += d * app;
01770 if (totalDist > maxDist) done = true;
01771 if (loops > 10) {
01772 done = true;
01773 totalDist = maxDist+1;
01774 DBGA("Force exit from gettAppDist");
01775 }
01776 }
01777
01778
01779 return totalDist;
01780 }
01781
01787 bool
01788 Robot::snapChainToContacts(int chainNum, CollisionReport colReport)
01789 {
01790 bool persistent = true;
01791
01792 KinematicChain *chain = getChain(chainNum);
01793 chain->filterCollisionReport(colReport);
01794 if (colReport.empty()) {
01795 DBGP("Snap to chain "<<chainNum<<" done from the start - no collisions");
01796 return true;
01797 }
01798
01799 std::vector<double> openVals(numDOF);
01800 std::vector<double> closedVals(numDOF);
01801 std::vector<double> openJointVals(numJoints);
01802 std::vector<double> closedJointVals(numJoints);
01803 CollisionReport openColReport;
01804
01805 getDOFVals(&closedVals[0]);
01806 getDOFVals(&openVals[0]);
01807 getJointValues(&closedJointVals[0]);
01808
01809 double SNAP = 0.1;
01810 while (1) {
01811 bool limitHit = true;
01812 int l = chain->getNumLinks() - 1;
01813 for (int j=chain->getLastJoint(l); j>=0; j--) {
01814 int d = chain->getJoint(j)->getDOFNum();
01815 double current = dofVec[d]->getVal();
01816 double target;
01817 if (dofVec[d]->getDefaultVelocity() < 0) {
01818 target = current + SNAP;
01819 if ( target > dofVec[d]->getMax() ) target = dofVec[d]->getMax();
01820 else limitHit = false;
01821 } else if (dofVec[d]->getDefaultVelocity() > 0) {
01822 target = current - SNAP;
01823 if ( target < dofVec[d]->getMin()) target = dofVec[d]->getMin();
01824 else limitHit = false;
01825 } else target = current;
01826 openVals[d] = target;
01827 }
01828
01829 forceDOFVals(&openVals[0]);
01830 myWorld->getCollisionReport(&openColReport);
01831 chainVec[chainNum]->filterCollisionReport(openColReport);
01832 if ( !openColReport.empty() ) {
01833 if (persistent && !limitHit) {
01834
01835 forceDOFVals(&closedVals[0]);
01836 SNAP += 0.1;
01837 }
01838 else break;
01839 } else {
01840 break;
01841 }
01842 }
01843 if (!openColReport.empty()) {
01844 DBGP("Snap to chain "<<chainNum<<" done - open position in collision");
01845 forceDOFVals(&closedVals[0]);
01846 return false;
01847 }
01848
01849 DBGP("Open values valid");
01850 getJointValues(&openJointVals[0]);
01851 double time;
01852 if (!interpolateJoints(&openJointVals[0], &closedJointVals[0], &colReport, &time)) {
01853 DBGP("Snap to chain "<<chainNum<<" interpolation failed");
01854 forceDOFVals(&closedVals[0]);
01855 return false;
01856 } else {
01857
01858 for (int d=0; d<numDOF; d++) {
01859 closedVals[d] = closedVals[d] * time + openVals[d] * ( 1.0 - time);
01860 }
01861 updateDofVals(&closedVals[0]);
01862 }
01863 DBGP("Snap to chain "<<chainNum<<" success");
01864 myWorld->findContacts(colReport);
01865 return true;
01866 }
01867
01868
01869
01870
01885 void
01886 Robot::setDesiredDOFVals(double *dofVals)
01887 {
01888 int i,j,d,numSteps;
01889 double timeNeeded;
01890 double t;
01891 double coeffs[5];
01892 double tpow,q1,q0,qd0,qd1;
01893 double *traj;
01894
01895 for (d=0;d<numDOF;d++) {
01896 if (dofVec[d]->getDefaultVelocity() == 0.0) continue;
01897
01898 DBGP("DOF "<<d<<" trajectory");
01899 dofVec[d]->setDesiredPos(dofVals[d]);
01900 if (dofVec[d]->getVal() != dofVals[d]) {
01901
01902 q0 = dofVec[d]->getVal();
01903 q1 = dofVals[d];
01904 qd0 = 0.0;
01905 qd1 = 0.0;
01906
01907 timeNeeded = fabs(dofVals[d]-dofVec[d]->getVal()) / fabs( dofVec[d]->getDesiredVelocity() );
01908
01909
01910 numSteps = (int)ceil(timeNeeded/myWorld->getTimeStep());
01911 timeNeeded = numSteps*myWorld->getTimeStep();
01912
01913 DBGP("numSteps: "<< numSteps << " time needed: " << timeNeeded);
01914 traj = new double[numSteps];
01915
01916 for (i=0;i<numSteps;i++) {
01917 t = (double)i/(double)(numSteps-1);
01918 coeffs[4] = 6.0*(q1 - q0) - 3.0*(qd1+qd0)*timeNeeded;
01919 coeffs[3] = -15.0*(q1 - q0) + (8.0*qd0 + 7.0*qd1)*timeNeeded;
01920 coeffs[2] = 10.0*(q1 - q0) - (6.0*qd0 + 4.0*qd1)*timeNeeded;
01921 coeffs[1] = 0.0;
01922 coeffs[0] = qd0*timeNeeded;
01923 traj[i] = q0;
01924
01925 tpow = 1.0;
01926 for (j=0;j<5;j++) {
01927 tpow *= t;
01928 traj[i] += tpow*coeffs[j];
01929 }
01930 DBGP(i << " " << t << " " << traj[i]);
01931 }
01932 dofVec[d]->setTrajectory(traj,numSteps);
01933 delete [] traj;
01934 }
01935 }
01936 }
01937
01943 void
01944 Robot::setChainEndTrajectory(std::vector<transf>& traj,int chainNum)
01945 {
01946 int i,j,numPts = traj.size();
01947 double *dofVals = new double[numDOF];
01948 bool *dofInChain = new bool[numDOF];
01949
01950 if (numPts < 1 || chainNum < 0 || chainNum > numChains-1) return;
01951 for (j=0;j<numDOF;j++)
01952 dofInChain[j] = false;
01953
01954 for (j=0;j<chainVec[chainNum]->getNumJoints();j++)
01955 dofInChain[chainVec[chainNum]->getJoint(j)->getDOFNum()] = true;
01956
01957 invKinematics(traj[0],dofVals,chainNum);
01958 for (j=0;j<numDOF;j++)
01959 if (dofInChain[j]) dofVec[j]->setTrajectory(&dofVals[j],1);
01960
01961 for (i=1;i<numPts;i++) {
01962 invKinematics(traj[i],dofVals,chainNum);
01963 for (j=0;j<numDOF;j++)
01964 if (dofInChain[j]) dofVec[j]->addToTrajectory(&dofVals[j],1);
01965 }
01966 delete [] dofVals;
01967 delete [] dofInChain;
01968 }
01969
01970
01981 void
01982 Robot::generateCartesianTrajectory(const transf &startTr, const transf &endTr,
01983 std::vector<transf> &traj,
01984 double startVel, double endVel,
01985 double timeNeeded)
01986 {
01987 int i,j,numSteps;
01988 double t,tpow,dist,angle,coeffs[5];
01989 vec3 newPos,axis;
01990 Quaternion newRot;
01991
01992 (endTr.rotation() * startTr.rotation().inverse()).ToAngleAxis(angle,axis);
01993
01994 if (timeNeeded <= 0.0) {
01995 if (defaultTranslVel == 0.0 || defaultRotVel == 0.0) return;
01996 timeNeeded =
01997 MAX((endTr.translation() - startTr.translation()).len()/defaultTranslVel,
01998 fabs(angle)/defaultRotVel);
01999 }
02000
02001
02002 numSteps = (int)ceil(timeNeeded/myWorld->getTimeStep());
02003 timeNeeded = numSteps*myWorld->getTimeStep();
02004 DBGP("Desired Tran Traj numSteps " << numSteps);
02005
02006 if (numSteps) {
02007 traj.clear();
02008 traj.reserve(numSteps);
02009 }
02010
02011 for (i=0;i<numSteps;i++) {
02012 t = (double)i/(double)(numSteps-1);
02013
02014 coeffs[4] = 6.0 - 3.0*(startVel+endVel)*timeNeeded;
02015 coeffs[3] = -15.0 + (8.0*startVel + 7.0*endVel)*timeNeeded;
02016 coeffs[2] = 10.0 - (6.0*startVel + 4.0*endVel)*timeNeeded;
02017 coeffs[1] = 0.0;
02018 coeffs[0] = startVel*timeNeeded;
02019
02020 dist = 0.0;
02021 tpow = 1.0;
02022 for (j=0;j<5;j++) {
02023 tpow *= t;
02024 dist += tpow*coeffs[j];
02025 }
02026 newRot = Quaternion::Slerp(dist,startTr.rotation(),endTr.rotation());
02027 newPos = (1.0-dist)*startTr.translation() + dist*endTr.translation();
02028 traj.push_back(transf(newRot,newPos));
02029 }
02030 }
02031
02038 void
02039 Robot::updateJointValuesFromDynamics()
02040 {
02041 double *jointVals = new double[ getNumJoints() ];
02042
02043 for (int f=0;f<numChains;f++) {
02044 for (int l=0;l<chainVec[f]->getNumLinks();l++) {
02045 if (chainVec[f]->getLink(l)->getDynJoint())
02046 chainVec[f]->getLink(l)->getDynJoint()->updateValues();
02047 }
02048 for (int j=0; j<chainVec[f]->getNumJoints(); j++) {
02049 jointVals[ chainVec[f]->getJoint(j)->getNum() ] = chainVec[f]->getJoint(j)->getDynamicsVal();
02050 }
02051 }
02052
02053 setJointValues(jointVals);
02054
02055
02056
02057
02058
02059 delete [] jointVals;
02060 }
02061
02071 void
02072 Robot::applyJointPassiveInternalWrenches()
02073 {
02074 for (int c=0; c<numChains; c++) {
02075 for (int j=0; j<getChain(c)->getNumJoints(); j++) {
02076 getChain(c)->getJoint(j)->applyPassiveInternalWrenches();
02077 }
02078 }
02079 }
02080
02085 void
02086 Robot::buildDOFLimitConstraints(std::map<Body*,int> &islandIndices, int numBodies,
02087 double* H, double *g, int &hcn)
02088 {
02089 for (int d=0; d<numDOF; d++) {
02090 dofVec[d]->buildDynamicLimitConstraints(islandIndices, numBodies, H, g, hcn);
02091 }
02092 }
02093
02098 void
02099 Robot::buildDOFCouplingConstraints(std::map<Body*,int> &islandIndices, int numBodies,
02100 double* Nu, double *eps, int &ncn)
02101 {
02102 for(int d=0; d<numDOF; d++) {
02103 dofVec[d]->buildDynamicCouplingConstraints(islandIndices, numBodies, Nu, eps, ncn);
02104 }
02105 return;
02106 }
02107
02114 void
02115 Robot::DOFController(double timeStep)
02116 {
02117 DBGP(" in Robot controller");
02118 if (myWorld->getWorldTime() > dofUpdateTime) {
02119 DBGP("Updating setpoints");
02120 for (int d=0;d<numDOF;d++) {
02121 dofVec[d]->updateSetPoint();
02122 }
02123 dofUpdateTime += myWorld->getTimeStep();
02124 }
02125 for (int d=0;d<numDOF;d++) {
02126 dofVec[d]->callController(timeStep);
02127 }
02128 }
02129
02130
02135 bool
02136 Robot::dynamicAutograspComplete()
02137 {
02138 for (int c=0; c<numChains; c++) {
02139 Link *l = chainVec[c]->getLink( chainVec[c]->getNumLinks()-1 );
02140
02141 if (l->getNumContacts()) continue;
02142 int jNum = chainVec[c]->getLastJoint(chainVec[c]->getNumLinks()-1);
02143 Joint *j = chainVec[c]->getJoint(jNum);
02144 double limit;
02145
02146 if (dofVec[j->getDOFNum()]->getDefaultVelocity() > 0) {
02147 if (j->getCouplingRatio() > 0) {
02148 limit = j->getMax();
02149 } else {
02150 limit = j->getMin();
02151 }
02152 } else if (dofVec[j->getDOFNum()]->getDefaultVelocity() < 0) {
02153 if (j->getCouplingRatio() < 0) {
02154 limit = j->getMax();
02155 } else {
02156 limit = j->getMin();
02157 }
02158 } else {
02159 assert(0);
02160 }
02161
02162 if (fabs(j->getDynamicsVal() - limit) < 3.0e-2) continue;
02163
02164 DBGP("Autograsp going on chain " << c << " joint " << jNum << ": val "
02165 << j->getDynamicsVal() << "; limit " << limit);
02166 return false;
02167 }
02168 return true;
02169 }
02170
02175 bool
02176 Robot::contactSlip()
02177 {
02178 double linearThreshold = 100.0;
02179 double angularThreshold = 2.0;
02180 for (int c=0; c<numChains; c++) {
02181 for (int l=0; l<getChain(c)->getNumLinks(); l++) {
02182 Link *link = getChain(c)->getLink(l);
02183 if (!link->getNumContacts()) continue;
02184 const double *v = link->getVelocity();
02185 double magn = 0.0;
02186 for (int i=0; i<3; i++) {
02187 magn += v[i] * v[i];
02188 }
02189 if (magn > linearThreshold * linearThreshold) {
02190 DBGA("Chain " << c << " link " << l << " moving with linear vel. magnitude " << magn);
02191 return true;
02192 }
02193 magn = 0.0;
02194 for (int i=3; i<6; i++) {
02195 magn += v[i] * v[i];
02196 }
02197 if (magn > angularThreshold * angularThreshold) {
02198 DBGA("Chain " << c << " link " << l << " moving with angular vel. magnitude " << magn);
02199 return true;
02200 }
02201 }
02202 }
02203 return false;
02204 }
02205
02207
02209
02211 Hand::Hand(World *w,const char *name) : Robot(w,name)
02212 {
02213 grasp = new Grasp(this);
02214 }
02215
02217 Hand::~Hand()
02218 {
02219 std::cout << "Deleting Hand: " << std::endl;
02220 delete grasp;
02221 }
02222
02226 void
02227 Hand::cloneFrom(Hand *original)
02228 {
02229 Robot::cloneFrom(original);
02230 grasp->setObjectNoUpdate( original->getGrasp()->getObject() );
02231 grasp->setGravity( original->getGrasp()->isGravitySet() );
02232 }
02233
02248 bool
02249 Hand::autoGrasp(bool renderIt, double speedFactor, bool stopAtContact)
02250 {
02251 int i;
02252 double *desiredVals = new double[numDOF];
02253
02254 if (myWorld->dynamicsAreOn()) {
02255 for (i=0;i<numDOF;i++) {
02256 if (speedFactor * dofVec[i]->getDefaultVelocity() > 0)
02257 desiredVals[i] = dofVec[i]->getMax();
02258 else if (speedFactor * dofVec[i]->getDefaultVelocity() < 0)
02259 desiredVals[i] = dofVec[i]->getMin();
02260 else desiredVals[i] = dofVec[i]->getVal();
02261 DBGP("Desired val "<<i<<" "<<desiredVals[i]);
02262
02263 dofVec[i]->setDesiredVelocity(speedFactor * dofVec[i]->getDefaultVelocity());
02264 }
02265 setDesiredDOFVals(desiredVals);
02266 delete [] desiredVals;
02267 return true;
02268 }
02269
02270 double *stepSize= new double[numDOF];
02271 for (i=0;i<numDOF;i++) {
02272 if (speedFactor * dofVec[i]->getDefaultVelocity() >= 0) desiredVals[i] = dofVec[i]->getMax();
02273 else desiredVals[i] = dofVec[i]->getMin();
02274 stepSize[i] = dofVec[i]->getDefaultVelocity()*speedFactor*AUTO_GRASP_TIME_STEP;
02275 }
02276
02277 bool moved = moveDOFToContacts(desiredVals, stepSize, stopAtContact, renderIt);
02278 delete [] desiredVals;
02279 delete [] stepSize;
02280 return moved;
02281 }
02282
02283
02284
02285
02286
02287
02288
02289 bool
02290 Hand::quickOpen(double speedFactor)
02291 {
02292 double *desiredVals = new double[numDOF];
02293 getDOFVals(desiredVals);
02294 double *desiredSteps = new double[numDOF];
02295 for (int i=0; i<numDOF; i++) {
02296 double d = -1 * dofVec[i]->getDefaultVelocity();
02297 if ( d > 0 ) {
02298 desiredSteps[i] = d * speedFactor * (dofVec[i]->getMax() - desiredVals[i]);
02299 } else if ( d < 0 ) {
02300 desiredSteps[i] = d * speedFactor * (desiredVals[i] - dofVec[i]->getMin() );
02301 } else {
02302 desiredSteps[i] = 0;
02303 }
02304 }
02305 bool done = false, success = false;
02306 int loops = 0;
02307 while (!done) {
02308 loops++;
02309
02310 done = true;
02311 for (int i=0; i<numDOF; i++) {
02312 desiredVals[i] += desiredSteps[i];
02313
02314 if ( desiredVals[i] > dofVec[i]->getMax() ) {desiredVals[i] = dofVec[i]->getMax();}
02315 else if ( desiredVals[i] < dofVec[i]->getMin() ){ desiredVals[i] = dofVec[i]->getMin();}
02316 else if (desiredSteps[i] != 0) {done = false;}
02317
02318 }
02319 forceDOFVals(desiredVals);
02320 if ( myWorld->noCollision() ) {
02321 done = true;
02322 success = true;
02323 }
02324 }
02325 if (loops > 20) DBGA("Open finger loops: " << loops << " Hand: " << myName.latin1());
02326 delete [] desiredVals;
02327 delete [] desiredSteps;
02328 return success;
02329 }
02330
02336 bool
02337 Hand::approachToContact(double moveDist, bool oneStep)
02338 {
02339 transf newTran = translate_transf(vec3(0,0,moveDist) * getApproachTran()) * getTran();
02340 bool result;
02341 if (oneStep) {
02342 result = moveTo(newTran, WorldElement::ONE_STEP, WorldElement::ONE_STEP);
02343 } else {
02344 result = moveTo(newTran, 50*Contact::THRESHOLD, M_PI/36.0);
02345 }
02346 if (result) {
02347 DBGP("Approach no contact");
02348 return false;
02349 } else {
02350 DBGP("Approach results in contact");
02351 return true;
02352 }
02353 }
02354
02360 bool
02361 Hand::findInitialContact(double moveDist)
02362 {
02363 CollisionReport colReport;
02364 while (myWorld->getCollisionReport(&colReport)) {
02365 transf newTran = translate_transf(vec3(0,0,-moveDist / 2.0) *
02366 getApproachTran()) * getTran();
02367 setTran(newTran);
02368 }
02369 return approachToContact(moveDist, false);
02370 }
02371
02372 Matrix
02373 Robot::getJacobianJointToDOF(int chainNum){
02374 Matrix m = Matrix(chainVec[chainNum]->getNumJoints(), numDOF);
02375
02376 m.setAllElements(0.0);
02377 for(int i = 0; i < m.rows(); ++i){
02378
02379 m.elem(i,chainVec[chainNum]->getJoint(i)->getDOFNum()) = chainVec[chainNum]->getJoint(i)->getCouplingRatio();
02380 }
02381 return m;
02382 }