Main Page | Namespace List | Class Hierarchy | Alphabetical List | Class List | File List | Namespace Members | Class Members | File Members | Related Pages

robot::KinematicChain Class Reference

Describes a kinematic chain of links, each possibly with a joint. More...

Inheritance diagram for robot::KinematicChain:

Inheritance graph
[legend]
Collaboration diagram for robot::KinematicChain:

Collaboration graph
[legend]
List of all members.

Public Types

enum  UnitType { Distance, Angle }
 unit type of parameters More...

enum  ExternalizationType { Input = 1, Output = 2, IO = 3 }

Public Member Functions

 KinematicChain ()
 KinematicChain (const Link &l)
 KinematicChain (const KinematicChain &kc)
virtual String className () const
KinematicChainoperator= (const KinematicChain &kc)
Int size () const
 no. of links in the chain

Int dof () const
 no. of degrees-of-freedom (sum of joint variables for each link)

bool isDHType () const
 true if the chain is comprised only of links for which link.isDHType() is true

const Linkoperator[] (Int i) const
void setLink (Int i, const Link &link)
const Linkat (Int i) const
void setLinkAt (Int i, const Link &link)
const LinklinkOfVariable (Int i) const
 get link that described joint controlled by variable i (0 <= i < dof())

Int linkIndexOfVariable (Int i) const
UnitType variableUnitType (Int i) const
Real variableMinLimit (Int i) const
Real variableMaxLimit (Int i) const
Real variableMinAccel (Int i) const
Real variableMaxAccel (Int i) const
void activateLink (Int i, bool active=true)
bool linkIsActive (Int i) const
Link front () const
Link back () const
void push_back (const Link &l)
void pop_back ()
void resize (Int newsize)
KinematicChain subChain (Int first, Int count) const
bool operator== (const KinematicChain &kc) const
bool operator!= (const KinematicChain &kc) const
KinematicChainoperator+= (const KinematicChain &kc)
KinematicChaininsert (Int pos, const KinematicChain &kc)
KinematicChaininsert (Int pos, const Link &l)
KinematicChainerase (Int pos)
KinematicChainerase (Int first, Int last)
void setInitialFrame (const String &name)
const String & getInitialFrame () const
void setLinkFrame (Int i, const String &name)
const String & getLinkFrame (Int i) const
Vector transform (Int fromLink, Int toLink, const Vector &v, const Vector &q) const
 transform point v from the reference frame of link i to the frame of link j, when chain is in configuration q

Vector transform (const String &fromFrame, const String &toFrame, const Vector &v, const Vector &q) const
Matrix getForwardKinematics (const Vector &q) const
 get the forward kinematics transform for joint parameters q

Matrix getJacobian (const Vector &q, bool includeOrientation=true) const
 get the Jacobian matrix for joint parameters q

array< VectorgetJointOrigins (const Vector &q) const
 get an array of the joint origin locations for parameters q

array< VectorgetLinkOrigins (const Vector &q) const
 get an array of the link origin locations for parameters q

void setKinematicEvaluator (ref< KinematicEvaluator > evaluator)
void convertJointTrajectory (ManipulatorJointTrajectory &jointTrajectory, ManipulatorJointTrajectory::AngularUnits units=ManipulatorJointTrajectory::Radians) const
virtual void serialize (base::Serializer &s)
 read or write object state to Serializer

virtual bool formatSupported (const String format, Real version=1.0, ExternalizationType type=IO) const
 < query if specific format is supported (for input, output or both)

virtual void externalize (base::Externalizer &e, String format="", Real version=1.0)
 read or write object state to Externalizer

virtual void externalize (base::Externalizer &e, String format="", Real version=1.0) const
 write object state to Externalizer (throws if e is in Input)

virtual base::array< base::BytehashCode () const
virtual bool isSameKindAs (const Object &) const
void load (ref< VFile > archive, const String &format="", Real version=1.0)
void save (ref< VFile > archive, const String &format="", Real version=1.0)

Static Public Member Functions

