Hello, Andy!
I have done some braining-activity and complemented ABkins.c (that is
how I temporarily called my customized kinematics module) with
formulas for forward and inverse kinematics.
As I have gantry style machine, I have a suspicion, that current
syntax is not good - joint[1] is not mentioned in forward kinematics,
but it appears in inverse kinematics. I do not know, if that is good,
so I think, that I am going to ask about it on the mailing list.
Another thing that I changed - since the nozzle tip offset distance
for A and B axis is equal, I think that it is fully sufficient to
define only one constant offset and to use it for all the forward and
inverse kinematics calculations.
Take a look, if You have some time and please feel free to comment on that.
with best regards,
Viesturs
/********************************************************************
* Description: rotatekins.c
* Simple example kinematics for a rotary table in software
*
* Derived from a work by Fred Proctor & Will Shackleford
*
* Author: Chris Radek
* License: GPL Version 2
* System: Linux
*
* Copyright (c) 2006 All rights reserved.
*
********************************************************************/
#include "rtapi_math.h"
#include "kinematics.h" /* these decls */
const double head_offset = 200;
PmCartesian old;
int kinematicsForward(const double *joints,
EmcPose * pos,
const KINEMATICS_FORWARD_FLAGS * fflags,
KINEMATICS_INVERSE_FLAGS * iflags)
{
double xy_tan = atan2(pos->tran.y - old.y,pos->tran.x - old.x);
pos->tran.x = joints[0] - head_offset * sin(joints[5]);
pos->tran.y = joints[2] + head_offset * sin(joints[4]);
pos->tran.z = joints[3] + cos(joints[4]) * cos(joints[5]) * head_offset;
pos->a = joints[4];
pos->b = joints[5];
pos->c = joints[6];
pos->u = joints[7];
pos->v = joints[8];
pos->w = joints[9];
return 0;
}
int kinematicsInverse(const EmcPose * pos,
double *joints,
const KINEMATICS_INVERSE_FLAGS * iflags,
KINEMATICS_FORWARD_FLAGS * fflags)
{
double c_rad = pos->c*M_PI/180;
joints[0] = pos->tran.x + head_offset * sin(joints[5]);
joints[1] = pos->tran.x + head_offset * sin(joints[5]);
joints[2] = pos->tran.y - head_offset * sin(joints[4]);
joints[3] = pos->tran.z - cos(joints[4]) * cos(joints[5]) * head_offset;
joints[4] = pos->b;
joints[5] = pos->c;
joints[6] = pos->u;
joints[7] = pos->v;
joints[8] = pos->w;
return 0;
}
/* implemented for these kinematics as giving joints preference */
int kinematicsHome(EmcPose * world,
double *joint,
KINEMATICS_FORWARD_FLAGS * fflags,
KINEMATICS_INVERSE_FLAGS * iflags)
{
*fflags = 0;
*iflags = 0;
return kinematicsForward(joint, world, fflags, iflags);
}
KINEMATICS_TYPE kinematicsType()
{
return KINEMATICS_BOTH;
}
#include "rtapi.h" /* RTAPI realtime OS API */
#include "rtapi_app.h" /* RTAPI realtime module decls */
#include "hal.h"
EXPORT_SYMBOL(kinematicsType);
EXPORT_SYMBOL(kinematicsForward);
EXPORT_SYMBOL(kinematicsInverse);
MODULE_LICENSE("GPL");
int comp_id;
int rtapi_app_main(void) {
comp_id = hal_init("rotatekins");
if(comp_id > 0) {
hal_ready(comp_id);
return 0;
}
return comp_id;
}
void rtapi_app_exit(void) { hal_exit(comp_id); }
------------------------------------------------------------------------------
ThinkGeek and WIRED's GeekDad team up for the Ultimate
GeekDad Father's Day Giveaway. ONE MASSIVE PRIZE to the
lucky parental unit. See the prize list and enter to win:
http://p.sf.net/sfu/thinkgeek-promo
_______________________________________________
Emc-users mailing list
[email protected]
https://lists.sourceforge.net/lists/listinfo/emc-users