Программная коррекция кривизны портала

Обсуждение установки, настройки и использования LinuxCNC. Вопросы по Gкоду.
Аватара пользователя
MX_Master
Мастер
Сообщения: 7465
Зарегистрирован: 27 июн 2015, 19:45
Репутация: 3088
Настоящее имя: Михаил
Откуда: Алматы
Контактная информация:

Re: Программная коррекция кривизны портала

Сообщение MX_Master »

Запилил новую версию. Коррекция для нескольких моторов на одной оси теперь работает как положено. Можно юзать коррекцию в отрицательном диапазоне. Можно указать начало диапазона коррекции с помощью доп. параметра offset. Названия HAL пинов коррекции теперь имеют более логичный вид.

Функция коррекции плоскости (к примеру, Z от XY) - в процессе.

Пример - взаимная коррекция осей XY:
  • На оси X - два мотора.
  • Шаг коррекции для X = 50 мм, для Y = 100 мм.
  • Кол-во точек коррекции для X = 11, для Y = 5.
  • Начало диапазона коррекции для X = -250 мм, для Y = 100 мм.

Код: Выделить всё

loadrt relkins coordinates=XYZX adjust=X,Y from=Y,X steps=11,5 step_size=50,100 offset=-250,100

Код: Выделить всё

# настройка точек коррекции для оси X от позиции оси Y
setp relkins.adjX.Y-250 0.0
setp relkins.adjX.Y-200 0.01
setp relkins.adjX.Y-150 0.02
setp relkins.adjX.Y-100 0.03
setp relkins.adjX.Y-50  0.04
setp relkins.adjX.Y0    0.05
setp relkins.adjX.Y50   0.04
setp relkins.adjX.Y100  0.03
setp relkins.adjX.Y150  0.02
setp relkins.adjX.Y200  0.01
setp relkins.adjX.Y250  0.0

Код: Выделить всё

# настройка точек коррекции для оси Y от позиции оси X
setp relkins.adjY.X100 0.0
setp relkins.adjY.X200 0.1
setp relkins.adjY.X300 0.2
setp relkins.adjY.X400 0.1
setp relkins.adjY.X500 0.0
Аватара пользователя
MX_Master
Мастер
Сообщения: 7465
Зарегистрирован: 27 июн 2015, 19:45
Репутация: 3088
Настоящее имя: Михаил
Откуда: Алматы
Контактная информация:

Re: Программная коррекция кривизны портала

Сообщение MX_Master »

Последние новости:
  1. Переименовал модуль кинематики из relkins в krivkins :)
  2. Добавил в модуль коррекцию плоскостей/поверхностей.
https://github.com/MX-Master/linuxcnc/b ... krivkins.c

Думаю, про первый пункт, пояснять ничё не надо. Остановимся на втором. Первым примером коррекции плоскости является коррекция высоты (Z) от положения XY. Это самый частый случай. Но никто не запрещает корректировать и другие плоскости и не плоскости - X от YZ, Y от XZ, A от XZ и т.д.

И сразу небольшой пример. Будем корректировать Z от XY c шагом 100 мм. Допустим, в станочной точке X100 Y100 у нас на столе шишка в 0.1 мм. Тогда HAL файл будет выглядеть примерно так:

Код: Выделить всё

loadrt krivkins coordinates=XYZ adjust=Z from=XY steps=3 step_size=100 offset=0

Код: Выделить всё

setp krivkins.adjZ.X100_Y100 0.1
Quark
Кандидат
Сообщения: 49
Зарегистрирован: 25 май 2016, 13:55
Репутация: 11
Контактная информация:

Re: Программная коррекция кривизны портала

Сообщение Quark »

А можно это использовать для коррекции Z при гравировки печатных плат? Подхватывает этот способ на лету изменения setp krivkins.adjZ ?
Аватара пользователя
MX_Master
Мастер
Сообщения: 7465
Зарегистрирован: 27 июн 2015, 19:45
Репутация: 3088
Настоящее имя: Михаил
Откуда: Алматы
Контактная информация:

Re: Программная коррекция кривизны портала

Сообщение MX_Master »

Да, всё на лету.
Quark
Кандидат
Сообщения: 49
Зарегистрирован: 25 май 2016, 13:55
Репутация: 11
Контактная информация:

Re: Программная коррекция кривизны портала

Сообщение Quark »

А можно тогда сделать чтобы таблица корректировки была в отдельном файле? Хотя бы как опция. Или подскажи как извне таблицу передать в систему.
Аватара пользователя
Serg
Мастер
Сообщения: 21923
Зарегистрирован: 17 апр 2012, 14:58
Репутация: 5181
Заслуга: c781c134843e0c1a3de9
Настоящее имя: Сергей
Откуда: Москва
Контактная информация:

Re: Программная коррекция кривизны портала

Сообщение Serg »

Её уже можно размещать в отдельном файле... :)
Я не Христос, рыбу не раздаю, но могу научить, как сделать удочку...
Аватара пользователя
MX_Master
Мастер
Сообщения: 7465
Зарегистрирован: 27 июн 2015, 19:45
Репутация: 3088
Настоящее имя: Михаил
Откуда: Алматы
Контактная информация:

Re: Программная коррекция кривизны портала

Сообщение MX_Master »

Quark писал(а):А можно тогда сделать чтобы таблица корректировки была в отдельном файле? Хотя бы как опция. Или подскажи как извне таблицу передать в систему.
Таблицу можно положить в отдельный HAL файл и в INI файле его указать. Но кол-во точек корректировки и прочие настройки останутся в основном HAL файле.

Код: Выделить всё

[HAL]
# основные настройки HAL
HALFILE = stanok.hal
# таблица корректировки
HALFILE = Z_adj_table.hal
Аватара пользователя
Serg
Мастер
Сообщения: 21923
Зарегистрирован: 17 апр 2012, 14:58
Репутация: 5181
Заслуга: c781c134843e0c1a3de9
Настоящее имя: Сергей
Откуда: Москва
Контактная информация:

Re: Программная коррекция кривизны портала

Сообщение Serg »

MX_Master писал(а):Но кол-во точек корректировки и прочие настройки останутся в основном HAL файле.
А кто мешает и их перенести в файл с точками?
Я не Христос, рыбу не раздаю, но могу научить, как сделать удочку...
Аватара пользователя
MX_Master
Мастер
Сообщения: 7465
Зарегистрирован: 27 июн 2015, 19:45
Репутация: 3088
Настоящее имя: Михаил
Откуда: Алматы
Контактная информация:

Re: Программная коррекция кривизны портала

Сообщение MX_Master »

UAVpilot писал(а):А кто мешает и их перенести в файл с точками?
Вощем-то, да, можно. И в INI файле поставить этот HAL файл первым.
a321
Мастер
Сообщения: 563
Зарегистрирован: 03 дек 2016, 00:30
Репутация: 65
Контактная информация:

Re: Программная коррекция кривизны портала

Сообщение a321 »

MX_Master писал(а):Последние новости:
  1. Переименовал модуль кинематики из relkins в krivkins :)
  2. Добавил в модуль коррекцию плоскостей/поверхностей.
https://github.com/MX-Master/linuxcnc/b ... krivkins.c

По этой ссылке, как и по аналогичным в этой теме, ничего не скачивается, ошибка 404.
nkp
Мастер
Сообщения: 8340
Зарегистрирован: 28 ноя 2011, 00:25
Репутация: 1589
Контактная информация:

Re: Программная коррекция кривизны портала

Сообщение nkp »

a321 писал(а):По этой ссылке, как и по аналогичным в этой теме, ничего не скачивается, ошибка 404.
напиши автору в личку,так он точно увидит...
старая редакция фала:

Код: Выделить всё

/********************************************************************
* Description: relkins.c
*
*   Trivial kinematics for 3 axis Cartesian machine
*   with position adjustment
*
* Author: Mikhail Vydrenko (mikhail@vydrenko.ru)
********************************************************************/

#define FOR_MACHINEKIT 0

#include "motion.h"
#include "kinematics.h"     /* these decls */
#include "rtapi.h"          /* RTAPI realtime OS API */
#include "rtapi_app.h"      /* RTAPI realtime module decls */
#include "hal.h"

#if FOR_MACHINEKIT
#include <stdlib.h>
#else
#include "rtapi_math.h"
#include "rtapi_string.h"
#include <linux/kernel.h>
#endif




#define ADJ_STEPS_MAX 255

#define PRINT_ERROR(MSG) \
    rtapi_print_msg(RTAPI_MSG_ERR, "%s: "MSG"\n", comp_name)

#define PRINT_ERROR_AND_RETURN(MSG,RETVAL) \
    { PRINT_ERROR(MSG); return RETVAL; }

#if FOR_MACHINEKIT
#define VTVERSION VTKINEMATICS_VERSION1
#endif

MODULE_AUTHOR("Mikhail Vydrenko");
MODULE_DESCRIPTION("Trivial kinematics with position adjustment");
MODULE_LICENSE("GPL");

typedef struct
{
    hal_bit_t enable;
    hal_u32_t joint_id[EMCMOT_MAX_JOINTS];
    hal_u32_t joint_cnt;

    hal_bit_t adj_enable;
    hal_s32_t adj_from[2];
    hal_s32_t adj_offset;
    hal_u32_t adj_steps;
    hal_u32_t adj_step_size;
} axis_t;




#if FOR_MACHINEKIT
static int vtable_id;
#endif
static int comp_id;
static const char *comp_name = "relkins";
static const char *axis_name0 = "xyzabcuvw";
static const char *axis_name1 = "XYZABCUVW";
static KINEMATICS_TYPE ktype = -1;
static axis_t * _axis;
static hal_float_t ** _adj[EMCMOT_MAX_JOINTS];

static char *coordinates = "XYZABCUVW";
RTAPI_MP_STRING(coordinates, "Existing Axes");
static char *kinstype = "1"; // use KINEMATICS_IDENTITY
RTAPI_MP_STRING(kinstype, "Kinematics Type (Identity,Both)");
static char *adjust = "";
RTAPI_MP_STRING(adjust, "adjust axis name/ID, comma separated");
static char *from = "";
RTAPI_MP_STRING(from, "related axes names/IDs, comma separated");
static char *offset = "";
RTAPI_MP_STRING(offset, "adjust from position offset in units, comma separated");
static char *steps = "";
RTAPI_MP_STRING(steps, "steps count, comma separated");
static char *step_size = "";
RTAPI_MP_STRING(step_size, "step size in units, comma separated");




#define adj_offset_f            ((hal_float_t)_axis[axis].adj_offset)
#define adj_steps_f             ((hal_float_t)_axis[axis].adj_steps)
#define adj_steps_i             _axis[axis].adj_steps
#define adj_step_size_f         ((hal_float_t)_axis[axis].adj_step_size)

