Main Page   Class Hierarchy   Alphabetical List   Data Structures   File List   Data Fields   Globals  

trivkins.c

Go to the documentation of this file.
00001 /*
00002   trivkins.c
00003 
00004   Trivial kinematics for 3 axis Cartesian machine
00005 
00006   Modification history:
00007 
00008   13-Mar-2000 WPS added unused attribute to ident to avoid 'defined but not used' compiler warning.
00009   11-Aug-1999  FMP added kinematicsType()
00010   9-Aug-1999  FMP added kinematicsHome(), changed naming from invK to kinI
00011   18-Dec-1997  FMP changed to PmPose
00012   16-Oct-1997  FMP created
00013   */
00014 
00015 #include "emcmot.h"             /* these decls */
00016 
00017 /* ident tag */
00018 #ifndef __GNUC__
00019 #ifndef __attribute__
00020 #define __attribute__(x)
00021 #endif
00022 #endif
00023 
00024 static char __attribute__((unused)) ident[] = "$Id: trivkins.c,v 1.4 2000/12/21 16:22:11 wshackle Exp $";
00025 
00026 int kinematicsForward(const double * joints,
00027                       EmcPose * pos,
00028                       const KINEMATICS_FORWARD_FLAGS * fflags,
00029                       KINEMATICS_INVERSE_FLAGS * iflags)
00030 {
00031   pos->tran.x = joints[0];
00032   pos->tran.y = joints[1];
00033   pos->tran.z = joints[2];
00034   pos->a = joints[3];
00035   pos->b = joints[4];
00036   pos->c = joints[5];
00037 
00038   return 0;
00039 }
00040 
00041 int kinematicsInverse(const EmcPose * pos,
00042                       double * joints,
00043                       const KINEMATICS_INVERSE_FLAGS * iflags,
00044                       KINEMATICS_FORWARD_FLAGS * fflags)
00045 {
00046   joints[0] = pos->tran.x;
00047   joints[1] = pos->tran.y;
00048   joints[2] = pos->tran.z;
00049   joints[3] = pos->a;
00050   joints[4] = pos->b;
00051   joints[5] = pos->c;
00052 
00053   return 0;
00054 }
00055 
00056 /* implemented for these kinematics as giving joints preference */
00057 int kinematicsHome(EmcPose * world,
00058                    double * joint,
00059                    KINEMATICS_FORWARD_FLAGS * fflags,
00060                    KINEMATICS_INVERSE_FLAGS * iflags)
00061 {
00062   *fflags = 0;
00063   *iflags = 0;
00064 
00065   return kinematicsForward(joint, world, fflags, iflags);
00066 }
00067 
00068 KINEMATICS_TYPE kinematicsType()
00069 {
00070   return KINEMATICS_IDENTITY;
00071 }

Generated on Sun Dec 2 15:27:44 2001 for EMC by doxygen1.2.11.1 written by Dimitri van Heesch, © 1997-2001