Skew correction/perpendicularity correction (millkins or millkins_xyz)

More
24 Dec 2024 08:19 #317268 by abdulasis12
Hi , Aciera
About 4 days .
I can only do this much (attacth file),
and the things I can't do are:
J[0], J[1], J[2]. I don't know how to transform them into the same format as trtkins (it's use joints).

int xyzacKinematicsInverse(const EmcPose * pos,
                           double *joints,
                           const KINEMATICS_INVERSE_FLAGS * iflags,
                           KINEMATICS_FORWARD_FLAGS * fflags)

Hope you advice me for next step.

Thank you,
Asis
 

File Attachment:

File Name: trtfuncs.c
File Size:15 KB
Attachments:

Please Log in or Create an account to join the conversation.

  • Aciera
  • Aciera's Avatar
  • Away
  • Administrator
  • Administrator
More
24 Dec 2024 11:01 - 24 Dec 2024 11:39 #317273 by Aciera
When I said

add the 'skew-y' pin and the corrective terms to the forward and inverse kinematic models


I meant you have to come up with a complete kinematic model for TCP where the machine coordinate system is skewed (ie no longer cartesian).
I'm afraid this is MUCH more complex than to just copy/paste a few lines from one file to another.
Basically what would be needed (I think) is a skew matrix multiplied to the beginning of the forward transformation:
linuxcnc.org/docs/html/motion/5-axis-kinematics.html
Note that adding skew to pure rotation and translation is likely going to make the derivation of the inverse kinematic more challenging.
Last edit: 24 Dec 2024 11:39 by Aciera.

Please Log in or Create an account to join the conversation.

  • Aciera
  • Aciera's Avatar
  • Away
  • Administrator
  • Administrator
More
24 Dec 2024 11:21 - 24 Dec 2024 11:22 #317274 by Aciera
As a little illustration I 'added' the skew-y to xyzbc tcp kinematics in what we might think would do the trick:

/**************************************************************************
* Copyright 2016 Rudy du Preez <rudy@asmsa.co.za>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
**************************************************************************/

/********************************************************************
* Kinematics functions (forward,inverse) for:
* 1) 5 axis mill (XYZAC)
* This mill has a tilting table (A axis) and horizontal rotary
* mounted to the table (C axis).
* 2) 5 axis mill (XYZBC)
* This mill has a tilting table (B axis) and horizontal rotary
* mounted to the table (C axis).
*
* Note: The directions of the rotational axes are the opposite of the
* conventional axis directions. See
* https://linuxcnc.org/docs/html/gcode/machining-center.html

********************************************************************/

#include "motion.h"
#include "hal.h"
#include "rtapi_math.h"
#include "rtapi_string.h"
#include "rtapi_ctype.h"

static int trtfuncs_max_joints;

// joint number assignments (-1 ==> not assigned)
static int JX = -1;
static int JY = -1;
static int JZ = -1;

static int JA = -1;
static int JB = -1;
static int JC = -1;

static int JU = -1;
static int JV = -1;
static int JW = -1;

struct haldata {
hal_float_t *x_rot_point;
hal_float_t *y_rot_point;
hal_float_t *z_rot_point;
hal_float_t *x_offset;
hal_float_t *y_offset;
hal_float_t *z_offset;
hal_float_t *tool_offset;
hal_float_t *skew_y;
} *haldata;


