Tekkotsu Homepage
Demos
Overview
Downloads
Dev. Resources
Reference
Credits

KinematicJoint Class Reference

Manages parameters which define the position and type of motion produced by an actuator (i.e. forward kinematics). More...

#include <KinematicJoint.h>

Inheritance diagram for KinematicJoint:

Detailed Description

Manages parameters which define the position and type of motion produced by an actuator (i.e. forward kinematics).

Definition at line 203 of file KinematicJoint.h.

List of all members.

Classes

class  BranchListener
class  ComponentsListener
struct  ControllerInfo
 Parameters for joint motion model, used for simulation. More...

Public Types

enum  JointType_t { REVOLUTE, PRISMATIC }
 

types of joints which are supported

More...
typedef plist::ArrayOf
< LinkComponent >
::const_iterator 
component_iterator
 for convenience when looping over components
typedef std::set
< KinematicJoint * >
::const_iterator 
branch_iterator
 type of iterators over sub-trees

Public Member Functions

 KinematicJoint ()
 constructor
 KinematicJoint (const KinematicJoint &kj)
 copy constructor (deep copy, but doesn't register with parent)
KinematicJointoperator= (const KinematicJoint &kj)
 deep copy via copyBranches(), replaces current branches. This does not affect listener list (other than calling them), the parent or depth values
void shallowCopy (const KinematicJoint &kj)
 copies all parameters from kj, except listeners, depth, parent or children; see copyBranches()
void copyBranches (const KinematicJoint &kj)
 releases current children and clones those from ; does not copy parameters, see shallowCopy()
virtual ~KinematicJoint ()
 destructor, recursively destroys sub-tree
void getObstacles (const fmat::Transform &worldT, class HierarchicalObstacle &obs, bool recurse) const
 Inserts 2D projections of this link's collision components into obs, if recurse is set, recurses on branches.
virtual BoundingBox3D getOwnAABB () const
 Returns the axis-aligned bounding box (relative to link frame) of this component only (i.e. KinematicJoint ignores subcomponents).
float getQ () const
 returns the current q value
void setQ (float x)
 sets the current joint position (q) (ignoring qmin, qmax) and updates the transformation matrix (if q has changed)
bool tryQ (float x)
 sets the current joint position (q) to x, clipped to [qmin,qmax], returning true if in range
void freezeQ (float x)
 sets the joint position, and qmin and qmax as well to prevent inverse kinematics from using it
bool validQ (float x) const
 returns true if x is within [qmin,qmax] (inclusive)
template<class M >
void pushChildrenQIntoArray (M &values, int deoffset, unsigned int max) const
 sets the joint position and its childrens' positions from a flat array, using outputOffset
template<class M >
void pushAncestorsQIntoArray (M &values, int deoffset, unsigned int max) const
 sets the joint position and its ancestors' positions from a flat array, using outputOffset
template<class M >
void pullChildrenQFromArray (M &values, int deoffset, unsigned int max)
 sets the joint position and its childrens' positions from a flat array, using outputOffset
template<class M >
void pullAncestorsQFromArray (M &values, int deoffset, unsigned int max)
 sets the joint position and its ancestors' positions from a flat array, using outputOffset
void zeroChildrenQ ()
 sets the joint position and its childrens' to zero
void zeroAncestorQ ()
 sets the joint position and its ancestors' to zero
fmat::Transform getFullT () const
 returns the tranformation matrix which converts from the link's reference frame (i.e. the frame which moves with the joint's q) to the base frame
fmat::Transform getFullInvT () const
 returns the tranformation matrix which converts from the base frame to the link's reference frame (i.e. the frame which moves with the joint's q)
fmat::Transform getT (const KinematicJoint &j) const
 returns the tranformation matrix which converts from the link's reference frame (i.e. the frame which moves with the joint's q) to the specified joint's link frame
const fmat::TransformgetTo () const
 returns the tranformation matrix which converts from the joint's reference frame (i.e. the frame in which the link moves) to the parent's frame
const fmat::TransformgetTq () const
 returns the tranformation matrix which converts from the link's reference frame (i.e. the frame which moves with the joint's q) to the parent's frame
void sumCenterOfMass (fmat::Column< 3 > &cOfM, float &totalMass) const
 returns the center of mass of this link and all of its branches, given their current positions, resulting position relative to this link
fmat::Column< 4 > sumCenterOfMass () const
 returns the unnormalized center of mass of this link and all of its branches, given their current positions, relative to this link
virtual fmat::Column< 4 > sumLinkCenterOfMass () const
 returns the unnormalized center of mass of this link only, not including any branches
virtual bool hasMass () const
 returns true if mass is greater than zero, of if this is a KinematicJoint, if any of the components have mass greater than zero
fmat::Column< 6 > getJointJacobian (const fmat::Column< 3 > &p) const
 returns a column vector indicating the joint's motion in base coordinates, at a point p (in base coordinates)
void getFullJacobian (const fmat::Column< 3 > &p, std::vector< fmat::Column< 6 > > &j) const
 computes the motion of this joint and all of its ancestors at a point p (in base coordinates), j should be empty on call, may wish to reserve depth+1
void getMobileJacobian (const fmat::Column< 3 > &p, std::vector< fmat::Column< 6 > > &j) const
 computes the motion of this joint and all of its ancestors at a point p (in base coordinates), j should be empty on call, may wish to reserve depth+1
