Tendon Class Reference

Defines a tendon geometry by listing its insertion points. More...

#include <humanHand.h>

List of all members.

Public Member Functions

void addInsertionPoint (int chain, int link, vec3 point, double mu, bool isPerm)
 Adds an insertion point at the end of the insPointList.
void applyForces ()
 Applies previously computed forces at links that have insertion points.
void checkWrapperIntersections ()
 Checks if tendon intersect a wrapper and adds insertion points around the wrapper if needed.
void computeSimplePassiveForces ()
 Computes a naive version of passive forces based on tendon excursion; more of a placeholder.
void deselect ()
bool forcesVisible ()
float getActiveForce ()
float getCurrentLength ()
 Gets the current length of the tendon. Assumes updateGeometry() has been called.
float getDefaultRestLength ()
float getExcursion ()
 Returns the excursion of the end of the tendon compared to its rest position.
double getFrictionCoefficientBetweenPermInsPoints (int start, int end, bool inclusive)
 Returns the total friction acting between two insertion points.
void getInsertionPointForceMagnitudes (std::vector< double > &magnitudes)
 Returns the magnitudes of the forces at each insertion point, assuming a total tendon force of 1.0.
void getInsertionPointLinkTransforms (std::list< std::pair< transf, Link * > > &insPointLinkTrans)
 Returns pairs of insertion points and their links, with ins. pt. transforms relative to their links.
void getInsertionPointTransforms (std::vector< transf > &insPointTrans)
 Returns the locations of all insertion points in world coordinates.
transf getInsertionPointWorldTransform (std::list< TendonInsertionPoint * >::iterator insPt)
SoSeparator * getIVRoot ()
QString getName ()
int getNumInsPoints () const
 Returns the total number of insertion points.
int getNumPermInsPoints () const
 Returns the number of permanent insertion points.
float getPassiveForce ()
TendonInsertionPointgetPermInsPoint (int n)
 Returns the n-th permanent insertion point.
float getPreTensionLength ()
RobotgetRobot ()
double getStiffness ()
float getTotalForce ()
double getTotalFrictionCoefficient ()
 Returns total friction acting along the tendon.
std::list
< TendonInsertionPoint * >
::iterator 
insertInsertionPoint (std::list< TendonInsertionPoint * >::iterator itPos, int chain, int link, vec3 point, double mu, bool isPerm)
 Inserts an insertion point at a given position in insPointList.
bool insPointInsideWrapper ()
 Returns true if any of the permanent insertion points is inside a wrapper.
bool isSelected ()
bool isVisible ()
bool loadFromXml (const TiXmlElement *root)
double minInsPointDistance ()
 Returns the minimum distance between two consecutive permanent insertion points.
std::list
< TendonInsertionPoint * >
::iterator 
removeInsertionPoint (std::list< TendonInsertionPoint * >::iterator itPos)
 Removes the insertion point pointed to by the given iterator.
void removeTemporaryInsertionPoints ()
 Removes all temporary insertion points.
void removeWrapperIntersections ()
 Removes wrapper intersections if they are no longer needed.
void select ()
void setActiveForce (float f)
void setApplyPassiveForce (bool b)
void setDefaultRestLength (double l)
void setForcesVisible (bool v)
void setName (QString name)
void setPassiveForce (float f)
void setPreTensionLength (double l)
void setRestLength (double length)
void setStiffness (double k)
void setVisible (bool v)
 Tendon (Robot *myOwner)
void updateGeometry ()
 Updates connector geometry based on movement of links that tendon inserts into.
void updateInsertionForces ()
 Updates insertion point forces based on movement of links that tendon inserts into.

Private Member Functions

void updateForceIndicators ()

Private Attributes

float mActiveForce
 Force applied as a result of voluntary muscle contraction.
bool mApplyPassiveForce
 Used to flip passive force application on or off.
float mCurrentLength
 The current length of the tendon.
