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

robot::NumericKinematicEvaluator Class Reference

Inheritance diagram for robot::NumericKinematicEvaluator:

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

Collaboration graph
[legend]
List of all members.

Public Member Functions

 NumericKinematicEvaluator ()
virtual String className () const
virtual Object & clone () const
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

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

 NumericKinematicEvaluator (const NumericKinematicEvaluator &nke)
 copy constructor


Protected Attributes

int _refCount
bool onUnreferenceEnabled

Detailed Description

A KinematicEvaluator that uses vector cross products to evaluate the Jacobian and forward kinematics matrices numerically

Definition at line 41 of file NumericKinematicEvaluator.


Constructor & Destructor Documentation

robot::NumericKinematicEvaluator::NumericKinematicEvaluator  ) 
 

Referenced by clone().

robot::NumericKinematicEvaluator::NumericKinematicEvaluator const NumericKinematicEvaluator nke  )  [inline, protected]
 

copy constructor

Definition at line 58 of file NumericKinematicEvaluator.


Member Function Documentation

virtual String robot::NumericKinematicEvaluator::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 46 of file NumericKinematicEvaluator.

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

Definition at line 47 of file NumericKinematicEvaluator.

References NewObj, and NumericKinematicEvaluator().

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.

virtual Matrix robot::NumericKinematicEvaluator::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.

virtual Matrix robot::NumericKinematicEvaluator::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::NumericKinematicEvaluator::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::NumericKinematicEvaluator::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().

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().


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