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

robot::JFKengine Class Reference

Inheritance diagram for robot::JFKengine:

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

Collaboration graph
[legend]
List of all members.

Public Member Functions

 JFKengine ()
virtual String className () const
 identifies this class type as a JFKengine

virtual Object & clone () const
 makes a copy of this JFKengine

virtual Matrix getForwardKinematics (const KinematicChain &chain, const Vector &q) const
 get the forward kinematics transform for the given chain, with joint parameter values q

virtual Matrix getJacobian (const KinematicChain &chain, const Vector &q, bool includeOrientation=true) const
 get the Jacobian matrix for the given chain, with joint parameter values q

virtual array< base::VectorgetJointOrigins (const KinematicChain &chain, const base::Vector &q) const
 computes the forward kinematics to return the joint origin locations

virtual array< base::VectorgetLinkOrigins (const KinematicChain &chain, const base::Vector &q) const
 computes the forward kinematics to return the link origin locations

base::ExpressionMatrix getForwardKinematics (const KinematicChain &chain) const
 forms symbolic forward kinematics expression matrix

base::ExpressionMatrix getJacobian (const KinematicChain &chain, bool includeOrientation=true) const
 forms a symbolic Jacobian expression matrix

virtual bool isSameKindAs (const ReferencedObject &) const
virtual bool isSameKindAs (const Object &) const
void reference () const
bool unreference () const
const int referenceCount () const
void enableOnUnreferenceCall (bool enabled)
virtual void onUnreference () const

Protected Member Functions

 JFKengine (const JFKengine &jfke)
 copy constructor


Protected Attributes

bool forwardKinematicsCached
 ==true signals that A and T have already been calculated and are cached

array< base::ExpressionMatrixA
 array of matrices that give position and orientation with respect to previous frame

array< base::ExpressionMatrixT
 array of matrices that give position and orientation with respect to base

KinematicChain chain_AT
 cached chain used to form A and T

bool JCached
 ==true signals that J has already been calculated and is cached

KinematicChain chain_J
 cached chain used to form J

base::ExpressionMatrix J
 contains the cached 6 x n Jacobian

int _refCount
bool onUnreferenceEnabled

Detailed Description

A KinematicEvaluator that uses symbolic differentiation to compute Jacobian and forward kinematics matrix expressions.

Definition at line 42 of file JFKengine.


Constructor & Destructor Documentation

robot::JFKengine::JFKengine  ) 
 

Referenced by clone().

robot::JFKengine::JFKengine const JFKengine jfke  )  [inline, protected]
 

copy constructor

Definition at line 91 of file JFKengine.


Member Function Documentation

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

identifies this class type as a JFKengine

Implements base::Object.

Definition at line 47 of file JFKengine.

virtual Object& robot::JFKengine::clone  )  const [inline, virtual]
 

makes a copy of this JFKengine

Definition at line 48 of file JFKengine.

References JFKengine(), and NewObj.

void base::Referenced::enableOnUnreferenceCall bool  enabled  )  [inline, inherited]
 

If enabled, each call to unreference() will also call virtual method onUnreference()

Definition at line 115 of file Referenced.

References base::Referenced::onUnreferenceEnabled.

base::ExpressionMatrix robot::JFKengine::getForwardKinematics const KinematicChain chain  )  const
 

forms symbolic forward kinematics expression matrix

Parameters:
chain a description of a chain of links from which expression matrices are to be formed.
Returns:
A 4 x 4 ExpressionMatrix containing transformation matrix T for the given SerialManipulator; T represents the position and orientation of the nth link with reference to the base coordinate frame of the manipulator.
Exceptions:
std::out_of_range exception, if no joints are specified or n is greater than the number of joints in manipulator

virtual Matrix robot::JFKengine::getForwardKinematics const KinematicChain chain,
const Vector q
const [virtual]
 

get the forward kinematics transform for the given chain, with joint parameter values q

Parameters:
chain a description of a chain of links
q array of Reals; q[0] is the value of the variable for the first dof
Returns:
a 4x4 homogeneous transform matrix from the first link to the end-effector

Implements robot::KinematicEvaluator.

base::ExpressionMatrix robot::JFKengine::getJacobian const KinematicChain chain,
bool  includeOrientation = true
const
 

forms a symbolic Jacobian expression matrix

Parameters:
chain a description of a chain of joints each specified via D-H parameters for which the Jacobian is to be formed.
includeOrientation if true, J will be a 6 x n ExpressionMatrix with orientation components otherwise it will be a 3 x n ExpressionMatrix including only position components
Returns:
A [6|3] x n ExpressionMatrix containing the Jacobian for the given SerialManipulator. n is the number of joints in the given chain.
Exceptions:
std::out_of_range exception, if no joints are specified

