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

Tekkotsu v5.1CVS
Generated Mon May 9 04:58:42 2016 by Doxygen 1.6.3