template<class BaseClass, class DerivedClass> void registerSerializableInstantiator (const SerializableInstantiator &instantiator)
void registerSerializableInstantiator (const String &baseClassTypeName, const String &derivedClassTypeName, const SerializableInstantiator &instantiator)
template<class BaseClass> const SerializableInstantiator & getSerializableInstantiator (const String &derivedClassTypeName)
const SerializableInstantiator & getSerializableInstantiator (const String &baseClassTypeName, const String &derivedClassTypeName)

Static Public Attributes

const Real unboundedMinAngleLimit
const Real unboundedMaxAngleLimit
const Real unboundedMinDistLimit
const Real unboundedMaxDistLimit

Protected Types

typedef base::array< LinkLinkArray
typedef base::array< std::pair<
Int, Int > > 
VariableIndexArray

Protected Member Functions

 KinematicChain (const LinkArray &la)
void computeVariables ()
 updates variables based on link joint dofs

void dirtyHash () const
void initKinematicEvaluator ()

Protected Attributes

LinkArray links
VariableIndexArray variables
ref< KinematicEvaluatorkinematicEvaluator
 KinematicEvaluator instance to use for this chain.

String initialFrame
bool hashDirty
array< base::Bytehash

Static Protected Attributes

bool KinematicEvaluatorInitialized
ref< KinematicEvaluatordefaultKinematicEvaluator

Detailed Description

Describes a kinematic chain of links, each possibly with a joint.

Definition at line 47 of file KinematicChain.


Member Typedef Documentation

typedef base::array<Link> robot::KinematicChain::LinkArray [protected]
 

Definition at line 364 of file KinematicChain.

Referenced by KinematicChain().

typedef base::array<std::pair<Int,Int> > robot::KinematicChain::VariableIndexArray [protected]
 

index is the variable no. for this chain, elements are a pair of Ints (link index, dof-index), where link index is link correpsonding to this joint variable (index into LinkArray), and dof-index is the degree of freedom for the link (for links representing joints with multiple dofs)

Definition at line 369 of file KinematicChain.


Member Enumeration Documentation

enum base::Externalizable::ExternalizationType [inherited]
 

Enumeration values:
Input 
Output 
IO 

Definition at line 40 of file Externalizable.

enum robot::KinematicChain::UnitType
 

unit type of parameters

Enumeration values:
Distance 
Angle 

Definition at line 52 of file KinematicChain.

Referenced by variableUnitType().


Constructor & Destructor Documentation

robot::KinematicChain::KinematicChain  )  [inline]
 

Definition at line 230 of file KinematicChain.

References initKinematicEvaluator().

robot::KinematicChain::KinematicChain const Link l  )  [inline]
 

Parameters:
l  empty chain (no links) 'chain' comprising a single link

Definition at line 232 of file KinematicChain.

References computeVariables(), initKinematicEvaluator(), and links.

robot::KinematicChain::KinematicChain const KinematicChain kc  )  [inline]
 

Definition at line 235 of file KinematicChain.

References kinematicEvaluator, links, and variables.

robot::KinematicChain::KinematicChain const LinkArray la  )  [inline, protected]
 

Definition at line 371 of file KinematicChain.

References computeVariables(), LinkArray, and links.


Member Function Documentation

void robot::KinematicChain::activateLink Int  i,
bool  active = true
[inline]
 

Definition at line 272 of file KinematicChain.

References Assert, computeVariables(), dirtyHash(), links, and size().

const Link& robot::KinematicChain::at Int  i  )  const [inline]
 

Definition at line 254 of file KinematicChain.

References Assert, links, and size().

Link robot::KinematicChain::back  )  const [inline]
 

Definition at line 278 of file KinematicChain.

References Assert, links, and size().

virtual String robot::KinematicChain::className  )  const [inline, virtual]
 

return the name of the object's class type. Must be defined by derived classes.

Implements base::Object.

Definition at line 239 of file KinematicChain.

void robot::KinematicChain::computeVariables  )  [protected]
 

updates variables based on link joint dofs

Referenced by activateLink(), KinematicChain(), pop_back(), push_back(), resize(), and serialize().

void robot::KinematicChain::convertJointTrajectory ManipulatorJointTrajectory jointTrajectory,
ManipulatorJointTrajectory::AngularUnits  units = ManipulatorJointTrajectory::Radians
const [inline]
 