int
kinematicsForward
(
    const double *                      joints,
    EmcPose *                           pos,
    const KINEMATICS_FORWARD_FLAGS *    fflags,
    KINEMATICS_INVERSE_FLAGS *          iflags
)
{
    static hal_bit_t r0_valid, r1_valid, c0_valid, c1_valid;
    static int32_t step_0, step_1, axis, r0, r1, c0, c1;
    static double adj, adj_0, adj_1, rm, cm, r0c0_adj, r0c1_adj, r1c0_adj, r1c1_adj;
    double* axis_pos[EMCMOT_MAX_JOINTS] =
    {
        &(pos->tran.x), &(pos->tran.y), &(pos->tran.z),
        &(pos->a), &(pos->b), &(pos->c),
        &(pos->u), &(pos->v), &(pos->w)
    };

#define joint_num               _axis[axis].joint_id[0]
#define joint_pos               joints[joint_num]

#define rel_axis0               _axis[axis].adj_from[0]
#define rel_joint0_num          _axis[rel_axis0].joint_id[0] // use only 1st joint of related axis
#define rel_joint0_pos          joints[rel_joint0_num]
#define rel_joint0_offset_pos   (rel_joint0_pos - adj_offset_f)

#define rel_axis1               _axis[axis].adj_from[1]
#define rel_joint1_num          _axis[rel_axis1].joint_id[0]
#define rel_joint1_pos          joints[rel_joint1_num]
#define rel_joint1_offset_pos   (rel_joint1_pos - adj_offset_f)

    for ( axis = EMCMOT_MAX_JOINTS; axis--; )
    {
        if ( !_axis[axis].enable ) continue;

        *axis_pos[axis] = joint_pos;

        if ( !_axis[axis].adj_enable ) continue;

        // line adjustment
        if ( rel_axis1 < 0 )
        {
            step_0 = (int32_t) (rel_joint0_offset_pos / adj_step_size_f);
            step_1 = step_0 + 1;

            adj_0 = step_0 >= 0 && step_0 < adj_steps_i ? *_adj[axis][step_0] : 0.0;
            adj_1 = step_1 >= 0 && step_1 < adj_steps_i ? *_adj[axis][step_1] : 0.0;

            adj = adj_0
                + (adj_1 - adj_0)
                * (rel_joint0_offset_pos - adj_step_size_f * ((hal_float_t)step_0))
                / adj_step_size_f;

            *axis_pos[axis] += adj;
        }
        // plane adjustment
        else
        {
            // get row data
            r0 = (int32_t) (rel_joint0_offset_pos / adj_step_size_f);
            r1 = r0 + 1;
            r0_valid = r0 >= 0 && r0 < adj_steps_i;
            r1_valid = r1 >= 0 && r1 < adj_steps_i;

            // get column data
            c0 = (int32_t) (rel_joint1_offset_pos / adj_step_size_f);
            c1 = c0 + 1;
            c0_valid = c0 >= 0 && c0 < adj_steps_i;
            c1_valid = c1 >= 0 && c1 < adj_steps_i;

            // no adjustment if current position is out of adjustment zone
//            if ( !r0_valid && !r1_valid && !c0_valid && !c1_valid ) continue;

            // get values of 4 adjustment cells around current position
            r0c0_adj = r0_valid && c0_valid ? *_adj[axis][r0*_axis[axis].adj_steps + c0] : 0.0;
            r0c1_adj = r0_valid && c1_valid ? *_adj[axis][r0*_axis[axis].adj_steps + c1] : 0.0;
            r1c0_adj = r1_valid && c0_valid ? *_adj[axis][r1*_axis[axis].adj_steps + c0] : 0.0;
            r1c1_adj = r1_valid && c1_valid ? *_adj[axis][r1*_axis[axis].adj_steps + c1] : 0.0;

            // calculate row/column multipliers
            rm = (rel_joint0_offset_pos - ((double)r0) * adj_step_size_f) / adj_step_size_f;
            cm = (rel_joint1_offset_pos - ((double)c0) * adj_step_size_f) / adj_step_size_f;
            if ( rm < 0.000001 ) rm = 0.0;
            else if ( rm > 0.999999 ) rm = 1.0;
            if ( cm < 0.000001 ) cm = 0.0;
            else if ( cm > 0.999999 ) cm = 1.0;

            adj_0 = (((r1c1_adj - r1c0_adj) * rm) - ((r0c1_adj - r0c0_adj) * rm)) * cm;
            adj_1 = (((r1c1_adj - r0c1_adj) * cm) - ((r1c0_adj - r0c0_adj) * cm)) * rm;

            adj = (adj_0 + adj_1) / 2;

            *axis_pos[axis] += adj;
        }
    }

#undef joint_num
#undef joint_pos

#undef rel_axis0
#undef rel_joint0_num
#undef rel_joint0_pos
#undef rel_joint0_offset_pos

#undef rel_axis1
#undef rel_joint1_num
#undef rel_joint1_pos
#undef rel_joint1_offset_pos

    return 0;
}

int
kinematicsInverse
(
    const EmcPose *                     pos,
    double *                            joints,
    const KINEMATICS_INVERSE_FLAGS *    iflags,
    KINEMATICS_FORWARD_FLAGS *          fflags
)
{
    static hal_bit_t r0_valid, r1_valid, c0_valid, c1_valid;
    static int32_t step_0, step_1, axis, n, r0, r1, c0, c1;
    static double adj, adj_0, adj_1, rm, cm, r0c0_adj, r0c1_adj, r1c0_adj, r1c1_adj;
    const double* axis_pos[EMCMOT_MAX_JOINTS] =
    {
        &(pos->tran.x), &(pos->tran.y), &(pos->tran.z),
        &(pos->a), &(pos->b), &(pos->c),
        &(pos->u), &(pos->v), &(pos->w)
    };

#define joint_num               _axis[axis].joint_id[n]
#define joint_pos               joints[joint_num]

#define rel_axis0               _axis[axis].adj_from[0]
#define rel_axis0_pos           *axis_pos[rel_axis0]
#define rel_axis0_offset_pos    (rel_axis0_pos - adj_offset_f)

#define rel_axis1               _axis[axis].adj_from[1]
#define rel_axis1_pos           *axis_pos[rel_axis1]
#define rel_axis1_offset_pos    (rel_axis1_pos - adj_offset_f)

    for ( axis = EMCMOT_MAX_JOINTS; axis--; )
    {
        if ( !_axis[axis].enable ) continue;

        for ( n = _axis[axis].joint_cnt; n--; )
        {
            joint_pos = *axis_pos[axis];

            if ( !_axis[axis].adj_enable ) continue;

            // line adjustment
            if ( rel_axis1 < 0 )
            {
                step_0 = (int32_t) (rel_axis0_offset_pos / adj_step_size_f);
                step_1 = step_0 + 1;

                adj_0 = step_0 >= 0 && step_0 < adj_steps_i ? *_adj[axis][step_0] : 0.0;
                adj_1 = step_1 >= 0 && step_1 < adj_steps_i ? *_adj[axis][step_1] : 0.0;

                adj = adj_0
                    + (adj_1 - adj_0)
                    * (rel_axis0_offset_pos - adj_step_size_f * ((hal_float_t)step_0))
                    / adj_step_size_f;

                joint_pos -= adj;
            }
            // plane adjustment
            else
            {
                // get row data
                r0 = (int32_t) (rel_axis0_offset_pos / adj_step_size_f);
                r1 = r0 + 1;
                r0_valid = r0 >= 0 && r0 < adj_steps_i;
                r1_valid = r1 >= 0 && r1 < adj_steps_i;

                // get column data
                c0 = (int32_t) (rel_axis1_offset_pos / adj_step_size_f);
                c1 = c0 + 1;
                c0_valid = c0 >= 0 && c0 < adj_steps_i;
                c1_valid = c1 >= 0 && c1 < adj_steps_i;

                // no adjustment if current position is out of adjustment zone
//                if ( !r0_valid && !r1_valid && !c0_valid && !c1_valid ) continue;

                // get values of 4 adjustment cells around current position
                r0c0_adj = r0_valid && c0_valid ? *_adj[axis][r0*_axis[axis].adj_steps + c0] : 0.0;
                r0c1_adj = r0_valid && c1_valid ? *_adj[axis][r0*_axis[axis].adj_steps + c1] : 0.0;
                r1c0_adj = r1_valid && c0_valid ? *_adj[axis][r1*_axis[axis].adj_steps + c0] : 0.0;
                r1c1_adj = r1_valid && c1_valid ? *_adj[axis][r1*_axis[axis].adj_steps + c1] : 0.0;

                // calculate row/column multipliers
                rm = (rel_axis0_offset_pos - ((double)r0) * adj_step_size_f) / adj_step_size_f;
                cm = (rel_axis1_offset_pos - ((double)c0) * adj_step_size_f) / adj_step_size_f;
                if ( rm < 0.000001 ) rm = 0.0;
                else if ( rm > 0.999999 ) rm = 1.0;
                if ( cm < 0.000001 ) cm = 0.0;
                else if ( cm > 0.999999 ) cm = 1.0;

                adj_0 = (((r1c1_adj - r1c0_adj) * rm) - ((r0c1_adj - r0c0_adj) * rm)) * cm;
                adj_1 = (((r1c1_adj - r0c1_adj) * cm) - ((r1c0_adj - r0c0_adj) * cm)) * rm;

                adj = (adj_0 + adj_1) / 2;

                joint_pos -= adj;
            }
        }
    }

#undef joint_num
#undef joint_pos

#undef rel_axis0
#undef rel_axis0_pos
#undef rel_axis0_offset_pos

#undef rel_axis1
#undef rel_axis1_pos
#undef rel_axis1_offset_pos

    return 0;
}

