kinecalc.h

00001 /*
00002  *  Player - One Hell of a Robot Server
00003  *  Copyright (C) 2000  
00004  *     Brian Gerkey, Kasper Stoy, Richard Vaughan, & Andrew Howard
00005  *                      
00006  *
00007  *  This program is free software; you can redistribute it and/or modify
00008  *  it under the terms of the GNU General Public License as published by
00009  *  the Free Software Foundation; either version 2 of the License, or
00010  *  (at your option) any later version.
00011  *
00012  *  This program is distributed in the hope that it will be useful,
00013  *  but WITHOUT ANY WARRANTY; without even the implied warranty of
00014  *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00015  *  GNU General Public License for more details.
00016  *
00017  *  You should have received a copy of the GNU General Public License
00018  *  along with this program; if not, write to the Free Software
00019  *  Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
00020  *
00021  */
00022 
00023 /*  Kinematics calculator class for the Pioneer arm.
00024  */
00025 
00026 #include <stdio.h>
00027 
00028 // Basic vector
00029 typedef struct
00030 {
00031   double x, y, z;
00032 } KineVector;
00033 
00034 // Struct that describes the pose of the end effector
00035 // (result of FK)
00036 typedef struct
00037 {
00038   KineVector p;
00039   KineVector n;
00040   KineVector o;
00041   KineVector a;
00042 } EndEffector;
00043 
00044 class KineCalc
00045 {
00046   public:
00047     KineCalc (void);
00048 
00049     // Kinematics functions
00050     void CalculateFK (const double fromJoints[]);
00051     bool CalculateIK (const EndEffector &fromPosition);
00052 
00053     // Accessor functions
00054     const KineVector& GetP (void) const   { return endEffector.p; }
00055     const KineVector& GetN (void) const   { return endEffector.n; }
00056     const KineVector& GetO (void) const   { return endEffector.o; }
00057     const KineVector& GetA (void) const   { return endEffector.a; }
00058     void SetP (const KineVector &newP)    { endEffector.p.x = newP.x; endEffector.p.y = newP.y; endEffector.p.z = newP.z; }
00059     void SetN (const KineVector &newN)    { endEffector.n.x = newN.x; endEffector.n.y = newN.y; endEffector.n.z = newN.z; }
00060     void SetO (const KineVector &newO)    { endEffector.o.x = newO.x; endEffector.o.y = newO.y; endEffector.o.z = newO.z; }
00061     void SetA (const KineVector &newA)    { endEffector.a.x = newA.x; endEffector.a.y = newA.y; endEffector.a.z = newA.z; }
00062     void SetP (double newPX, double newPY, double newPZ);
00063     void SetN (double newNX, double newNY, double newNZ);
00064     void SetO (double newOX, double newOY, double newOZ);
00065     void SetA (double newAX, double newAY, double newAZ);
00066 
00067     double GetTheta (unsigned int index);
00068     const double* GetThetas (void) const  { return joints; }
00069     void SetTheta (unsigned int index, double newVal);
00070     void SetLinkLengths (double newLink1, double newLink2, double newLink3, double newLink4, double newLink5);
00071     void SetOffset (unsigned int joint, double newOffset);
00072     void SetJointRange (unsigned int joint, double min, double max);
00073 
00074     // Use this to calculate N
00075     KineVector CalculateN (const EndEffector &pose);
00076     KineVector Normalise (const KineVector &vector);
00077 
00078   protected:
00079     void CalcTheta4and5 (double angles[], const EndEffector &fromPosition);
00080     int ChooseSolution (const EndEffector &fromPosition, const double solutions[][5]);
00081     double CalcSolutionError (const double solution[], const EndEffector &fromPosition);
00082     EndEffector CalcFKForJoints (const double angles[]);
00083     bool SolutionInRange (const double angles[]);
00084 
00085     void PrintEndEffector (const EndEffector &endEffector);
00086 
00087     // The 4 vectors that describe the position and orientation of the
00088     // end effector.
00089     // These should be computed when performing forward kinematics
00090     // and are used to provide data to the client.
00091     EndEffector endEffector;
00092 
00093     // The 5 joint angles.
00094     // These are computed when performing inverse kinematics and
00095     // are used for positioning the arm.
00096     double joints[5];
00097     // Joint offsets, as calibrated and supplied in the config file
00098     double jointOffsets[5];
00099     // Joint ranges
00100     double jointMin[5];
00101     double jointMax[5];
00102 
00103     // The link lengths are required for any of the kinematics to be useful.
00104     // I can't see them changing, but just in case better to have the ability to
00105     // specify them in the config file.
00106     double link1, link2, link3, link4, link5;
00107 };

Last updated 12 September 2005 21:38:45