int trtKinematicsSetup(const int comp_id,
const char* coordinates,
kparms* kp)
{
int i,jno,res=0;
int axis_idx_for_jno[EMCMOT_MAX_JOINTS];
int rqdjoints = strlen(kp->required_coordinates);

if (rqdjoints > kp->max_joints) {
rtapi_print_msg(RTAPI_MSG_ERR,
"ERROR %s: supports %d joints, <%s> requires %d\n",
kp->kinsname,
kp->max_joints,
coordinates,
rqdjoints);
goto error;
}
trtfuncs_max_joints = kp->max_joints;

if (map_coordinates_to_jnumbers(coordinates,
kp->max_joints,
kp->allow_duplicates,
axis_idx_for_jno)) {
goto error;
}
// require all chars in reqd_coords (order doesn't matter)
for (i=0; i < rqdjoints; i++) {
char reqd_char;
reqd_char = *(kp->required_coordinates + i);
if ( !strchr(coordinates,toupper(reqd_char))
&& !strchr(coordinates,tolower(reqd_char)) ) {
rtapi_print_msg(RTAPI_MSG_ERR,
"ERROR %s:\nrequired coordinates:%s\n"
"specified coordinates:%s\n",
kp->kinsname, kp->required_coordinates, coordinates);
goto error;
}
}

// assign principal joint numbers (first found in coordinates map)
// duplicates are handled by position_to_mapped_joints()
for (jno=0; jno < EMCMOT_MAX_JOINTS; jno++) {
if (axis_idx_for_jno[jno] == 0 && JX==-1) {JX = jno;}
if (axis_idx_for_jno[jno] == 1 && JY==-1) {JY = jno;}
if (axis_idx_for_jno[jno] == 2 && JZ==-1) {JZ = jno;}
if (axis_idx_for_jno[jno] == 3 && JA==-1) {JA = jno;}
if (axis_idx_for_jno[jno] == 4 && JB==-1) {JB = jno;}
if (axis_idx_for_jno[jno] == 5 && JC==-1) {JC = jno;}
if (axis_idx_for_jno[jno] == 6 && JU==-1) {JU = jno;}
if (axis_idx_for_jno[jno] == 7 && JV==-1) {JV = jno;}
if (axis_idx_for_jno[jno] == 8 && JW==-1) {JW = jno;}
}

rtapi_print("%s coordinates=%s assigns:\n", kp->kinsname,coordinates);
for (jno=0; jno<EMCMOT_MAX_JOINTS; jno++) {
if (axis_idx_for_jno[jno] == -1) break; //fini
rtapi_print(" Joint %d ==> Axis %c\n",
jno,"XYZABCUVW"[axis_idx_for_jno[jno]]);
}

haldata = hal_malloc(sizeof(struct haldata));
if (!haldata) {goto error;}

res += hal_pin_float_newf(HAL_IN, &;(haldata->x_rot_point), comp_id,
"%s.x-rot-point",kp->halprefix);
res += hal_pin_float_newf(HAL_IN, &;(haldata->y_rot_point), comp_id,
"%s.y-rot-point",kp->halprefix);
res += hal_pin_float_newf(HAL_IN, &;(haldata->z_rot_point), comp_id,
"%s.z-rot-point",kp->halprefix);
res += hal_pin_float_newf(HAL_IN, &;(haldata->x_offset), comp_id,
"%s.x-offset",kp->halprefix);
res += hal_pin_float_newf(HAL_IN, &;(haldata->y_offset), comp_id,
"%s.y-offset",kp->halprefix);
res += hal_pin_float_newf(HAL_IN, &;(haldata->z_offset), comp_id,
"%s.z-offset",kp->halprefix);
res += hal_pin_float_newf(HAL_IN, &;(haldata->tool_offset), comp_id,
"%s.tool-offset",kp->halprefix);
res += hal_pin_float_newf(HAL_IN ,&;(haldata->skew_y) , comp_id,
"%s.skew-y" ,kp->halprefix);
if (res) {goto error;}
return 0;

error:
rtapi_print_msg(RTAPI_MSG_ERR,"trtKinematicsSetup() FAIL\n");
return -1;
} // trtKinematicsSetup()

