Planning to Retrofit a Mazak Integrex200Y Mill-Turn Machine

More
11 Apr 2025 16:44 #326084 by matti.juntunen
I will be back at work in a few weeks, and i can look up the manuals for it then. These older ones can be tricky to find digitally, but sometimes one gets lucky.
The following user(s) said Thank You: jochen91

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

  • Aciera
  • Aciera's Avatar
  • Away
  • Administrator
  • Administrator
More
11 Apr 2025 17:17 #326090 by Aciera
I think this is a post with a kinematic for such a lathe configuration:
forum.linuxcnc.org/show-your-stuff/53476...rical-mapping#307444
The following user(s) said Thank You: jochen91

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

More
11 Apr 2025 19:05 #326099 by jochen91
Thank you mate! Exactly what i was looking for.

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

More
11 Apr 2025 20:16 #326105 by jochen91
So i worked the whole day with resources from the forum and ChatGPT to create this Kinematic. ChatGPT checked the math forwards and inverse and it seems to check out. I try to set up vismach asap and check it for myself.
component  xyzcb_tdr_kins "Switchable kinematics for 5 axis machine with rotary table C and B and virtual Y Axis";

description
"""

This is a switchable kinematics module for a 5-axis milling configuration
using 3 cartesian linear joints (XYZ) and 2 rotary table joints (CB).

The module contains two kinematic models:

type0 (default) is a trivial XYZCB configuration with joints 0..4 mapped to
axes XYZCB respectively.

type1 is a XYZCB configuration with tool center point (TCP) compensation.

Additionally a virtual Y Axis was added for a Mazak Integrex 200Y
""";

pin out s32 dummy=0"one pin needed to satisfy halcompile requirement";

license "GPL";
author "Jochen Rohm";
;;

#include "rtapi_math.h"
#include "kinematics.h"

static struct haldata {

  // Declare hal pin pointers used for XYZCB_tdr kinematics:
  hal_float_t *tool_offset_z;
  hal_float_t *x_offset;
  hal_float_t *z_offset;
  hal_float_t *x_rot_point;
  hal_float_t *y_rot_point;
  hal_float_t *z_rot_point;
  hal_float_t *angleXX;

  //Declare hal pin pointers used for switchable kinematics
  hal_bit_t   *kinstype_is_0;
  hal_bit_t   *kinstype_is_1;
} *haldata;

static int XYZCB_tdr_setup(void) {
#define HAL_PREFIX "xyzcb_tdr_kins"
    int res=0;
    // inherit comp_id from rtapi_main()
    if (comp_id < 0) goto error;
    // set unready to allow creation of pins
    if (hal_set_unready(comp_id)) goto error;

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

    // hal pins required for XYZCB_tdr kinematics:
    res += hal_pin_float_newf(HAL_IN ,&(haldata->tool_offset_z) ,comp_id,"%s.tool-offset-z" ,HAL_PREFIX);
    res += hal_pin_float_newf(HAL_IN ,&(haldata->x_offset) ,comp_id,"%s.x-offset" ,HAL_PREFIX);
    res += hal_pin_float_newf(HAL_IN ,&(haldata->z_offset) ,comp_id,"%s.z-offset" ,HAL_PREFIX);
    res += hal_pin_float_newf(HAL_IN ,&haldata->x_rot_point ,comp_id,"%s.x-rot-point" ,HAL_PREFIX);
    res += hal_pin_float_newf(HAL_IN ,&haldata->y_rot_point ,comp_id,"%s.y-rot-point" ,HAL_PREFIX);
    res += hal_pin_float_newf(HAL_IN ,&haldata->z_rot_point ,comp_id,"%s.z-rot-point" ,HAL_PREFIX);

    // hal pins required for switchable kinematics:
    res += hal_pin_bit_new("kinstype.is-0", HAL_OUT, &(haldata->kinstype_is_0), comp_id);
    res += hal_pin_bit_new("kinstype.is-1", HAL_OUT, &(haldata->kinstype_is_1), comp_id);

    // define default kinematics at startup for switchable kinematics
    *haldata->kinstype_is_0 = 1; //default at startup -> identity kinematics
    *haldata->kinstype_is_1 = 0; //-> XYZCB TCP

    if (res) goto error;
    hal_ready(comp_id);
    rtapi_print("*** %s setup ok\n",__FILE__);
    return 0;
error:
    rtapi_print("\n!!! %s setup failed res=%d\n\n",__FILE__,res);
    return -1;
#undef HAL_PREFIX
}