convert the components of the joint vectors in jointTrajectory corresponding to Revolute joints of the chain to the specified units

Definition at line 339 of file KinematicChain.

References Angle, robot::ManipulatorJointTrajectory::convertComponentUnits(), dof(), and variableUnitType().

void robot::KinematicChain::dirtyHash  )  const [inline, protected]
 

Definition at line 389 of file KinematicChain.

Referenced by activateLink(), operator=(), pop_back(), push_back(), resize(), serialize(), setInitialFrame(), setLink(), setLinkAt(), and setLinkFrame().

Int robot::KinematicChain::dof  )  const [inline]
 

no. of degrees-of-freedom (sum of joint variables for each link)

Definition at line 247 of file KinematicChain.

References base::array< T >::size(), and variables.

Referenced by convertJointTrajectory(), linkIndexOfVariable(), linkOfVariable(), robot::operator<<(), and variableUnitType().

KinematicChain& robot::KinematicChain::erase Int  first,
Int  last
 

KinematicChain& robot::KinematicChain::erase Int  pos  ) 
 

virtual void robot::KinematicChain::externalize base::Externalizer e,
String  format = "",
Real  version = 1.0
const [inline, virtual]
 

write object state to Externalizer (throws if e is in Input)

Reimplemented from base::Externalizable.

Definition at line 357 of file KinematicChain.

virtual void robot::KinematicChain::externalize base::Externalizer e,
String  format = "",
Real  version = 1.0
[virtual]
 

read or write object state to Externalizer

Implements base::Externalizable.

virtual bool robot::KinematicChain::formatSupported const String  format,
Real  version = 1.0,
ExternalizationType  type = IO
const [inline, virtual]
 

< query if specific format is supported (for input, output or both)

Implements base::Externalizable.

Definition at line 354 of file KinematicChain.

Link robot::KinematicChain::front  )  const [inline]
 

Definition at line 277 of file KinematicChain.

References Assert, links, and size().

Matrix robot::KinematicChain::getForwardKinematics const Vector q  )  const
 

get the forward kinematics transform for joint parameters q

const String& robot::KinematicChain::getInitialFrame  )  const [inline]
 

Definition at line 305 of file KinematicChain.

References initialFrame.

Matrix robot::KinematicChain::getJacobian const Vector q,
bool  includeOrientation = true
const
 

get the Jacobian matrix for joint parameters q

array<Vector> robot::KinematicChain::getJointOrigins const Vector q  )  const
 

get an array of the joint origin locations for parameters q

const String& robot::KinematicChain::getLinkFrame Int  i  )  const [inline]
 

Definition at line 308 of file KinematicChain.

References Assert, links, and size().

array<Vector> robot::KinematicChain::getLinkOrigins const Vector q  )  const
 

get an array of the link origin locations for parameters q

const SerializableInstantiator& base::Serializable::getSerializableInstantiator const String baseClassTypeName,
const String derivedClassTypeName
[static, inherited]
 

template<class BaseClass>
const SerializableInstantiator& base::Serializable::getSerializableInstantiator const String derivedClassTypeName  )  [inline, static, inherited]
 

Definition at line 71 of file Serializable.

References base::String.

virtual base::array<base::Byte> robot::KinematicChain::hashCode  )  const [virtual]
 

Whenever invoked on the same object more than once, the same byte array must be returned, provided no information used in == comparisons on the object is modified.

Implements base::Hashable.

void robot::KinematicChain::initKinematicEvaluator  )  [protected]
 

Referenced by KinematicChain().

KinematicChain& robot::KinematicChain::insert Int  pos,
const Link l
 

KinematicChain& robot::KinematicChain::insert Int  pos,
const KinematicChain kc
 

bool robot::KinematicChain::isDHType  )  const
 

true if the chain is comprised only of links for which link.isDHType() is true

virtual bool base::Object::isSameKindAs const Object  )  const [inline, virtual, inherited]
 

Definition at line 47 of file Object.

Int robot::KinematicChain::linkIndexOfVariable Int  i  )  const [inline]
 