fmat::Column< 3 > getWorldPosition () const
 returns the position of this joint in base coordinates (as a length 3 vector)
fmat::Matrix< 3, 3 > getWorldRotation () const
 returns the orientation of this joint in base coordinates (as a 3x3 matrix)
fmat::Column< 3 > getPosition () const
 returns the position of this joint relative to its parent's link frame
fmat::Column< 3 > getParentPosition () const
 returns the position of the parent origin relative to this joint's link frame
fmat::Matrix< 3, 3 > getRotation () const
 returns the orientation of this joint relative to its parent's link frame (as a 3x3 matrix)
fmat::Quaternion getWorldQuaternion () const
 returns the orientation of this joint in base coordinates (as a quaternion (w,x,y,z))
fmat::Quaternion getQuaternion (const KinematicJoint &j) const
 returns the orientation of this joint in base coordinates (as a quaternion (w,x,y,z))
fmat::Quaternion getQuaternion () const
 returns the orientation of this joint relative to its parent's link frame (as a quaternion (w,x,y,z))
virtual void loadXML (xmlNode *node)
 if the node is an array, loads the sub-tree, otherwise expects a dict to load the joint's own parameters
virtual void saveXML (xmlNode *node, bool onlyOverwrite, std::set< std::string > &seen) const
 if the node is NULL, has no parent, or is a plist node, writes human-readable help text as a comment and then recurses through the subtrees (otherwise saves only this joint's parameters)
template<class M >
void buildChildMap (M &childMap, int deoffset, unsigned int max)
 Builds a map from output offsets to this and child joints (call it on the root node –– doesn't handle ancestors.
template<class M >
void buildChildMap (M &childMap, int deoffset, unsigned int max) const
 builds a map from output offsets to this and child joints (call it on the root node –– doesn't handle ancestors
template<class M >
void buildMobileChildMap (M &childMap, int deoffset, unsigned int max)
 builds a map from output offsets to this and child joints (call it on the root node –– doesn't handle ancestors
template<class M >
void buildMobileChildMap (M &childMap, int deoffset, unsigned int max) const
 builds a map from output offsets to this and child joints (call it on the root node –– doesn't handle ancestors
const std::set< KinematicJoint * > & getBranches () const
 returns a reference to branches so you can iterator over sub-trees
KinematicJointaddBranch (KinematicJoint *b)
 adds the joint to the branches, control over memory (de)allocation is assumed by this instance until/unless removeBranch() is called
KinematicJointremoveBranch (KinematicJoint *b)
 removes the specified joint from branches, returning control of (de)allocation of b to caller.
void clearBranches ()
 deletes all entries of branches en masse
bool isBranch () const
 returns true if the link following this joint has more than one additional joint attached (i.e. if branches.size() > 1)
KinematicJointcloneBranch () const
 Clones joints from this back to and including the root, not cloning side branches; returns a pointer to the last (i.e. leaf) joint in the cloned branch.
KinematicJointnextJoint () const
 returns the 'first' element of branches, or NULL if this is a leaf
bool isMobile () const
 returns true if qmin≠qmax (i.e. the joint is considered "mobile", and not just a abstract reference frame)
KinematicJointgetRoot ()
 returns root joint (will return 'this' if this is the first joint), see addBranch()/removeBranch()
const KinematicJointgetRoot () const
 returns root joint (will return 'this' if this is the first joint), see addBranch()/removeBranch()
std::string getPath (const std::string &sep="/") const
 returns a string containing the names of all ancestors' outputOffset values separated by sep
size_t getDepth () const
 returns 0 if this is the root (no parent), otherwise one plus the parent's depth
void addBranchListener (BranchListener *l) const
void removeBranchListener (BranchListener *l) const
bool isBranchListener (BranchListener *l) const
IKSolvergetIK () const
 returns an IKSolver instance, which will be cached internally for future accesses
virtual KinematicJointclone () const __attribute__((warn_unused_result))
 clone implementation for Dictionary

Public Attributes

plist::NamedEnumeration
< JointType_t
jointType
 the type of motion produced by this joint
plist::Angle theta
 rotation about the previous joint's z-axis to point its x-axis parallel to the common normal with this joint's z-axis (aka "Modified Denavit-Hartenberg")
plist::Primitive< fmat::fmatReald
 translation along the previous joint's z-axis to align its x-axis with the common normal with this joint's z-axis (aka "Modified Denavit-Hartenberg")
plist::Angle alpha
 rotation about this joint's x-axis to make the previous joint's z-axis parallel to this one (aka "Modified Denavit-Hartenberg")
plist::Primitive< fmat::fmatRealr
 translation from the previous joint's z-axis along the common normal to place this joint's origin (aka "Modified Denavit-Hartenberg")
plist::Angle qOffset
 a constant offset to the q setting to define the physical zero-point of the joint
plist::Angle qmin
 indicates the minimum q value which inverse kinematics may provide (if equal to qmax, the joint is considered immobile)
plist::Angle qmax
 indicates the maximum q value which inverse kinematics may provide (if equal to qmin, the joint is considered immobile)
plist::ArrayOf< LinkComponentcomponents
 a list of link features, for simple display or collision models with more than one primitive
plist::Primitive< floatfrictionForce
 conversion from velocity to friction force (default 0.5)
plist::Point anistropicFrictionRatio
 direction sensitivity of friction, '1' in all directions means it is not direction sensitive
plist::Primitive< std::string > ikSolver
 specifies the name of the inverse kinematics solver to use with this appendage
plist::ArrayOf< SensorInfosensorInfo
 Stores sensor parameters for simulated input, type indicated by SensorType entry corresponding to a SensorInfo subclass.
ControllerInfo controllerInfo
 Stores controller parameters for simulated input, type indicated by ControllerType entry corresponding to a ControllerInfo subclass.
plist::OutputSelector outputOffset
 name or index of the joint this maps to so we can integrate with Tekkotsu's flat arrays

Static Public Attributes

static const char * jointTypeNames [3] = { "revolute", "prismatic", NULL }
 provides human readable names for JointType_t, for loading/saving jointType (null terminated)

Protected Member Functions

void initEntries ()
 add the plist entries to the dictionary superclass
void getFullT (fmat::Transform &t, const KinematicJoint *endj) const
 recursively computes the full transformation matrix, converting from this joint's frame to the specified joint's frame, or the base frame if is NULL
void getQuaternion (fmat::Quaternion &quat, const KinematicJoint *endj) const
void doSaveXMLNode (std::set< std::string > &seen, xmlNode *node, const std::string &key, const std::string &indentStr, size_t longestKeyLen) const
 shorthand for saving a specific node, forwarding call to saveXMLNode()
virtual void plistValueChanged (const plist::PrimitiveBase &pl)
 This will be called whenever a plist you have registered with is changed.
virtual void addSelfListener ()
 subscribes the instance to be notified of changes to its public plist::Primitive members, and then calls updateTo()
virtual void removeSelfListener ()
 unsubscribes the instance from its public plist::Primitive members
void updateTo ()
 regenerates To from the a, d, alpha, and theta parameters, includes call to updateTq() as well
void updateTq ()
 updates Tq from the q and qOffset parameters (based on current To)
virtual void updateBB () const
 recomputes boundingBoxLow and boundingBoxHigh based on collision model parameters
void updateDepth ()
void fireBranchAdded (KinematicJoint &val)
void fireBranchRemoved (KinematicJoint &val)
void fireReconfigured ()
void setParent (LinkComponent &link)
 for use by ComponentsListener, work around parent being protected
void unsetParent (LinkComponent &link)
 for use by ComponentsListener, work around parent being protected
virtual void dirtyBB ()
 sets bbDirty to true to cause it to be recomputed on next getAABB() call

Protected Attributes

std::set< KinematicJoint * > branches
 sub-chains of joints, supporting branches but not cycles (nor NULL entries)
std::set< BranchListener * > * branchListeners
size_t depth
 one plus parent's depth, or 0 if parentless
fmat::fmatReal q
 current joint position (radian rotation about z if revolute, displacement along z if prismatic)
fmat::Transform To
 transformation to the joint's origin
fmat::Transform Tq
 transformation to origin, including final q rotation
IKSolverik
 an instance of the IKSolver corresponding to ikSolver
KinematicJoint::ComponentsListener componentsListener

Friends

class KinematicJointLoader
class KinematicJointSaver

Member Typedef Documentation

type of iterators over sub-trees

Definition at line 537 of file KinematicJoint.h.

for convenience when looping over components

Definition at line 312 of file KinematicJoint.h.


Member Enumeration Documentation

types of joints which are supported

Enumerator:
REVOLUTE 

a joint which rotates around the z-axis

PRISMATIC 

a joint which slides along the z-axis

Definition at line 291 of file KinematicJoint.h.


Constructor & Destructor Documentation

KinematicJoint::KinematicJoint (  ) 

constructor

Definition at line 215 of file KinematicJoint.h.

KinematicJoint::KinematicJoint ( const KinematicJoint kj  ) 

copy constructor (deep copy, but doesn't register with parent)

Definition at line 226 of file KinematicJoint.h.

KinematicJoint::~KinematicJoint (  )  [virtual]

destructor, recursively destroys sub-tree

Definition at line 122 of file KinematicJoint.cc.


Member Function Documentation

KinematicJoint * KinematicJoint::addBranch ( KinematicJoint b  ) 

adds the joint to the branches, control over memory (de)allocation is assumed by this instance until/unless removeBranch() is called

For convenience, returns b

Definition at line 761 of file KinematicJoint.cc.

Referenced by cloneBranch(), copyBranches(), and KinematicJointLoader::loadXMLNode().

void KinematicJoint::addBranchListener ( BranchListener l  )  const

Definition at line 131 of file KinematicJoint.cc.

void KinematicJoint::addSelfListener (  )  [protected, virtual]

subscribes the instance to be notified of changes to its public plist::Primitive members, and then calls updateTo()

Definition at line 457 of file KinematicJoint.cc.

Referenced by initEntries(), and loadXML().

template<class M >
void KinematicJoint::buildChildMap ( M &  childMap,
int  deoffset,
unsigned int  max 
) const

builds a map from output offsets to this and child joints (call it on the root node –– doesn't handle ancestors

The map must be initialized to NULL values before calling this method. deoffset will be subtracted from each index, and the result only added to the map if it (as unsigned int) is less than max. This is intended to allow you to extract the mapping for only a region of outputs in use, e.g. childMap[NumArmJoints], offset=ArmOffset and max=NumArmJoints

Definition at line 506 of file KinematicJoint.h.

template<class M >
void KinematicJoint::buildChildMap ( M &  childMap,
int  deoffset,
unsigned int  max 
)

Builds a map from output offsets to this and child joints (call it on the root node –– doesn't handle ancestors.

The map must be initialized to NULL values before calling this method. deoffset will be subtracted from each index, and the result only added to the map if it (as unsigned int) is less than max. This is intended to allow you to extract the mapping for only a region of outputs in use, e.g. childMap[NumArmJoints], offset=ArmOffset and max=NumArmJoints

Definition at line 494 of file KinematicJoint.h.

Referenced by ArmController::doStart(), GaitedFootstepMC::GaitedFootstepMC(), Kinematics::init(), Kinematics::Kinematics(), Kinematics::operator=(), GaitedFootsteps::setGait(), and XWalkMC::XWalkMC().

template<class M >
void KinematicJoint::buildMobileChildMap ( M &  childMap,
int  deoffset,
unsigned int  max 
) const

builds a map from output offsets to this and child joints (call it on the root node –– doesn't handle ancestors

The map must be initialized to NULL values before calling this method. deoffset will be subtracted from each index, and the result only added to the map if it (as unsigned int) is less than max. This is intended to allow you to extract the mapping for only a region of outputs in use, e.g. childMap[NumArmJoints], offset=ArmOffset and max=NumArmJoints

Definition at line 529 of file KinematicJoint.h.

template<class M >
void KinematicJoint::buildMobileChildMap ( M &  childMap,
int  deoffset,
unsigned int  max 
)

builds a map from output offsets to this and child joints (call it on the root node –– doesn't handle ancestors

The map must be initialized to NULL values before calling this method. deoffset will be subtracted from each index, and the result only added to the map if it (as unsigned int) is less than max. This is intended to allow you to extract the mapping for only a region of outputs in use, e.g. childMap[NumArmJoints], offset=ArmOffset and max=NumArmJoints

Definition at line 518 of file KinematicJoint.h.

Referenced by CBracketGrasperPredicate< N >::CBracketGrasperPredicate().

void KinematicJoint::clearBranches (  ) 

deletes all entries of branches en masse

Definition at line 787 of file KinematicJoint.cc.

Referenced by copyBranches(), loadXML(), and ~KinematicJoint().

KinematicJoint * KinematicJoint::clone (  )  const [virtual]

clone implementation for Dictionary

implements the clone function for dictionary

Reimplemented from LinkComponent.

Definition at line 174 of file KinematicJoint.cc.

Referenced by GaitedFootsteps::setGait().

KinematicJoint * KinematicJoint::cloneBranch (  )  const

Clones joints from this back to and including the root, not cloning side branches; returns a pointer to the last (i.e. leaf) joint in the cloned branch.

To clone a joint and all its children (instead of its direct ancestors as is done here), use the copy constructor or operator=. Just use getRoot() on the result if you want to store the root joint instead of the end joint.

Definition at line 798 of file KinematicJoint.cc.

Referenced by ArmController::ArmController(), CBracketGrasperPredicate< N >::CBracketGrasperPredicate(), RRTNode3DR< N >::CollisionChecker::CollisionChecker(), RRTNode2DR< N >::CollisionChecker::CollisionChecker(), Grasper::computeGoalStates(), Grasper::PlanArmApproach::doStart(), HeadPointerMC::lookAtPoint(), HeadPointerMC::lookInDirection(), ArmMC::moveOffsetToPoint(), ArmMC::moveOffsetToPointWithOrientation(), ShapeSpacePlanner2DR< N >::ShapeSpacePlanner2DR(), and ShapeSpacePlanner3DR< N >::ShapeSpacePlanner3DR().

void KinematicJoint::copyBranches ( const KinematicJoint kj  ) 

releases current children and clones those from ; does not copy parameters, see shallowCopy()

Definition at line 276 of file KinematicJoint.h.

Referenced by KinematicJoint(), and operator=().

virtual void KinematicJoint::dirtyBB (  )  [protected, virtual]

sets bbDirty to true to cause it to be recomputed on next getAABB() call

Reimplemented from LinkComponent.

Definition at line 689 of file KinematicJoint.h.

Referenced by setParent(), and unsetParent().

void KinematicJoint::doSaveXMLNode ( std::set< std::string > &  seen,
xmlNode node,
const std::string &  key,
const std::string &  indentStr,
size_t  longestKeyLen 
) const [protected]

shorthand for saving a specific node, forwarding call to saveXMLNode()

Definition at line 633 of file KinematicJoint.h.

Referenced by saveXML().

void KinematicJoint::fireBranchAdded ( KinematicJoint val  )  [protected]

Definition at line 176 of file KinematicJoint.cc.

Referenced by addBranch().

void KinematicJoint::fireBranchRemoved ( KinematicJoint val  )  [protected]

Definition at line 188 of file KinematicJoint.cc.

Referenced by removeBranch().

void KinematicJoint::fireReconfigured (  )  [protected]

Definition at line 200 of file KinematicJoint.cc.

Referenced by plistValueChanged(), and shallowCopy().

void KinematicJoint::freezeQ ( float  x  ) 

sets the joint position, and qmin and qmax as well to prevent inverse kinematics from using it

Definition at line 356 of file KinematicJoint.h.

Referenced by XWalkMC::updateOutputsWalking().

size_t KinematicJoint::getDepth (  )  const

returns 0 if this is the root (no parent), otherwise one plus the parent's depth

Definition at line 575 of file KinematicJoint.h.

Referenced by XWalkMC::sendLoadPredictions(), IKGradientSolver::solve(), and IKGradientSolver::step().

fmat::Transform KinematicJoint::getFullInvT (  )  const

returns the tranformation matrix which converts from the base frame to the link's reference frame (i.e. the frame which moves with the joint's q)

Definition at line 412 of file KinematicJoint.h.

Referenced by IKThreeLink::computeSecondLinkPrismatic(), IKThreeLink::computeSecondLinkRevolute(), IKThreeLink::computeThirdLinkPrismatic(), IKThreeLink::computeThirdLinkRevolute(), and getT().

void KinematicJoint::getFullJacobian ( const fmat::Column< 3 > &  p,
std::vector< fmat::Column< 6 > > &  j 
) const

computes the motion of this joint and all of its ancestors at a point p (in base coordinates), j should be empty on call, may wish to reserve depth+1

The first 3 rows indicate the ∂x, ∂y, and ∂z values per ∂q corresponding to each column. The last 3 rows indicate the axis of rotation for each joint (or all 0's for prismatic joints)

Definition at line 448 of file KinematicJoint.h.

Referenced by getFullJacobian(), XWalkMC::sendLoadPredictions(), and IKGradientSolver::step().

void KinematicJoint::getFullT ( fmat::Transform t,
const KinematicJoint endj 
) const [protected]

recursively computes the full transformation matrix, converting from this joint's frame to the specified joint's frame, or the base frame if is NULL

t does not need to be initialized to anything prior to call, but will be 4x4 on return
endj must be an ancestor of this joint or the function will segfault (NULL is the ancestor of the root, so that's valid)

Definition at line 615 of file KinematicJoint.h.

fmat::Column< 6 > KinematicJoint::getJointJacobian ( const fmat::Column< 3 > &  p  )  const

returns a column vector indicating the joint's motion in base coordinates, at a point p (in base coordinates)

The first 3 rows indicate the ∂x/∂q, ∂y/∂q, and ∂z/∂q values. The last 3 rows indicate the axis of rotation (or all 0's for a prismatic joint)

Definition at line 322 of file KinematicJoint.cc.

Referenced by getFullJacobian(), and getMobileJacobian().

void KinematicJoint::getMobileJacobian ( const fmat::Column< 3 > &  p,
std::vector< fmat::Column< 6 > > &  j 
) const

computes the motion of this joint and all of its ancestors at a point p (in base coordinates), j should be empty on call, may wish to reserve depth+1

The first 3 rows indicate the ∂x, ∂y, and ∂z values per ∂q corresponding to each column. The last 3 rows indicate the axis of rotation for each joint (or all 0's for prismatic joints)

Definition at line 457 of file KinematicJoint.h.

Referenced by getMobileJacobian().

void KinematicJoint::getObstacles ( const fmat::Transform worldT,
class HierarchicalObstacle obs,
bool  recurse 
) const

Inserts 2D projections of this link's collision components into obs, if recurse is set, recurses on branches.

Reimplemented from LinkComponent.

Definition at line 577 of file KinematicJoint.cc.

virtual BoundingBox3D KinematicJoint::getOwnAABB (  )  const [virtual]

Returns the axis-aligned bounding box (relative to link frame) of this component only (i.e. KinematicJoint ignores subcomponents).

KinematicJoint uses cache members to store the expanded subcomponent BB, so must recompute the local BB each time

Reimplemented from LinkComponent.

Definition at line 344 of file KinematicJoint.h.

fmat::Column< 3 > KinematicJoint::getParentPosition (  )  const

returns the position of the parent origin relative to this joint's link frame

Definition at line 345 of file KinematicJoint.cc.

std::string KinematicJoint::getPath ( const std::string &  sep = "/"  )  const

returns a string containing the names of all ancestors' outputOffset values separated by sep

Definition at line 573 of file KinematicJoint.h.

Referenced by getPath().

fmat::Column<3> KinematicJoint::getPosition (  )  const

returns the position of this joint relative to its parent's link frame

Definition at line 470 of file KinematicJoint.h.

Referenced by IKSolver::solve(), XWalkMC::solveIK(), and IKSolver::step().

void KinematicJoint::getQuaternion ( fmat::Quaternion quat,
const KinematicJoint endj 
) const [protected]

Definition at line 623 of file KinematicJoint.h.

fmat::Quaternion KinematicJoint::getQuaternion (  )  const

returns the orientation of this joint relative to its parent's link frame (as a quaternion (w,x,y,z))

Definition at line 481 of file KinematicJoint.h.

Referenced by getQuaternion(), and getWorldQuaternion().

fmat::Quaternion KinematicJoint::getQuaternion ( const KinematicJoint j  )  const

returns the orientation of this joint in base coordinates (as a quaternion (w,x,y,z))

Definition at line 356 of file KinematicJoint.cc.

Referenced by getQuaternion(), IKSolver::solve(), and IKSolver::step().

const KinematicJoint* KinematicJoint::getRoot (  )  const

returns root joint (will return 'this' if this is the first joint), see addBranch()/removeBranch()

Definition at line 571 of file KinematicJoint.h.

KinematicJoint* KinematicJoint::getRoot (  ) 
fmat::Matrix<3,3> KinematicJoint::getRotation (  )  const

returns the orientation of this joint relative to its parent's link frame (as a 3x3 matrix)

Definition at line 474 of file KinematicJoint.h.

Referenced by IKThreeLink::computeSecondLinkRevolute().

fmat::Transform KinematicJoint::getT ( const KinematicJoint j  )  const
const fmat::Transform& KinematicJoint::getTo (  )  const

returns the tranformation matrix which converts from the joint's reference frame (i.e. the frame in which the link moves) to the parent's frame

This transformation is constant in terms of q.

Definition at line 419 of file KinematicJoint.h.

Referenced by IKThreeLink::computeFirstLinkPrismatic(), IKThreeLink::computeFirstLinkRevolute(), IKThreeLink::computeSecondLinkPrismatic(), IKThreeLink::computeThirdLinkPrismatic(), ArmController::doStart(), IKCalliope::IKCalliope(), ArmController::pointPicked(), and ArmController::sendReachablePoints().

const fmat::Transform& KinematicJoint::getTq (  )  const

returns the tranformation matrix which converts from the link's reference frame (i.e. the frame which moves with the joint's q) to the parent's frame

This transformation is changes with q.

Definition at line 423 of file KinematicJoint.h.

Referenced by getObstacles().

fmat::Quaternion KinematicJoint::getWorldQuaternion (  )  const

returns the orientation of this joint in base coordinates (as a quaternion (w,x,y,z))

Definition at line 350 of file KinematicJoint.cc.

Referenced by IKThreeLink::solve(), IKThreeLink::step(), IKGradientSolver::step(), and IKCalliope::step().

fmat::Matrix<3,3> KinematicJoint::getWorldRotation (  )  const

returns the orientation of this joint in base coordinates (as a 3x3 matrix)

Definition at line 467 of file KinematicJoint.h.

bool KinematicJoint::hasMass (  )  const [virtual]

returns true if mass is greater than zero, of if this is a KinematicJoint, if any of the components have mass greater than zero

Reimplemented from LinkComponent.

Definition at line 313 of file KinematicJoint.cc.

void KinematicJoint::initEntries (  )  [protected]

add the plist entries to the dictionary superclass

Definition at line 588 of file KinematicJoint.h.

Referenced by KinematicJoint().

bool KinematicJoint::isBranch (  )  const

returns true if the link following this joint has more than one additional joint attached (i.e. if branches.size() > 1)

Definition at line 554 of file KinematicJoint.h.

bool KinematicJoint::isBranchListener ( BranchListener l  )  const

Definition at line 152 of file KinematicJoint.cc.

void KinematicJoint::loadXML ( xmlNode node  )  [virtual]

if the node is an array, loads the sub-tree, otherwise expects a dict to load the joint's own parameters

Reimplemented from plist::DictionaryBase.

Definition at line 384 of file KinematicJoint.cc.

KinematicJoint* KinematicJoint::nextJoint (  )  const

returns the 'first' element of branches, or NULL if this is a leaf

The choice of 'first' is arbitrary (and not necessarily consistent run-to-run), you should not use this if you expect to encounter branching chains

Definition at line 563 of file KinematicJoint.h.

Referenced by ShapeSpacePlanner3DR< N >::getBoxes(), ShapeSpacePlanner2DR< N >::getBoxes(), ShapeSpacePlanner3DR< N >::plotPath(), and ShapeSpacePlanner3DR< N >::plotTree().

KinematicJoint& KinematicJoint::operator= ( const KinematicJoint kj  ) 

deep copy via copyBranches(), replaces current branches. This does not affect listener list (other than calling them), the parent or depth values

Definition at line 240 of file KinematicJoint.h.

Referenced by shallowCopy().

void KinematicJoint::plistValueChanged ( const plist::PrimitiveBase pl  )  [protected, virtual]

This will be called whenever a plist you have registered with is changed.

pl is const to help you avoid infinite recursion from an accidental modification of pl's value -- use a const cast if you're sure you know what you're doing

Implements plist::PrimitiveListener.

Definition at line 434 of file KinematicJoint.cc.

Referenced by addSelfListener().

template<class M >
void KinematicJoint::pullAncestorsQFromArray ( M &  values,
int  deoffset,
unsigned int  max 
)

sets the joint position and its ancestors' positions from a flat array, using outputOffset

deoffset will be subtracted from each index, and the result only added to the map if it (as unsigned int) is less than max. This is intended to allow you to extract the joint values for only a region of outputs in use, e.g. values[NumArmJoints], offset=ArmOffset and max=NumArmJoints

Definition at line 394 of file KinematicJoint.h.

Referenced by pullAncestorsQFromArray().

template<class M >
void KinematicJoint::pullChildrenQFromArray ( M &  values,
int  deoffset,
unsigned int  max 
)

sets the joint position and its childrens' positions from a flat array, using outputOffset

deoffset will be subtracted from each index, and the result only added to the map if it (as unsigned int) is less than max. This is intended to allow you to extract the joint values for only a region of outputs in use, e.g. values[NumArmJoints], offset=ArmOffset and max=NumArmJoints

Definition at line 384 of file KinematicJoint.h.

Referenced by XWalkMC::start(), XWalkMC::updateOutputs(), and XWalkMC::updateOutputsInitial().

template<class M >
void KinematicJoint::pushAncestorsQIntoArray ( M &  values,
int  deoffset,
unsigned int  max 
) const

sets the joint position and its ancestors' positions from a flat array, using outputOffset

deoffset will be subtracted from each index, and the result only added to the map if it (as unsigned int) is less than max. This is intended to allow you to extract the joint values for only a region of outputs in use, e.g. values[NumArmJoints], offset=ArmOffset and max=NumArmJoints

Definition at line 374 of file KinematicJoint.h.

Referenced by pushAncestorsQIntoArray().

template<class M >
void KinematicJoint::pushChildrenQIntoArray ( M &  values,
int  deoffset,
unsigned int  max 
) const

sets the joint position and its childrens' positions from a flat array, using outputOffset

deoffset will be subtracted from each index, and the result only added to the map if it (as unsigned int) is less than max. This is intended to allow you to extract the joint values for only a region of outputs in use, e.g. values[NumArmJoints], offset=ArmOffset and max=NumArmJoints

Definition at line 364 of file KinematicJoint.h.

KinematicJoint * KinematicJoint::removeBranch ( KinematicJoint b  ) 

removes the specified joint from branches, returning control of (de)allocation of b to caller.

For convenience, returns b

Definition at line 778 of file KinematicJoint.cc.

Referenced by clearBranches().

void KinematicJoint::removeBranchListener ( BranchListener l  )  const

Definition at line 139 of file KinematicJoint.cc.

void KinematicJoint::removeSelfListener (  )  [protected, virtual]

unsubscribes the instance from its public plist::Primitive members

Definition at line 467 of file KinematicJoint.cc.

Referenced by loadXML(), and ~KinematicJoint().

void KinematicJoint::saveXML ( xmlNode node,
bool  onlyOverwrite,
std::set< std::string > &  seen 
) const [virtual]

if the node is NULL, has no parent, or is a plist node, writes human-readable help text as a comment and then recurses through the subtrees (otherwise saves only this joint's parameters)

Reimplemented from plist::DictionaryBase.

Definition at line 405 of file KinematicJoint.cc.

void KinematicJoint::setParent ( LinkComponent link  )  [protected]
void KinematicJoint::setQ ( float  x  ) 

sets the current joint position (q) (ignoring qmin, qmax) and updates the transformation matrix (if q has changed)

Definition at line 350 of file KinematicJoint.h.

Referenced by freezeQ(), CBracketGrasperPredicate< N >::gripperPosition(), pullAncestorsQFromArray(), pullChildrenQFromArray(), ArmController::setJoint(), IKGradientSolver::step(), PostureEngine::update(), Kinematics::update(), and zeroChildrenQ().

void KinematicJoint::shallowCopy ( const KinematicJoint kj  ) 

copies all parameters from kj, except listeners, depth, parent or children; see copyBranches()

Definition at line 246 of file KinematicJoint.h.

Referenced by cloneBranch(), and operator=().

fmat::Column< 4 > KinematicJoint::sumCenterOfMass (  )  const

returns the unnormalized center of mass of this link and all of its branches, given their current positions, relative to this link

The last element (homogeneous scale factor) is left as the total mass, so divide by this value to normalize.

Definition at line 291 of file KinematicJoint.cc.

Referenced by sumCenterOfMass().

void KinematicJoint::sumCenterOfMass ( fmat::Column< 3 > &  cOfM,
float totalMass 
) const

returns the center of mass of this link and all of its branches, given their current positions, resulting position relative to this link

Definition at line 283 of file KinematicJoint.cc.

Referenced by GaitedFootsteps::expand().

fmat::Column< 4 > KinematicJoint::sumLinkCenterOfMass (  )  const [virtual]

returns the unnormalized center of mass of this link only, not including any branches

The last element (homogeneous scale factor) is left as the total mass, so divide by this value to normalize.

Reimplemented from LinkComponent.

Definition at line 306 of file KinematicJoint.cc.

Referenced by sumCenterOfMass().

bool KinematicJoint::tryQ ( float  x  ) 

sets the current joint position (q) to x, clipped to [qmin,qmax], returning true if in range

returning false here can cause IK to invert solutions... for better stability, only return false if a joint limit is "significantly" exceeded.

Definition at line 214 of file KinematicJoint.cc.

Referenced by IKThreeLink::computeFirstLinkPrismatic(), IKThreeLink::computeFirstLinkRevolute(), IKThreeLink::computeSecondLinkPrismatic(), IKThreeLink::computeSecondLinkRevolute(), IKThreeLink::computeThirdLinkPrismatic(), IKThreeLink::computeThirdLinkRevolute(), IKCalliope::gradientSolve(), IKThreeLink::solve(), IKCalliope::solve(), XWalkMC::solveIK(), and IKGradientSolver::step().

void KinematicJoint::unsetParent ( LinkComponent link  )  [protected]

for use by ComponentsListener, work around parent being protected

Definition at line 670 of file KinematicJoint.h.

Referenced by KinematicJoint::ComponentsListener::plistCollectionEntryRemoved().

void KinematicJoint::updateBB (  )  const [protected, virtual]

recomputes boundingBoxLow and boundingBoxHigh based on collision model parameters

Reimplemented from LinkComponent.

Definition at line 624 of file KinematicJoint.cc.

void KinematicJoint::updateDepth (  )  [protected]

Definition at line 646 of file KinematicJoint.h.

Referenced by addBranch().

void KinematicJoint::updateTo (  )  [protected]

regenerates To from the a, d, alpha, and theta parameters, includes call to updateTq() as well

Definition at line 476 of file KinematicJoint.cc.

Referenced by plistValueChanged().

void KinematicJoint::updateTq (  )  [protected]

updates Tq from the q and qOffset parameters (based on current To)

Definition at line 506 of file KinematicJoint.cc.

Referenced by setQ(), tryQ(), and updateTo().

bool KinematicJoint::validQ ( float  x  )  const

returns true if x is within [qmin,qmax] (inclusive)

Definition at line 359 of file KinematicJoint.h.

Referenced by IKGradientSolver::step().

void KinematicJoint::zeroAncestorQ (  ) 

sets the joint position and its ancestors' to zero

Definition at line 244 of file KinematicJoint.cc.

void KinematicJoint::zeroChildrenQ (  ) 

sets the joint position and its childrens' to zero

Definition at line 237 of file KinematicJoint.cc.


Friends And Related Function Documentation

friend class KinematicJointLoader [friend]

Definition at line 204 of file KinematicJoint.h.

Referenced by loadXML().

friend class KinematicJointSaver [friend]

Definition at line 205 of file KinematicJoint.h.

Referenced by saveXML().


Member Data Documentation

rotation about this joint's x-axis to make the previous joint's z-axis parallel to this one (aka "Modified Denavit-Hartenberg")

Definition at line 303 of file KinematicJoint.h.

Referenced by addSelfListener(), IKThreeLink::computeSecondLinkRevolute(), IKThreeLink::computeThirdLinkRevolute(), ArmController::doStart(), initEntries(), removeSelfListener(), shallowCopy(), and updateTo().

direction sensitivity of friction, '1' in all directions means it is not direction sensitive

Definition at line 315 of file KinematicJoint.h.

Referenced by initEntries(), and shallowCopy().

Stores controller parameters for simulated input, type indicated by ControllerType entry corresponding to a ControllerInfo subclass.

Definition at line 335 of file KinematicJoint.h.

Referenced by initEntries(), and shallowCopy().

translation along the previous joint's z-axis to align its x-axis with the common normal with this joint's z-axis (aka "Modified Denavit-Hartenberg")

Definition at line 302 of file KinematicJoint.h.

Referenced by addSelfListener(), IKThreeLink::computeSecondLinkRevolute(), IKThreeLink::computeThirdLinkPrismatic(), IKThreeLink::computeThirdLinkRevolute(), initEntries(), removeSelfListener(), shallowCopy(), IKCalliope::solve(), and updateTo().

size_t KinematicJoint::depth [protected]

one plus parent's depth, or 0 if parentless

Definition at line 662 of file KinematicJoint.h.

Referenced by addBranch(), getDepth(), removeBranch(), and updateDepth().

conversion from velocity to friction force (default 0.5)

Definition at line 314 of file KinematicJoint.h.

Referenced by initEntries(), and shallowCopy().

IKSolver* KinematicJoint::ik [mutable, protected]

an instance of the IKSolver corresponding to ikSolver

Definition at line 667 of file KinematicJoint.h.

Referenced by getIK(), plistValueChanged(), and ~KinematicJoint().

specifies the name of the inverse kinematics solver to use with this appendage

Definition at line 317 of file KinematicJoint.h.

Referenced by getIK(), initEntries(), plistValueChanged(), and shallowCopy().

const char * KinematicJoint::jointTypeNames = { "revolute", "prismatic", NULL } [static]

provides human readable names for JointType_t, for loading/saving jointType (null terminated)

Definition at line 296 of file KinematicJoint.h.

Referenced by KinematicJointSaver::saveXML().

current joint position (radian rotation about z if revolute, displacement along z if prismatic)

Definition at line 664 of file KinematicJoint.h.

Referenced by getQ(), pushAncestorsQIntoArray(), pushChildrenQIntoArray(), setQ(), shallowCopy(), tryQ(), and updateTq().

translation from the previous joint's z-axis along the common normal to place this joint's origin (aka "Modified Denavit-Hartenberg")

Definition at line 304 of file KinematicJoint.h.

Referenced by addSelfListener(), IKThreeLink::computeSecondLinkRevolute(), IKThreeLink::computeThirdLinkPrismatic(), IKThreeLink::computeThirdLinkRevolute(), IKCalliope::IKCalliope(), initEntries(), removeSelfListener(), shallowCopy(), IKCalliope::solve(), and updateTo().

Stores sensor parameters for simulated input, type indicated by SensorType entry corresponding to a SensorInfo subclass.

Definition at line 319 of file KinematicJoint.h.

Referenced by initEntries(), and shallowCopy().

rotation about the previous joint's z-axis to point its x-axis parallel to the common normal with this joint's z-axis (aka "Modified Denavit-Hartenberg")

Definition at line 301 of file KinematicJoint.h.

Referenced by addSelfListener(), initEntries(), removeSelfListener(), shallowCopy(), and updateTo().

transformation to the joint's origin

Definition at line 665 of file KinematicJoint.h.

Referenced by getTo(), shallowCopy(), updateTo(), and updateTq().

transformation to origin, including final q rotation

Definition at line 666 of file KinematicJoint.h.

Referenced by getFullT(), getParentPosition(), getPosition(), getQuaternion(), getRotation(), getTq(), shallowCopy(), updateTo(), and updateTq().


The documentation for this class was generated from the following files:

Tekkotsu v5.1CVS
Generated Mon May 9 04:59:10 2016 by Doxygen 1.6.3