EXPORT_SYMBOL(kinematicsType);
EXPORT_SYMBOL(kinematicsSwitchable);
EXPORT_SYMBOL(kinematicsSwitch);
EXPORT_SYMBOL(kinematicsInverse);
EXPORT_SYMBOL(kinematicsForward);

static hal_u32_t switchkins_type;

int kinematicsSwitchable() {return 1;}

int kinematicsSwitch(int new_switchkins_type)
{
    switchkins_type = new_switchkins_type;
    rtapi_print("kinematicsSwitch(): type=%d\n",switchkins_type);
    // create case structure for switchable kinematics
    switch (switchkins_type) {
        case 0: rtapi_print_msg(RTAPI_MSG_INFO,
                "kinematicsSwitch:TYPE0\n");
                *haldata->kinstype_is_0 = 1;
                *haldata->kinstype_is_1 = 0;
                break;
        case 1: rtapi_print_msg(RTAPI_MSG_INFO,
                "kinematicsSwitch:TYPE1\n");
                *haldata->kinstype_is_0 = 0;
                *haldata->kinstype_is_1 = 1;
                break;
       default: rtapi_print_msg(RTAPI_MSG_ERR,
                "kinematicsSwitch:BAD VALUE <%d>\n",
                switchkins_type);
                *haldata->kinstype_is_1 = 0;
                *haldata->kinstype_is_0 = 0;
                return -1; // FAIL
    }
    return 0; // ok
}

KINEMATICS_TYPE kinematicsType()
{
static bool is_setup=0;
    if (!is_setup)  XYZCB_tdr_setup();
    return KINEMATICS_BOTH; // set as required
           // Note: If kinematics are identity, using KINEMATICS_BOTH
           //       may be used in order to allow a gui to display
           //       joint values in preview prior to homing
} // kinematicsType()

int kinematicsForward(const double *j,
                      EmcPose * pos,
                      const KINEMATICS_FORWARD_FLAGS * fflags,
                      KINEMATICS_INVERSE_FLAGS * iflags)

{
    (void)fflags;
    (void)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 dz = *(haldata->z_offset);
    double dt = *(haldata->tool_offset_z);
    

    // substitutions as used in mathematical documentation
    // including degree -> radians angle conversion
    double       sc = sin(j[3]*TO_RAD);
    double       cc = cos(j[3]*TO_RAD);
    double       sb = sin(j[4]*TO_RAD);
    double       cb = cos(j[4]*TO_RAD);

    // used to be consistent with math in the documentation
    double       px = 0;
    double       py = 0;
    double       pz = 0;
    
    #define DEFAULT_ANGLE   (60.0)
    
    // define forward kinematic models using case structure for
    // for switchable kinematics
    switch (switchkins_type) {
        case 0: // ====================== IDENTITY kinematics FORWARD ====================
            double angle = *(haldata->angleXX) * PM_PI / 180.0;
            
            pos->tran.x =   j[0] + j[1] * cos(angle)
            pos->tran.y = - j[1] * sin(angle);
            pos->tran.z =   j[2];
            pos->c      =   j[3];
            pos->b      =   j[4];
            break;
        case 1: // ========================= TCP kinematics FORWARD ======================
            px          =    j[0] - x_rot_point + j[1] * cos(angle);
            py          = - (j[1] - y_rot_point) * sin(angle);
            pz          =    j[2] - z_rot_point - dt;

            pos->tran.x =   cb * (cc * px - sc * py) + sb * pz + x_rot_point;
            pos->tran.y =   sc * px + cc * py + y_rot_point;
            pos->tran.z =  -sb * (cc * px - sc * py) + cb * pz + z_rot_point + dz + dt;
            pos->c      = j[3];
            pos->b      = j[4];
            break;
    }
    // unused coordinates:
    pos->a = 0;
    pos->u = 0;
    pos->v = 0;
    pos->w = 0;

    return 0;
} // kinematicsForward()