int xyzacKinematicsForward(const double *joints,
EmcPose * pos,
const KINEMATICS_FORWARD_FLAGS * fflags,
KINEMATICS_INVERSE_FLAGS * iflags)
{
double x_rot_point = *(haldata->x_rot_point);
double y_rot_point = *(haldata->y_rot_point);
double z_rot_point = *(haldata->z_rot_point);
double dt = *(haldata->tool_offset);
double dy = *(haldata->y_offset);
double dz = *(haldata->z_offset);
double a_rad = joints[JA]*TO_RAD;
double c_rad = joints[JC]*TO_RAD;

dz = dz + dt;

pos->tran.x = + cos(c_rad) * (joints[JX] - x_rot_point)
+ sin(c_rad) * cos(a_rad) * (joints[JY] - dy - y_rot_point)
+ sin(c_rad) * sin(a_rad) * (joints[JZ] - dz - z_rot_point)
+ sin(c_rad) * dy
+ x_rot_point;

pos->tran.y = - sin(c_rad) * (joints[JX] - x_rot_point)
+ cos(c_rad) * cos(a_rad) * (joints[JY] - dy - y_rot_point)
+ cos(c_rad) * sin(a_rad) * (joints[JZ] - dz - z_rot_point)
+ cos(c_rad) * dy
+ y_rot_point;

pos->tran.z = + 0
- sin(a_rad) * (joints[JY] - dy - y_rot_point)
+ cos(a_rad) * (joints[JZ] - dz - z_rot_point)
+ dz
+ z_rot_point;

pos->a = joints[JA];
pos->c = joints[JC];

// optional letters (specify with coordinates module parameter)
pos->b = (JB != -1)? joints[JB] : 0;
pos->u = (JU != -1)? joints[JU] : 0;
pos->v = (JV != -1)? joints[JV] : 0;
pos->w = (JW != -1)? joints[JW] : 0;

return 0;
} // xyzacKinematicsForward()

int xyzacKinematicsInverse(const EmcPose * pos,
double *joints,
const KINEMATICS_INVERSE_FLAGS * iflags,
KINEMATICS_FORWARD_FLAGS * fflags)
{
double x_rot_point = *(haldata->x_rot_point);
double y_rot_point = *(haldata->y_rot_point);
double z_rot_point = *(haldata->z_rot_point);
double dy = *(haldata->y_offset);
double dz = *(haldata->z_offset);
double dt = *(haldata->tool_offset);
double a_rad = pos->a*TO_RAD;
double c_rad = pos->c*TO_RAD;

EmcPose P; // computed position

dz = dz + dt;

P.tran.x = + cos(c_rad) * (pos->tran.x - x_rot_point)
- sin(c_rad) * (pos->tran.y - y_rot_point)
+ x_rot_point;

P.tran.y = + sin(c_rad) * cos(a_rad) * (pos->tran.x - x_rot_point)
+ cos(c_rad) * cos(a_rad) * (pos->tran.y - y_rot_point)
- sin(a_rad) * (pos->tran.z - z_rot_point)
- cos(a_rad) * dy
+ sin(a_rad) * dz
+ dy
+ y_rot_point;

P.tran.z = + sin(c_rad) * sin(a_rad) * (pos->tran.x - x_rot_point)
+ cos(c_rad) * sin(a_rad) * (pos->tran.y - y_rot_point)
+ cos(a_rad) * (pos->tran.z - z_rot_point)
- sin(a_rad) * dy
- cos(a_rad) * dz
+ dz
+ z_rot_point;


P.a = pos->a;
P.c = pos->c;

// optional letters (specify with coordinates module parameter)
P.b = (JB != -1)? pos->b : 0;
P.u = (JU != -1)? pos->u : 0;
P.v = (JV != -1)? pos->v : 0;
P.w = (JW != -1)? pos->w : 0;

// update joints with support for
// multiple-joints per-coordinate letter:
// based on computed position
position_to_mapped_joints(trtfuncs_max_joints,
&P,
joints);

return 0;
} // xyzacKinematicsInverse()