float mDefaultRestLength
 The default rest length, or -1 if no default has been specified.
bool mForcesVisible
std::list< TendonInsertionPoint * > mInsPointList
 The list of insertion points that defines the geometry of the tendon.
SoSeparator * mIVForceIndicators
 Root for the arrows themselves showing forces at insertion points.
SoMaterial * mIVForceIndMaterial
 Material for force indicators.
SoSeparator * mIVForceIndRoot
 Root for holding all related to force indicators rendering.
SoDrawStyle * mIVForceIndToggle
 Used to toggle wether force indicators are visible or not.
SoSeparator * mIVRoot
SoDrawStyle * mIVVisibleToggle
 Used to toggle wether the tendon is visible or not; is inserted as first child of the root.
double mK
 The spring constant of this tendon, if thought of as a linear spring.
RobotmOwner
float mPassiveForce
 Force applied as a result of tendon / muscle elongation.
float mPreTensionLength
float mRestLength
 The currently used length of the tendon at the resting position.
bool mSelected
QString mTendonName
bool mVisible

Detailed Description

Defines a tendon geometry by listing its insertion points.

Definition at line 206 of file humanHand.h.


Constructor & Destructor Documentation

Tendon::Tendon ( Robot myOwner  ) 

Definition at line 177 of file humanHand.cpp.


Member Function Documentation

void Tendon::addInsertionPoint ( int  chain,
int  link,
vec3  point,
double  mu,
bool  isPerm 
)

Adds an insertion point at the end of the insPointList.

Definition at line 831 of file humanHand.cpp.

void Tendon::applyForces (  ) 

Applies previously computed forces at links that have insertion points.

Forces MUST have been updated by updateGeometry() and updateInsertionForces()

Definition at line 885 of file humanHand.cpp.

void Tendon::checkWrapperIntersections (  ) 

Checks if tendon intersect a wrapper and adds insertion points around the wrapper if needed.

Definition at line 396 of file humanHand.cpp.

void Tendon::computeSimplePassiveForces (  ) 

Computes a naive version of passive forces based on tendon excursion; more of a placeholder.

Simple method for some passive force computation

  • assume inextensible tendon is attached to a muscle, therefore tendon elongation is actually muscle elongation
  • hard-code some values for muscle rest length and max. force (each muscle should actually have its own values)
  • use formula from Hill-type model (Tsang et al.) for computing muscle force

Definition at line 678 of file humanHand.cpp.

void Tendon::deselect (  ) 

Definition at line 787 of file humanHand.cpp.

bool Tendon::forcesVisible (  )  [inline]

Definition at line 358 of file humanHand.h.

float Tendon::getActiveForce (  )  [inline]

Definition at line 330 of file humanHand.h.

float Tendon::getCurrentLength (  )  [inline]

Gets the current length of the tendon. Assumes updateGeometry() has been called.

Definition at line 375 of file humanHand.h.

float Tendon::getDefaultRestLength (  )  [inline]

Definition at line 340 of file humanHand.h.

float Tendon::getExcursion (  )  [inline]

Returns the excursion of the end of the tendon compared to its rest position.

For the moment we consider that tendon elongation is actually excursion, as if the origin was free to move.

Definition at line 372 of file humanHand.h.

double Tendon::getFrictionCoefficientBetweenPermInsPoints ( int  start,
int  end,
bool  inclusive 
)

Returns the total friction acting between two insertion points.

Definition at line 641 of file humanHand.cpp.

void Tendon::getInsertionPointForceMagnitudes ( std::vector< double > &  magnitudes  ) 

Returns the magnitudes of the forces at each insertion point, assuming a total tendon force of 1.0.

Definition at line 614 of file humanHand.cpp.

void Tendon::getInsertionPointLinkTransforms ( std::list< std::pair< transf, Link * > > &  insPointLinkTrans  ) 

Returns pairs of insertion points and their links, with ins. pt. transforms relative to their links.

