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 <Inventor/sensors/SoIdleSensor.h>
00027
00028 #include "egPlanner.h"
00029 #include "searchState.h"
00030 #include "searchEnergy.h"
00031 #include "robot.h"
00032 #include "barrett.h"
00033 #include "robotiq.h"
00034 #include "pr2Gripper.h"
00035 #include "body.h"
00036 #include "simAnn.h"
00037 #include "world.h"
00038 #include "gloveInterface.h"
00039 #include "eigenGrasp.h"
00040 #include "collisionInterface.h"
00041
00042
00043 #include "debug.h"
00044
00045
00046 #include "profiling.h"
00047
00048 PROF_DECLARE(EG_PLANNER);
00049
00050 #define BEST_LIST_SIZE 20
00051
00052 EGPlanner::EGPlanner(Hand *h)
00053 {
00054 mHand = h;
00055 init();
00056 mEnergyCalculator = new SearchEnergy();
00057 }
00058
00062 void
00063 EGPlanner::init()
00064 {
00065 mProfileInstance = new Profiling::ProfileInstance();
00066
00067 mIdleSensor = NULL;
00068 mCurrentState = NULL;
00069 mTargetState = NULL;
00070 mInputType = INPUT_NONE;
00071 mRenderType = RENDER_LEGAL;
00072 mRepeat = false;
00073 mCurrentStep = 0;
00074 mRenderCount = 0;
00075 mLastRenderState = NULL;
00076 mMaxSteps = 100000;
00077 mMaxTime = -1;
00078 mMultiThread = false;
00079 mState = INIT;
00080 mUsesClone = false;
00081 mOut = NULL;
00082 }
00083
00084 EGPlanner::~EGPlanner()
00085 {
00086 delete mProfileInstance;
00087 clearSolutions();
00088 if (mEnergyCalculator) delete mEnergyCalculator;
00089 if (mUsesClone) {
00090 mHand->getWorld()->destroyElement(mHand);
00091 }
00092 if (mCurrentState) delete mCurrentState;
00093 if (mTargetState) delete mTargetState;
00094 if (mIdleSensor) delete mIdleSensor;
00095 }
00096
00103 void
00104 EGPlanner::setState(PlannerState s)
00105 {
00106 if (mMultiThread) mControlMutex.lock();
00107 if (mState == DONE && s != DONE && s != EXITED) {
00108 DBGA("Planner is DONE; change state no longer possible");
00109 } else if (mState == EXITED && s != EXITED) {
00110 DBGA("Planner is EXITED; change state no longer possible");
00111 } else {
00112 mState = s;
00113 }
00114 if (mMultiThread) mControlMutex.unlock();
00115 }
00116
00117 PlannerState
00118 EGPlanner::getState()
00119 {
00120 if (mMultiThread) mControlMutex.lock();
00121 PlannerState s = mState;
00122 if (mMultiThread) mControlMutex.unlock();
00123 return s;
00124 }
00125
00130 void
00131 EGPlanner::resetParameters()
00132 {
00133 mCurrentStep = 0;
00134 mRenderCount = 0;
00135 }
00136
00147 bool
00148 EGPlanner::resetPlanner()
00149 {
00150 if ( getState() == RUNNING || getState() == DONE) {
00151 DBGA("Planner is either running or dead; cannot reset");
00152 return false;
00153 }
00154 if (!initialized()) {
00155 DBGA("Planner is not ready; not all necessary information has been set");
00156 return false;
00157 }
00158 clearSolutions();
00159 resetParameters();
00160
00161 mProfileInstance->reset();
00162
00163 setState(READY);
00164 if (!mMultiThread) emit update();
00165 return true;
00166 }
00167
00168 bool
00169 EGPlanner::checkTerminationConditions()
00170 {
00171 if (!isActive()) return true;
00172 bool termination = false;
00173
00174 if (mMaxSteps != -1 && mCurrentStep >= mMaxSteps){
00175 if (!mRepeat) {
00176 pausePlanner();
00177 termination = true;
00178 } else {
00179 resetParameters();
00180 }
00181 if (!mMultiThread) {
00182 emit update();
00183 }
00184 } else if (mMaxTime != -1 ) {
00185
00186
00187 if (getRunningTime() > mMaxTime) {
00188 termination = true;
00189 stopPlanner();
00190 }
00191 }
00192 if (termination) {
00193 emit complete();
00194 }
00195 return termination;
00196 }
00197
00198 void
00199 EGPlanner::createAndUseClone()
00200 {
00201 if (isActive()) {
00202 DBGA("Can not change hands while planner is running");
00203 return;
00204 }
00205 if (mMultiThread) {
00206
00207 mHand->getWorld()->getCollisionInterface()->newThread();
00208 }
00209 Hand *clone;
00210 if (mHand->isA("Barrett")) {
00211 clone = new Barrett( mHand->getWorld(), "Barrett clone");
00212 } else if (mHand->isA("Pr2Gripper")) {
00213 clone = new Pr2Gripper( mHand->getWorld(), "PR2 Gripper clone");
00214 } else if (mHand->isA("RobotIQ")) {
00215 clone = new RobotIQ( mHand->getWorld(), "RobotIQ clone");
00216 } else {
00217 clone = new Hand(mHand->getWorld(), "Hand clone");
00218 }
00219 clone->cloneFrom(mHand);
00220 clone->setRenderGeometry(false);
00221 clone->showVirtualContacts(false);
00222 if (mMultiThread) {
00223
00224
00225 mHand->getWorld()->addRobot(clone,false);
00226 } else {
00227 mHand->getWorld()->addRobot(clone,true);
00228 }
00229 mHand->getWorld()->toggleCollisions(false, mHand, clone);
00230 clone->setTran( mHand->getTran() );
00231 mHand = clone;
00232 mUsesClone = true;
00233 if (mCurrentState) mCurrentState->changeHand(mHand);
00234 }
00235
00242 void
00243 EGPlanner::showClone(bool s)
00244 {
00245 if (!mUsesClone) {
00246 DBGA("Planner is not using a clone");
00247 return;
00248 }
00249 if (!s) {
00250 mHand->getWorld()->removeElementFromSceneGraph(mHand);
00251 } else {
00252 mHand->getWorld()->addElementToSceneGraph(mHand);
00253 }
00254 }
00255
00256 void
00257 EGPlanner::setEnergyType(SearchEnergyType s)
00258 {
00259 assert (mEnergyCalculator);
00260 mEnergyCalculator->setType(s);
00261 }
00262
00263 void
00264 EGPlanner::setContactType(SearchContactType c)
00265 {
00266 assert (mEnergyCalculator);
00267 mEnergyCalculator->setContactType(c);
00268 }
00269
00270 void
00271 EGPlanner::sensorCB(void *data, SoSensor *)
00272 {
00273 EGPlanner *planner = (EGPlanner*)data;
00274 if (planner->checkTerminationConditions()) {
00275
00276 return;
00277 }
00278 planner->mainLoop();
00279 planner->mIdleSensor->schedule();
00280 }
00281
00282 void EGPlanner::threadLoop()
00283 {
00284 bool done = false;
00285 while (!done) {
00286 PlannerState s = getState();
00287 switch(s) {
00288 case STARTING_THREAD:
00289 break;
00290 case INIT:
00291 sleep(0.1);
00292 break;
00293 case READY:
00294 sleep(0.1);
00295 break;
00296 case RUNNING:
00297 mainLoop();
00298 break;
00299 case DONE:
00300 done = true;
00301 break;
00302 case EXITED:
00303 break;
00304 }
00305 if (!done) checkTerminationConditions();
00306 }
00307 setState(EXITED);
00308 DBGP("Thread is done!");
00309 }
00310
00311
00312 double
00313 EGPlanner::getRunningTime()
00314 {
00315 return 1.0e-6 * mProfileInstance->getTotalTimeMicroseconds();
00316 }
00317
00318 void
00319 EGPlanner::run()
00320 {
00321 mMultiThread = true;
00322 mRenderType = RENDER_NEVER;
00323
00324 createAndUseClone();
00325
00326 setState(INIT);
00327 threadLoop();
00328 }
00329
00335 void
00336 EGPlanner::startThread()
00337 {
00338 if (mMultiThread) {
00339 DBGA("Can not start thread; already multi-threaded");
00340 }
00341 if (getState()!=INIT) {
00342 DBGA("Can not start thread; state is not INIT");
00343 }
00344 setState(STARTING_THREAD);
00345 start();
00346 mMultiThread = true;
00347
00348 while (getState() == STARTING_THREAD);
00349
00350
00351
00352 mHand->getWorld()->addElementToSceneGraph(mHand);
00353 }
00354
00355 void
00356 EGPlanner::startPlanner()
00357 {
00358 if ( getState() != READY ) {
00359 DBGA("Planner not ready to start!");
00360 return;
00361 }
00362 if (!mMultiThread) {
00363 mHand->showVirtualContacts(false);
00364 mIdleSensor = new SoIdleSensor(sensorCB, this);
00365 mIdleSensor->schedule();
00366 }
00367 PROF_RESET_ALL;
00368 PROF_START_TIMER(EG_PLANNER);
00369
00370 mProfileInstance->startTimer();
00371
00372 setState( RUNNING );
00373 }
00374
00379 void
00380 EGPlanner::stopPlanner()
00381 {
00382 if (getState()==DONE || getState()==EXITED) return;
00383
00384 pausePlanner();
00385
00386 setState(DONE);
00387 if (mMultiThread) {
00388 DBGP("Waiting for exit");
00389
00390 while (getState()!=EXITED);
00391 DBGP("Exited");
00392 }
00393 }
00394
00395 void
00396 EGPlanner::pausePlanner()
00397 {
00398 if (getState() != RUNNING) return;
00399 mProfileInstance->stopTimer();
00400 if (!mMultiThread) {
00401 if (mIdleSensor) delete mIdleSensor;
00402 mIdleSensor = NULL;
00403 mHand->showVirtualContacts(true);
00404 }
00405 setState(READY);
00406 PROF_STOP_TIMER(EG_PLANNER);
00407 PROF_PRINT_ALL;
00408 if (!mMultiThread) emit complete();
00409 }
00410
00411 void
00412 EGPlanner::render()
00413 {
00414 if (mMultiThread) {
00415
00416
00417 return;
00418 }
00419 if (mRenderType == RENDER_BEST) {
00420 if ( mBestList.empty() ) return;
00421 if ( mLastRenderState == mBestList.front() ) return;
00422 mLastRenderState = mBestList.front();
00423 mBestList.front()->execute();
00424 } else if (mRenderType == RENDER_LEGAL) {
00425 if (mRenderCount >= 20) {
00426 DBGP("Render: geom is " << mHand->getRenderGeometry() );
00427 mRenderCount = 0;
00428 if ( mCurrentState && mCurrentState->isLegal() ) mCurrentState->execute();
00429 } else mRenderCount++;
00430 } else if (mRenderType==RENDER_ALWAYS) {
00431 mCurrentState->execute();
00432 } else if ( mRenderType == RENDER_NEVER ) {
00433 return;
00434 }
00435 }
00436
00437 const GraspPlanningState*
00438 EGPlanner::getGrasp(int i)
00439 {
00440 assert (i>=0 && i<(int)mBestList.size());
00441 std::list<GraspPlanningState*>::iterator it = mBestList.begin();
00442 for (int k=0; k<i; k++) {
00443 it++;
00444 }
00445 return (*it);
00446 }
00447
00448 void
00449 EGPlanner::showGrasp(int i)
00450 {
00451 assert (i>=0 && i<getListSize());
00452 const GraspPlanningState *s = getGrasp(i);
00453 s->execute();
00454 bool l; double e;
00455 mEnergyCalculator->analyzeCurrentPosture(s->getHand(), s->getObject(), l, e, false);
00456 DBGA("Re-computed energy: " << e);
00457 }
00458
00459 void
00460 EGPlanner::clearSolutions()
00461 {
00462 while ( !mBestList.empty() ) {
00463 delete(mBestList.back());
00464 mBestList.pop_back();
00465 }
00466 }
00467 bool
00468 EGPlanner::setInput(unsigned char input, bool on)
00469 {
00470 if (input == INPUT_NONE) {
00471 mInputType = INPUT_NONE;
00472 } else if (on) {
00473 mInputType = mInputType | input;
00474 } else {
00475 mInputType = mInputType & (~input);
00476 }
00477 return true;
00478 }
00479
00480 bool
00481 EGPlanner::processInput()
00482 {
00483 assert(mTargetState);
00484 if (mInputType & INPUT_GLOVE) {
00485
00486
00487
00488 assert(mHand->getGloveInterface());
00489 double *gloveDOF = new double [mHand->getNumDOF()];
00490 for (int d=0; d<mHand->getNumDOF(); d++) {
00491 if (mHand->getGloveInterface()->isDOFControlled(d)) {
00492 gloveDOF[d] = mHand->getGloveInterface()->getDOFValue(d);
00493 } else {
00494 gloveDOF[d] = mHand->getDOF(d)->getVal();
00495 }
00496 }
00497 mTargetState->getPosture()->storeHandDOF(gloveDOF);
00498 delete [] gloveDOF;
00499 }
00500
00501
00502
00503
00504 return true;
00505 }
00506
00507 double
00508 EGPlanner::stateDistance(const GraspPlanningState *s1, const GraspPlanningState *s2) {
00509 return s1->distance(s2);
00510 }
00511
00520 bool
00521 EGPlanner::addToListOfUniqueSolutions(GraspPlanningState *s, std::list<GraspPlanningState*> *list, double distance)
00522 {
00523 std::list<GraspPlanningState*>::iterator it;
00524 it = list->begin();
00525 bool add = true;
00526 while (it!=list->end()) {
00527 double d = stateDistance(s,*it);
00528 if ( fabs(d) < distance ) {
00529 DBGP("Distance: " << fabs(d) );
00530
00531 if ( s->getEnergy() < (*it)->getEnergy() ) {
00532
00533 delete (*it);
00534 it = list->erase(it);
00535 DBGP("Old state removed");
00536 } else {
00537
00538 add = false;
00539 break;
00540 }
00541 } else {
00542
00543 it++;
00544 }
00545 }
00546 if (add) {
00547 list->push_back(s);
00548 }
00549 return add;
00550 }
00551
00552 void
00553 EGPlanner::setStatStream(std::ostream *out) const
00554 {
00555 mOut = out;
00556 assert(mEnergyCalculator);
00557 mEnergyCalculator->setStatStream(out);
00558 }