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 "dof.h"
00027
00028 #include <QTextStream>
00029
00030 #include "robot.h"
00031 #include "joint.h"
00032 #include "dynJoint.h"
00033 #include "body.h"
00034 #include "world.h"
00035
00036
00037 #include "debug.h"
00038
00040 DOF::DOF() : owner(NULL), q(0.0),desiredq(0.0), desiredVelocity(0.0),defaultVelocity(0.0),
00041 actualVelocity(0.0), maxAccel(10.0), force(0.0),maxForce(0.0),
00042 extForce(0.0), Kv(0.0),Kp(0.0),mHistoryMaxSize(10), mDynStartTime(0.0), currTrajPt(0),
00043 draggerScale(20.0)
00044 {
00045 }
00046
00051 DOF::DOF(const DOF *original)
00052 {
00053 owner = NULL;
00054 dofNum = original->dofNum;
00055 maxq = original->maxq;
00056 minq = original->minq;
00057 q = 0.0;
00058 desiredq = 0.0;
00059
00060 defaultVelocity = original->defaultVelocity;
00061 maxAccel = original->maxAccel;
00062 desiredVelocity = 0.0;
00063 actualVelocity = 0.0;
00064
00065 maxForce = original->maxForce;
00066 force = 0.0;
00067 extForce = 0.0;
00068
00069 Kv = original->Kv;
00070 Kp = original->Kp;
00071
00072 mHistoryMaxSize = original->mHistoryMaxSize;
00073 draggerScale = original->draggerScale;
00074 currTrajPt = 0;
00075 }
00076
00082 void
00083 DOF::initDOF(Robot *myRobot,const std::list<Joint *>& jList)
00084 {
00085 owner = myRobot;
00086 jointList = jList;
00087 updateMinMax();
00088 }
00089
00092 void DOF::updateMinMax()
00093 {
00094 maxq = (*jointList.begin())->getMax()/getStaticRatio(*jointList.begin());
00095 minq = (*jointList.begin())->getMin()/getStaticRatio(*jointList.begin());
00096 DBGP("Joint 0 min " << minq << " max " << maxq);
00097 if (maxq < minq) std::swap(maxq, minq);
00098 DBGP("maxq " << maxq << " minq " << minq);
00099 std::list<Joint *>::iterator j;
00100 double testMin, testMax;
00101 DBGST(int num = 0;)
00102 for(j=++jointList.begin();j!=jointList.end();j++) {
00103 testMax = (*j)->getMax()/getStaticRatio(*j);
00104 testMin = (*j)->getMin()/getStaticRatio(*j);
00105
00106 if (testMax < testMin) std::swap(testMin, testMax);
00107 DBGP("Joint " << num++ << " min " << testMin << " max " << testMax);
00108 maxq = ( testMax < maxq ? testMax : maxq);
00109 minq = ( testMin > minq ? testMin : minq);
00110 DBGP("maxq " << maxq << " minq " << minq);
00111 }
00112 }
00113
00120 void
00121 DOF::updateSetPoint() {
00122 if (!trajectory.empty()) {
00123 setPoint = trajectory[currTrajPt++];
00124 if (trajectory.begin()+currTrajPt==trajectory.end()) {
00125 trajectory.clear();
00126 }
00127 }else if (setPoint != desiredq) {
00128 setPoint=desiredq;
00129 }
00130 DBGP("Update set point: " << setPoint);
00131 }
00132
00137 void
00138 DOF::setTrajectory(double *traj,int numPts)
00139 {
00140 trajectory.clear();
00141 currTrajPt = 0;
00142 trajectory.reserve(numPts);
00143 for (int i=0;i<numPts;i++) {
00144 trajectory.push_back(traj[i]);
00145 }
00146 desiredq = traj[numPts-1];
00147 mErrorHistory.clear();
00148 mPositionHistory.clear();
00149 mForceHistory.clear();
00150
00151 mDynStartTime = owner->getWorld()->getWorldTime();
00152 }
00153
00155 void
00156 DOF::addToTrajectory(double *traj,int numPts)
00157 {
00158 for (int i=0;i<numPts;i++){
00159 trajectory.push_back(traj[i]);
00160 }
00161 desiredq = trajectory.back();
00162 }
00163
00167 void
00168 DOF::callController(double timeStep)
00169 {
00170
00171
00172 updateFromJointValues();
00173
00174
00175 mErrorHistory.push_front(setPoint - q);
00176 while ((int)mErrorHistory.size() > mHistoryMaxSize) {
00177 mErrorHistory.pop_back();
00178 }
00179
00180
00181
00182
00183
00184
00185
00186
00187 if (!mPositionHistory.empty()) {
00188 mVelocityHistory.push_front( (q - mPositionHistory.front() ) / timeStep );
00189 while ((int)mVelocityHistory.size() > mHistoryMaxSize) {
00190 mVelocityHistory.pop_back();
00191 }
00192 }
00193
00194 mPositionHistory.push_front(q);
00195 while ((int)mPositionHistory.size() > mHistoryMaxSize) {
00196 mPositionHistory.pop_back();
00197 }
00198
00199
00200 double newForce = PDPositionController(timeStep);
00201
00202 setForce(newForce);
00203
00204 mForceHistory.push_front(newForce);
00205 while ((int)mForceHistory.size() > mHistoryMaxSize) {
00206 mForceHistory.pop_back();
00207 }
00208 }
00209
00216 double
00217 DOF::PDPositionController(double timeStep)
00218 {
00219 double error = mErrorHistory.front(), lastError;
00220 if (mErrorHistory.size() >= 2) {
00221 lastError = *(++mErrorHistory.begin());
00222 } else {
00223 lastError = error;
00224 }
00225
00226 double newForce;
00227
00228 newForce = Kp * error + Kv * (error-lastError)/timeStep;
00229
00230 DBGP("DOF " << getDOFNum() );
00231 DBGP("setPoint ="<<setPoint<<" error ="<<error<<" edot = "<<(error-lastError));
00232 DBGP("proportional: "<<error<<"*"<<Kp<<"="<<error*Kp);
00233 DBGP("derivative: "<<Kv<<"*"<<(error-lastError)/timeStep);
00234 DBGP("cap: "<<getMaxForce()*0.8 << " Force: "<<newForce);
00235 DBGP("e " << error << " de " << error-lastError << " ts " << timeStep << " f " << newForce);
00236 return newForce;
00237 }
00238
00243 bool
00244 DOF::dynamicsProgress()
00245 {
00246 return true;
00247 }
00248
00253 bool
00254 DOF::readParametersFromXml(const TiXmlElement* root)
00255 {
00256 if(!getDouble(root,"defaultVelocity", defaultVelocity))
00257 return false;
00258 if(!getDouble(root,"maxEffort", maxForce))
00259 return false;
00260 if(!getDouble(root,"Kp", Kp))
00261 return false;
00262 if(!getDouble(root,"Kd", Kv))
00263 return false;
00264 if(!getDouble(root,"draggerScale", draggerScale))
00265 return false;
00266 return true;
00267 }
00268
00272 bool
00273 DOF::writeToStream(QTextStream &stream)
00274 {
00275 stream << q;
00276 return true;
00277 }
00278
00282 bool
00283 DOF::readFromStream(QTextStream &stream)
00284 {
00285 if (stream.atEnd()) return false;
00286 stream >> q;
00287 return true;
00288 }
00289
00295 void
00296 RigidDOF::setForce(double f)
00297 {
00298 Joint *activeJoint = *(jointList.begin());
00299 if (f > maxForce) force = maxForce;
00300 else if (f < -maxForce) force = -maxForce;
00301 else force = f;
00302
00303
00304 activeJoint->applyInternalWrench(force);
00305 DBGP("Applied force = " << force);
00306 }
00307
00314 double
00315 RigidDOF::getClosestJointLimit(int *direction)
00316 {
00317 bool firstTime = true;
00318 double closestLimit = 0.0;
00319 *direction = 0.0;
00320 std::list<Joint*>::iterator j;
00321 for (j=jointList.begin(); j!=jointList.end(); j++) {
00322 double val = (*j)->getVal();
00323 double maxError = val - (*j)->getMax();
00324 double minError = (*j)->getMin() - val;
00325 double error; int jdir;
00326 if (maxError > minError) {
00327 error = maxError;
00328 jdir = -1;
00329 } else {
00330 error = minError;
00331 jdir = +1;
00332 }
00333 error /= getStaticRatio(*j);
00334 if (firstTime || fabs(error) > fabs(closestLimit)) {
00335 closestLimit = error;
00336 *direction = jdir;
00337 firstTime = false;
00338 }
00339 }
00340 return closestLimit;
00341 }
00342
00346 int
00347 RigidDOF::getNumLimitConstraints()
00348 {
00349 int d;
00350 if (getClosestJointLimit(&d) < -0.01) return 0;
00351 return 1;
00352 }
00353
00358 void
00359 RigidDOF::buildDynamicLimitConstraints(std::map<Body*,int> &islandIndices, int numBodies,
00360 double* H, double *g, int &hcn)
00361 {
00362 int dir;
00363 double error = getClosestJointLimit(&dir);
00364 if ( error < -0.01) return;
00365
00366 g[hcn] = MIN(0.0, -error - 0.005);
00367 DBGP("adding dof limit constraint for DOF " << dofNum << " in dir " << dir << "; error: "<<g[hcn]);
00368
00369
00370 Joint *currentJoint = jointList.front();
00371 DynamicBody *prevLink = currentJoint->dynJoint->getPrevLink();
00372 DynamicBody *nextLink = currentJoint->dynJoint->getNextLink();
00373
00374 assert( islandIndices[prevLink]>=0 );
00375 int row = 6*islandIndices[prevLink];
00376 H[(hcn)*6*numBodies + row+3] -= dir * currentJoint->getWorldAxis()[0];
00377 H[(hcn)*6*numBodies + row+4] -= dir * currentJoint->getWorldAxis()[1];
00378 H[(hcn)*6*numBodies + row+5] -= dir * currentJoint->getWorldAxis()[2];
00379
00380 assert( islandIndices[nextLink]>=0 );
00381 row = 6*islandIndices[nextLink];
00382 H[(hcn)*6*numBodies + row+3] += dir * currentJoint->getWorldAxis()[0];
00383 H[(hcn)*6*numBodies + row+4] += dir * currentJoint->getWorldAxis()[1];
00384 H[(hcn)*6*numBodies + row+5] += dir * currentJoint->getWorldAxis()[2];
00385
00386 hcn++;
00387 }
00388
00393 void
00394 RigidDOF::buildDynamicCouplingConstraints(std::map<Body*,int> &islandIndices, int numBodies,
00395 double* Nu, double*, int &ncn)
00396 {
00397
00398 Joint *masterJoint = jointList.front();
00399
00400 DynamicBody *masterPrevLink = masterJoint->dynJoint->getPrevLink();
00401 DynamicBody *masterNextLink = masterJoint->dynJoint->getNextLink();
00402 double masterRatio = getStaticRatio(masterJoint);
00403 vec3 masterFreeRotAxis = masterJoint->getWorldAxis();
00404
00405 std::list<Joint*>::iterator it = jointList.begin();
00406 while(++it != jointList.end()) {
00407 Joint *currentJoint = (*it);
00408
00409
00410
00411
00412
00413 if (currentJoint->getType() != REVOLUTE) continue;
00414
00415 DynamicBody *prevLink = currentJoint->dynJoint->getPrevLink();
00416 DynamicBody *nextLink = currentJoint->dynJoint->getNextLink();
00417 vec3 freeRotAxis = currentJoint->getWorldAxis();
00418
00419
00420 double ratio = 1.0/getStaticRatio(currentJoint);
00421 assert( islandIndices[prevLink] >= 0 );
00422 int row = 6*islandIndices[prevLink];
00423 Nu[(ncn)*6*numBodies + row+3] -= ratio * freeRotAxis[0];
00424 Nu[(ncn)*6*numBodies + row+4] -= ratio * freeRotAxis[1];
00425 Nu[(ncn)*6*numBodies + row+5] -= ratio * freeRotAxis[2];
00426 assert( islandIndices[nextLink] >= 0 );
00427 row = 6*islandIndices[nextLink];
00428 Nu[(ncn)*6*numBodies + row+3] += ratio * freeRotAxis[0];
00429 Nu[(ncn)*6*numBodies + row+4] += ratio * freeRotAxis[1];
00430 Nu[(ncn)*6*numBodies + row+5] += ratio * freeRotAxis[2];
00431
00432
00433 ratio = 1.0/masterRatio;
00434 assert( islandIndices[masterPrevLink] >= 0 );
00435 row = 6*islandIndices[masterPrevLink];
00436 Nu[(ncn)*6*numBodies + row+3] += ratio * masterFreeRotAxis[0];
00437 Nu[(ncn)*6*numBodies + row+4] += ratio * masterFreeRotAxis[1];
00438 Nu[(ncn)*6*numBodies + row+5] += ratio * masterFreeRotAxis[2];
00439 assert( islandIndices[masterNextLink] >= 0 );
00440 row = 6*islandIndices[masterNextLink];
00441 Nu[(ncn)*6*numBodies + row+3] += - ratio * masterFreeRotAxis[0];
00442 Nu[(ncn)*6*numBodies + row+4] += - ratio * masterFreeRotAxis[1];
00443 Nu[(ncn)*6*numBodies + row+5] += - ratio * masterFreeRotAxis[2];
00444
00445 ncn++;
00446
00447
00448 }
00449 }
00450
00451 double
00452 RigidDOF::getStaticRatio(Joint *j) const
00453 {
00454 return j->getCouplingRatio();
00455 }
00456
00457 void
00458 RigidDOF::getJointValues(double *jointVals) const
00459 {
00460 std::list<Joint*>::const_iterator j;
00461 for(j=jointList.begin();j!=jointList.end();j++) {
00462 jointVals[ (*j)->getNum() ] = q * getStaticRatio(*j);
00463 }
00464 }
00465
00468 bool
00469 RigidDOF::accumulateMove(double q1, double *jointVals, int *stoppedJoints)
00470 {
00471 if ( fabs(q-q1) < 1.0e-5 ) return false;
00472 std::list<Joint*>::iterator j;
00473 if (stoppedJoints) {
00474 for(j=jointList.begin();j!=jointList.end();j++) {
00475 if ( stoppedJoints[ (*j)->getNum()] ) return false;
00476 }
00477 }
00478 for(j=jointList.begin();j!=jointList.end();j++) {
00479 jointVals[ (*j)->getNum() ] = q1 * getStaticRatio(*j);
00480 }
00481 return true;
00482 }
00483
00489 void
00490 RigidDOF::updateFromJointValues(const double *jointVals)
00491 {
00492 assert(!jointList.empty());
00493 double val;
00494 if (jointVals) {
00495 val = jointVals[ jointList.front()->getNum() ];
00496 }
00497 else {
00498 val = jointList.front()->getVal();
00499 }
00500 q = val / getStaticRatio(jointList.front());
00501 DBGP("DOF " << getDOFNum() << ": set value " << q);
00502 }
00503
00504 BreakAwayDOF::~BreakAwayDOF()
00505 {
00506 if (mInBreakAway) delete [] mInBreakAway;
00507 if (mBreakAwayValues) delete [] mBreakAwayValues;
00508 }
00509
00510 void BreakAwayDOF::initDOF(Robot *myRobot, const std::list<Joint*> &jList)
00511 {
00512 DOF::initDOF(myRobot, jList);
00513 int size = (int)jList.size();
00514 assert(size>0);
00515 mInBreakAway = new int[size];
00516 mBreakAwayValues = new double[size];
00517 for (int i=0; i<size; i++) {
00518 mInBreakAway[i] = 0;
00519
00520 mBreakAwayValues[i] = -10;
00521 }
00522 }
00523
00527 void
00528 BreakAwayDOF::getJointValues(double *jointVals) const
00529 {
00530 int index = -1;
00531 std::list<Joint*>::const_iterator j;
00532 for (j=jointList.begin(); j!=jointList.end(); j++) {
00533 index++;
00534 if (mInBreakAway[index] && q > mBreakAwayValues[index]) {
00535 jointVals[ (*j)->getNum() ] = mBreakAwayValues[index] * getStaticRatio(*j);
00536 } else {
00537 jointVals[ (*j)->getNum() ] = q * getStaticRatio(*j);
00538 }
00539 }
00540 }
00541
00545 bool
00546 BreakAwayDOF::accumulateMove(double q1, double *jointVals, int *stoppedJoints)
00547 {
00548 if ( fabs(q-q1) < 1.0e-5 ) {
00549 DBGP("DOF new value same as current value");
00550 return false;
00551 }
00552 std::list<Joint*>::iterator j;
00553
00554 for (j=jointList.begin(); j!=jointList.end(); j++) {
00555 if (stoppedJoints && stoppedJoints[ (*j)->getNum()] ) {
00556 if (q1 < q){
00557 DBGP("Joint stopped in the negative direction; stopping all movement");
00558 return false;
00559 }
00560 }
00561 }
00562
00563
00564 bool movement = false;
00565 int index = -1;
00566 for (j=jointList.begin(); j!=jointList.end(); j++) {
00567 index++;
00568 if (mInBreakAway[index] && q1 > mBreakAwayValues[index]) {
00569 DBGP("Joint " << index << " is in break away");
00570 continue;
00571 }
00572 double newVal = q1 * getStaticRatio(*j);
00573 DBGP("q1 " << q1 << " * ratio " << getStaticRatio(*j) << " = " << newVal);
00574 double oldVal = (*j)->getVal();
00575 if (stoppedJoints) {
00576 if (newVal > oldVal && (stoppedJoints[ (*j)->getNum()] & 1) ) {
00577 DBGP("Joint " << index << " is stopped in the positive direction");
00578 continue;
00579 }
00580 if (newVal < oldVal && (stoppedJoints[ (*j)->getNum()] & 2) ) {
00581 DBGP("Joint " << index << " is stopped in the negative direction");
00582 continue;
00583 }
00584 }
00585 jointVals[ (*j)->getNum() ] = newVal;
00586 movement = true;
00587 }
00588 return movement;
00589 }
00590
00591 void
00592 BreakAwayDOF::updateVal(double q1)
00593 {
00594 std::list<Joint*>::iterator j;
00595 int index;
00596 for(j=jointList.begin(), index=0; j!=jointList.end(); j++,index++) {
00597 double jVal = (*j)->getVal() / getStaticRatio(*j);
00598 if (mInBreakAway[index]) {
00599 if (q1 < mBreakAwayValues[index] - 1.0e-5) {
00600 mInBreakAway[index] = false;
00601 DBGP("DOF " << dofNum << " joint " << index << " re-engaged");
00602 }
00603 } else {
00604 if (jVal < q1 - 1.0e-5) {
00605 DBGP("DOF " << dofNum << " joint " << index << " disengaged at " << jVal);
00606 mInBreakAway[index] = true;
00607 mBreakAwayValues[index] = jVal;
00608 }
00609 }
00610 }
00611 q = q1;
00612 }
00613
00617 void
00618 BreakAwayDOF::updateFromJointValues(const double *jointVals)
00619 {
00620 std::list<Joint*>::iterator j;
00621 int index;
00622 double val;
00623 for(j=jointList.begin(),index=0; j!=jointList.end(); j++,index++) {
00624 if (mInBreakAway[index]) continue;
00625 if (!jointVals) {
00626 val = (*j)->getVal() / getStaticRatio(*j);
00627 } else {
00628 val = jointVals[ (*j)->getNum() ] / getStaticRatio(*j);
00629 }
00630 break;
00631 }
00632
00633 assert( j!= jointList.end() );
00634 q = val;
00635 DBGP("DOF " << getDOFNum() << ": set value " << q);
00636 }
00637
00639 void
00640 BreakAwayDOF::reset()
00641 {
00642 if (!mInBreakAway) return;
00643 for (int j=0; j<(int)jointList.size(); j++) {
00644 mInBreakAway[j] = false;
00645 }
00646 }
00647
00648 bool
00649 BreakAwayDOF::writeToStream(QTextStream &stream)
00650 {
00651 stream << q;
00652 for (int j=0; j<(int)jointList.size(); j++) {
00653 if (!mInBreakAway || !mInBreakAway[j]) {
00654 stream << " " << 0;
00655 } else {
00656 stream << " " << 1 << " " << mBreakAwayValues[j];
00657 }
00658 }
00659 return true;
00660 }
00661
00665 double
00666 BreakAwayDOF::getSaveVal() const
00667 {
00668 if (!mInBreakAway) return q;
00669 double val = q;
00670 for (int j=0; j<(int)jointList.size(); j++) {
00671 if ( mInBreakAway[j] ) {
00672 if ( mBreakAwayValues[j] < val ) {
00673 val = mBreakAwayValues[j];
00674 }
00675 }
00676 }
00677 return val;
00678 }
00679
00680 bool
00681 BreakAwayDOF::readFromStream(QTextStream &stream)
00682 {
00683 if (stream.atEnd()) return false;
00684 stream >> q;
00685 DBGP("Value: " << q);
00686 for (int j=0; j<(int)jointList.size(); j++) {
00687 assert(mInBreakAway);
00688 stream >> mInBreakAway[j];
00689 DBGP(" bway: " << mInBreakAway[j]);
00690 if (mInBreakAway[j] == 1) {
00691 stream >> mBreakAwayValues[j];
00692 } else if (mInBreakAway[j]==0) {
00693 mBreakAwayValues[j] = -10;
00694 } else {
00695 return false;
00696 }
00697 }
00698 return true;
00699 }
00700
00701 bool
00702 BreakAwayDOF::readParametersFromXml(const TiXmlElement* root)
00703 {
00704 if (!DOF::readParametersFromXml(root)) return false;
00705 if(!getDouble(root,"breakAwayTorque", mBreakAwayTorque)||mBreakAwayTorque < 0){
00706
00707 DBGA("BreakAway torque missing or negative, using default value 0.0");
00708 mBreakAwayTorque = 0.0f;
00709 } else {
00710
00711 mBreakAwayTorque *= 1.0e3;
00712 }
00713 return true;
00714 }
00715
00721 bool
00722 BreakAwayDOF::computeStaticJointTorques(double *jointTorques, double)
00723 {
00724 std::list<Joint*>::iterator j;
00725 int index;
00726 for(j=jointList.begin(), index=0; j!=jointList.end(); j++,index++) {
00727 if (mInBreakAway[index]) {
00728 jointTorques[ (*j)->getNum() ] += mBreakAwayTorque;
00729 }
00730 }
00731 return true;
00732 }
00733
00734 void
00735 CompliantDOF::initDOF(Robot *myRobot, const std::list<Joint*> &jList)
00736 {
00737 DOF::initDOF(myRobot, jList);
00738 std::list<Joint*>::iterator j;
00739 for(j=jointList.begin(); j!=jointList.end(); j++) {
00740 if ( (*j)->getSpringStiffness() == 0.0 ) {
00741 DBGA("ERROR: Compliant joint has no stiffness! DEFAULT VALUE will be used!");
00742 }
00743 }
00744 }
00745
00746 double
00747 CompliantDOF::getStaticRatio(Joint *j) const {
00748 double ref = jointList.front()->getSpringStiffness();
00749 assert(ref!=0.0);
00750 double k = j->getSpringStiffness();
00751 if (k == 0.0) k = ref;
00752
00753
00754
00755 int jn = j->getNum();
00756 if (jn==0 || jn==2 || jn== 4 || jn==6) {
00757 return j->getCouplingRatio();
00758 } else {
00759 double tau2 = j->getCouplingRatio();
00760 double tau1 = jointList.front()->getCouplingRatio();
00761 return (ref / k) * ( tau1 * tau2) / (tau1 + tau2);
00762 }
00763 }
00764
00765 void
00766 CompliantDOF::getJointValues(double* jointVals) const
00767 {
00768 std::list<Joint*>::const_iterator j;
00769 for (j=jointList.begin(); j!=jointList.end(); j++) {
00770 jointVals[ (*j)->getNum() ] = q * getStaticRatio(*j);
00771 }
00772 }
00773
00779 void
00780 CompliantDOF::updateFromJointValues(const double* jointVals)
00781 {
00782 double max = -1.0e5;
00783 std::list<Joint*>::const_iterator j;
00784 for (j=jointList.begin(); j!=jointList.end(); j++) {
00785 double v;
00786 if (jointVals) {
00787 v = jointVals[ (*j)->getNum() ] / getStaticRatio(*j);
00788 } else {
00789 v = (*j)->getVal() / getStaticRatio(*j);
00790 }
00791 max = std::max(max,v);
00792 }
00793 q = max;
00794 }
00795
00797 bool
00798 CompliantDOF::accumulateMove(double q1, double *jointVals, int *stoppedJoints)
00799 {
00800 if ( fabs(q-q1) < 1.0e-5 ) {
00801 DBGP("DOF is already at desired value");
00802 return false;
00803 }
00804
00805 bool movement = false;
00806 std::list<Joint*>::const_iterator j; int index;
00807 for (j=jointList.begin(), index=0; j!=jointList.end(); j++, index++) {
00808 double newVal = q1 * getStaticRatio(*j);
00809 double oldVal = (*j)->getVal();
00810 if (stoppedJoints) {
00811 if (newVal > oldVal && (stoppedJoints[ (*j)->getNum()] & 1) ) {
00812 DBGP("Joint " << index << " is stopped in the positive direction");
00813 continue;
00814 }
00815 if (newVal < oldVal && (stoppedJoints[ (*j)->getNum()] & 2) ) {
00816 DBGP("Joint " << index << " is stopped in the negative direction");
00817 continue;
00818 }
00819 }
00820 jointVals[ (*j)->getNum() ] = newVal;
00821 movement = true;
00822 }
00823 return movement;
00824 }
00825
00826
00832 bool
00833 CompliantDOF::computeStaticJointTorques(double *jointTorques, double dofForce)
00834 {
00835
00836
00837
00838
00839
00840 bool retVal = true;
00841
00842 double maxDofTorque = 0.0;
00843 std::list<Joint*>::iterator j;
00844 Joint *pj = NULL;
00845 int count = 0;
00846 for(j=jointList.begin(); j!=jointList.end(); j++) {
00847 double springTorque = (*j)->getSpringForce();
00848 DBGP("Inner spring: " << springTorque);
00849 jointTorques[ (*j)->getNum() ] -= springTorque;
00850
00851 if (count==1 || count==3 || count==5 || count==7) {
00852 assert(pj);
00853 vec3 axis1 = (*j)->dynJoint->getPrevLink()->getTran().affine().row(2);
00854 vec3 axis2 = pj->dynJoint->getPrevLink()->getTran().affine().row(2);
00855 double t = fabs(axis1 % axis2);
00856
00857 jointTorques[pj->getNum()] += springTorque * t;
00858 }
00859 pj = (*j);
00860 count++;
00861 }
00862
00863
00864
00865
00866
00867
00868
00869
00870 for(j=jointList.begin(); j!=jointList.end(); j++) {
00871 double springTorque = - jointTorques[(*j)->getNum()];
00872 double dofTorque = springTorque / (*j)->getCouplingRatio();
00873 if (fabs(dofTorque) > fabs(maxDofTorque)) {
00874 maxDofTorque = dofTorque;
00875 }
00876 }
00877 DBGP("Max dof torque: " << maxDofTorque);
00878
00879 double dofTorque;
00880 if (dofForce < 0) {
00881
00882
00883
00884 dofTorque = maxDofTorque;
00885 } else {
00886
00887
00888
00889 dofTorque = force * 40.0;
00890 if (dofTorque < maxDofTorque) {
00891 DBGA("For now, dof torque must at least balance spring forces!");
00892
00893 dofTorque = maxDofTorque + 3.0e7;
00894 }
00895 }
00896
00897
00898 for(j=jointList.begin(); j!=jointList.end(); j++) {
00899 double jointTorque = dofTorque * (*j)->getCouplingRatio();
00900 jointTorques[ (*j)->getNum() ] += jointTorque;
00901 if ( jointTorques[ (*j)->getNum() ] < -1.0e-5) {
00902 DBGP("Error: negative torque on joint " << (*j)->getNum());
00903
00904
00905 }
00906
00907 if ( fabs(jointTorques[(*j)->getNum()]) < 1.0e-5) {
00908 jointTorques[ (*j)->getNum() ] = 0.0;
00909 }
00910 DBGP(jointTorques[ (*j)->getNum() ]);
00911 }
00912
00913
00914
00915
00916
00917
00918
00919 return retVal;
00920 }
00921
00924 int
00925 CompliantDOF::getNumLimitConstraints()
00926 {
00927 int numCon = 0;
00928 std::list<Joint*>::iterator j;
00929 for(j=jointList.begin(); j!=jointList.end(); j++) {
00930 if ( (*j)->getVal() >= (*j)->getMax() - 0.01) numCon ++;
00931 else if ( (*j)->getVal() <= (*j)->getMin() + 0.01) numCon ++;
00932 }
00933 return numCon;
00934 }
00935
00940 void
00941 CompliantDOF::buildDynamicLimitConstraints(std::map<Body*,int> &islandIndices, int numBodies,
00942 double* H, double *g, int &hcn)
00943 {
00944 std::list<Joint*>::iterator j;
00945 int count = 0;
00946 for(j=jointList.begin(); j!=jointList.end(); j++) {
00947 Joint *currentJoint = *j;
00948 DynamicBody *prevLink = currentJoint->dynJoint->getPrevLink();
00949 DynamicBody *nextLink = currentJoint->dynJoint->getNextLink();
00950 int row, dir;
00951 double error;
00952 if (currentJoint->getVal() >= currentJoint->getMax()-0.01) {
00953 error = currentJoint->getMax() - currentJoint->getVal();
00954 dir = -1;
00955 } else if (currentJoint->getVal() <= currentJoint->getMin()+0.01) {
00956 error = currentJoint->getVal() - currentJoint->getMin();
00957 dir = +1;
00958 } else continue;
00959
00960 g[hcn] = MIN(0.0, error - 0.005);
00961 DBGP("adding dof limit constraint for DOF " << dofNum << " error: "<<g[hcn]);
00962
00963 assert( islandIndices[prevLink]>=0 );
00964 row = 6*islandIndices[prevLink];
00965 H[(hcn)*6*numBodies + row+3] -= dir * currentJoint->getWorldAxis()[0];
00966 H[(hcn)*6*numBodies + row+4] -= dir * currentJoint->getWorldAxis()[1];
00967 H[(hcn)*6*numBodies + row+5] -= dir * currentJoint->getWorldAxis()[2];
00968
00969 assert( islandIndices[nextLink]>=0 );
00970 row = 6*islandIndices[nextLink];
00971 H[(hcn)*6*numBodies + row+3] += dir * currentJoint->getWorldAxis()[0];
00972 H[(hcn)*6*numBodies + row+4] += dir * currentJoint->getWorldAxis()[1];
00973 H[(hcn)*6*numBodies + row+5] += dir * currentJoint->getWorldAxis()[2];
00974
00975 hcn++;
00976 count++;
00977 }
00978 }
00979
00980 void
00981 CompliantDOF::setForce(double f)
00982 {
00983
00984 if (f > maxForce) force = maxForce;
00985 if (force < 0) force = 0;
00986 else if (f < -maxForce) force = -maxForce;
00987 else force = f;
00988
00989
00990
00991 std::list<Joint*>::iterator j;
00992 for(j=jointList.begin(); j!=jointList.end(); j++) {
00993 double torqueRatio = (*j)->getCouplingRatio();
00994 DynamicBody* body = (*j)->dynJoint->getNextLink();
00995
00996
00997
00998
00999 double jointTorque = force * 40.0 * torqueRatio;
01000
01001
01002 body->addTorque(jointTorque * (*j)->getWorldAxis());
01003
01004
01005
01006
01007
01008
01009
01010
01011
01012
01013
01014
01015
01016
01017
01018
01019
01020
01021
01022 }
01023 }
01024
01029 double
01030 CompliantDOF::PDPositionController(double timeStep)
01031 {
01032
01033 return smoothProfileController(timeStep);
01034
01035
01036 }
01037
01041 bool
01042 CompliantDOF::dynamicsProgress()
01043 {
01044 double eps = 1.0e-5;
01045 if ((int)mPositionHistory.size() < mHistoryMaxSize) return true;
01046 std::list<double>::iterator it = mPositionHistory.begin();
01047 double ref = *it; it++;
01048
01049 while (it!=mPositionHistory.end()) {
01050
01051 if ( fabs(*it-ref) > eps) {
01052
01053 return true;
01054 }
01055 it++;
01056 }
01057
01058 return false;
01059 }
01060
01065 double
01066 CompliantDOF::smoothProfileController(double)
01067 {
01068 double time = owner->getWorld()->getWorldTime() - mDynStartTime;
01069 time = std::min(time, 1.0);
01070 if (time < 0) {
01071 DBGA("Zero elapsed time in CD controller");
01072 }
01073 time = std::max(time, 0.0);
01074 return time * getMaxForce();
01075 }