The result of this function can be fed directly into the Grasp::Jacobian computation

Definition at line 598 of file humanHand.cpp.

void Tendon::getInsertionPointTransforms ( std::vector< transf > &  insPointTrans  ) 

Returns the locations of all insertion points in world coordinates.

The transform is such that the resultant tendon force, if any, points along the z axis of the local insertion point coordinate frame.

Definition at line 583 of file humanHand.cpp.

transf Tendon::getInsertionPointWorldTransform ( std::list< TendonInsertionPoint * >::iterator  insPt  ) 

Definition at line 562 of file humanHand.cpp.

SoSeparator* Tendon::getIVRoot (  )  [inline]

Definition at line 272 of file humanHand.h.

QString Tendon::getName (  )  [inline]

Definition at line 350 of file humanHand.h.

int Tendon::getNumInsPoints (  )  const [inline]

Returns the total number of insertion points.

Definition at line 302 of file humanHand.h.

int Tendon::getNumPermInsPoints (  )  const

Returns the number of permanent insertion points.

Definition at line 847 of file humanHand.cpp.

float Tendon::getPassiveForce (  )  [inline]

Definition at line 332 of file humanHand.h.

TendonInsertionPoint * Tendon::getPermInsPoint ( int  n  ) 

Returns the n-th permanent insertion point.

Definition at line 858 of file humanHand.cpp.

float Tendon::getPreTensionLength (  )  [inline]

Definition at line 344 of file humanHand.h.

Robot* Tendon::getRobot (  )  [inline]

Definition at line 270 of file humanHand.h.

double Tendon::getStiffness (  )  [inline]

Definition at line 338 of file humanHand.h.

float Tendon::getTotalForce (  )  [inline]

Definition at line 334 of file humanHand.h.

double Tendon::getTotalFrictionCoefficient (  ) 

Returns total friction acting along the tendon.

Definition at line 635 of file humanHand.cpp.

std::list< TendonInsertionPoint * >::iterator Tendon::insertInsertionPoint ( std::list< TendonInsertionPoint * >::iterator  itPos,
int  chain,
int  link,
vec3  point,
double  mu,
bool  isPerm 
)

Inserts an insertion point at a given position in insPointList.

Definition at line 837 of file humanHand.cpp.

bool Tendon::insPointInsideWrapper (  ) 

Returns true if any of the permanent insertion points is inside a wrapper.

Definition at line 236 of file humanHand.cpp.

bool Tendon::isSelected (  )  [inline]

Definition at line 324 of file humanHand.h.

bool Tendon::isVisible (  )  [inline]

Definition at line 354 of file humanHand.h.

bool Tendon::loadFromXml ( const TiXmlElement root  ) 

Definition at line 902 of file humanHand.cpp.

double Tendon::minInsPointDistance (  ) 

Returns the minimum distance between two consecutive permanent insertion points.

Definition at line 271 of file humanHand.cpp.

std::list< TendonInsertionPoint * >::iterator Tendon::removeInsertionPoint ( std::list< TendonInsertionPoint * >::iterator  itPos  ) 

Removes the insertion point pointed to by the given iterator.

Definition at line 872 of file humanHand.cpp.

void Tendon::removeTemporaryInsertionPoints (  ) 

Removes all temporary insertion points.

Definition at line 225 of file humanHand.cpp.

void Tendon::removeWrapperIntersections (  ) 

Removes wrapper intersections if they are no longer needed.

Definition at line 353 of file humanHand.cpp.

void Tendon::select (  ) 

Definition at line 769 of file humanHand.cpp.

void Tendon::setActiveForce ( float  f  ) 

Definition at line 209 of file humanHand.cpp.

void Tendon::setApplyPassiveForce ( bool  b  )  [inline]

Definition at line 364 of file humanHand.h.

void Tendon::setDefaultRestLength ( double  l  )  [inline]

Definition at line 342 of file humanHand.h.

