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
00026 #include "searchState.h"
00027 #include "searchStateImpl.h"
00028
00029 #include <QString>
00030
00031 #include <Inventor/nodes/SoSeparator.h>
00032 #include <Inventor/nodes/SoCube.h>
00033 #include <Inventor/nodes/SoSphere.h>
00034 #include <Inventor/nodes/SoTransform.h>
00035 #include <Inventor/nodes/SoMaterial.h>
00036 #include <Inventor/nodes/SoGroup.h>
00037 #include "SoArrow.h"
00038
00039 #include "robot.h"
00040 #include "body.h"
00041 #include "world.h"
00042 #include "eigenGrasp.h"
00043
00044
00045 #include "debug.h"
00046
00047 SearchVariable::SearchVariable(QString name, double min, double max, double maxJump, bool circular)
00048 {
00049 mName = name;
00050 mMinVal = min; mMaxVal = max;
00051 mMaxJump = maxJump;
00052 mValue = 0;
00053 mFixed = false;
00054 mCircular = circular;
00055 }
00056
00057 SearchVariable::SearchVariable(const SearchVariable *v)
00058 {
00059 mName = v->mName;
00060 mMinVal = v->mMinVal; mMaxVal = v->mMaxVal;
00061 mMaxJump = v->mMaxJump;
00062 mValue = v->mValue;
00063 mFixed = v->mFixed;
00064 mCircular = v->mCircular;
00065 }
00066
00067
00068
00069 VariableSet::~VariableSet()
00070 {
00071 clearVariables();
00072 }
00073
00074 VariableSet::VariableSet(const VariableSet &vs)
00075 {
00076 for (int var = 0; var<vs.getNumVariables(); var++) {
00077 mVariables.push_back(new SearchVariable(vs.getVariable(var)));
00078 }
00079 for (int par=0; par<(int)vs.mParameters.size(); par++) {
00080 mParameters.push_back(SearchParameter(vs.mParameters[par]));
00081 }
00082 mHand = vs.mHand;
00083 }
00084
00085 void
00086 VariableSet::clearVariables()
00087 {
00088 for (int i=0; i < (int)mVariables.size(); i++)
00089 delete mVariables[i];
00090 mVariables.clear();
00091 }
00092
00093 void
00094 VariableSet::changeHand(const Hand *h, bool sticky)
00095 {
00096 if (sticky) {
00097 assert(mHand->getNumDOF() == h->getNumDOF());
00098 assert(mHand->getEigenGrasps()->getSize() == h->getEigenGrasps()->getSize());
00099 }
00100 mHand = h;
00101 if (!sticky) {
00102 clearVariables();
00103 createVariables();
00104 }
00105 }
00106
00107 void
00108 VariableSet::setAllConfidences(double c)
00109 {
00110 for (int i=0; i<(int)mVariables.size(); i++) {
00111 mVariables[i]->setConfidence(c);
00112 }
00113 }
00114
00115 void
00116 VariableSet::setAllFixed(bool f)
00117 {
00118 for (int i=0; i<(int)mVariables.size(); i++) {
00119 mVariables[i]->setFixed(f);
00120 }
00121 }
00122
00123 int
00124 VariableSet::getNumUsedVariables() const
00125 {
00126 int n=0;
00127 for (unsigned int i=0; i<mVariables.size(); i++)
00128 if (!mVariables[i]->isFixed()) n++;
00129 return n;
00130 }
00131
00132 SearchVariable*
00133 VariableSet::getVariable(QString name)
00134 {
00135 for (unsigned int i=0; i < mVariables.size(); i++) {
00136 if (mVariables[i]->getName() == name) return mVariables[i];
00137 }
00138 DBGP("Requested variable " << name.latin1() << " not found in search state");
00139 return NULL;
00140 }
00141
00142 const SearchVariable*
00143 VariableSet::getConstVariable(QString name) const
00144 {
00145 for (unsigned int i=0; i < mVariables.size(); i++) {
00146 if (mVariables[i]->getName() == name) return mVariables[i];
00147 }
00148 DBGP("Requested variable " << name.latin1() << " not found in search state");
00149 return NULL;
00150 }
00151
00152 double
00153 VariableSet::readVariable(QString name) const
00154 {
00155 for (unsigned int i=0; i < mVariables.size(); i++) {
00156 if (mVariables[i]->getName() == name) return mVariables[i]->getValue();
00157 }
00158 DBGP("Requested variable " << name.latin1() << " not found in search state");
00159 return 0;
00160 }
00161
00162 void
00163 VariableSet::setParameter(QString name, double value)
00164 {
00165 std::vector<SearchParameter>::iterator it;
00166 for(it = mParameters.begin(); it!=mParameters.end(); it++) {
00167 if ( it->name() == name ) break;
00168 }
00169 if (it==mParameters.end()) {
00170 DBGA("Parameter " << name.latin1() << " not found!");
00171 assert(0);
00172 return;
00173 }
00174 it->set(value);
00175 }
00176
00177 double
00178 VariableSet::getParameter (QString name) const
00179 {
00180 std::vector<SearchParameter>::const_iterator it;
00181 for(it = mParameters.begin(); it!=mParameters.end(); it++) {
00182 if ( it->name() == name ) break;
00183 }
00184 if (it==mParameters.end()) {
00185 DBGA("Parameter " << name.latin1() << " not found!");
00186 assert(0);
00187 return 0;
00188 }
00189 return it->get();
00190 }
00191
00192 void
00193 VariableSet::addParameter(QString name, double value)
00194 {
00195 std::vector<SearchParameter>::iterator it;
00196 for(it = mParameters.begin(); it!=mParameters.end(); it++) {
00197 if ( it->name() == name ) break;
00198 }
00199 if (it!=mParameters.end()) {
00200 DBGA("Parameter " << name.latin1() << " already present!");
00201 assert(0);
00202 return;
00203 }
00204 mParameters.push_back(SearchParameter(name, value));
00205 }
00206
00207 void
00208 VariableSet::removeParameter(QString name)
00209 {
00210 std::vector<SearchParameter>::iterator it;
00211 for(it = mParameters.begin(); it!=mParameters.end(); it++) {
00212 if ( it->name() == name ) break;
00213 }
00214 if (it==mParameters.end()) {
00215 DBGA("Parameter " << name.latin1() << " does not exist!");
00216 assert(0);
00217 return;
00218 }
00219 mParameters.erase(it);
00220 }
00221
00222 void
00223 VariableSet::writeToFile(FILE *fp) const
00224 {
00225 fprintf(fp,"%d ",getType());
00226 for (int i=0; i<getNumVariables(); i++)
00227 fprintf(fp,"%f ",mVariables[i]->getValue() );
00228 fprintf(fp,"\n");
00229 }
00230
00231 bool
00232 VariableSet::readFromFile(FILE *fp)
00233 {
00234
00235 int type;
00236 if( fscanf(fp,"%d",&type) <= 0) {
00237 DBGA("VariableSet::readFromFile - failed to get variable set type");
00238 return false;
00239 }
00240 if (type != getType()) {
00241 fprintf(stderr,"Wrong type %d in state file (%d expected)\n",type,getType());
00242 return false;
00243 }
00244
00245 char line[10000];
00246 int offset;
00247 float v;
00248 if (!fgets(line, 10000, fp)) {
00249 fprintf(stderr,"Failed to read data from file!\n");
00250 return false;
00251 }
00252
00253 offset = 0;
00254
00255 for (int i=0; i<getNumVariables(); i++) {
00256 if ( line[offset]=='\0' ) {
00257 fprintf(stderr,"Line to short to read all state variables\n");
00258 return false;
00259 }
00260 while( isspace(*(line+offset)) ) offset++;
00261 sscanf(line+offset,"%f",&v);
00262 mVariables[i]->setValue(v);
00263 while( !isspace(*(line+offset)) ) offset++;
00264 }
00265 return true;
00266 }
00267
00268 bool
00269 VariableSet::readFromArray(std::vector<double> array)
00270 {
00271 if(getNumVariables() != (int) array.size())
00272 {
00273 DBGA("size does not match" << getNumVariables() << " " << array.size());
00274 return false;
00275 }
00276 for(int i = 0; i < getNumVariables(); i ++)
00277 {
00278 mVariables[i]->setValue(array[i]);
00279 }
00280 return true;
00281 }
00282
00283
00289 double
00290 VariableSet::distance(const VariableSet *s) const
00291 {
00292 if (getNumVariables() != s->getNumVariables()) return -1;
00293 double distance = 0;
00294 for (int i=0; i<getNumVariables(); i++) {
00295 double altD;
00296 double d = readVariable(i) - s->readVariable(i);
00297
00298 if ( getVariable(i)->isCircular() ) {
00299
00300
00301 altD = fabs( readVariable(i) - getVariable(i)->mMinVal ) +
00302 fabs( s->readVariable(i) - getVariable(i)->mMaxVal );
00303 d = std::min(d, altD);
00304
00305 altD = fabs( s->readVariable(i) - getVariable(i)->mMinVal ) +
00306 fabs( readVariable(i) - getVariable(i)->mMaxVal );
00307 d = std::min(d, altD);
00308 }
00309 d = fabs(d) / getVariable(i)->getRange();
00310 distance = std::max(d, distance);
00311 }
00312 return distance;
00313 }
00314
00315 void
00316 VariableSet::print() const
00317 {
00318 fprintf(stderr,"\n");
00319 fprintf(stderr,"Type: %d\n",getType());
00320 for (int i=0; i<getNumVariables(); i++) {
00321 fprintf(stderr,"%s = %.2f; ",mVariables[i]->getName().latin1(),mVariables[i]->getValue());
00322 }
00323 fprintf(stderr,"\n");
00324 }
00325
00326 PostureState* PostureState::createInstance(StateType type, const Hand *h)
00327 {
00328 switch(type) {
00329 case POSE_EIGEN:
00330 return new PostureStateEigen(h);
00331 case POSE_DOF:
00332 return new PostureStateDOF(h);
00333 default:
00334 assert(0);
00335 return NULL;
00336 }
00337 }
00338
00339 PositionState* PositionState::createInstance(StateType type, const Hand *h)
00340 {
00341 switch(type) {
00342 case SPACE_COMPLETE:
00343 return new PositionStateComplete(h);
00344 case SPACE_ELLIPSOID:
00345 return new PositionStateEllipsoid(h);
00346 case SPACE_APPROACH:
00347 return new PositionStateApproach(h);
00348 case SPACE_AXIS_ANGLE:
00349 return new PositionStateAA(h);
00350 default:
00351 assert(0);
00352 return NULL;
00353 }
00354 }
00355
00356
00357 HandObjectState::HandObjectState(Hand *h)
00358 {
00359 init();
00360 mPosture = PostureState::createInstance(POSE_EIGEN,h);
00361 mPosition = PositionState::createInstance(SPACE_COMPLETE,h);
00362 mAttributes = new AttributeSet(h);
00363 mHand = h;
00364 }
00365
00366 void
00367 HandObjectState::init()
00368 {
00369 mRefTran = transf::IDENTITY;
00370 mTargetObject = NULL;
00371 mPosture = NULL;
00372 mPosition = NULL;
00373 mAttributes = NULL;
00374 IVRoot = NULL;
00375 IVMat = NULL;
00376 IVTran = NULL;
00377 }
00378
00379 HandObjectState::~HandObjectState()
00380 {
00381 hideVisualMarker();
00382 if (IVRoot) {
00383
00384 IVRoot->unref();
00385 }
00386 delete mPosture;
00387 delete mPosition;
00388 delete mAttributes;
00389 }
00390
00391 void HandObjectState::changeHand(Hand *h, bool sticky)
00392 {
00393 mHand = h;
00394 mPosition->changeHand(h, sticky);
00395 mPosture->changeHand(h, sticky);
00396 }
00397
00398 void HandObjectState::saveCurrentHandState()
00399 {
00400 transf newTran = mHand->getTran() * mRefTran.inverse();
00401 mPosition->setTran(newTran);
00402
00403 double *dof = new double[mHand->getNumDOF()];
00404
00405 mHand->storeDOFVals(dof);
00406
00407 mPosture->storeHandDOF(dof);
00408 delete [] dof;
00409 }
00410
00416 void HandObjectState::setPositionType(StateType type, bool sticky)
00417 {
00418 if (type == mPosition->getType()) return;
00419 PositionState *p = PositionState::createInstance(type, mHand);
00420 transf t;
00421 if (sticky) {
00422 t = mPosition->getCoreTran();
00423 }
00424 delete mPosition;
00425 mPosition = p;
00426 if (sticky) {
00427 mPosition->setTran(t);
00428 } else {
00429 mPosition->reset();
00430 }
00431 }
00432
00438 void HandObjectState::setPostureType(StateType type, bool sticky)
00439 {
00440 if (type == mPosture->getType()) return;
00441 PostureState *p = PostureState::createInstance(type, mHand);
00442 double *dof;
00443 if (sticky) {
00444 dof = new double [mHand->getNumDOF()];
00445 mPosture->getHandDOF(dof);
00446 }
00447 delete mPosture;
00448 mPosture = p;
00449 if (sticky) {
00450 mPosture->storeHandDOF(dof);
00451 delete [] dof;
00452 } else {
00453 mPosture->reset();
00454 }
00455 }
00456
00461 void HandObjectState::setRefTran(transf t, bool sticky)
00462 {
00463 transf totalTran;
00464 if (sticky) {
00465 totalTran = mPosition->getCoreTran() * mRefTran;
00466 }
00467 mRefTran = t;
00468 if (sticky) {
00469 mPosition->setTran( totalTran * mRefTran.inverse() );
00470 }
00471 }
00472
00473 bool HandObjectState::readFromFile(FILE *fp)
00474 {
00475
00476 int type; fpos_t pos;
00477 fgetpos(fp,&pos);
00478 if (!fscanf(fp,"%d",&type)) return false;
00479 DBGP("Pose type: " << type);
00480 if ( (StateType)type != POSE_DOF && (StateType)type != POSE_EIGEN ) return false;
00481 if ( type != mPosture->getType() ) {
00482 setPostureType((StateType)type);
00483 }
00484 fsetpos(fp,&pos);
00485 if ( !mPosture->readFromFile(fp) ) {
00486 DBGA("Failed");
00487 return false;
00488 }
00489 fgetpos(fp,&pos);
00490 if (!fscanf(fp,"%d",&type)) return false;
00491 DBGP("Space type: " << type);
00492 if ( (StateType)type != SPACE_COMPLETE && (StateType)type != SPACE_APPROACH &&
00493 (StateType)type != SPACE_AXIS_ANGLE && (StateType)type != SPACE_ELLIPSOID ) return false;
00494 if ( type != mPosition->getType() ) {
00495 setPositionType((StateType)type);
00496 }
00497 fsetpos(fp,&pos);
00498 if ( !mPosition->readFromFile(fp) ) return false;
00499 return true;
00500 }
00501
00502 void HandObjectState::writeToFile(FILE *fp) const
00503 {
00504 mPosture->writeToFile(fp);
00505 mPosition->writeToFile(fp);
00506 }
00507
00508 bool HandObjectState::execute(Hand *h) const
00509 {
00510 if (!h) h = mHand;
00511 else assert( h->getNumDOF() == mHand->getNumDOF());
00512
00513 if (h->setTran( mPosition->getCoreTran() * mRefTran ) == FAILURE) return false;
00514 double *dof = new double[ h->getNumDOF() ];
00515 mPosture->getHandDOF(dof);
00516
00517 h->forceDOFVals( dof );
00518 delete [] dof;
00519 return true;
00520 }
00521
00522 SearchVariable* HandObjectState::getVariable(int i)
00523 {
00524 if ( i < 0 ) assert(0);
00525 else if ( i < mPosture->getNumVariables() ) return mPosture->getVariable(i);
00526 else if ( i < getNumVariables() ) return mPosition->getVariable( i - mPosture->getNumVariables() );
00527 else assert(0);
00528 return NULL;
00529 }
00530
00531 const SearchVariable* HandObjectState::getVariable(int i) const
00532 {
00533 if ( i < mPosture->getNumVariables() ) return mPosture->getVariable(i);
00534 else if ( i < getNumVariables() ) return mPosition->getVariable( i - mPosture->getNumVariables() );
00535 else assert(0);
00536 return NULL;
00537 }
00538
00539 SearchVariable* HandObjectState::getVariable (QString name)
00540 {
00541 SearchVariable *v = mPosture->getVariable(name);
00542 if (v) return v;
00543 return mPosition->getVariable(name);
00544 }
00545
00546 const SearchVariable* HandObjectState::getConstVariable (QString name) const
00547 {
00548 const SearchVariable *v = mPosture->getConstVariable(name);
00549 if (v) return v;
00550 return mPosition->getConstVariable(name);
00551 }
00552
00553 double
00554 HandObjectState::distance(const HandObjectState *s) const
00555 {
00556
00557
00558
00559
00560
00561
00562
00563
00564
00565
00566
00567
00568
00569
00570
00571
00572
00573 transf t1 = mHand->getApproachTran() * getTotalTran();
00574 transf t2 = mHand->getApproachTran() * s->getTotalTran();
00575
00576 vec3 dvec = t1.translation() - t2.translation();
00577 double d = dvec.len();
00578
00579 if (mTargetObject->isA("GraspableBody")) {
00580 d = d / ((GraspableBody*)mTargetObject)->getMaxRadius();
00581 } else {
00582 d = d / 200;
00583 }
00584
00585 Quaternion qvec = t1.rotation() * t2.rotation().inverse();
00586 vec3 axis; double angle;
00587 qvec.ToAngleAxis(angle,axis);
00588 double q = 0.5 * fabs(angle) / M_PI;
00589
00590 return std::max(d,q);
00591 }
00592
00593 SoSeparator*
00594 HandObjectState::getIVRoot()
00595 {
00596 if (!IVRoot) {
00597 IVRoot = new SoSeparator;
00598 IVTran = new SoTransform;
00599 IVMat = new SoMaterial;
00600 IVRoot->addChild(IVTran);
00601 IVRoot->addChild(IVMat);
00602
00603 IVRoot->ref();
00604
00605
00606
00607
00608
00609
00610
00611
00612
00613
00614
00615
00616
00617
00618
00619
00620
00621
00622
00623
00624
00625
00626
00627
00628
00629
00630
00631
00632
00633
00634
00635
00636
00637
00638
00639
00640
00641
00642
00643 SoArrow *arrow = new SoArrow;
00644 arrow->height = 18;
00645 arrow->cylRadius = 1.5;
00646 arrow->coneRadius = 3.25;
00647 arrow->coneHeight = 8;
00648 SoTransform *arrowTran = new SoTransform();
00649 arrowTran->rotation.setValue(SbVec3f(1,0,0),(float)(M_PI/2.0));
00650 IVRoot->addChild(arrowTran);
00651 SoTransform *moveTran = new SoTransform();
00652 moveTran->translation.setValue(SbVec3f(0, -18, 0));
00653 IVRoot->addChild(moveTran);
00654 IVRoot->addChild(arrow);
00655
00656 }
00657
00658
00659
00660
00661 transf t = mHand->getApproachTran() * getTotalTran();
00662 t.toSoTransform(IVTran);
00663 return IVRoot;
00664 }
00665
00666 void
00667 HandObjectState::setIVMarkerColor(double r, double g, double b) const
00668 {
00669 if (!IVRoot || !IVMat) {
00670 DBGA("Attempting to set marker color, but marker not created");
00671 return;
00672 }
00673 IVMat->diffuseColor = SbColor(r,g,b);
00674 IVMat->ambientColor = SbColor(r,g,b);
00675 }
00676
00677 void
00678 HandObjectState::showVisualMarker()
00679 {
00680
00681 if (IVRoot) {
00682 int i = mHand->getWorld()->getIVRoot()->findChild( IVRoot );
00683 if (i>=0) {
00684 DBGP("Search state marker is already in world root");
00685 return;
00686 }
00687 }
00688 mHand->getWorld()->getIVRoot()->addChild( getIVRoot() );
00689 }
00690
00691 void
00692 HandObjectState::hideVisualMarker()
00693 {
00694 if (!IVRoot) return;
00695 int i = mHand->getWorld()->getIVRoot()->findChild( IVRoot );
00696 if ( i < 0 ) {
00697 DBGP("Could not find search state marker in the world root");
00698 } else {
00699 mHand->getWorld()->getIVRoot()->removeChild(i);
00700 }
00701 }
00702
00703 bool
00704 GraspPlanningState::compareStates(const GraspPlanningState *s1, const GraspPlanningState *s2)
00705 {
00706 if (s1->getEnergy() <= s2->getEnergy()) return true;
00707 return false;
00708
00709 }
00710
00711 bool
00712 GraspPlanningState::compareStatesDistances(const GraspPlanningState *s1, const GraspPlanningState *s2)
00713 {
00714 if (s1->getDistance() <= s2->getDistance()) return true;
00715 return false;
00716 }
00717
00718