int kinematicsInverse(const EmcPose * pos,
                      double *j,
                      const KINEMATICS_INVERSE_FLAGS * iflags,
                      KINEMATICS_FORWARD_FLAGS * fflags)
{
    (void)iflags;
    (void)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_z);

    // substitutions as used in mathematical documentation
    // including degree -> radians angle conversion
    double       sc = sin(pos->c*TO_RAD);
    double       cc = cos(pos->c*TO_RAD);
    double       sb = sin(pos->b*TO_RAD);
    double       cb = cos(pos->b*TO_RAD);

    // used to be consistent with math in the documentation
    double       qx = 0;
    double       qy = 0;
    double       qz = 0;

    switch (switchkins_type) {
        case 0:// ====================== IDENTITY kinematics INVERSE =====================
            double angle = *(haldata->angleXX) * PM_PI / 180.0;
            
            j[0] =   pos->tran.x + pos->tran.y / tan(angle);
            j[1] = - pos->tran.y / sin(angle);
            j[2] =   pos->tran.z;
            j[3] =   pos->c;
            j[4] =   pos->b;
            break;
        case 1: // ========================= TCP kinematics INVERSE ======================
            qx   = pos->tran.x - x_rot_point - dx;
            qy   = pos->tran.y - y_rot_point;
            qz   = pos->tran.z - z_rot_point - dz - dt;

            // Hier integrieren wir die virtuelle Achse (pos->tran.y) wie im Identity-Fall:
            double qx_virtual = qx + qy / tan(angle);
            double qy_virtual = -qy / sin(angle);

            j[0] = cc * (cb * qx_virtual - sb * qz) + sc * qy_virtual + cb * dx - sb * dz + x_rot_point;
            j[1] = -sc * (cb * qx_virtual - sb * qz) + cc * qy_virtual + y_rot_point;
            j[2] = sb * qx_virtual + cb * qz + sb * dx + cb * dz + z_rot_point + dt;
            j[3] = pos->c;
            j[4] = pos->b;
            break;
    }

    return 0;
} // kinematicsInverse()

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

More
13 Apr 2025 21:49 - 13 Apr 2025 23:03 #326233 by jochen91
I could need a little help. I compiled my kinematics with halcompile --install. And i used the vismach xyzbc-trt-kins (switchkins) demo. I tried to replace the original Kinematics with my custom kinematics and after some commenting out i got this error message. Would be glad for some input to guide me in the right direction.

I continued a little bit and now its this:

Note: Using POSIX realtime
motmod: dlopen: /usr/lib/linuxcnc/modules/motmod.so: undefined symbol: kinematicsSwitch
././xyzbc-trt_cmds.hal:38: waitpid failed /usr/bin/rtapi_app motmod
././xyzbc-trt_cmds.hal:38: /usr/bin/rtapi_app exited without becoming ready
././xyzbc-trt_cmds.hal:38: insmod for motmod failed, returned -1
20961
Stopping realtime threads
Unloading hal components
Note: Using POSIX realtime
Last edit: 13 Apr 2025 23:03 by jochen91.

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

  • Aciera
  • Aciera's Avatar
  • Away
  • Administrator
  • Administrator
More
14 Apr 2025 06:45 #326246 by Aciera
Not sure, halcompile output looks ok. Starting your config from a terminal may give more debug information.
$ linuxcnc

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