Definition at line 261 of file KinematicChain.

References Assert, dof(), and variables.

bool robot::KinematicChain::linkIsActive Int  i  )  const [inline]
 

Definition at line 274 of file KinematicChain.

References Assert, links, and size().

const Link& robot::KinematicChain::linkOfVariable Int  i  )  const [inline]
 

get link that described joint controlled by variable i (0 <= i < dof())

Definition at line 258 of file KinematicChain.

References Assert, dof(), links, and variables.

Referenced by variableMaxAccel(), variableMaxLimit(), variableMinAccel(), variableMinLimit(), and variableUnitType().

void base::Externalizable::load ref< VFile archive,
const String format = "",
Real  version = 1.0
[inherited]
 

bool robot::KinematicChain::operator!= const KinematicChain kc  )  const [inline]
 

Definition at line 293 of file KinematicChain.

References links.

KinematicChain& robot::KinematicChain::operator+= const KinematicChain kc  ) 
 

KinematicChain& robot::KinematicChain::operator= const KinematicChain kc  )  [inline]
 

Definition at line 241 of file KinematicChain.

References dirtyHash(), links, and variables.

bool robot::KinematicChain::operator== const KinematicChain kc  )  const [inline]
 

Definition at line 292 of file KinematicChain.

References links.

const Link& robot::KinematicChain::operator[] Int  i  )  const [inline]
 

Definition at line 251 of file KinematicChain.

References links.

void robot::KinematicChain::pop_back  )  [inline]
 

Definition at line 283 of file KinematicChain.

References computeVariables(), dirtyHash(), links, base::array< T >::resize(), and size().

void robot::KinematicChain::push_back const Link l  )  [inline]
 

Definition at line 280 of file KinematicChain.

References base::array< T >::at(), computeVariables(), dirtyHash(), links, and size().

void base::Serializable::registerSerializableInstantiator const String baseClassTypeName,
const String derivedClassTypeName,
const SerializableInstantiator instantiator
[static, inherited]
 

template<class BaseClass, class DerivedClass>
void base::Serializable::registerSerializableInstantiator const SerializableInstantiator instantiator  )  [inline, static, inherited]
 

Definition at line 62 of file Serializable.

void robot::KinematicChain::resize Int  newsize  )  [inline]
 

Definition at line 286 of file KinematicChain.

References computeVariables(), dirtyHash(), links, and base::array< T >::resize().

void base::Externalizable::save ref< VFile archive,
const String format = "",
Real  version = 1.0
[inherited]
 

virtual void robot::KinematicChain::serialize base::Serializer s  )  [inline, virtual]
 

read or write object state to Serializer

Implements base::Serializable.

Definition at line 350 of file KinematicChain.

References computeVariables(), dirtyHash(), base::Serializer::isInput(), and links.

void robot::KinematicChain::setInitialFrame const String &  name  )  [inline]
 

Definition at line 304 of file KinematicChain.

References dirtyHash(), and initialFrame.

void robot::KinematicChain::setKinematicEvaluator ref< KinematicEvaluator evaluator  )  [inline]
 

Definition at line 333 of file KinematicChain.

References kinematicEvaluator.

void robot::KinematicChain::setLink Int  i,
const Link link
[inline]
 

Definition at line 252 of file KinematicChain.

References dirtyHash(), and links.

void robot::KinematicChain::setLinkAt Int  i,
const Link link
[inline]
 

Definition at line 255 of file KinematicChain.

References Assert, dirtyHash(), links, and size().

void robot::KinematicChain::setLinkFrame Int  i,
const String &  name
[inline]
 

Definition at line 307 of file KinematicChain.

References Assert, dirtyHash(), links, and size().

Int robot::KinematicChain::size  )  const [inline]
 

no. of links in the chain

Definition at line 246 of file KinematicChain.

References links, and base::array< T >::size().

Referenced by activateLink(), at(), back(), front(), getLinkFrame(), linkIsActive(), robot::operator<<(), pop_back(), push_back(), setLinkAt(), and setLinkFrame().

KinematicChain robot::KinematicChain::subChain Int  first,
Int  count
const
 

