Tekkotsu Homepage
Demos
Overview
Downloads
Dev. Resources
Reference
Credits

IKSolver.h

Go to the documentation of this file.
00001 //-*-c++-*-
00002 #ifndef INCLUDED_IKSolver_h
00003 #define INCLUDED_IKSolver_h
00004 
00005 #include "Motion/KinematicJoint.h"
00006 #include "Shared/fmat.h"
00007 #include "Shared/FamilyFactory.h"
00008 #include <stdexcept>
00009 
00010 //! Provides an abstract interface to inverse kinematic solvers
00011 class IKSolver {
00012 public:
00013   //! Indicates the type of progress made by the step() family
00014   enum StepResult_t {
00015     SUCCESS, //!< goal was reached
00016     PROGRESS, //!< step moved closer
00017     LIMITS, //!< not able to progress due to joint limits
00018     RANGE //!< not able to progress due to target out of reach
00019   };
00020   
00021   struct Point;
00022   struct Rotation;
00023   
00024   //! abstract base class for position information
00025   /*! Subclasses may allow for some freedom in solutions -- not every solution has to be to a single point! */
00026   struct Position {
00027     virtual ~Position() {}
00028     //! return vector pointing in direction of decreasing error at point @a p and rotation @a r
00029     virtual void computeErrorGradient(const Point& p, const Rotation& r, fmat::Column<3>& de) const = 0;
00030   };
00031   //! abstract base class for orientation information
00032   /*! Subclasses may allow for some freedom in solutions -- not every solution has to be to a single rotation! */
00033   struct Orientation {
00034     virtual ~Orientation() {}
00035     //! return quaternion indicating direction of decreasing error at point @a p and rotation @a r
00036     virtual void computeErrorGradient(const Point& p, const Rotation& r, fmat::Quaternion& de) const = 0;
00037   };
00038   
00039   //! Points allow 0 freedoms
00040   struct Point : public Position, public fmat::Column<3> {
00041     Point() : Position(), fmat::Column<3>(0.f), x(data[0]), y(data[1]), z(data[2]) {}
00042     Point(float xi, float yi, float zi) : Position(), fmat::Column<3>(fmat::pack(xi,yi,zi)), x(data[0]), y(data[1]), z(data[2]) {}
00043     Point(const Point& p) : Position(), fmat::Column<3>(p), x(data[0]), y(data[1]), z(data[2]) {}
00044     Point(const fmat::Column<3>& p) : Position(), fmat::Column<3>(p), x(data[0]), y(data[1]), z(data[2]) {}
00045     Point(const fmat::SubVector<3,const fmat::fmatReal>& p) : Position(), fmat::Column<3>(p), x(data[0]), y(data[1]), z(data[2]) {}
00046     Point& operator=(const Point& p) { fmat::Column<3>::operator=(p); return *this; }
00047     using fmat::Column<3>::operator=;
00048     virtual void computeErrorGradient(const Point& p, const Rotation&, fmat::Column<3>& de) const {
00049       de[0]=x-p.x; de[1]=y-p.y; de[2]=z-p.z;
00050     }
00051     fmat::fmatReal& x;
00052     fmat::fmatReal& y;
00053     fmat::fmatReal& z;
00054   };
00055   
00056   //! Lines allow 1 freedom, slide along line
00057   struct Line : public Position {
00058     //virtual void computeErrorGradient(const Point& p, const Rotation&, fmat::Column<3>& de) const {}
00059     float nx;
00060     float ny;
00061     float nz;
00062     float dx;
00063     float dy;
00064     float dz;
00065   };
00066   
00067   //! Planes allow 2 freedoms, move in plane
00068   struct Plane : public Position {
00069     virtual void computeErrorGradient(const Point& p, const Rotation&, fmat::Column<3>& de) const {
00070       float t = -( p.x*x + p.y*y + p.z*z + d );
00071       de[0] = t*x;
00072       de[1] = t*y;
00073       de[2] = t*z;
00074     }
00075     float x;
00076     float y;
00077     float z;
00078     float d;
00079   };
00080   
00081   //! Rotation allow 0 freedoms (here specified as a quaternion)
00082   struct Rotation : public Orientation, public fmat::Quaternion {
00083     Rotation() : Orientation(), fmat::Quaternion() {}
00084     Rotation(float wi, float xi, float yi, float zi) : Orientation(), fmat::Quaternion(wi,xi,yi,zi) {}
00085     Rotation(const fmat::Quaternion& q) : Orientation(), fmat::Quaternion(q) {}
00086     
00087     virtual void computeErrorGradient(const Point&, const Rotation& r, fmat::Quaternion& de) const {
00088       de = fmat::crossProduct(r,*this);
00089     }
00090   };
00091   
00092   //! Parallel allows 1 freedom (roll along z vector)
00093   struct Parallel : public Orientation {
00094     Parallel(float xi, float yi, float zi) : Orientation(), x(xi), y(yi), z(zi) {}
00095     virtual void computeErrorGradient(const Point&, const Rotation& r, fmat::Quaternion& de) const {
00096       //std::cout << "Current rotation: " << r << std::endl;
00097       fmat::Column<3> clv = r * Point(0,0,1);
00098       fmat::Column<3> res = fmat::crossProduct(clv,fmat::SubVector<3,const float>(&x));
00099       float ang = std::asin(res.norm());
00100       de = fmat::Quaternion::fromAxisAngle(res,ang);
00101       //std::cout << "Error rotation: " << de << std::endl;
00102     }
00103     float x; // the "target" unit z vector, in base coordinates
00104     float y;
00105     float z;
00106   };
00107   
00108   //! Cone allows 1-2 freedoms (roll, trade off pitch vs. yaw)
00109   struct Cone : public Orientation {
00110     float lx;
00111     float ly;
00112     float lz;
00113     float tx;
00114     float ty;
00115     float tz;
00116     float a;
00117   };
00118   
00119   //! destructor
00120   virtual ~IKSolver() {}
00121   
00122   //! Solve to get an 'effector' point @a pEff (relative to link following @a j) to a solution of @a pTgt (or at least a local minimum)
00123   /*! @param pEff The point on the effector that should be brought to the target.
00124     Typically [0,0,0] if the effector is GripperFrame.
00125     @param j The kinematic joint at the end of the chain (e.g., GripperFrame)
00126     @param pTgt The Position constraint that pEff should satisfy, i.e., the target location
00127   */
00128   virtual bool solve(const Point& pEff, KinematicJoint& j, const Position& pTgt) const {
00129     Rotation curOri(j.getQuaternion());
00130     return solve(pEff,curOri,j,pTgt,1,curOri,0);
00131   }
00132   //! Solve to get an 'effector' orientation @a oriEff (relative to link following @a j) to a solution of @a oriTgt (or at least a local minimum)
00133   /*! @param oriEff Rotation of the effector's reference frame; used to align some effector axis with the target's Orientation axes. For example, if @a oriTgt is a Parallel constraint, the effector will be free to rotate about the target's z-axis. If we want the effector to rotate about its y-axis, we use @a oriEff to rotate the effector y-axis to the target's z-axis.
00134     @param j The kinematic joint at the end of the chain (e.g., GripperFrame)
00135     @param oriTgt The Orientation constraint that pEff should satisfy at the target location
00136   */
00137   virtual bool solve(const Rotation& oriEff, KinematicJoint& j, const Orientation& oriTgt) const {
00138     Point curPos(j.getPosition());
00139     return solve(curPos,oriEff,j,curPos,0,oriTgt,1);
00140   }
00141   
00142   //! Solve to get an 'effector' (@a pEff, @a oriEff, relative to link following @a j) to a solution of @a pTgt, @a oriTgt (or at least a local minimum)
00143   /*! @param pEff The point on the effector that should be brought to the target.
00144     Typically [0,0,0] if the effector is GripperFrame.
00145     @param oriEff Rotation of the effector's reference frame; used to align some effector axis with the target's Orientation axes. For example, if @a oriTgt is a Parallel constraint, the effector will be free to rotate about the target's z-axis. If we want the effector to rotate about its y-axis, we use @a oriEff to rotate the effector y-axis to the target's z-axis.
00146     @param j The kinematic joint at the end of the chain (e.g., GripperFrame)
00147     @param pTgt The Position constraint that pEff should satisfy, i.e., the target location
00148     @param oriTgt The Orientation constraint that pEff should satisfy at the target location
00149     @param posPri,oriPri Relative priorities (weightings) of position and orientation solutions in case they are mutually exclusive
00150   */
00151   virtual bool solve(const Point& pEff, const Rotation& oriEff, KinematicJoint& j, const Position& pTgt, float posPri, const Orientation& oriTgt, float oriPri) const=0;
00152   
00153   //! Move an 'effector' point @a pEff (relative to link following @a j) towards a solution of @a pTgt (or at least a local minimum)
00154   /*! @a pDist specifies the maximum distance to move */
00155   virtual StepResult_t step(const Point& pEff, KinematicJoint& j, const Position& pTgt, float pDist) const {
00156     Rotation curOri(j.getQuaternion());
00157     return step(pEff,curOri,j,pTgt,1,pDist,curOri,0,0);
00158   }
00159   //! Move an 'effector' orientation @a oriEff (relative to link following @a j) towards a solution of @a oriTgt (or at least a local minimum)
00160   /*! @a oriDist specifies the maximum distance to move in radians */
00161   virtual StepResult_t step(const Rotation& oriEff, KinematicJoint& j, const Orientation& oriTgt, float oriDist) const {
00162     Point curPos(j.getPosition());
00163     return step(curPos,oriEff,j,curPos,0,0,oriTgt,1,oriDist);
00164   }
00165   
00166   //! Move an 'effector' (@a pEff, @a oriEff, relative to link following @a j) towards a solution of @a pTgt, @a oriTgt (or at least a local minimum)
00167   /*! @a pDist and @a oriDist specifies the maximum distance to move towards each solution;
00168     *  @a posPri and @a oriPri specify relative weighting of each solution in case they are mutually exclusive */
00169   virtual StepResult_t step(const Point& pEff, const Rotation& oriEff, KinematicJoint& j, const Position& pTgt, float pDist, float posPri, const Orientation& oriTgt, float oriDist, float oriPri) const=0;
00170   
00171   //! shorthand for type registry to allow dynamically instantiating IKSolvers based on the name found in configuration files
00172   typedef FamilyFactory<IKSolver,std::string,Factory0Arg<IKSolver> > registry_t;
00173   static registry_t& getRegistry() { static registry_t registry; return registry; }
00174 };
00175 
00176 /*! @file
00177  * @brief Defines IKSolver interface, which provides an abstract interface to inverse kinematic solvers
00178  * @author Ethan Tira-Thompson (ejt) (Creator)
00179  */
00180 
00181 #endif

Tekkotsu v5.1CVS
Generated Sat May 4 06:32:50 2013 by Doxygen 1.6.3