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 #ifndef HUMAN_HAND_H
00027 #define HUMAN_HAND_H
00028
00046 #include <vector>
00047 #include <limits>
00048 #include <set>
00049
00050 #include <Inventor/SoType.h>
00051 #include "robot.h"
00052
00053 class SoSeparator;
00054 class SoSphere;
00055 class SoCylinder;
00056 class SoTransform;
00057 class SoDrawStyle;
00058 class Tendon;
00059
00068 class TendonInsertionPoint {
00069 private:
00071 vec3 mAttachPoint;
00072
00074
00076 bool mPermanent;
00077
00079
00080 int mAttachChainNr;
00082 int mAttachLinkNr;
00083
00085 double mMu;
00086
00087 SoSeparator *mIVInsertion;
00088 SoMaterial *mIVInsertionMaterial;
00089 SoTransform *mIVInsertionTran;
00090 SoSphere *mIVInsertionGeom;
00091
00092 SoSeparator *mIVConnector;
00093 SoMaterial *mIVConnectorMaterial;
00094 SoTransform *mIVConnectorTran;
00095 SoCylinder *mIVConnectorGeom;
00096
00097 Tendon* mOwner;
00098
00099 void createInsertionGeometry();
00100 void createConnectorGeometry();
00101 public:
00102
00104 vec3 mInsertionForce;
00105
00106 TendonInsertionPoint(Tendon* myOwner, int chain, int link, vec3 point, double mu, bool isPerm=true);
00107
00108 void removeAllGeometry();
00109
00110 Tendon* getTendon(){return mOwner;}
00111
00112 void setPermanent(bool p){mPermanent=p;}
00113
00114 bool isPermanent() const {return mPermanent;}
00115
00116 SbVec3f getWorldPosition();
00117
00118 vec3 getAttachPoint() const {return mAttachPoint;}
00119
00120 void setAttachPoint(vec3 attachPoint);
00121
00122 double getMu() const {return mMu;}
00123
00124 void setMu(double mu){mMu = mu;}
00125
00127
00128 Link* getAttachedLink();
00129
00130 SoSeparator* getIVInsertion(){return mIVInsertion;}
00131 SoSphere* getIVInsertionGeom(){return mIVInsertionGeom;}
00132 SoMaterial* getIVInsertionMaterial(){return mIVInsertionMaterial;}
00133
00134 SoSeparator* getIVConnector(){return mIVConnector;}
00135 SoMaterial* getIVConnectorMaterial(){return mIVConnectorMaterial;}
00136 SoTransform* getIVConnectorTran(){return mIVConnectorTran;}
00137 SoCylinder* getIVConnectorGeom(){return mIVConnectorGeom;}
00138
00139 static const double INSERTION_POINT_RADIUS;
00140 static const double CONNECTOR_RADIUS;
00141 };
00142
00147 class TendonWrapper{
00148 public:
00150 class WrappingSide {
00151 public:
00152 QString mTendonName;
00153 vec3 mDirection;
00154 };
00155 private:
00156 int attachLinkNr;
00157 int attachChainNr;
00158 double mMu;
00159 Robot *owner;
00160
00161 SoSeparator *IVWrapper;
00162 SoMaterial *IVWrapperMaterial;
00163 SoTransform *IVWrapperTran;
00164 SoCylinder *IVWrapperGeom;
00165
00167 std::list<QString> mExemptList;
00168
00170 std::vector<WrappingSide> mWrappingSideVec;
00171
00172 public:
00173 vec3 location, orientation;
00174 double radius, length;
00175
00176 TendonWrapper(Robot* myOwner);
00177 Link* getAttachedLink();
00178 Robot* getRobot(){return owner;}
00179
00180 void setLocation(vec3 loc);
00181 vec3 getLocation() const {return location;}
00182
00183 void setOrientation(vec3 orient);
00184 vec3 getOrientation() const {return orientation;}
00185
00186 void setRadius(double r);
00187 double getRadius() const {return radius;}
00188
00189 void setMu(double mu){mMu = mu;}
00190 double getMu() const {return mMu;}
00191
00192 void createGeometry();
00193 void updateGeometry();
00194 SoSeparator* getIVRoot(){return IVWrapper;}
00195 int getChainNr(){return attachChainNr;}
00196 int getLinkNr(){return attachLinkNr;}
00197 bool loadFromXml(const TiXmlElement* root);
00199 bool isExempt(QString name);
00200
00202 bool wrappingSide(QString tendonName, vec3 &direction);
00203 };
00204
00206 class Tendon{
00207 private:
00208 Robot* mOwner;
00209
00210 SoSeparator *mIVRoot;
00211
00213 SoDrawStyle* mIVVisibleToggle;
00214
00216 SoSeparator* mIVForceIndRoot;
00217
00219 SoDrawStyle* mIVForceIndToggle;
00220
00222 SoMaterial *mIVForceIndMaterial;
00223
00225 SoSeparator *mIVForceIndicators;
00226
00228 float mActiveForce;
00229
00231 float mPassiveForce;
00232
00234 bool mApplyPassiveForce;
00235
00237 double mK;
00238
00240
00241 std::list<TendonInsertionPoint *> mInsPointList;
00242
00243 QString mTendonName;
00244
00245 bool mVisible;
00246
00247 bool mForcesVisible;
00248
00249 bool mSelected;
00250
00252 float mCurrentLength;
00253
00255 float mRestLength;
00256
00259 float mPreTensionLength;
00260
00262 float mDefaultRestLength;
00263
00264 void updateForceIndicators();
00265
00266 public:
00267
00268 Tendon(Robot* myOwner);
00269
00270 Robot *getRobot(){return mOwner;}
00271
00272 SoSeparator* getIVRoot(){return mIVRoot;}
00273
00275 void addInsertionPoint(int chain,int link,vec3 point, double mu, bool isPerm);
00276
00278 std::list<TendonInsertionPoint*>::iterator
00279 insertInsertionPoint(std::list<TendonInsertionPoint*>::iterator itPos,
00280 int chain, int link, vec3 point, double mu, bool isPerm);
00281
00283 std::list<TendonInsertionPoint*>::iterator
00284 removeInsertionPoint(std::list<TendonInsertionPoint*>::iterator itPos);
00285
00287 void updateGeometry();
00288
00290 void updateInsertionForces();
00291
00293 void computeSimplePassiveForces();
00294
00296 void checkWrapperIntersections();
00297
00299 void removeWrapperIntersections();
00300
00302 int getNumInsPoints() const {return mInsPointList.size();}
00303
00305 int getNumPermInsPoints() const;
00306
00308 TendonInsertionPoint* getPermInsPoint(int n);
00309
00311 double getTotalFrictionCoefficient();
00312
00314 double getFrictionCoefficientBetweenPermInsPoints(int start, int end, bool inclusive);
00315
00317 void removeTemporaryInsertionPoints();
00318
00320 double minInsPointDistance();
00321
00322 void select();
00323 void deselect();
00324 bool isSelected(){return mSelected;}
00325
00326 void setActiveForce(float f);
00327
00328 void setPassiveForce(float f);
00329
00330 float getActiveForce(){return mActiveForce;}
00331
00332 float getPassiveForce(){return mPassiveForce;}
00333
00334 float getTotalForce(){if (mApplyPassiveForce) return mActiveForce+mPassiveForce; else return mActiveForce;}
00335
00336 void setStiffness(double k){mK = k;}
00337
00338 double getStiffness() {return mK;}
00339
00340 float getDefaultRestLength(){return mDefaultRestLength;}
00341
00342 void setDefaultRestLength(double l){mDefaultRestLength = l;}
00343
00344 float getPreTensionLength(){return mPreTensionLength;}
00345
00346 void setPreTensionLength(double l){mPreTensionLength = l;}
00347
00348 void setName(QString name){mTendonName=name;}
00349
00350 QString getName(){return mTendonName;}
00351
00352 void setVisible(bool v);
00353
00354 bool isVisible(){return mVisible;}
00355
00356 void setForcesVisible(bool v);
00357
00358 bool forcesVisible() {return mForcesVisible;}
00359
00361
00362 void applyForces();
00363
00364 void setApplyPassiveForce(bool b){mApplyPassiveForce=b;}
00365
00366
00367 void setRestLength(double length);
00368
00370
00372 float getExcursion(){return mCurrentLength - mRestLength;}
00373
00375 float getCurrentLength(){return mCurrentLength;}
00376
00377 bool loadFromXml(const TiXmlElement *root);
00378
00379 transf getInsertionPointWorldTransform(std::list<TendonInsertionPoint*>::iterator insPt);
00380
00382
00385 void getInsertionPointTransforms(std::vector<transf> &insPointTrans);
00386
00388 void getInsertionPointForceMagnitudes(std::vector<double> &magnitudes);
00389
00391 void getInsertionPointLinkTransforms(std::list< std::pair<transf, Link*> > &insPointLinkTrans);
00392
00394 bool insPointInsideWrapper();
00395 };
00396
00398
00404 class HumanHand : public Hand {
00405 Q_OBJECT
00406 protected:
00407 std::vector<Tendon *> mTendonVec;
00408
00409 std::vector<TendonWrapper *> mTendonWrapperVec;
00410
00412 void applyTendonForces();
00413
00414 public:
00415 HumanHand(World*,const char*);
00416 virtual ~HumanHand() {}
00417
00418 virtual int loadFromXml(const TiXmlElement* root,QString rootPath);
00419
00420 void updateTendonGeometry();
00421
00422 int getNumTendons(){return mTendonVec.size();}
00423
00424 int getNumTendonWrappers(){return mTendonWrapperVec.size();}
00425
00426 Tendon* getTendon(int i){return mTendonVec[i];}
00427
00428 TendonWrapper* getTendonWrapper(int i){return mTendonWrapperVec[i];}
00429
00430 void selectTendon(int i){mTendonVec[i]->select();}
00431
00432 void deselectTendon(int i){mTendonVec[i]->deselect();}
00433
00435 virtual void DOFController(double timeStep);
00436
00438 virtual int tendonEquilibrium(const std::set<size_t> &activeTendons,
00439 const std::set<size_t> &passiveTendons,
00440 bool compute_tendon_forces,
00441 std::vector<double> &activeTendonForces,
00442 std::vector<double> &jointResiduals,
00443 double& unbalanced_magnitude,
00444 bool useJointSprings = true);
00445
00447 int contactEquilibrium(std::list<Contact*> contacts,
00448 const std::set<size_t> &activeTendons,
00449 std::vector<double> &activeTendonForces,
00450 double &unbalanced_magnitude);
00451
00453 int contactForcesFromTendonForces(std::list<Contact*> contacts,
00454 std::vector<double> &contactForces,
00455 const std::set<size_t> &activeTendons,
00456 const std::vector<double> &activeTendonForces);
00457
00460 int contactTorques(std::list<Contact*> contacts,
00461 std::vector<double> &jointTorques);
00462
00464 bool insPointInsideWrapper();
00465
00468 void setRestPosition()
00469 {
00470 for(size_t i=0; i<mTendonVec.size(); i++)
00471 {
00472 if (mTendonVec[i]->getDefaultRestLength() < 0.0)
00473 {
00474 if (mTendonVec[i]->getPreTensionLength() < 0.0)
00475 {
00476 mTendonVec[i]->setRestLength( mTendonVec[i]->getCurrentLength() );
00477 }
00478 else
00479 {
00480 mTendonVec[i]->setRestLength( mTendonVec[i]->getCurrentLength() -
00481 mTendonVec[i]->getPreTensionLength() );
00482 }
00483 }
00484 else
00485 {
00486 mTendonVec[i]->setRestLength( mTendonVec[i]->getDefaultRestLength() );
00487 }
00488 }
00489 }
00490
00492 void removeTemporaryInsertionPoints()
00493 {
00494 for(size_t i=0; i<mTendonVec.size(); i++)
00495 {
00496 mTendonVec[i]->removeTemporaryInsertionPoints();
00497 }
00498 }
00499
00502 double minInsPointDistance()
00503 {
00504 double minDist = std::numeric_limits<double>::max();
00505 for(size_t i=0; i<mTendonVec.size(); i++)
00506 {
00507 minDist = std::min(minDist, mTendonVec[i]->minInsPointDistance());
00508 }
00509 return minDist;
00510 }
00511
00512 };
00513
00514 #endif