Kinematics modification
17 Sep 2015 17:57 #62685
by andypugh
I am not 100% clear if just reversing the motor sense (swapping wires, or changing HAL) would have the desired effect.
Replied by andypugh on topic Kinematics modification
SIM config is gantry and also "head-head" design of BC axis (same as mine), so I could use it's kinematics module, except rotation of B-axis should be inverted somehow.
I am not 100% clear if just reversing the motor sense (swapping wires, or changing HAL) would have the desired effect.
Please Log in or Create an account to join the conversation.
17 Sep 2015 19:18 #62686
by tommy
That doesn't help ..
As it is my machine set now, jog for each axis works as it should (positive/negative direction) and also is showed correctly in DRO. Problem occurs when rotating (jog or run) B-axis, which because of pivot length offset and tool length offset triggers movement of X axis, and in this case X moves in wrong direction.
Replied by tommy on topic Kinematics modification
I am not 100% clear if just reversing the motor sense (swapping wires, or changing HAL) would have the desired effect.
That doesn't help ..
As it is my machine set now, jog for each axis works as it should (positive/negative direction) and also is showed correctly in DRO. Problem occurs when rotating (jog or run) B-axis, which because of pivot length offset and tool length offset triggers movement of X axis, and in this case X moves in wrong direction.
Please Log in or Create an account to join the conversation.
17 Sep 2015 19:23 #62687
by andypugh
Is the Y-axis correct?
Are your machine axes a right-handed coordinate set when viewed from the point of view of tool movement relative to the work? It can sometimes be a little confusing, especially with a moving-table gantry.
It is relatively easy to alter the kinematics, if you are sure that your coordinate system is correct.
Replied by andypugh on topic Kinematics modification
As it is my machine set now, jog for each axis works as it should (positive/negative direction) and also is showed correctly in DRO. Problem occurs when rotating (jog or run) B-axis, which because of pivot length offset and tool length offset triggers movement of X axis, and in this case X moves in wrong direction.
Is the Y-axis correct?
Are your machine axes a right-handed coordinate set when viewed from the point of view of tool movement relative to the work? It can sometimes be a little confusing, especially with a moving-table gantry.
It is relatively easy to alter the kinematics, if you are sure that your coordinate system is correct.
Please Log in or Create an account to join the conversation.
17 Sep 2015 20:46 - 17 Sep 2015 20:46 #62698
by tommy
No, also Y axis moves in wrong direction when for example G0 B45 C45 is executed, as in this case X and Y should move in positive direction.
I hope this image helps, directions of axis are same and C rotates around Z (clockwise), B rotates around Y (clockwise) :
Replied by tommy on topic Kinematics modification
Is the Y-axis correct?
No, also Y axis moves in wrong direction when for example G0 B45 C45 is executed, as in this case X and Y should move in positive direction.
Are your machine axes a right-handed coordinate set when viewed from the point of view of tool movement relative to the work? It can sometimes be a little confusing, especially with a moving-table gantry.
It is relatively easy to alter the kinematics, if you are sure that your coordinate system is correct.
I hope this image helps, directions of axis are same and C rotates around Z (clockwise), B rotates around Y (clockwise) :
Last edit: 17 Sep 2015 20:46 by tommy.
Please Log in or Create an account to join the conversation.
17 Sep 2015 21:12 #62701
by andypugh
Replied by andypugh on topic Kinematics modification
The picture link doesn't seem to work.
The convention is that looking from the negative end of the axis towards the positive that positive rotations are clockwise. (So, as an aside, the typical mill spindle rotates backwards in the C-axis sense, but a lathe spindle turns forwards on a front-tool lathe.)
If your machine is set up that way and the kins still doesn't work,then you need to swap a few + and - signs about.
The convention is that looking from the negative end of the axis towards the positive that positive rotations are clockwise. (So, as an aside, the typical mill spindle rotates backwards in the C-axis sense, but a lathe spindle turns forwards on a front-tool lathe.)
If your machine is set up that way and the kins still doesn't work,then you need to swap a few + and - signs about.
Please Log in or Create an account to join the conversation.
17 Sep 2015 21:25 #62703
by tommy
That is exactly how I setup my machine (B and C axis rotations)!
I hope this picture works (vertical machining center):
Replied by tommy on topic Kinematics modification
The convention is that looking from the negative end of the axis towards the positive that positive rotations are clockwise.
That is exactly how I setup my machine (B and C axis rotations)!
I hope this picture works (vertical machining center):
Please Log in or Create an account to join the conversation.
17 Sep 2015 23:13 #62716
by tommy
Solved! some experimenting with sim configuration calling modified kinematics did the trick!
Modifications were needed in this section of kinematics file:
Replied by tommy on topic Kinematics modification
If your machine is set up that way and the kins still doesn't work,then you need to swap a few + and - signs about.
Solved! some experimenting with sim configuration calling modified kinematics did the trick!
Modifications were needed in this section of kinematics file:
joints[0] = pos->tran.x - r.x;
joints[1] = pos->tran.y - r.y;
joints[2] = pos->tran.z - *(haldata->pivot_length) - r.z;
joints[3] = pos->a;
joints[4] = pos->b;
joints[5] = pos->c;
joints[6] = pos->tran.y -r.y;
joints[7] = pos->v;
joints[8] = pos->w;
Please Log in or Create an account to join the conversation.
13 Dec 2015 18:56 #66929
by tommy
Replied by tommy on topic Kinematics modification
I noticed one thing after doing modifications above, and that is if B axis is not at zero position and I switch from MDI to Manual Control following error on linear axis shows up!
I guess modifying just those lines is not enough or might be wrong entirely...
Any suggestions what else should be done to work properly, just to refresh from a start, I just wanted to reverse B axis rotation.
Here is my current kinematics:
I guess modifying just those lines is not enough or might be wrong entirely...
Any suggestions what else should be done to work properly, just to refresh from a start, I just wanted to reverse B axis rotation.
Here is my current kinematics:
/********************************************************************
* Description: my5axiskins.c
* Trivial kinematics for 3 axis Cartesian machine
*
* Derived from a work by Fred Proctor & Will Shackleford
*
* Author:
* License: GPL Version 2
* System: Linux
*
* Copyright (c) 2007 Chris Radek
*
* Last change:
********************************************************************/
#include "kinematics.h" /* these decls */
#include "posemath.h"
#include "hal.h"
#include "rtapi_math.h"
#define d2r(d) ((d)*PM_PI/180.0)
#define r2d(r) ((r)*180.0/PM_PI)
struct haldata {
hal_float_t *tool_length;
hal_float_t *pivot_length;
} *haldata;
static PmCartesian s2r(double r, double t, double p) {
PmCartesian c;
t = d2r(t), p = d2r(p);
c.x = r * sin(p) * cos(t);
c.y = r * sin(p) * sin(t);
c.z = r * cos(p);
return c;
}
int kinematicsForward(const double *joints,
EmcPose * pos,
const KINEMATICS_FORWARD_FLAGS * fflags,
KINEMATICS_INVERSE_FLAGS * iflags)
{
PmCartesian r = s2r(*(haldata->pivot_length) + joints[8], joints[5], 180.0 - joints[4]);
pos->tran.x = joints[0] + r.x;
pos->tran.y = joints[1] + r.y;
pos->tran.z = joints[2] + *(haldata->pivot_length) + r.z;
pos->a = joints[3];
pos->b = joints[4];
pos->c = joints[5];
pos->u = joints[6];
pos->v = joints[7];
pos->w = joints[8];
return 0;
}
int kinematicsInverse(const EmcPose * pos,
double *joints,
const KINEMATICS_INVERSE_FLAGS * iflags,
KINEMATICS_FORWARD_FLAGS * fflags)
{
PmCartesian r = s2r(*(haldata->pivot_length) + pos->w, pos->c, 180.0 - pos->b);
joints[0] = pos->tran.x - r.x;
joints[1] = pos->tran.y - r.y;
joints[2] = pos->tran.z - *(haldata->pivot_length) - r.z;
joints[3] = pos->a;
joints[4] = pos->b;
joints[5] = pos->c;
joints[6] = pos->tran.y - r.y;
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) {
int result;
comp_id = hal_init("my5axiskins");
if(comp_id < 0) return comp_id;
haldata = hal_malloc(sizeof(struct haldata));
result = hal_pin_float_new("my5axiskins.tooloffset.z", HAL_IN, &(haldata->tool_length), comp_id);
if(result < 0) goto error;
result = hal_pin_float_new("my5axiskins.pivot-length", HAL_IO, &(haldata->pivot_length), comp_id);
if(result < 0) goto error;
*(haldata->pivot_length) = 161.0;
hal_ready(comp_id);
return 0;
error:
hal_exit(comp_id);
return result;
}
void rtapi_app_exit(void) { hal_exit(comp_id); }
Please Log in or Create an account to join the conversation.
14 Dec 2015 12:16 #66952
by andypugh
That isn't really a surprise, because when you switch to world-mode the Y axis is suddenly a long way out of position.
Was this the situation previously? Is it acceptable to home B to zero before switching modes?
Replied by andypugh on topic Kinematics modification
I noticed one thing after doing modifications above, and that is if B axis is not at zero position and I switch from MDI to Manual Control following error on linear axis shows up!
That isn't really a surprise, because when you switch to world-mode the Y axis is suddenly a long way out of position.
Was this the situation previously? Is it acceptable to home B to zero before switching modes?
Please Log in or Create an account to join the conversation.
14 Dec 2015 12:46 #66953
by tommy
With "original" 5axis kinematics there was no problem, but but unfortunately B rotates in wrong direction.
Homing is done in Joint mode so there is no issue.
I'm not sure this is related to this problem, but when I do homing of B axis in joint mode in preview window this axis rotates in opposite direction as it is on machine. After switching to world mode, preview rotates correctly.
Replied by tommy on topic Kinematics modification
That isn't really a surprise, because when you switch to world-mode the Y axis is suddenly a long way out of position.
Was this the situation previously? Is it acceptable to home B to zero before switching modes?
With "original" 5axis kinematics there was no problem, but but unfortunately B rotates in wrong direction.
Homing is done in Joint mode so there is no issue.
I'm not sure this is related to this problem, but when I do homing of B axis in joint mode in preview window this axis rotates in opposite direction as it is on machine. After switching to world mode, preview rotates correctly.
Please Log in or Create an account to join the conversation.
Time to create page: 0.187 seconds