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

robot/KinematicEvaluator

Go to the documentation of this file.
00001 /* **-*-c++-*-**************************************************************
00002   Copyright (C)2003 David Jung <opensim@pobox.com>
00003 
00004   This program/file is free software; you can redistribute it and/or modify
00005   it under the terms of the GNU General Public License as published by
00006   the Free Software Foundation; either version 2 of the License, or
00007   (at your option) any later version.
00008   
00009   This program is distributed in the hope that it will be useful,
00010   but WITHOUT ANY WARRANTY; without even the implied warranty of
00011   MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00012   GNU General Public License for more details. (http://www.gnu.org)
00013   
00014   You should have received a copy of the GNU General Public License
00015   along with this program; if not, write to the Free Software
00016   Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
00017   
00018   $Id: KinematicEvaluator 1039 2004-02-11 20:50:52Z jungd $
00019   $Revision: 1.1 $
00020   $Date: 2004-02-11 15:50:52 -0500 (Wed, 11 Feb 2004) $
00021   $Author: jungd $
00022  
00023 ****************************************************************************/
00024 
00025 #ifndef _ROBOT_KINEMATICEVALUATOR_
00026 #define _ROBOT_KINEMATICEVALUATOR_
00027 
00028 #include <robot/robot>
00029 
00030 #include <base/ReferencedObject>
00031 
00032 #include <base/array>
00033 #include <base/Vector>
00034 #include <base/Matrix>
00035 
00036 
00037 namespace robot {
00038 
00039 class KinematicChain;  
00040   
00041   
00042 
00043 /**
00044  * An abstract interface for forward and inverse kinematic expression evaluation.
00045  *  Typically, a single instance will be created per application, but the user is free
00046  *  to create multiple instances
00047  * Implementations may cache internal state to optimize evaluations.
00048  */
00049 class KinematicEvaluator : public base::ReferencedObject
00050 {
00051 public:
00052 
00053   /// get the forward kinematics transform for the given chain, with joint parameter values q
00054   /**  
00055    *   @param  chain       a description of a chain of links 
00056    *   @param  q           array of Reals; q[0] is the value of the variable for the first dof
00057    *   @return             a 4x4 homogeneous transform matrix from the first link to the end-effector
00058    */
00059   virtual Matrix getForwardKinematics(const KinematicChain& chain, const Vector& q) const = 0;
00060   
00061   
00062   /// get the Jacobian matrix for the given chain, with joint parameter values q
00063   /**  
00064    *   @param  chain       a description of a chain of links 
00065    *   @param  q           array of Reals; q[0] is the value of the variable for the first dof
00066    *   @param  includeOrientation   include orientation components in the Jacobian if true
00067    *   @return             a [6|3] x N  Jacobian matrix, where N=chain.dof and the number of rows
00068    *                       will be 6 unless includeOrientation is false.
00069    */
00070   virtual Matrix getJacobian(const KinematicChain& chain, const Vector& q, bool includeOrientation = true) const = 0;
00071   
00072   
00073 
00074   /// computes the forward kinematics to return the joint origin locations
00075   /**  
00076    *   @param  chain       a description of a chain of links 
00077    *   @param  q           array of Reals; q[0] is the value of the variable for the first dof
00078    *   @return             array of [x,y,z] Vectors that give the location of each joint's origin ( size()==chain.dof() )
00079    */
00080   virtual array<base::Vector> getJointOrigins(const KinematicChain& chain, const base::Vector& q ) const = 0;
00081   
00082   
00083   /// computes the forward kinematics to return the link origin locations
00084   /**
00085    *   @param  chain       a description of a chain of links 
00086    *   @param  q           array of Reals; q[0] is the value of the variable for the first dof
00087    *   @return             array of [x,y,z] Vectors that give the location of each link's origin ( size()==chain.size() )
00088    */
00089   virtual array<base::Vector> getLinkOrigins(const KinematicChain& chain, const base::Vector& q ) const = 0;
00090 };
00091 
00092 } // namespace robot
00093 
00094 #endif

Generated on Thu Jul 29 15:56:37 2004 for OpenSim by doxygen 1.3.6