00001 #include "Shared/RobotInfo.h"
00002 #if defined(TGT_HAS_LEGS) && !defined(TGT_IS_AIBO)
00003
00004 #include "XWalkMC.h"
00005 #include "Events/LocomotionEvent.h"
00006 #include "Motion/IKGradientSolver.h"
00007 #include "Motion/IKThreeLink.h"
00008 #include "Motion/Kinematics.h"
00009 #include "Shared/newmat/newmatap.h"
00010 #include <cmath>
00011
00012 using namespace std;
00013
00014 KinematicJoint* XWalkMC::kine=NULL;
00015 KinematicJoint* XWalkMC::childMap[NumReferenceFrames];
00016
00017 void XWalkMC::setTargetVelocity(float x, float y, float a) {
00018
00019
00020 velocityMode = true;
00021 if(targetVel[0]==x && targetVel[1]==y && targetAngVel==a)
00022 return;
00023
00024 unsigned int sysTime = get_time();
00025 float time = (sysTime-startTime)/1000.f;
00026 computePhase(time);
00027
00028 float speed=targetVel.norm(), origSpeed=speed;
00029 bool inAir[NumLegs];
00030 float phases[NumLegs];
00031 fmat::Column<3> curPos[NumLegs];
00032 for(unsigned int leg=0; leg<NumLegs; ++leg) {
00033 computeLegPhase(leg,inAir[leg],phases[leg]);
00034 computeCurrentPosition(leg, inAir[leg], speed, phases[leg], curPos[leg]);
00035 }
00036 fmat::Column<2> origOff;
00037 float origOffA=0;
00038 if(adaptiveLegOrder)
00039 computeCurrentBodyOffset(phases, speed, origOff[0], origOff[1], origOffA);
00040
00041
00042
00043
00044
00045
00046 unsigned int origOrder[NumLegs];
00047 for(unsigned int leg=0; leg<NumLegs; ++leg)
00048 origOrder[leg]=legStates[leg].reorder;
00049
00050 fmat::Column<3> origVel=fmat::pack(targetVel,targetAngVel);
00051 targetVel[0]=x;
00052 targetVel[1]=y;
00053 targetAngVel=a;
00054 fmat::Column<3> newVel=fmat::pack(targetVel,targetAngVel);
00055 LocomotionEvent e(EventBase::locomotionEGID, getID(), EventBase::statusETID);
00056 e.setXYA(x, y, a);
00057 postEvent(e);
00058
00059 speed=targetVel.norm();
00060 float dirAlignment = fmat::dotProduct(origVel,newVel)/origSpeed/speed;
00061
00062 bool standStill = resetPeriod(time,speed);
00063
00064 if(standStill) {
00065
00066 } else if(!adaptiveLegOrder) {
00067 for(unsigned int leg=0; leg<NumLegs; ++leg)
00068 legStates[leg].reorder = leg;
00069 } else if(std::abs(dirAlignment-1) > EPSILON) {
00070
00071
00072
00073
00074 std::pair<float,unsigned int> fAngle[NumLegs];
00075 for(unsigned int leg=0; leg<NumLegs; ++leg) {
00076 fmat::Column<3> ep = childMap[LegOffset+leg*JointsPerLeg]->getT(*kine).column(3);
00077 fAngle[leg] = std::pair<float,unsigned int>(std::atan2(ep[1],ep[0]),leg);
00078 }
00079 std::stable_sort(fAngle,fAngle+NumLegs);
00080
00081
00082 float dir = 0;
00083 if (speed>EPSILON)
00084 dir += std::atan2(y,x);
00085 if (std::abs(targetAngVel) > speed*EPSILON) {
00086 fmat::Column<2> v=rotationCenter-targetVel;
00087 dir += std::atan2(v[1],v[0]) - std::atan2(rotationCenter[1],rotationCenter[0]);
00088 }
00089
00090
00091 std::pair<float,unsigned int> tAngle[NumLegs];
00092 for(unsigned int leg=0; leg<NumLegs; ++leg) {
00093 tAngle[leg] = std::pair<float,unsigned int>(fAngle[leg].first-dir,fAngle[leg].second);
00094 if(tAngle[leg].first<(float)M_PI)
00095 tAngle[leg].first+=2*(float)M_PI;
00096 if(tAngle[leg].first>(float)M_PI)
00097 tAngle[leg].first-=2*(float)M_PI;
00098 }
00099 std::stable_sort(tAngle,tAngle+NumLegs);
00100
00101
00102 for(unsigned int leg=0; leg<NumLegs; ++leg)
00103 legStates[fAngle[leg].second].reorder = tAngle[leg].second;
00104 }
00105
00106 if(initialPlacement)
00107 return;
00108
00109 bool legsReordered=false;
00110 for(unsigned int leg=0; leg<NumLegs; ++leg) {
00111 if(origOrder[leg]!=legStates[leg].reorder) {
00112 legsReordered=true;
00113 break;
00114 }
00115 }
00116
00117 if(legsReordered) {
00118 unsigned int bestLeg=-1U;
00119
00120
00121 for(unsigned int leg=0; leg<NumLegs; ++leg) {
00122 if(inAir[leg]) {
00123
00124 bestLeg=leg;
00125 break;
00126 } else {
00127
00128
00129
00130
00131
00132
00133 }
00134 }
00135 if(bestLeg==-1U) {
00136
00137 } else {
00138 float legphase;
00139 bool inAirTmp;
00140 computeLegPhase(bestLeg,inAirTmp,legphase);
00141
00142 float tgtPhase = phases[bestLeg];
00143
00144 if(dirAlignment<0)
00145 tgtPhase = 1-tgtPhase;
00146
00147 float shift;
00148 if(inAirTmp)
00149 shift = (legphase-tgtPhase)*p.legParams[bestLeg].flightDuration;
00150 else {
00151 float strideTime = period - p.legParams[bestLeg].flightDuration/1000.f;
00152 shift = (1-tgtPhase)*p.legParams[bestLeg].flightDuration - (p.legParams[bestLeg].flightDuration+legphase*strideTime*1000.f);
00153 }
00154 startTime-=shift;
00155 time = (sysTime-startTime)/1000.f;
00156 computePhase(time);
00157 }
00158
00159 bool inAirTmp;
00160
00161 for(unsigned int leg=0; leg<NumLegs; ++leg)
00162 computeLegPhase(leg,inAirTmp,phases[leg]);
00163
00164
00165
00166
00167
00168 }
00169
00170 for(unsigned int leg=0; leg<NumLegs; ++leg)
00171 resetLegState(leg,phases[leg],curPos[leg],inAir[leg],speed);
00172
00173
00174 if(legsReordered) {
00175 fmat::Column<2> off;
00176 float offA=0;
00177 computeCurrentBodyOffset(phases, speed, off[0], off[1], offA);
00178 off-=origOff;
00179 for(unsigned int leg=0; leg<NumLegs; ++leg)
00180 if(!inAir[leg])
00181 legStates[leg].downPos-=off;
00182
00183 }
00184 }
00185
00186 void XWalkMC::setTargetVelocity(float xvel, float yvel, float avel, float time) {
00187 plantingLegs = false;
00188 targetDisp = fmat::pack(xvel*time,yvel*time);
00189 targetAngDisp = avel*time;
00190 displacementTime = get_time();
00191 if ( xvel == 0 && yvel == 0 && avel == 0 ) {
00192 setTargetVelocity(0, 0, 0);
00193 } else {
00194 setTargetVelocity(xvel,yvel,avel);
00195 velocityMode = false;
00196 }
00197 }
00198
00199 void XWalkMC::setTargetDisplacement(float xdisp, float ydisp, float adisp, float time) {
00200
00201 if ( xdisp == 0 && ydisp == 0 && adisp == 0 ) {
00202 velocityMode = false;
00203 plantingLegs = false;
00204 targetDisp = fmat::pack(xdisp,ydisp);
00205 targetAngDisp = adisp;
00206 displacementTime = get_time();
00207 setTargetVelocity(0, 0, 0);
00208 return;
00209 }
00210 const float tx = std::abs(xdisp/getMaxXVel());
00211 const float ty = std::abs(ydisp/getMaxYVel());
00212 const float ta = std::abs(adisp/getMaxAVel());
00213 const float maxTime = std::max(time,std::max(tx,std::max(ty,ta)));
00214 setTargetVelocity(xdisp/maxTime, ydisp/maxTime, adisp/maxTime, maxTime);
00215 velocityMode = false;
00216 }
00217
00218 int XWalkMC::updateOutputs() {
00219 unsigned int curTime=get_time();
00220 unsigned int dispTime = curTime-displacementTime;
00221 float dispSecs = dispTime / 1000.f;
00222
00223 if(!isDirty()) {
00224 if ( plantingLegs ) {
00225 postEvent(EventBase(EventBase::motmanEGID, getID(), EventBase::statusETID, dispTime));
00226 plantingLegs = false;
00227 }
00228 return 0;
00229 }
00230
00231 if ( ! velocityMode ) {
00232 if ( fabs(dispSecs*targetVel[0]) >= fabs(targetDisp[0]) &&
00233 fabs(dispSecs*targetVel[1]) >= fabs(targetDisp[1]) &&
00234 fabs(dispSecs*targetAngVel) >= fabs(targetAngDisp) ) {
00235 setTargetVelocity(0, 0, 0);
00236 plantingLegs = true;
00237
00238 }
00239 }
00240
00241
00242 fmat::Column<3> ground, gravity;
00243 packGroundGravity(ground, gravity);
00244
00245 float speed = targetVel.norm();
00246 float dt = (curTime-startTime)/1000.f;
00247
00248 kine->pullChildrenQFromArray(state->outputs, 0, NumOutputs);
00249
00250 if(active.size()>0) {
00251 updateNeutralPos(curTime);
00252
00253
00254
00255
00256
00257
00258
00259
00260
00261
00262 }
00263
00264 IKSolver::Point tgts[NumLegs];
00265
00266 if(initialPlacement)
00267 updateOutputsInitial(curTime,ground,gravity,tgts);
00268 else
00269 updateOutputsWalking(dt,ground,gravity,speed,tgts);
00270
00271 sendLoadPredictions(tgts);
00272
00273
00274
00275
00276
00277 return JointsPerLeg*NumLegs;
00278 }
00279
00280 void XWalkMC::start() {
00281 MotionCommand::start();
00282 kine->pullChildrenQFromArray(state->outputs, 0, NumOutputs);
00283 #ifdef TGT_IS_BIPED
00284 initialPlacement=false;
00285 #else
00286 initialPlacement=true;
00287 #endif
00288 startTime=get_time();
00289 if(period == 0)
00290 for(unsigned int leg=0; leg<NumLegs; ++leg)
00291 period += legParams[leg].totalDuration() * 2 / 1000.f;
00292 computePhase(0);
00293 for(unsigned int leg=0; leg<NumLegs; ++leg) {
00294 fmat::Column<3> curPos = childMap[FootFrameOffset+leg]->getWorldPosition();
00295 legStates[leg].liftPos = fmat::SubVector<2>(curPos);
00296 legStates[leg].inAir=true;
00297 legStates[leg].support=0;
00298 legStates[leg].initialHeight = curPos[2];
00299 resetLegState(leg,0,curPos,true,0);
00300 }
00301 }
00302
00303 void XWalkMC::stop() {
00304 DriverMessaging::LoadPrediction loads;
00305 for(unsigned int i=0; i<NumLegs; ++i) {
00306 KinematicJoint * kj = childMap[FootFrameOffset+i];
00307 while(kj!=NULL) {
00308 if(kj->outputOffset<NumOutputs)
00309 loads.loads[kj->outputOffset.get()] = 0;
00310 kj=kj->getParent();
00311 }
00312 }
00313 DriverMessaging::postMessage(loads);
00314
00315
00316 if(contactMsg.size()>0) {
00317 contactMsg.clear();
00318 contactMsg.flushOnMotionUpdate=false;
00319 DriverMessaging::postMessage(contactMsg);
00320 }
00321
00322 MotionCommand::stop();
00323 }
00324
00325 void XWalkMC::zeroVelocities() {
00326 unsigned int t=get_time();
00327 setTargetVelocity(0,0,0);
00328 #ifdef TGT_HAS_WHEELS
00329 for (unsigned int i = WheelOffset; i < WheelOffset + NumWheels; i++)
00330 motman->setOutput(this, i, 0.0f);
00331 #endif
00332 LocomotionEvent e(EventBase::locomotionEGID, getID(), EventBase::deactivateETID, t-displacementTime);
00333 displacementTime = t;
00334 postEvent(e);
00335 }
00336
00337
00338 #if 0
00339 void XWalkMC::lockLegsInPlace() {
00340 setTargetVelocity(0,0,0);
00341
00342 float minHeight=std::numeric_limits<float>::max();
00343 for(unsigned int leg=0; leg<NumLegs; ++leg) {
00344 bool inAir;
00345 float phases;
00346 computeLegPhase(leg,inAir,phases);
00347 fmat::Column<3> curPos;
00348 computeCurrentPosition(leg, inAir, 0, phases, curPos);
00349
00350 KinematicJoint * kj = childMap[FootFrameOffset+leg];
00351 float legr=0;
00352 while(kj!=NULL && kj->outputOffset!=LegOffset+leg*JointsPerLeg) {
00353 legr += kj->r;
00354 kj = kj->getParent();
00355 }
00356 fmat::Transform baseToElv = childMap[LegOffset+leg*JointsPerLeg+1]->getFullInvT();
00357 fmat::Column<2> curPosElv(baseToElv*curPos);
00358 float curr = curPosElv.norm();
00359
00360
00361
00362 float tgtheight = 0;
00363 }
00364 }
00365 #endif
00366
00367 void XWalkMC::updateNeutralPos(unsigned int curTime) {
00368 std::set<ParameterTransition*> deactivated;
00369 for(std::set<ParameterTransition*>::const_iterator it=active.begin(); it!=active.end(); ++it)
00370 if(!(*it)->update(curTime))
00371 deactivated.insert(*it);
00372 for(std::set<ParameterTransition*>::const_iterator it=deactivated.begin(); it!=deactivated.end(); ++it)
00373 active.erase(*it);
00374
00375
00376
00377 for(unsigned int leg=0; leg<NumLegs; ++leg) {
00378 LegParameters& legParam = p.legParams[leg];
00379 KinematicJoint * legRoot = childMap[LegOffset+JointsPerLeg*leg];
00380 fmat::Column<3> fstPos = legRoot->getWorldPosition();
00381 legStates[leg].neutralPos[0] = fstPos[0] + legParam.strideBias;
00382 legStates[leg].neutralPos[1] = ((fstPos[1]<0) ? -*legParam.stanceWidth : *legParam.stanceWidth);
00383 }
00384 }
00385
00386 bool XWalkMC::resetPeriod(float time, float speed) {
00387 bool standStill=false;
00388
00389 if (std::abs(targetAngVel) <= speed*EPSILON) {
00390
00391 if(speed>EPSILON) {
00392
00393
00394
00395 float minAirTime = std::numeric_limits<float>::infinity();
00396 for(unsigned int leg=0; leg<NumLegs; ++leg) {
00397 float t = legParams[leg].totalDuration();
00398
00399 if(t<minAirTime)
00400 minAirTime=t;
00401 }
00402 minAirTime/=1000.f;
00403
00404
00405
00406 fmat::Column<2> d = fmat::pack(strideLenX*targetVel[1], strideLenY*targetVel[0]);
00407 float groundTime = strideLenX*strideLenY / std::sqrt(d[0]*d[0] + d[1]*d[1]);
00408 period = groundTime + minAirTime;
00409
00410 } else {
00411 period = nominalPeriod();
00412 standStill=true;
00413 }
00414
00415 } else {
00416
00417 rotationCenter[0] = -targetVel[1];
00418 rotationCenter[1] = targetVel[0];
00419 rotationCenter/=targetAngVel;
00420
00421
00422
00423
00424 period = std::numeric_limits<float>::infinity();
00425 for(unsigned int leg=0; leg<NumLegs; ++leg) {
00426 fmat::Column<2> radial = legStates[leg].neutralPos - rotationCenter;
00427 if(radial.norm() < EPSILON)
00428 continue;
00429
00430
00431 fmat::Column<2> ivel = fmat::pack(-radial[1],radial[0])*targetAngVel;
00432 fmat::Column<2> d = fmat::pack(strideLenX*ivel[1], strideLenY*ivel[0]);
00433 float groundTime = strideLenX*strideLenY / d.norm();
00434 float airTime = legParams[leg].totalDuration() / 1000.f;
00435
00436 if(groundTime + airTime < period)
00437 period = groundTime + airTime;
00438
00439 }
00440
00441 }
00442
00443 if(!initialPlacement) {
00444 float origPhase=globPhase;
00445 computePhase(time);
00446 float shift = (origPhase-globPhase)*period;
00447 startTime-=shift*1000.f;
00448 globPhase = origPhase;
00449
00450
00451
00452
00453 }
00454
00455 return standStill;
00456 }
00457
00458 void XWalkMC::resetLegState(unsigned int leg, float phase, const fmat::Column<3>& curPos, bool inAir, float speed) {
00459 fmat::Column<3> tgt;
00460 if(inAir) {
00461 legStates[leg].downPos = legStates[leg].neutralPos;
00462
00463 computeCurrentPosition(leg, false, speed, -0.5f, tgt);
00464 legStates[leg].downPos = fmat::SubVector<2>(tgt);
00465
00466
00467
00468
00469
00470 fmat::Column<2> cur(curPos);
00471 if(phase>.8) {
00472
00473 legStates[leg].liftPos = (cur-legStates[leg].downPos)/phase + legStates[leg].downPos;
00474 } else {
00475
00476 fmat::Column<2> downDir = legStates[leg].downPos - cur;
00477 downDir/=downDir.norm();
00478 (cur-legStates[leg].liftPos).norm()/(1-phase)*phase * downDir;
00479 }
00480 } else {
00481 legStates[leg].downPos = fmat::Column<2>(curPos);
00482
00483 computeCurrentPosition(leg, false, speed, -phase, tgt);
00484 legStates[leg].downPos = fmat::SubVector<2>(tgt);
00485 }
00486 }
00487
00488
00489 void XWalkMC::updateOutputsInitial(unsigned int curTime, const fmat::Column<3>& ground, const fmat::Column<3>& gravity, IKSolver::Point tgts[]) {
00490 initialPlacement = false;
00491 bool contactMsgDirty=false;
00492
00493 float phases[NumLegs];
00494 bool inAirFixed = true;
00495 for(unsigned int leg=0; leg<NumLegs; ++leg) {
00496 computeLegPhase(leg,inAirFixed,phases[leg]);
00497 }
00498
00499 fmat::Column<2> off;
00500 float offa=0;
00501 computeCurrentBodyOffset(phases, 0, off[0], off[1], offa);
00502 fmat::Matrix<2,2> offaM = fmat::rotation2D(offa);
00503
00504 for(unsigned int leg=0; leg<NumLegs; ++leg) {
00505 legStates[leg].support=0;
00506 tgts[leg][0]=legStates[leg].neutralPos[0];
00507 tgts[leg][1]=legStates[leg].neutralPos[1];
00508 tgts[leg][2]=p.legParams[leg].flightHeight;
00509 (fmat::SubVector<2>)tgts[leg] = offaM * fmat::SubVector<2>(tgts[leg]) + off;
00510
00511 float raiseDur = p.legParams[leg].raiseDuration*2;
00512 float lowerDur = p.legParams[leg].lowerDuration*2;
00513 float flightDur = p.legParams[leg].flightDuration*2;
00514
00515
00516
00517 fmat::Column<3> curP(legStates[leg].liftPos);
00518 curP[2] = legStates[leg].initialHeight;
00519 float phase;
00520 if(curP[2]>tgts[leg][2]) {
00521
00522 phase = (curTime-startTime)/(raiseDur+flightDur);
00523 if(phase<1) {
00524 tgts[leg] *= phase;
00525 tgts[leg] += curP*(1-phase);
00526 initialPlacement = true;
00527 }
00528 } else {
00529
00530 phase = (curTime-startTime)/raiseDur;
00531 if(phase<1) {
00532
00533 tgts[leg][0] = curP[0];
00534 tgts[leg][1] = curP[1];
00535 tgts[leg][2] *= phase;
00536 tgts[leg][2] += curP[2]*(1-phase);
00537 initialPlacement = true;
00538 } else {
00539
00540 phase = (curTime-startTime-raiseDur)/flightDur;
00541 if(phase<1) {
00542 curP[2] = tgts[leg][2];
00543 tgts[leg] *= phase;
00544 tgts[leg] += curP*(1-phase);
00545 initialPlacement = true;
00546 }
00547 }
00548 }
00549 if(phase>=1) {
00550
00551 phase = (curTime-startTime-raiseDur-flightDur)/(lowerDur);
00552
00553 if(p.groundPlane[3] > 0) {
00554 phase += 1;
00555
00556 fmat::Column<3>& physPos = tgts[leg];
00557 legStates[leg].liftPos = fmat::SubVector<2>(physPos);
00558 legStates[leg].initialHeight = physPos[2];
00559 }
00560
00561 if(phase<1) {
00562
00563 curP=tgts[leg];
00564 tgts[leg][2]=0;
00565 tgts[leg] *= phase;
00566 tgts[leg] += curP*(1-phase);
00567
00568
00569 fmat::Column<3>& physPos = tgts[leg];
00570 legStates[leg].liftPos = fmat::SubVector<2>(physPos);
00571 initialPlacement = true;
00572 } else {
00573 phase-=1;
00574
00575 if(phase<1) {
00576 if(legParams[leg].usable) {
00577 if(legStates[leg].inAir && !contactMsgDirty) {
00578 contactMsg.clear();
00579 contactMsgDirty=true;
00580 }
00581 contactMsg.addEntry(FootFrameOffset+leg, fmat::Column<3>());
00582 }
00583
00584 legStates[leg].inAir=false;
00585 legStates[leg].support=.5f;
00586 if(p.groundPlane[3] <= 0)
00587 curP[2]=0;
00588 tgts[leg]=curP;
00589 projectToGround(ground, p.groundPlane[3], gravity, tgts[leg]);
00590 tgts[leg] *= phase;
00591 tgts[leg] += curP*(1-phase);
00592 initialPlacement = true;
00593 }
00594 }
00595 }
00596 }
00597 if(contactMsgDirty) {
00598 contactMsg.flushOnMotionUpdate=true;
00599 DriverMessaging::postMessage(contactMsg);
00600 }
00601 if(initialPlacement) {
00602 for(unsigned int leg=0; leg<NumLegs; ++leg)
00603 solveIK(leg,tgts[leg]);
00604 } else {
00605
00606 unsigned int timingleg = legStates[0].reorder==-1U ? 0 : legStates[0].reorder;
00607 float endflightphase = p.legParams[timingleg].flightPhase + p.legParams[0].flightDuration/1000.f/period;
00608 float shift = (endflightphase-globPhase)*period;
00609 startTime-=shift*1000.f;
00610 computePhase((curTime-startTime)/1000.f);
00611 kine->pullChildrenQFromArray(state->outputs, 0, NumOutputs);
00612 for(unsigned int leg=0; leg<NumLegs; ++leg) {
00613 bool inAir;
00614 float phase;
00615 computeLegPhase(leg,inAir,phase);
00616
00617 fmat::Column<3> physPos = childMap[FootFrameOffset+leg]->getWorldPosition();
00618
00619 (fmat::SubVector<2>)physPos = offaM.transpose()*fmat::SubVector<2>(physPos) - offaM.transpose()*off;
00620 resetLegState(leg,phase,physPos,false,targetVel.norm());
00621 legStates[leg].support=1;
00622 legStates[leg].onGround=true;
00623 }
00624 LocomotionEvent e(EventBase::locomotionEGID,getID(),EventBase::activateETID,0);
00625 e.setXYA(targetVel[0], targetVel[1], targetAngVel);
00626 postEvent(e);
00627 }
00628 displacementTime=get_time();
00629 }
00630
00631 void XWalkMC::updateOutputsWalking(float dt, const fmat::Column<3>& ground, const fmat::Column<3>& gravity, float speed, IKSolver::Point tgts[]) {
00632
00633
00634
00635
00636
00637
00638 bool inAir[NumLegs];
00639 float phases[NumLegs];
00640
00641
00642
00643 computePhase(dt);
00644
00645 for(unsigned int leg=0; leg<NumLegs; ++leg) {
00646 computeLegPhase(leg,inAir[leg],phases[leg]);
00647
00648 if(legStates[leg].inAir!=inAir[leg]) {
00649
00650
00651 if(speed>0 || std::abs(targetAngVel)>EPSILON || !inAir[leg]) {
00652 legStates[leg].inAir=inAir[leg];
00653 } else {
00654 inAir[leg] = false;
00655 }
00656 if(inAir[leg]) {
00657 legStates[leg].downPos = legStates[leg].neutralPos;
00658 computeCurrentPosition(leg, false, speed, -0.5f, tgts[leg]);
00659 legStates[leg].downPos = fmat::SubVector<2>(tgts[leg]);
00660 }
00661 }
00662 }
00663
00664 fmat::Column<2> off;
00665 float offa=0;
00666 computeCurrentBodyOffset(phases, speed, off[0], off[1], offa);
00667 fmat::Matrix<2,2> offaM = fmat::rotation2D(offa);
00668
00669 for(unsigned int leg=0; leg<NumLegs; ++leg) {
00670
00671
00672
00673
00674
00675
00676
00677
00678
00679 computeCurrentPosition(leg, inAir[leg], speed, phases[leg], tgts[leg]);
00680 if(!inAir[leg])
00681 legStates[leg].liftPos = fmat::SubVector<2>(tgts[leg]);
00682 (fmat::SubVector<2>)tgts[leg] = offaM * fmat::SubVector<2>(tgts[leg]) + off;
00683 }
00684
00685
00686 for(plist::DictionaryOf<SinusoidalParameters>::const_iterator it=nonLegJoints.begin(); it!=nonLegJoints.end(); ++it) {
00687 unsigned int idx = capabilities.findOutputOffset(it->first.c_str());
00688 if(idx!=-1U) {
00689 float val = (*it->second)(globPhase,phases);
00690 motman->setOutput(this,idx,val);
00691 if(KinematicJoint * kj = childMap[idx])
00692 kj->freezeQ(val);
00693 }
00694 }
00695
00696 bool contactChanged=false;
00697
00698
00699
00700 for(unsigned int leg=0; leg<NumLegs; ++leg) {
00701 projectToGround(ground, p.groundPlane[3], gravity, tgts[leg]);
00702
00703 if(inAir[leg]) {
00704 tgts[leg] += ground*(p.legParams[leg].flightHeight + bounce(globPhase,phases));
00705 legStates[leg].support=0;
00706 } else {
00707 float strideTime = period - p.legParams[leg].flightDuration/1000.f;
00708 float height = p.legParams[leg].flightHeight;
00709 float t = (1-phases[leg])*strideTime;
00710 float lowerDur = p.legParams[leg].lowerDuration/1000.f;
00711 float raiseDur = p.legParams[leg].raiseDuration/1000.f;
00712 if(t>strideTime - lowerDur && legStates[leg].support<1) {
00713 float acc = 4 * p.legParams[leg].flightHeight / lowerDur / lowerDur;
00714 t = strideTime - t;
00715 if(t<lowerDur/2) {
00716 height -= acc * t * t / 2;
00717 } else {
00718 t = lowerDur - t;
00719 height = acc * t * t / 2;
00720 }
00721 tgts[leg] += ground*height;
00722 legStates[leg].support=0;
00723 } else if(t<raiseDur && (speed>EPSILON || std::abs(targetAngVel)>EPSILON)) {
00724 float acc = 4 * p.legParams[leg].flightHeight / raiseDur / raiseDur;
00725 if(t<raiseDur/2) {
00726 height -= acc * t * t / 2;
00727 } else {
00728 t = raiseDur - t;
00729 height = acc * t * t / 2;
00730 }
00731 tgts[leg] += ground*height;
00732 legStates[leg].support=0;
00733 } else {
00734 legStates[leg].support=1;
00735 }
00736 tgts[leg] += ground*bounce(globPhase,phases);
00737
00738 if( (legStates[leg].support>=1) != legStates[leg].onGround) {
00739 contactChanged=true;
00740
00741
00742
00743
00744
00745
00746
00747
00748
00749
00750
00751
00752
00753 }
00754 legStates[leg].onGround = (legStates[leg].support>=1);
00755 }
00756
00757
00758
00759 solveIK(leg,tgts[leg]);
00760
00761
00762 }
00763
00764 if(contactChanged) {
00765
00766 if(DriverMessaging::hasListener(DriverMessaging::FixedPoints::NAME)) {
00767 contactMsg.clear();
00768 for(unsigned int leg=0; leg<NumLegs; ++leg) {
00769 if(legStates[leg].onGround && legParams[leg].usable)
00770 contactMsg.addEntry(FootFrameOffset+leg, fmat::Column<3>());
00771 }
00772 contactMsg.flushOnMotionUpdate=true;
00773 postMessage(contactMsg);
00774 }
00775 }
00776
00777
00778
00779
00780 }
00781
00782 void XWalkMC::sendLoadPredictions(IKSolver::Point tgts[]) {
00783
00784
00785 DriverMessaging::LoadPrediction loads;
00786
00787
00788 KinematicJoint * base = childMap[BaseFrameOffset];
00789 std::set<KinematicJoint*> nonsupports(base->getBranches().begin(),base->getBranches().end());
00790 std::map<unsigned int, KinematicJoint*> supports;
00791 for(unsigned int leg=0; leg<NumLegs; ++leg) {
00792 if(legStates[leg].inAir || legStates[leg].support<EPSILON || !legParams[leg].usable) {
00793
00794 KinematicJoint * j = childMap[LegOffset+JointsPerLeg*leg];
00795 while(j->getParent()!=base) {
00796 if(j->outputOffset<NumOutputs)
00797 loads.loads[j->outputOffset.get()]=0;
00798 j = j->getParent();
00799 }
00800 } else {
00801 KinematicJoint * j = childMap[LegOffset+JointsPerLeg*leg];
00802 while(j->getParent()!=base)
00803 j = j->getParent();
00804 supports[leg]=j;
00805 nonsupports.erase(j);
00806 }
00807 }
00808 if(supports.size()>0) {
00809 fmat::Column<4> com = base->getMassVector();
00810 for(std::set<KinematicJoint*>::const_iterator it=nonsupports.begin(); it!=nonsupports.end(); ++it)
00811 com += (*it)->getTq() * (*it)->sumCenterOfMass();
00812
00813
00814 std::vector<fmat::Column<2> > contacts;
00815
00816 for(std::map<unsigned int, KinematicJoint*>::const_iterator it=supports.begin(); it!=supports.end(); ++it)
00817 contacts.push_back(fmat::SubVector<2>(tgts[it->first]));
00818
00819
00820 std::vector<float> pressures;
00821 std::vector<unsigned int> negatives;
00822 do {
00823 computePressure(com[3],com[0]/com[3],com[1]/com[3],contacts,pressures);
00824
00825
00826
00827 negatives.clear();
00828 std::map<unsigned int, KinematicJoint*>::const_iterator it=supports.end();
00829 for(unsigned int i=pressures.size(); i!=0;) {
00830 --it;
00831 if(pressures[--i]<0) {
00832 negatives.push_back(it->first);
00833 contacts.erase(contacts.begin()+i);
00834 }
00835 }
00836 for(unsigned int i=0; i<negatives.size(); ++i)
00837 supports.erase(negatives[i]);
00838 } while(!negatives.empty());
00839
00840
00841 std::vector<float>::const_iterator pressureIt=pressures.begin();
00842 for(std::map<unsigned int, KinematicJoint*>::const_iterator it=supports.begin(); it!=supports.end(); ++it,++pressureIt) {
00843 std::vector<fmat::Column<6> > j;
00844 KinematicJoint * kj = childMap[FootFrameOffset+it->first];
00845
00846 kj->getFullJacobian(tgts[it->first],j);
00847 while(kj!=NULL) {
00848 if(kj->outputOffset<NumOutputs) {
00849
00850 loads.loads[kj->outputOffset.get()] = (*pressureIt)*j[kj->getDepth()][2]/1000;
00851 }
00852 kj=kj->getParent();
00853 }
00854 }
00855 DriverMessaging::postMessage(loads);
00856 }
00857 }
00858
00859
00860 void XWalkMC::computePhase(float time) {
00861 if(!isDirty())
00862 return;
00863 globPhase = time/period;
00864 globPhase -= std::floor(globPhase);
00865 }
00866
00867 void XWalkMC::computeLegPhase(unsigned int leg, bool& inAir, float& phase) {
00868 unsigned int timingLeg = leg;
00869 if(adaptiveLegOrder && legStates[leg].reorder!=-1U)
00870 timingLeg = legStates[leg].reorder;
00871
00872 float legphase = globPhase - p.legParams[timingLeg].flightPhase;
00873 if(legphase<0)
00874 legphase+=1;
00875 float flightphase = p.legParams[leg].flightDuration/1000.f/period;
00876 inAir=(legphase<flightphase);
00877 phase = (inAir) ? 1-legphase/flightphase : (legphase-flightphase)/(1-flightphase);
00878 if(phase<0)
00879 phase+=1;
00880 }
00881
00882 void XWalkMC::computeCurrentPosition(unsigned int leg, bool inAir, float speed, float phase, fmat::Column<3>& tgt) {
00883 const fmat::Column<2>& sp = legStates[leg].downPos;
00884
00885 if(inAir) {
00886 (fmat::SubVector<2>)(tgt) = sp + phase*(legStates[leg].liftPos - sp);
00887
00888
00889 } else {
00890 float nonFlightTime = period - legParams[leg].flightDuration/1000.f;
00891
00892
00893
00894 if (std::abs(targetAngVel) <= speed*EPSILON) {
00895 (fmat::SubVector<2>)(tgt) = sp + -phase*nonFlightTime*targetVel;
00896 } else {
00897
00898 (fmat::SubVector<2>)(tgt) = fmat::rotation2D(-phase*nonFlightTime*targetAngVel) * (sp-rotationCenter) + rotationCenter;
00899 }
00900 }
00901 }
00902
00903 void XWalkMC::computeCurrentBodyOffset(float* legPhases, float speed, float& offx, float& offy, float& offa) {
00904 offx = surge(globPhase,legPhases);
00905 offy = sway(globPhase,legPhases);
00906 offa = 0;
00907 if(rotateBodyMotion && (offx!=0 || offy!=0) && std::abs(speed)>EPSILON) {
00908 float s = targetVel[1]/speed, c = targetVel[0]/speed;
00909 float tmpx = c*offx - s*offy;
00910 float tmpy = s*offx + c*offy;
00911 offx=tmpx;
00912 offy=tmpy;
00913 }
00914 offx-=p.offsetX;
00915 offy-=p.offsetY;
00916 offa-=p.offsetA;
00917 }
00918
00919 void XWalkMC::solveIK(unsigned int leg, const IKSolver::Point& tgt) {
00920 if(!legParams[leg].usable)
00921 return;
00922
00923 KinematicJoint * eff = childMap[FootFrameOffset+leg];
00924
00925 #ifndef TGT_IS_BIPED
00926 eff = childMap[FootFrameOffset+leg];
00927 eff->getIK().solve(IKSolver::Point(), *eff, tgt);
00928 #else
00929
00930
00931
00932
00933
00934
00935
00936
00937
00938
00939
00940
00941
00942
00943
00944
00945
00946
00947 IKSolver::Point new_tgt;
00948 new_tgt[0] = tgt[0];
00949 new_tgt[1] = tgt[1];
00950 new_tgt[2] = tgt[2]+55;
00951
00952
00953
00954
00955
00956
00957 fmat::Column<3> anklePos = childMap[LegOffset+leg*JointsPerLeg + LegAnkleOffset]->getPosition();
00958
00959 eff = childMap[LegOffset+LegKneeOffset+leg*JointsPerLeg];
00960 eff->getIK().solve(anklePos, *eff, new_tgt);
00961 float temp = eff->getQ() + eff->getParent()->getQ();
00962 float other_tmp = eff->getParent()->getParent()->getQ();
00963 eff = childMap[FootFrameOffset+leg];
00964 eff->getParent()->tryQ(other_tmp*-1);
00965 eff->getParent()->getParent()->tryQ(temp);
00966
00967
00968
00969
00970
00971
00972
00973
00974
00975
00976
00977 #endif
00978
00979
00980
00981 for(; eff!=NULL; eff=eff->getParent()) {
00982 if(eff->outputOffset!=plist::OutputSelector::UNUSED && eff->outputOffset<NumOutputs) {
00983
00984
00985 #ifndef PLATFORM_APERIOS
00986 if(!std::isnan(eff->getQ()))
00987 #endif
00988 {
00989 motman->setOutput(this, eff->outputOffset, eff->getQ());
00990 }
00991 }
00992 }
00993 }
00994
00995 void XWalkMC::computePressure(float mass, float massx, float massy, const std::vector<fmat::Column<2> >& contacts, std::vector<float>& pressures) {
00996 const float gAcc = 9.80665f;
00997 NEWMAT::ColumnVector weight(3);
00998 const float force = mass*gAcc;
00999 weight(1) = force;
01000 weight(2) = massx/1000.f*force;
01001 weight(3) = massy/1000.f*force;
01002
01003
01004
01005
01006 NEWMAT::Matrix statics(3,contacts.size());
01007 for(unsigned int i=0; i<contacts.size(); ++i) {
01008 statics(1,i+1) = 1;
01009 statics(2,i+1) = contacts[i][0]/1000.f;
01010 statics(3,i+1) = contacts[i][1]/1000.f;
01011 }
01012
01013 NEWMAT::ColumnVector f;
01014 if(statics.ncols() == 0) {
01015
01016 } else if(statics.ncols() < 3) {
01017
01018 NEWMAT::Matrix U, V;
01019 NEWMAT::DiagonalMatrix Q;
01020 NEWMAT::SVD(statics,Q,U,V,true,true);
01021 for(int i=1; i<=Q.ncols(); ++i) {
01022 if(Q(i)<EPSILON)
01023 Q(i)=0;
01024 else
01025 Q(i)=1/Q(i);
01026 }
01027 f = V*Q*U.t()*weight;
01028 } else if(statics.ncols() == 3) {
01029
01030 try {
01031 f = statics.i()*weight;
01032 } catch(...) {
01033
01034 NEWMAT::Matrix U, V;
01035 NEWMAT::DiagonalMatrix Q;
01036 NEWMAT::SVD(statics,Q,U,V,true,true);
01037 for(int i=1; i<=Q.ncols(); ++i) {
01038 if(Q(i)<EPSILON)
01039 Q(i)=0;
01040 else
01041 Q(i)=1/Q(i);
01042 }
01043 f = V*Q*U.t()*weight;
01044 }
01045 } else {
01046
01047 NEWMAT::Matrix U, V;
01048 NEWMAT::DiagonalMatrix Q;
01049 NEWMAT::SVD(statics.t(),Q,U,V,true,true);
01050 for(int i=1; i<=Q.ncols(); ++i) {
01051 if(Q(i)<EPSILON)
01052 Q(i)=0;
01053 else
01054 Q(i)=1/Q(i);
01055 }
01056 f = U*Q*V.t()*weight;
01057 }
01058
01059 pressures.resize(contacts.size());
01060 for(unsigned int i=0; i<contacts.size(); ++i)
01061 pressures[i]=f(i+1);
01062 }
01063
01064
01065 void XWalkMC::spiderSettings(plist::DictionaryBase& src, plist::DictionaryBase& dst) {
01066 for(plist::DictionaryBase::const_iterator itS=src.begin(), itD=dst.begin(); itS!=src.end(); ++itS, ++itD) {
01067 if(plist::DictionaryBase* dcol=dynamic_cast<plist::DictionaryBase*>(itS->second)) {
01068 spiderSettings(*dcol,dynamic_cast<plist::DictionaryBase&>(*itD->second));
01069 } else if(plist::ArrayBase* acol=dynamic_cast<plist::ArrayBase*>(itS->second)) {
01070 spiderSettings(*acol,dynamic_cast<plist::ArrayBase&>(*itD->second));
01071 } else if(plist::PrimitiveBase* prim=dynamic_cast<plist::PrimitiveBase*>(itS->second)) {
01072 plist::PrimitiveBase& primDst = dynamic_cast<plist::PrimitiveBase&>(*itD->second);
01073 ParameterTransition * trans = new ParameterTransition(*prim,primDst,active,transitionDuration);
01074 transitions.insert(trans);
01075 }
01076 }
01077 }
01078
01079 void XWalkMC::spiderSettings(plist::ArrayBase& src, plist::ArrayBase& dst) {
01080 for(unsigned int i=0; i<src.size(); ++i) {
01081 if(plist::DictionaryBase* dcol=dynamic_cast<plist::DictionaryBase*>(&src[i])) {
01082 spiderSettings(*dcol,dynamic_cast<plist::DictionaryBase&>(dst[i]));
01083 } else if(plist::ArrayBase* acol=dynamic_cast<plist::ArrayBase*>(&src[i])) {
01084 spiderSettings(*acol,dynamic_cast<plist::ArrayBase&>(dst[i]));
01085 } else if(plist::PrimitiveBase* prim=dynamic_cast<plist::PrimitiveBase*>(&src[i])) {
01086 plist::PrimitiveBase& primDst = dynamic_cast<plist::PrimitiveBase&>(dst[i]);
01087 ParameterTransition * trans = new ParameterTransition(*prim,primDst,active,transitionDuration);
01088 transitions.insert(trans);
01089 }
01090 }
01091 }
01092
01093
01094 void XWalkMC::ParameterTransition::plistValueChanged(const plist::PrimitiveBase& ) {
01095 decelerate=false;
01096 lastUpdate=startTime=get_time();
01097 float dur = duration/2.f;
01098 cura = 2 * ( (src.castTo<float>()-dst.castTo<float>())/2 - curd * dur ) / (dur*dur);
01099 active.insert(this);
01100 }
01101
01102 bool XWalkMC::ParameterTransition::update(unsigned int curTime) {
01103 if(curTime>startTime+duration) {
01104 curd=0;
01105 dst=src;
01106 return false;
01107 }
01108 float srcV = src.castTo<float>(), dstV = dst.castTo<float>();
01109 float dt = (startTime+duration)-lastUpdate;
01110 float f = dstV + curd*dt + 0.5f * -cura*dt*dt;
01111 if( (f>=srcV && dstV<=srcV) || (f<=srcV && dstV>=srcV) )
01112 decelerate=true;
01113 if(decelerate) {
01114
01115 float dist = srcV-dstV;
01116
01117
01118
01119
01120 float acc = - curd*curd / (2 * dist);
01121 startTime = (unsigned int)(curTime + 2 * dist / curd - duration + .5f);
01122
01123 dt = curTime-lastUpdate;
01124 f = plist::Primitive<float>(dstV + curd*dt + acc * dt * dt / 2);
01125
01126 if( (f>=srcV && dstV<=srcV) || (f<=srcV && dstV>=srcV) ) {
01127 curd=0;
01128 dst=src;
01129 return false;
01130 }
01131 dst = f;
01132 curd += acc*dt;
01133 } else {
01134
01135 dt = curTime-lastUpdate+.5f;
01136 dst = plist::Primitive<float>(dstV + curd*dt + cura*dt*dt/2);
01137 curd += cura*dt;
01138 }
01139 lastUpdate=curTime;
01140 return true;
01141 }
01142
01143
01144
01145
01146
01147
01148 #endif // TGT_HAS_LEGS