Todo:
check & document if this is the Geometric Jacobian or Analytical Jacobian (in Jg the orientation components represent ang. vel (omega), in Ja the orientation components represent the time derivative of Euler angles - theta_dot) - I think this implementation is Jg. (omega is better for representing ang. velocity than theta_dot. On the other hand, the intergral of theta_dot, Euler angles themselves (theta) can easily represent orientation, but the intergral of omega has no physical meaning (called quasi-coordinates))

virtual Matrix robot::JFKengine::getJacobian const KinematicChain chain,
const Vector q,
bool  includeOrientation = true
const [virtual]
 

get the Jacobian matrix for the given chain, with joint parameter values q

Parameters:
chain a description of a chain of links
q array of Reals; q[0] is the value of the variable for the first dof
includeOrientation include orientation components in the Jacobian if true
Returns:
a [6|3] x N Jacobian matrix, where N=chain.dof and the number of rows will be 6 unless includeOrientation is false.

Implements robot::KinematicEvaluator.

virtual array<base::Vector> robot::JFKengine::getJointOrigins const KinematicChain chain,
const base::Vector q
const [virtual]
 

computes the forward kinematics to return the joint origin locations

Parameters:
chain a description of a chain of links
q array of Reals; q[0] is the value of the variable for the first dof
Returns:
array of [x,y,z] Vectors that give the location of each joint's origin ( size()==chain.dof() )

Implements robot::KinematicEvaluator.

virtual array<base::Vector> robot::JFKengine::getLinkOrigins const KinematicChain chain,
const base::Vector q
const [virtual]
 

computes the forward kinematics to return the link origin locations

Parameters:
chain a description of a chain of links
q array of Reals; q[0] is the value of the variable for the first dof
Returns:
array of [x,y,z] Vectors that give the location of each link's origin ( size()==chain.size() )

Implements robot::KinematicEvaluator.

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

Definition at line 47 of file Object.

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

Definition at line 52 of file ReferencedObject.

virtual void base::Referenced::onUnreference  )  const [inline, virtual, inherited]
 

Called by unreference() if enabled via enableOnUnreferenceCall(true). Typically overridden in subclasses that wish to know about unreference() calls - for example to handle manually breaking cyclic references

Reimplemented in robot::control::ControllableAdaptor::AdaptorControlInterface, and robot::control::ControllableAdaptor.

Definition at line 121 of file Referenced.

Referenced by base::Referenced::unreference().

void base::Referenced::reference  )  const [inline, inherited]
 

Increment the reference count by one, indicating that this object has another pointer which is referencing it.

Definition at line 65 of file Referenced.

References base::Referenced::_refCount.

const int base::Referenced::referenceCount  )  const [inline, inherited]
 

Return the number pointers currently referencing this object.

Definition at line 112 of file Referenced.

References base::Referenced::_refCount.

Referenced by robot::control::ControllableAdaptor::AdaptorControlInterface::onUnreference().

bool base::Referenced::unreference  )  const [inline, inherited]
 

Decrement the reference count by one, indicating that a pointer to this object is referencing it. If the refence count goes to zero, it is assumed that this object is nolonger referenced and is automatically deleted.

Definition at line 81 of file Referenced.

References base::Referenced::_refCount, Exception, base::Referenced::onUnreference(), and base::Referenced::onUnreferenceEnabled.


Member Data Documentation

int base::Referenced::_refCount [mutable, protected, inherited]
 

Definition at line 136 of file Referenced.

Referenced by base::Referenced::reference(), base::Referenced::referenceCount(), base::Referenced::Referenced(), base::Referenced::unreference(), and base::Referenced::~Referenced().

array<base::ExpressionMatrix> robot::JFKengine::A [mutable, protected]
 

array of matrices that give position and orientation with respect to previous frame

Definition at line 94 of file JFKengine.

KinematicChain robot::JFKengine::chain_AT [mutable, protected]
 

cached chain used to form A and T

Definition at line 96 of file JFKengine.

KinematicChain robot::JFKengine::chain_J [mutable, protected]
 

cached chain used to form J

Definition at line 98 of file JFKengine.

bool robot::JFKengine::forwardKinematicsCached [mutable, protected]
 

==true signals that A and T have already been calculated and are cached

Definition at line 93 of file JFKengine.

base::ExpressionMatrix robot::JFKengine::J [mutable, protected]
 

contains the cached 6 x n Jacobian

Definition at line 99 of file JFKengine.

bool robot::JFKengine::JCached [mutable, protected]
 

==true signals that J has already been calculated and is cached

Definition at line 97 of file JFKengine.

bool base::Referenced::onUnreferenceEnabled [protected, inherited]
 

Definition at line 137 of file Referenced.

Referenced by base::Referenced::enableOnUnreferenceCall(), base::Referenced::Referenced(), and base::Referenced::unreference().

array<base::ExpressionMatrix> robot::JFKengine::T [mutable, protected]
 

array of matrices that give position and orientation with respect to base

Definition at line 95 of file JFKengine.


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