int xyzbcKinematicsForward(const double *joints,
EmcPose * pos,
const KINEMATICS_FORWARD_FLAGS * fflags,
KINEMATICS_INVERSE_FLAGS * iflags)
{
// Note: 'principal' joints are used
double x_rot_point = *(haldata->x_rot_point);
double y_rot_point = *(haldata->y_rot_point);
double z_rot_point = *(haldata->z_rot_point);
double dx = *(haldata->x_offset);
double dz = *(haldata->z_offset);
double dt = *(haldata->tool_offset);
double skew_y = *(haldata->skew_y);
dz = dz + dt;
double b_rad = joints[JB]*TO_RAD;
double c_rad = joints[JC]*TO_RAD;



pos->tran.x = cos(c_rad) * cos(b_rad) * ((joints[JX] - dx - x_rot_point)+(joints[JY]- y_rot_point)*skew_y)
+ sin(c_rad) * (joints[JY] - y_rot_point)
- cos(c_rad) * sin(b_rad) * (joints[JZ] - dz - z_rot_point)
+ cos(c_rad) * dx
+ x_rot_point;

pos->tran.y = - sin(c_rad) * cos(b_rad) * ((joints[JX] - dx - x_rot_point)+(joints[JY]- y_rot_point)*skew_y)
+ cos(c_rad) * (joints[JY] - y_rot_point)
+ sin(c_rad) * sin(b_rad) * (joints[JZ] - dz - z_rot_point)
- sin(c_rad) * dx
+ y_rot_point;

pos->tran.z = sin(b_rad) * ((joints[JX] - dx - x_rot_point)+(joints[JY]- y_rot_point)*skew_y)
+ cos(b_rad) * (joints[JZ] - dz - z_rot_point)
+ dz
+ z_rot_point;

pos->b = joints[JB];
pos->c = joints[JC];

// optional letters (specify with coordinates module parameter)
pos->a = (JA != -1)? joints[JA] : 0;
pos->u = (JU != -1)? joints[JU] : 0;
pos->v = (JV != -1)? joints[JV] : 0;
pos->w = (JW != -1)? joints[JW] : 0;

return 0;
} // xyzbcKinematicsForward()

int xyzbcKinematicsInverse(const EmcPose * pos,
double *joints,
const KINEMATICS_INVERSE_FLAGS * iflags,
KINEMATICS_FORWARD_FLAGS * fflags)
{
double x_rot_point = *(haldata->x_rot_point);
double y_rot_point = *(haldata->y_rot_point);
double z_rot_point = *(haldata->z_rot_point);
double dx = *(haldata->x_offset);
double dz = *(haldata->z_offset);
double dt = *(haldata->tool_offset);
double skew_y = *(haldata->skew_y);
dz = dz + dt;
double b_rad = pos->b*TO_RAD;
double c_rad = pos->c*TO_RAD;
double dpx = -cos(b_rad)*dx - sin(b_rad)*dz + dx;
double dpz = sin(b_rad)*dx - cos(b_rad)*dz + dz;

EmcPose P; // computed position

P.tran.x = + cos(c_rad) * cos(b_rad) * ((pos->tran.x - x_rot_point) - (pos->tran.y - y_rot_point)*skew_y)
- sin(c_rad) * cos(b_rad) * (pos->tran.y - y_rot_point)
+ sin(b_rad) * (pos->tran.z - z_rot_point)
+ dpx
+ x_rot_point;

P.tran.y = + sin(c_rad) * ((pos->tran.x - x_rot_point) - (pos->tran.y - y_rot_point)*skew_y)
+ cos(c_rad) * (pos->tran.y - y_rot_point)
+ y_rot_point;

P.tran.z = - cos(c_rad) * sin(b_rad) * ((pos->tran.x - x_rot_point) - (pos->tran.y - y_rot_point)*skew_y)
+ sin(c_rad) * sin(b_rad) * (pos->tran.y - y_rot_point)
+ cos(b_rad) * (pos->tran.z - z_rot_point)
+ dpz
+ z_rot_point;

P.b = pos->b;
P.c = pos->c;

// optional letters (specify with coordinates module parameter)
P.a = (JA != -1)? pos->a : 0;
P.u = (JU != -1)? pos->u : 0;
P.v = (JV != -1)? pos->v : 0;
P.w = (JW != -1)? pos->w : 0;

// update joints with support for
// multiple-joints per-coordinate letter:
// based on computed position
position_to_mapped_joints(trtfuncs_max_joints,
&P,
joints);

return 0;
} // xyzbcKinematicsInverse()

Note that things seem to look great when we start out with no rotation of the table:
 

However when we rotate the table 90° we realize that we have actually skewed the Work Coordinate system:
 
Attachments:
Last edit: 24 Dec 2024 11:22 by Aciera.
The following user(s) said Thank You: tommylight, abdulasis12

Please Log in or Create an account to join the conversation.