More
14 Apr 2025 07:47 #326253 by jochen91
This is the Error Message i got from my config:

LINUXCNC - 2.9.4
Machine configuration directory is '/home/mazak/linuxcnc/configs/sim.axis.vismach.5axis.table-rotary-tilting'
Machine configuration file is 'xyzbc-trt.ini'
check_config: Unchecked: [KINS]KINEMATICS=xyzcb_tdr_kins
Starting LinuxCNC...
linuxcnc TPMOD=tpmod HOMEMOD=homemod EMCMOT=motmod
Note: Using POSIX realtime
Found file(REL): ././xyzbc-trt_cmds.hal
motmod: dlopen: /usr/lib/linuxcnc/modules/motmod.so: undefined symbol: kinematicsSwitch
././xyzbc-trt_cmds.hal:38: waitpid failed /usr/bin/rtapi_app motmod
././xyzbc-trt_cmds.hal:38: /usr/bin/rtapi_app exited without becoming ready
././xyzbc-trt_cmds.hal:38: insmod for motmod failed, returned -1
Shutting down and cleaning up LinuxCNC...
Note: Using POSIX realtime
LinuxCNC terminated with an error. You can find more information in the log:
/home/mazak/linuxcnc_debug.txt
and
/home/mazak/linuxcnc_print.txt
as well as in the output of the shell command 'dmesg' and in the terminal


Additionally i created another bare bone config with step conf and just replaced the KINEMATICS Name in the .ini file with my kinematic file. (It starts up with a 5 axis demo kinematics file, just not with mine) I assume there is something wrong in my kinematics ?

LINUXCNC - 2.9.4
Machine configuration directory is '/home/mazak/linuxcnc/configs/my-mill'
Machine configuration file is 'my-mill.ini'
check_config: Unchecked: [KINS]KINEMATICS=xyzbc_MAZAK_kins
Starting LinuxCNC...
linuxcnc TPMOD=tpmod HOMEMOD=homemod EMCMOT=motmod
Note: Using POSIX realtime
Found file(REL): ./my-mill.hal
*** xyzbc_MAZAK_kins.comp setup ok
Found file(REL): ./custom.hal
rtapi_app: caught signal 11 - dumping core
USRMOT: ERROR: command timeout
emcMotionInit: emcTrajInit failed
note: MAXV max: 25.000 units/sec 1500.000 units/min
note: LJOG max: 25.000 units/sec 1500.000 units/min
note: LJOG default: 2.500 units/sec 150.000 units/min
note: AJOG max: 360.000 units/sec 21600.000 units/min
note: AJOG default: 36.000 units/sec 2160.000 units/min
waiting for s.joints<0>, s.kinematics_type<0>
waiting for s.joints<0>, s.kinematics_type<0>
waiting for s.joints<0>, s.kinematics_type<0>
waiting for s.joints<0>, s.kinematics_type<0>
waiting for s.joints<0>, s.kinematics_type<0>
waiting for s.joints<0>, s.kinematics_type<0>
waiting for s.joints<0>, s.kinematics_type<0>
Waiting for component 'inihal' to become ready....waiting for s.joints<0>, s.kinematics_type<0>
.......USRMOT: ERROR: command timeout
emcMotionInit: emcTrajInit failed
......waiting for s.joints<0>, s.kinematics_type<0>
..............USRMOT: ERROR: command timeout
emcMotionInit: emcTrajInit failed
...........A configuration error is preventing LinuxCNC from starting.
More information may be available when running from a terminal.
.Shutting down and cleaning up LinuxCNC...
........USRMOT: ERROR: command timeout
emcMotionInit: emcTrajInit failed
..................
<commandline>:0: milltask exited without becoming ready
Waited 3 seconds for master. giving up.
Note: Using POSIX realtime
sim_axis_hardware: not loaded
<commandline>:0: exit value: 255
<commandline>:0: rmmod failed, returned -1
Note: Using POSIX realtime
stepgen: not loaded
<commandline>:0: exit value: 255
<commandline>:0: rmmod failed, returned -1
Note: Using POSIX realtime
sim_parport: not loaded
<commandline>:0: exit value: 255
<commandline>:0: rmmod failed, returned -1
Note: Using POSIX realtime
motmod: not loaded
<commandline>:0: exit value: 255
<commandline>:0: rmmod failed, returned -1
Note: Using POSIX realtime
xyzbc_MAZAK_kins: not loaded
<commandline>:0: exit value: 255
<commandline>:0: rmmod failed, returned -1
Note: Using POSIX realtime
homemod: not loaded
<commandline>:0: exit value: 255
<commandline>:0: rmmod failed, returned -1
Note: Using POSIX realtime
tpmod: not loaded
<commandline>:0: exit value: 255
<commandline>:0: rmmod failed, returned -1
<commandline>:0: unloadrt failed
Note: Using POSIX realtime
LinuxCNC terminated with an error. You can find more information in the log:
/home/mazak/linuxcnc_debug.txt
and
/home/mazak/linuxcnc_print.txt
as well as in the output of the shell command 'dmesg' and in the terminal

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