void Tendon::setForcesVisible ( bool  v  ) 

Definition at line 819 of file humanHand.cpp.

void Tendon::setName ( QString  name  )  [inline]

Definition at line 348 of file humanHand.h.

void Tendon::setPassiveForce ( float  f  ) 

Definition at line 216 of file humanHand.cpp.

void Tendon::setPreTensionLength ( double  l  )  [inline]

Definition at line 346 of file humanHand.h.

void Tendon::setRestLength ( double  length  ) 

Definition at line 760 of file humanHand.cpp.

void Tendon::setStiffness ( double  k  )  [inline]

Definition at line 336 of file humanHand.h.

void Tendon::setVisible ( bool  v  ) 

Definition at line 805 of file humanHand.cpp.

void Tendon::updateForceIndicators (  )  [private]

Definition at line 503 of file humanHand.cpp.

void Tendon::updateGeometry (  ) 

Updates connector geometry based on movement of links that tendon inserts into.

Definition at line 443 of file humanHand.cpp.

void Tendon::updateInsertionForces (  ) 

Updates insertion point forces based on movement of links that tendon inserts into.

Definition at line 704 of file humanHand.cpp.


Member Data Documentation

float Tendon::mActiveForce [private]

Force applied as a result of voluntary muscle contraction.

Definition at line 228 of file humanHand.h.

Used to flip passive force application on or off.

Definition at line 234 of file humanHand.h.

float Tendon::mCurrentLength [private]

The current length of the tendon.

Definition at line 252 of file humanHand.h.

float Tendon::mDefaultRestLength [private]

The default rest length, or -1 if no default has been specified.

Definition at line 262 of file humanHand.h.

bool Tendon::mForcesVisible [private]

Definition at line 247 of file humanHand.h.

The list of insertion points that defines the geometry of the tendon.

This has to be a list because we create ins points dynamically when wrapping around wrappers.

Definition at line 241 of file humanHand.h.

SoSeparator* Tendon::mIVForceIndicators [private]

Root for the arrows themselves showing forces at insertion points.

Definition at line 225 of file humanHand.h.

SoMaterial* Tendon::mIVForceIndMaterial [private]

Material for force indicators.

Definition at line 222 of file humanHand.h.

SoSeparator* Tendon::mIVForceIndRoot [private]

Root for holding all related to force indicators rendering.

Definition at line 216 of file humanHand.h.

SoDrawStyle* Tendon::mIVForceIndToggle [private]

Used to toggle wether force indicators are visible or not.

Definition at line 219 of file humanHand.h.

SoSeparator* Tendon::mIVRoot [private]

Definition at line 210 of file humanHand.h.

SoDrawStyle* Tendon::mIVVisibleToggle [private]

Used to toggle wether the tendon is visible or not; is inserted as first child of the root.

Definition at line 213 of file humanHand.h.

double Tendon::mK [private]

The spring constant of this tendon, if thought of as a linear spring.

Definition at line 237 of file humanHand.h.

Robot* Tendon::mOwner [private]

Definition at line 208 of file humanHand.h.

float Tendon::mPassiveForce [private]

Force applied as a result of tendon / muscle elongation.

Definition at line 231 of file humanHand.h.

float Tendon::mPreTensionLength [private]

pre tensioning subtracted from rest length, of -1 if no pre-tensioning is used used only if mDefaultRestLength (absolute default rest length is specified)

Definition at line 259 of file humanHand.h.

float Tendon::mRestLength [private]

The currently used length of the tendon at the resting position.

Definition at line 255 of file humanHand.h.

bool Tendon::mSelected [private]

Definition at line 249 of file humanHand.h.

QString Tendon::mTendonName [private]

Definition at line 243 of file humanHand.h.

bool Tendon::mVisible [private]

Definition at line 245 of file humanHand.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


graspit
Author(s):
autogenerated on Fri Jan 11 11:20:40 2013