Vector robot::KinematicChain::transform const String &  fromFrame,
const String &  toFrame,
const Vector v,
const Vector q
const
 

transform point v from reference frame 'fromFrame' to 'toFrame' when chain is in cofiguration q e.g. if from=='ee' and to=='world', passing v=0 will give the ee coords. in the world frame (if 'ee' and 'world' are appropriately defined frame names) throws invalid_argument exception if either link frame names are unknown

Vector robot::KinematicChain::transform Int  fromLink,
Int  toLink,
const Vector v,
const Vector q
const
 

transform point v from the reference frame of link i to the frame of link j, when chain is in configuration q

Real robot::KinematicChain::variableMaxAccel Int  i  )  const [inline]
 

Definition at line 269 of file KinematicChain.

References linkOfVariable(), robot::KinematicChain::Link::maxAccel(), and variables.

Real robot::KinematicChain::variableMaxLimit Int  i  )  const [inline]
 

Definition at line 267 of file KinematicChain.

References linkOfVariable(), robot::KinematicChain::Link::maxLimit(), and variables.

Real robot::KinematicChain::variableMinAccel Int  i  )  const [inline]
 

Definition at line 268 of file KinematicChain.

References linkOfVariable(), robot::KinematicChain::Link::minAccel(), and variables.

Real robot::KinematicChain::variableMinLimit Int  i  )  const [inline]
 

Definition at line 266 of file KinematicChain.

References linkOfVariable(), robot::KinematicChain::Link::minLimit(), and variables.

UnitType robot::KinematicChain::variableUnitType Int  i  )  const [inline]
 

Definition at line 263 of file KinematicChain.

References Assert, dof(), robot::KinematicChain::Link::dofUnitType(), linkOfVariable(), UnitType, and variables.

Referenced by convertJointTrajectory().


Member Data Documentation

ref<KinematicEvaluator> robot::KinematicChain::defaultKinematicEvaluator [static, protected]
 

Definition at line 381 of file KinematicChain.

array<base::Byte> robot::KinematicChain::hash [mutable, protected]
 

Definition at line 388 of file KinematicChain.

bool robot::KinematicChain::hashDirty [mutable, protected]
 

Definition at line 387 of file KinematicChain.

String robot::KinematicChain::initialFrame [protected]
 

Definition at line 385 of file KinematicChain.

Referenced by getInitialFrame(), and setInitialFrame().

ref<KinematicEvaluator> robot::KinematicChain::kinematicEvaluator [protected]
 

KinematicEvaluator instance to use for this chain.

Definition at line 383 of file KinematicChain.

Referenced by KinematicChain(), and setKinematicEvaluator().

bool robot::KinematicChain::KinematicEvaluatorInitialized [static, protected]
 

Definition at line 380 of file KinematicChain.

LinkArray robot::KinematicChain::links [protected]
 

Definition at line 376 of file KinematicChain.

Referenced by activateLink(), at(), back(), front(), getLinkFrame(), KinematicChain(), linkIsActive(), linkOfVariable(), operator!=(), operator=(), operator==(), operator[](), pop_back(), push_back(), resize(), serialize(), setLink(), setLinkAt(), setLinkFrame(), and size().

const Real robot::KinematicChain::unboundedMaxAngleLimit [static]
 

Definition at line 56 of file KinematicChain.

const Real robot::KinematicChain::unboundedMaxDistLimit [static]
 

Definition at line 58 of file KinematicChain.

const Real robot::KinematicChain::unboundedMinAngleLimit [static]
 

Definition at line 55 of file KinematicChain.

const Real robot::KinematicChain::unboundedMinDistLimit [static]
 

Definition at line 57 of file KinematicChain.

VariableIndexArray robot::KinematicChain::variables [protected]
 

Definition at line 377 of file KinematicChain.

Referenced by dof(), KinematicChain(), linkIndexOfVariable(), linkOfVariable(), operator=(), variableMaxAccel(), variableMaxLimit(), variableMinAccel(), variableMinLimit(), and variableUnitType().


The documentation for this class was generated from the following file:
Generated on Thu Jul 29 16:41:53 2004 for OpenSim by doxygen 1.3.6