More
14 Apr 2025 08:27 #326258 by tommylight
motmod: dlopen: /usr/lib/linuxcnc/modules/motmod.so: undefined symbol: kinematicsSwitch
Linux is case sensitive, so kinematicsswitch is not the same as kinematicsSwitch, notice the upper case S.

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

More
14 Apr 2025 08:44 - 14 Apr 2025 08:47 #326260 by jochen91
Hi Tommy,

i think i never used the lower case "s". I used the millturn.comp for this function. Here is the part from my comp file:

EXPORT_SYMBOL(kinematicsType);
EXPORT_SYMBOL(kinematicsSwitchable);
EXPORT_SYMBOL(kinematicsSwitch);
EXPORT_SYMBOL(kinematicsInverse);
EXPORT_SYMBOL(kinematicsForward);

static hal_u32_t switchkins_type;

int kinematicsSwitchable() {return 1;}

int kinematicsSwitch(int new_switchkins_type)
{
switchkins_type = new_switchkins_type;
rtapi_print("kinematicsSwitch(): type=%d\n",switchkins_type);
// create case structure for switchable kinematics
switch (switchkins_type)
{
case 0: rtapi_print_msg(RTAPI_MSG_INFO,
"kinematicsSwitch:TYPE0\n");
*haldata->kinstype_is_0 = 1;
*haldata->kinstype_is_1 = 0;
break;
case 1: rtapi_print_msg(RTAPI_MSG_INFO,
"kinematicsSwitch:TYPE1\n");
*haldata->kinstype_is_0 = 0;
*haldata->kinstype_is_1 = 1;
break;
default: rtapi_print_msg(RTAPI_MSG_ERR,
"kinematicsSwitch:BAD VALUE <%d>\n",
switchkins_type);
*haldata->kinstype_is_1 = 0;
*haldata->kinstype_is_0 = 0;
return -1; // FAIL
}
return 0; // ok
}
Last edit: 14 Apr 2025 08:47 by jochen91.

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

  • Aciera
  • Aciera's Avatar
  • Away
  • Administrator
  • Administrator
More
14 Apr 2025 10:54 - 14 Apr 2025 11:13 #326264 by Aciera
The message about 'undefined symbol: kinematicsSwitch' is actually a spurious error that will pop up whenever the kinematic fails to load.
I believe the actual problem is:
rtapi_app: caught signal 11 - dumping core

which unfortunately is a bit cryptic.

I would start out with an unmodified 'xyzcb_tdr_kins.comp' and do the modifications in small steps while frequently 'halcompiling' the file to find out when it breaks.
Last edit: 14 Apr 2025 11:13 by Aciera.

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

Time to create page: 0.143 seconds
Powered by Kunena Forum