More
25 Dec 2024 11:51 - 25 Dec 2024 11:58 #317343 by abdulasis12
Hi , Aciera
I see in your sim and result  its so AWSOME ....

I want to try, I create file name 
xyzbc-trt-kins.comp  and inside I put your code skew + xyzbc .
and compile it's.
but show error can't to unpack

what I'm wrong for compile file ?

FYI: I compile on new PC to test first , Because I fear this made my CNC PC broken and can't to working.

Thank you,
Asis

 
Attachments:
Last edit: 25 Dec 2024 11:58 by abdulasis12.

Please Log in or Create an account to join the conversation.

  • Aciera
  • Aciera's Avatar
  • Away
  • Administrator
  • Administrator
More
25 Dec 2024 12:24 - 25 Dec 2024 12:27 #317345 by Aciera
1. It's not a '.comp' file but '.c' (the 'comp' format is a more recently added way of creating kinematics files ) also you must not change the file name as the trt-kinematics consists of more than just 'trtfuncs.c'
2. if you want to try to compile it with halcompile just use my file to replace the standard 'trtfuncs.c' file and then do
sudo halcompile --install src/emc/kinematics/trtfuncs.c
3. If halcompile fails to compile it then you probably need to build linuxcnc locally from the repo first,  replace the 'trtfuncs.c' and recompile using 'make'
linuxcnc.org/docs/master/html/code/building-linuxcnc.html
Last edit: 25 Dec 2024 12:27 by Aciera.
The following user(s) said Thank You: abdulasis12

Please Log in or Create an account to join the conversation.

More
25 Dec 2024 15:31 - 25 Dec 2024 15:33 #317354 by abdulasis12
Thank you for fast reply

I try
sudo halcompile --install src/emc/kinematics/trtfuncs.c
I change to dir downloads and change cmd to  : sudo halcompile --install trtfuncs.c
this correct ?
then like halcompile respond but found error about code inside file, or can't use halcompile ?
I see in error red letter on  " ; "  don't know problem from its or not.

thank you,
Asis
 
 
Attachments:
Last edit: 25 Dec 2024 15:33 by abdulasis12.

Please Log in or Create an account to join the conversation.

  • Aciera
  • Aciera's Avatar
  • Away
  • Administrator
  • Administrator
More
25 Dec 2024 21:18 #317373 by Aciera
There is a problem with linebreaks in the code above from pasting. I'll post the file tomorrow. Or you can fix it in a text editor in the mean time.

Please Log in or Create an account to join the conversation.

More
26 Dec 2024 01:39 #317382 by abdulasis12
Hi Aciera,
Thank you for reply.

Update......
Now I delete  " ; "    and try  again.
result is  no error about   " ; "
but error   "syntax error in VERSION script"

Thank you,
Asis

 
Attachments:

Please Log in or Create an account to join the conversation.

  • Aciera
  • Aciera's Avatar
  • Away
  • Administrator
  • Administrator
More
26 Dec 2024 07:47 #317391 by Aciera
That's what I expected. As a workaround you can build linuxcnc on your computer:

linuxcnc.org/docs/master/html/code/building-linuxcnc.html
The following user(s) said Thank You: abdulasis12

Please Log in or Create an account to join the conversation.

More
26 Dec 2024 15:18 #317410 by abdulasis12
Hi Aciera

I use this 

$ git clone github.com/LinuxCNC/linuxcnc.git linuxcnc-source-dir
$ cd linuxcnc-source-dir/src


and I replace file trtfuncs.c  (inside skew func) on this step (correct right ?)
Then, cmd :

$ ./autogen.sh
$ ./configure --with-realtime=uspace


it's look good  and I use  cmd : $ make

it's loading and show in picture attach file  , this not complete compile right ?

Error :

/bin/bash: line 1: a2x: command not found
make: * [../docs/src/Submakefile:1001: ../docs/man/man1/5axisgui.1] Error 127


How to solve this problem ?
I think it's near succes with your help ^^"

Thank you,
Asis

 
Attachments:

Please Log in or Create an account to join the conversation.

Time to create page: 0.159 seconds
Powered by Kunena Forum