#undef adj_offset_f
#undef adj_steps_f
#undef adj_steps_i
#undef adj_step_size_f

/* 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 ktype;
}

#if FOR_MACHINEKIT
static vtkins_t vtk =
{
    .kinematicsForward = kinematicsForward,
    .kinematicsInverse  = kinematicsInverse,
//  .kinematicsHome = kinematicsHome,
    .kinematicsType = kinematicsType
};
#else
EXPORT_SYMBOL(kinematicsType);
EXPORT_SYMBOL(kinematicsForward);
EXPORT_SYMBOL(kinematicsInverse);
#endif




static int axis_name_to_id(char axis_char)
{
    int axis;

    for ( axis = EMCMOT_MAX_JOINTS; axis--; )
    {
        if ( axis_char == axis_name0[axis] || axis_char == axis_name1[axis] ) return axis;
    }

    return -1;
}




int rtapi_app_main(void)
{
    int32_t retval, axis, joint, id, axis_list[EMCMOT_MAX_JOINTS] = {-1};
    int32_t r, c;
    char *data, *token;

    // component init
    comp_id = hal_init(comp_name);
    if ( comp_id < 0 ) return -1;

#if FOR_MACHINEKIT
    // export kinematics table
    vtable_id = hal_export_vtable(comp_name, VTVERSION, &vtk, comp_id);
    if ( vtable_id < 0 )
    {
        rtapi_print_msg(RTAPI_MSG_ERR,
            "%s: ERROR: hal_export_vtable(%s,%d,%p) failed: %d\n",
            comp_name, comp_name, VTVERSION, &vtk, vtable_id);
        return -1;
    }
#endif

    // shared memory allocation
    _axis = hal_malloc(EMCMOT_MAX_JOINTS * sizeof(axis_t));
    if ( !_axis ) PRINT_ERROR_AND_RETURN("hal_malloc() failed",-1);

    // parse `kinstype`
    switch (*kinstype)
    {
      case 'b': case 'B': ktype = KINEMATICS_BOTH;         break;
      case 'f': case 'F': ktype = KINEMATICS_FORWARD_ONLY; break;
      case 'i': case 'I': ktype = KINEMATICS_INVERSE_ONLY; break;
      case '1': default:  ktype = KINEMATICS_IDENTITY;
    }

    // parse `coordinates`
    for ( joint = 0, token = coordinates; *token && joint < EMCMOT_MAX_JOINTS; token++ )
    {
        if ( *token == ' ' || *token == '\t' || *token == ',' ) continue;

        axis = axis_name_to_id(*token);
        if ( axis >= 0 && axis < EMCMOT_MAX_JOINTS )
        {
            _axis[axis].enable = 1;
            _axis[axis].joint_id[ _axis[axis].joint_cnt++ ] = joint;
        }

        joint++;
    }

    // parse `adjust`
    for ( id = 0, token = adjust; *token && id < EMCMOT_MAX_JOINTS; token++ )
    {
        if ( *token == ' ' || *token == '\t' || *token == ',' ) continue;

        axis = axis_name_to_id(*token);
        if ( axis >= 0 && axis < EMCMOT_MAX_JOINTS && _axis[axis].enable )
        {
            _axis[axis].adj_enable = 1;
            axis_list[id] = axis;
        }

        id++;
    }

    // parse `from`
#if FOR_MACHINEKIT
    for ( id = 0, data = from; (token = strtok(data, ",")) != NULL; id++ )
    {
        if ( data != NULL ) data = NULL;
#else
    for ( id = 0, data = from; (token = strsep(&data, ",")) != NULL; id++ )
    {
#endif
        axis = axis_list[id];
        if ( axis < 0 || !_axis[axis].adj_enable ) break;

        _axis[axis].adj_from[0] = axis_name_to_id(token[0]);
        _axis[axis].adj_from[1] = axis_name_to_id(token[1]);

        if ( _axis[axis].adj_from[0] < 0 ) _axis[axis].adj_enable = 0;
    }

    // parse `steps`
#if FOR_MACHINEKIT
    for ( id = 0, data = steps; (token = strtok(data, ",")) != NULL; id++ )
    {
        if ( data != NULL ) data = NULL;
#else
    for ( id = 0, data = steps; (token = strsep(&data, ",")) != NULL; id++ )
    {
#endif
        axis = axis_list[id];
        if ( axis < 0 || !_axis[axis].adj_enable ) break;

#if FOR_MACHINEKIT
        _axis[axis].adj_steps = (hal_u32_t) strtoul(token, NULL, 10);
#else
        retval = kstrtou32(token, 10, (uint32_t*) &_axis[axis].adj_steps);
#endif
        if ( !_axis[axis].adj_steps ) _axis[axis].adj_enable = 0;
        if ( _axis[axis].adj_steps > ADJ_STEPS_MAX ) _axis[axis].adj_steps = ADJ_STEPS_MAX;
    }

    // parse `step_size`
#if FOR_MACHINEKIT
    for ( id = 0, data = step_size; (token = strtok(data, ",")) != NULL; id++ )
    {
        if ( data != NULL ) data = NULL;
#else
    for ( id = 0, data = step_size; (token = strsep(&data, ",")) != NULL; id++ )
    {
#endif
        axis = axis_list[id];
        if ( axis < 0 || !_axis[axis].adj_enable ) break;

#if FOR_MACHINEKIT
        _axis[axis].adj_step_size = (hal_u32_t) strtoul(token, NULL, 10);
#else
        retval = kstrtou32(token, 10, (uint32_t*) &_axis[axis].adj_step_size);
#endif
        if ( !_axis[axis].adj_step_size ) _axis[axis].adj_enable = 0;
    }

    // parse `offset`
#if FOR_MACHINEKIT
    for ( id = 0, data = offset; (token = strtok(data, ",")) != NULL; id++ )
    {
        if ( data != NULL ) data = NULL;
#else
    for ( id = 0, data = offset; (token = strsep(&data, ",")) != NULL; id++ )
    {
#endif
        axis = axis_list[id];
        if ( axis < 0 || !_axis[axis].adj_enable ) break;

#if FOR_MACHINEKIT
        _axis[axis].adj_offset = (hal_s32_t) strtol(token, NULL, 10);
#else
        retval = kstrtos32(token, 10, (int32_t*) &_axis[axis].adj_offset);
#endif
    }

    // mem alloc, export pins
    for ( axis = EMCMOT_MAX_JOINTS; axis--; )
    {
        if ( !_axis[axis].adj_enable ) continue;

        // plane adjustment
        if ( _axis[axis].adj_from[1] >= 0 )
        {
            // mem alloc
            _adj[axis] = hal_malloc(_axis[axis].adj_steps * _axis[axis].adj_steps * sizeof(hal_float_t*));
            if ( !_adj[axis] ) PRINT_ERROR_AND_RETURN("hal_malloc() failed",-1);

            // HAL pins export
            for ( r = 0, retval = 0; r < _axis[axis].adj_steps; r++ )
            {
                for ( c = 0; c < _axis[axis].adj_steps; c++ )
                {
                    retval += hal_pin_float_newf( HAL_IN,
                        &(_adj[axis][r * _axis[axis].adj_steps + c]), comp_id,
                        "%s.adj%c.%c%d_%c%d", comp_name, axis_name1[axis],
                        axis_name1[ _axis[axis].adj_from[0] ],
                        (r * _axis[axis].adj_step_size + _axis[axis].adj_offset),
                        axis_name1[ _axis[axis].adj_from[1] ],
                        (c * _axis[axis].adj_step_size + _axis[axis].adj_offset)
                    );
                }
            }
            if ( retval ) PRINT_ERROR_AND_RETURN("HAL plane step pins export failed",-1);
        }
        // line adjustment
        else
        {
            // mem alloc
            _adj[axis] = hal_malloc(_axis[axis].adj_steps * sizeof(hal_float_t*));
            if ( !_adj[axis] ) PRINT_ERROR_AND_RETURN("hal_malloc() failed",-1);

            // HAL pins export
            for ( r = 0, retval = 0; r < _axis[axis].adj_steps; r++ )
            {
                retval += hal_pin_float_newf( HAL_IN, &_adj[axis][r], comp_id,
                    "%s.adj%c.%c%d", comp_name, axis_name1[axis],
                    axis_name1[ _axis[axis].adj_from[0] ],
                    (r * _axis[axis].adj_step_size + _axis[axis].adj_offset) );
            }
            if ( retval ) PRINT_ERROR_AND_RETURN("HAL line step pins export failed",-1);
        }
    }

    hal_ready(comp_id);
    return 0;
}




void rtapi_app_exit(void)
{
#if FOR_MACHINEKIT
    hal_remove_vtable(vtable_id);
#endif
    hal_exit(comp_id);
}
Аватара пользователя
MX_Master
Мастер
Сообщения: 7465
Зарегистрирован: 27 июн 2015, 19:45
Репутация: 3088
Настоящее имя: Михаил
Откуда: Алматы
Контактная информация:

Re: Программная коррекция кривизны портала

Сообщение MX_Master »

a321 писал(а):По этой ссылке, как и по аналогичным в этой теме, ничего не скачивается, ошибка 404.
https://github.cnc32.ru/MX_Master/linux ... krivkins.c
a321
Мастер
Сообщения: 563
Зарегистрирован: 03 дек 2016, 00:30
Репутация: 65
Контактная информация:

Re: Программная коррекция кривизны портала

Сообщение a321 »

MX_Master писал(а):Да, всё на лету.
Как именно делать это на лету? Где вводить команду уже при запущенном и захомленном LinuxCNC?
a321
Мастер
Сообщения: 563
Зарегистрирован: 03 дек 2016, 00:30
Репутация: 65
Контактная информация:

Re: Программная коррекция кривизны портала

Сообщение a321 »

Не взлетает.

Что сделано -
скачаны модули relkins + krivkins, оба скомпилированы -

Код: Выделить всё

 halcompile --install relkins.c 
make KBUILD_EXTRA_SYMBOLS=/usr/realtime-3.4-9-rtai-686-pae/modules/linuxcnc/Module.symvers -C /usr/src/linux-headers-3.4-9-rtai-686-pae SUBDIRS=`pwd` CC=gcc V=0 modules
make[1]: Entering directory `/usr/src/linux-headers-3.4-9-rtai-686-pae'
  CC [M]  /tmp/tmpLjgR0Z/relkins.o
  Building modules, stage 2.
  MODPOST 1 modules
  CC      /tmp/tmpLjgR0Z/relkins.mod.o
  LD [M]  /tmp/tmpLjgR0Z/relkins.ko
make[1]: Leaving directory `/usr/src/linux-headers-3.4-9-rtai-686-pae'
cp relkins.ko /usr/realtime-3.4-9-rtai-686-pae/modules/linuxcnc/
root@cnc:/home/wau# reboot

Broadcast message from root@cnc (pts/0) (Mon Apr  6 17:58:14 2020):

The system is going down for reboot NOW!
Перезагрузка.

В ini станка первым поставлен кастом.hal. в котором (попеременно пробовал) -

Код: Выделить всё


loadrt krivkins coordinates=XY adjust=X from=Y steps=2 step_size=1000 offset=-550

# настройка точек коррекции для оси X от позиции оси Y (0 и 30 - демопараметры)
setp krivkins.adjX.Y-500 0
setp krivkins.adjX.Y500 30


#loadrt relkins coordinates=XY adjust=X from=Y steps=2 step_size=1000 offset=-550

# настройка точек коррекции для оси X от позиции оси Y
#setp relkins.adjX.Y-500 0
#setp relkins.adjX.Y500 30
В главном hal закомментировал -
#loadrt trivkins

Проверочные мероприятия - если в кастом-хал все закомментить LCNC не загружается по причине незагрузки loadrt кинематика. Если раскомментировать loadrt - нормально загружается и работает = модуль relkins & krivkins нормально скомпилированы, системе известны, ею находятся и загружаются. Но стоит только раскрыть хоть один параметр setp кинематика = вылет с ошибкой =

./custom.hal:4: parameter or pin 'krivkins.adjX.Y-500' not found

LinuxCNC 2.7.15.

Вопрос - ЧЯДНТ?
Вложения
log.ngc
(56.95 КБ) 280 скачиваний
nkp
Мастер
Сообщения: 8340
Зарегистрирован: 28 ноя 2011, 00:25
Репутация: 1589
Контактная информация:

Re: Программная коррекция кривизны портала

Сообщение nkp »

halcompile --install relkins.c
это rip версия ?
я про отсутствие sudo
a321
Мастер
Сообщения: 563
Зарегистрирован: 03 дек 2016, 00:30
Репутация: 65
Контактная информация:

Re: Программная коррекция кривизны портала

Сообщение a321 »

сперва было sudo su (о чем говорило root@cnc:/home/wau# ). Иначе бы не скомпилировалось. Оно скомпилировалось и считывается, оба модуля, каждый отдельно пробовал.
Сперва я собрал модуль krivkins и попытался запустить его. Не взлетело. Подумалось - за краткостью описания мог измениться синтаксис задания параметров коррекции (в примере был приведен сразу трехосевой) и тогда попробовал предыдущую версию relkins - результат одинаковый.
nkp
Мастер
Сообщения: 8340
Зарегистрирован: 28 ноя 2011, 00:25
Репутация: 1589
Контактная информация:

Re: Программная коррекция кривизны портала

Сообщение nkp »

a321 писал(а): Иначе бы не скомпилировалось.
halcompile --install relkins.c
такой командой компилируется для rip версии(емс собранный из исходников)
потому и спросил
Аватара пользователя
MX_Master
Мастер
Сообщения: 7465
Зарегистрирован: 27 июн 2015, 19:45
Репутация: 3088
Настоящее имя: Михаил
Откуда: Алматы
Контактная информация:

Re: Программная коррекция кривизны портала

Сообщение MX_Master »

a321 писал(а):./custom.hal:4: parameter or pin 'krivkins.adjX.Y-500' not found

Код: Выделить всё

halcmd show pin krivkins
a321
Мастер
Сообщения: 563
Зарегистрирован: 03 дек 2016, 00:30
Репутация: 65
Контактная информация:

Re: Программная коррекция кривизны портала

Сообщение a321 »

halcmd show pin krivkins
RTAPI: ERROR: could not open shared memory (No such file or directory)
HAL: ERROR: could not initialize RTAPI
halcmd: hal_init() failed: -22
NOTE: 'rtapi' kernel module must be loaded
a321
Мастер
Сообщения: 563
Зарегистрирован: 03 дек 2016, 00:30
Репутация: 65
Контактная информация:

Re: Программная коррекция кривизны портала

Сообщение a321 »

хуже того, я прошляпил дописку -
kins=krivkins tp=tp

С ней не запускается, вылетает с ошибкой -
Error: could not insert module /usr/realtime-3.4-9-rtai-686-pae/modules/linuxcnc/motmod.ko: Unknown symbol in module
./custom.hal:2: exit value: 1
./custom.hal:2: insmod for motmod failed, returned -1
See the output of 'dmesg' for more information.
8431
Stopping realtime threads
Unloading hal components

Код: Выделить всё

ls -la /usr/realtime-3.4-9-rtai-686-pae/modules/linuxcnc/
итого 21508
drwxr-xr-x 2 root root   20480 Апр  6 17:57 .
drwxr-xr-x 3 root root    4096 Май 24  2019 ..
-rw-r--r-- 1 root root   94448 Янв  3 03:20 5axiskins.ko
-rw-r--r-- 1 root root   95960 Янв  3 03:20 abs.ko
-rw-r--r-- 1 root root   95978 Янв  3 03:20 abs_s32.ko
-rw-r--r-- 1 root root   94673 Янв  3 03:20 and2.ko
-rw-r--r-- 1 root root  107524 Янв  3 03:20 at_pid.ko
-rw-r--r-- 1 root root  101677 Янв  3 03:20 axistest.ko
-rw-r--r-- 1 root root   94522 Янв  3 03:20 bin2gray.ko
-rw-r--r-- 1 root root  103144 Янв  3 03:20 biquad.ko
-rw-r--r-- 1 root root   96451 Янв  3 03:20 bitslice.ko
-rw-r--r-- 1 root root   96901 Янв  3 03:20 bitwise.ko
-rw-r--r-- 1 root root  106366 Янв  3 03:20 bldc_hall3.ko
-rw-r--r-- 1 root root  149462 Янв  3 03:20 bldc.ko
-rw-r--r-- 1 root root   96230 Янв  3 03:20 blend.ko
-rw-r--r-- 1 root root  118024 Янв  3 03:20 boss_plc.ko
-rw-r--r-- 1 root root  108019 Янв  3 03:20 carousel.ko
-rw-r--r-- 1 root root   92328 Янв  3 03:20 charge_pump.ko
-rw-r--r-- 1 root root   95940 Янв  3 03:20 clarke2.ko
-rw-r--r-- 1 root root   96554 Янв  3 03:20 clarke3.ko
-rw-r--r-- 1 root root   97515 Янв  3 03:20 clarkeinv.ko
-rw-r--r-- 1 root root  607286 Янв  3 03:20 classicladder_rt.ko
-rw-r--r-- 1 root root   96911 Янв  3 03:20 comp.ko
-rw-r--r-- 1 root root   94391 Янв  3 03:20 constant.ko
-rw-r--r-- 1 root root   94593 Янв  3 03:20 conv_bit_s32.ko
-rw-r--r-- 1 root root   94581 Янв  3 03:20 conv_bit_u32.ko
-rw-r--r-- 1 root root   96553 Янв  3 03:20 conv_float_s32.ko
-rw-r--r-- 1 root root   96413 Янв  3 03:20 conv_float_u32.ko
-rw-r--r-- 1 root root   96182 Янв  3 03:20 conv_s32_bit.ko
-rw-r--r-- 1 root root   94715 Янв  3 03:20 conv_s32_float.ko
-rw-r--r-- 1 root root   96303 Янв  3 03:20 conv_s32_u32.ko
-rw-r--r-- 1 root root   96082 Янв  3 03:20 conv_u32_bit.ko
-rw-r--r-- 1 root root   94703 Янв  3 03:20 conv_u32_float.ko
-rw-r--r-- 1 root root   96303 Янв  3 03:20 conv_u32_s32.ko
-rw-r--r-- 1 root root   95784 Янв  3 03:20 counter.ko
-rw-r--r-- 1 root root   94412 Янв  3 03:20 ddt.ko
-rw-r--r-- 1 root root   95973 Янв  3 03:20 deadzone.ko
-rw-r--r-- 1 root root   96273 Янв  3 03:20 debounce.ko
-rw-r--r-- 1 root root   97974 Янв  3 03:20 edge.ko
-rw-r--r-- 1 root root  103472 Янв  3 03:20 encoder.ko
-rw-r--r-- 1 root root   98524 Янв  3 03:20 encoder_ratio.ko
-rw-r--r-- 1 root root   97451 Янв  3 03:20 estop_latch.ko
-rw-r--r-- 1 root root   96308 Янв  3 03:20 feedcomp.ko
-rw-r--r-- 1 root root   95555 Янв  3 03:20 flipflop.ko
-rw-r--r-- 1 root root   96027 Янв  3 03:20 gantrykins.ko
-rw-r--r-- 1 root root  102363 Янв  3 03:20 gantry.ko
-rw-r--r-- 1 root root   99400 Янв  3 03:20 gearchange.ko
-rw-r--r-- 1 root root  310961 Янв  3 03:20 genhexkins.ko
-rw-r--r-- 1 root root  416045 Янв  3 03:20 genserkins.ko
-rw-r--r-- 1 root root   94570 Янв  3 03:20 gray2bin.ko
-rw-r--r-- 1 root root  109910 Янв  3 03:20 hal_ax5214h.ko
-rw-r--r-- 1 root root   98560 Янв  3 03:20 hal_evoreg.ko
-rw-r--r-- 1 root root  197758 Янв  3 03:20 hal_gm.ko
-rw-r--r-- 1 root root  275879 Янв  3 03:20 hal_lib.ko
-rw-r--r-- 1 root root  134542 Янв  3 03:20 hal_motenc.ko
-rw-r--r-- 1 root root  149928 Янв  3 03:20 hal_parport.ko
-rw-r--r-- 1 root root  224477 Янв  3 03:20 hal_ppmc.ko
-rw-r--r-- 1 root root   90523 Янв  3 03:20 hal_skeleton.ko
-rw-r--r-- 1 root root   91397 Янв  3 03:20 hal_speaker.ko
-rw-r--r-- 1 root root  132631 Янв  3 03:20 hal_stg.ko
-rw-r--r-- 1 root root   95600 Янв  3 03:20 hal_tiro.ko
-rw-r--r-- 1 root root  134904 Янв  3 03:20 hal_vti.ko
-rw-r--r-- 1 root root  105091 Янв  3 03:20 histobins.ko
-rw-r--r-- 1 root root  229885 Янв  3 03:20 hm2_7i43.ko
-rw-r--r-- 1 root root  231109 Янв  3 03:20 hm2_7i90.ko
-rw-r--r-- 1 root root  205702 Янв  3 03:20 hm2_pci.ko
-rw-r--r-- 1 root root  187916 Янв  3 03:20 hm2_test.ko
-rw-r--r-- 1 root root 1884913 Янв  3 03:20 hostmot2.ko
-rw-r--r-- 1 root root   95206 Янв  3 03:20 hypot.ko
-rw-r--r-- 1 root root   97259 Янв  3 03:20 ilowpass.ko
-rw-r--r-- 1 root root   96313 Янв  3 03:20 integ.ko
-rw-r--r-- 1 root root   95764 Янв  3 03:20 invert.ko
-rw-r--r-- 1 root root  100094 Янв  3 03:20 joyhandle.ko
-rw-r--r-- 1 root root   97277 Янв  3 03:20 knob2float.ko
-rw-r--r-- 1 root root  107036 Апр  6 12:34 krivkins.ko
-rw-r--r-- 1 root root  103514 Янв  3 03:20 latencybins.ko
-rw-r--r-- 1 root root  112380 Янв  3 03:20 lcd.ko
-rw-r--r-- 1 root root   95525 Янв  3 03:20 limit1.ko
-rw-r--r-- 1 root root   97492 Янв  3 03:20 limit2.ko
-rw-r--r-- 1 root root  105978 Янв  3 03:20 limit3.ko
-rw-r--r-- 1 root root   99408 Янв  3 03:20 lincurve.ko
-rw-r--r-- 1 root root   97741 Янв  3 03:20 logic.ko
-rw-r--r-- 1 root root   97098 Янв  3 03:20 lowpass.ko
-rw-r--r-- 1 root root  101109 Янв  3 03:20 lut5.ko
-rw-r--r-- 1 root root   95777 Янв  3 03:20 maj3.ko
-rw-r--r-- 1 root root   99808 Янв  3 03:20 match8.ko
-rw-r--r-- 1 root root   98915 Янв  3 03:20 matrix_kb.ko
-rw-r--r-- 1 root root   95265 Янв  3 03:20 maxkins.ko
-rw-r--r-- 1 root root  105221 Янв  3 03:20 mesa_7i65.ko
-rw-r--r-- 1 root root  102112 Янв  3 03:20 mesa_uart.ko
-rw-r--r-- 1 root root   97967 Янв  3 03:20 message.ko
-rw-r--r-- 1 root root   95457 Янв  3 03:20 minmax.ko
-rw-r--r-- 1 root root   94615 Янв  3 03:20 modmath.ko
-rw-r--r-- 1 root root   54860 Янв  3 03:20 Module.symvers
-rw-r--r-- 1 root root 1324319 Янв  3 03:20 motmod.ko
-rw-r--r-- 1 root root  125618 Янв  3 03:20 moveoff.ko
-rw-r--r-- 1 root root   94441 Янв  3 03:20 mult2.ko
-rw-r--r-- 1 root root  104312 Янв  3 03:20 multiclick.ko
-rw-r--r-- 1 root root   96919 Янв  3 03:20 multiswitch.ko
-rw-r--r-- 1 root root  100345 Янв  3 03:20 mux16.ko
-rw-r--r-- 1 root root   95313 Янв  3 03:20 mux2.ko
-rw-r--r-- 1 root root   96892 Янв  3 03:20 mux4.ko
-rw-r--r-- 1 root root   98921 Янв  3 03:20 mux8.ko
-rw-r--r-- 1 root root  101733 Янв  3 03:20 mux_generic.ko
-rw-r--r-- 1 root root   96587 Янв  3 03:20 near.ko
-rw-r--r-- 1 root root   94062 Янв  3 03:20 not.ko
-rw-r--r-- 1 root root   96238 Янв  3 03:20 offset.ko
-rw-r--r-- 1 root root   99231 Янв  3 03:20 oneshot.ko
-rw-r--r-- 1 root root  123346 Янв  3 03:20 opto_ac5.ko
-rw-r--r-- 1 root root   94663 Янв  3 03:20 or2.ko
-rw-r--r-- 1 root root   99385 Янв  3 03:20 orient.ko
-rw-r--r-- 1 root root  108753 Янв  3 03:20 pci_8255.ko
-rw-r--r-- 1 root root  103822 Янв  3 03:20 pcl720.ko
-rw-r--r-- 1 root root  105042 Янв  3 03:20 pid.ko
-rw-r--r-- 1 root root  192734 Янв  3 03:20 pluto_servo.ko
-rw-r--r-- 1 root root  189965 Янв  3 03:20 pluto_step.ko
-rw-r--r-- 1 root root  317273 Янв  3 03:20 pumakins.ko
-rw-r--r-- 1 root root   99099 Янв  3 03:20 pwmgen.ko
-rw-r--r-- 1 root root  109854 Апр  6 17:57 relkins.ko
-rw-r--r-- 1 root root   91736 Янв  3 03:20 rotatekins.ko
-rw-r--r-- 1 root root  254620 Янв  3 03:20 rtapi.ko
-rw-r--r-- 1 root root   94924 Янв  3 03:20 sample_hold.ko
-rw-r--r-- 1 root root  103207 Янв  3 03:20 sampler.ko
-rw-r--r-- 1 root root   94838 Янв  3 03:20 scale.ko
-rw-r--r-- 1 root root  303263 Янв  3 03:20 scarakins.ko
-rw-r--r-- 1 root root   97762 Янв  3 03:20 scope_rt.ko
-rw-r--r-- 1 root root   95911 Янв  3 03:20 select8.ko
-rw-r--r-- 1 root root  104595 Янв  3 03:20 serport.ko
-rw-r--r-- 1 root root  142136 Янв  3 03:20 setsserial.ko
-rw-r--r-- 1 root root   97905 Янв  3 03:20 siggen.ko
-rw-r--r-- 1 root root  121518 Янв  3 03:20 sim_axis_hardware.ko
-rw-r--r-- 1 root root   99366 Янв  3 03:20 sim_encoder.ko
-rw-r--r-- 1 root root   95796 Янв  3 03:20 sim_home_switch.ko
-rw-r--r-- 1 root root  127643 Янв  3 03:20 sim_parport.ko
-rw-r--r-- 1 root root   98403 Янв  3 03:20 simple_tp.ko
-rw-r--r-- 1 root root   97215 Янв  3 03:20 sim_spindle.ko
-rw-r--r-- 1 root root   97922 Янв  3 03:20 sphereprobe.ko
-rw-r--r-- 1 root root  116202 Янв  3 03:20 stepgen.ko
-rw-r--r-- 1 root root  102197 Янв  3 03:20 steptest.ko
-rw-r--r-- 1 root root  103505 Янв  3 03:20 streamer.ko
-rw-r--r-- 1 root root   95875 Янв  3 03:20 sum2.ko
-rw-r--r-- 1 root root   92691 Янв  3 03:20 supply.ko
-rw-r--r-- 1 root root  101130 Янв  3 03:20 thc.ko
-rw-r--r-- 1 root root   99250 Янв  3 03:20 thcud.ko
-rw-r--r-- 1 root root   93868 Янв  3 03:20 threads.ko
-rw-r--r-- 1 root root   94558 Янв  3 03:20 threadtest.ko
-rw-r--r-- 1 root root   96765 Янв  3 03:20 timedelay.ko
-rw-r--r-- 1 root root   97836 Янв  3 03:20 timedelta.ko
-rw-r--r-- 1 root root   98970 Янв  3 03:20 time.ko
-rw-r--r-- 1 root root   95641 Янв  3 03:20 toggle2nist.ko
-rw-r--r-- 1 root root   95532 Янв  3 03:20 toggle.ko
-rw-r--r-- 1 root root   92827 Янв  3 03:20 tripodkins.ko
-rw-r--r-- 1 root root   94865 Янв  3 03:20 tristate_bit.ko
-rw-r--r-- 1 root root   95176 Янв  3 03:20 tristate_float.ko
-rw-r--r-- 1 root root   89824 Янв  3 03:20 trivkins.ko
-rw-r--r-- 1 root root   98141 Янв  3 03:20 updown.ko
-rw-r--r-- 1 root root   95452 Янв  3 03:20 watchdog.ko
-rw-r--r-- 1 root root   96434 Янв  3 03:20 wcomp.ko
-rw-r--r-- 1 root root   95604 Янв  3 03:20 weighted_sum.ko
-rw-r--r-- 1 root root  111458 Янв  3 03:20 xhc_hb04_util.ko
-rw-r--r-- 1 root root   94797 Янв  3 03:20 xor2.ko

Последний раз редактировалось a321 06 апр 2020, 19:59, всего редактировалось 1 раз.
Ответить

Вернуться в «LinuxCNC»