Все-таки SCARA

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

Re: Все-таки SCARA

Сообщение Serg »

РЕКЛАМА писал(а):При попытке выполнить задание пишет:
Правильно пишет - в режиме joint (сочленений) оно не будет ездить по координатам, только отдельными моторами. Надо переключить в режим world (координат). Переключается в меню Вид, в самом конце, при этом вместо осей 0, 1, 2 будут оси X, Y, Z, ну и внизу надпись поменяется.
Я не Христос, рыбу не раздаю, но могу научить, как сделать удочку...
Аватара пользователя
РЕКЛАМА
Почётный участник
Почётный участник
Сообщения: 736
Зарегистрирован: 11 дек 2012, 21:46
Репутация: 80
Откуда: Брянск
Контактная информация:

Re: Все-таки SCARA

Сообщение РЕКЛАМА »

Понял.переключил. Ездит
nkp писал(а):а хал файле в конце прописать по принципу:
У меня 2 файла.hal :
scara_sim_4.hal там много чего. но формул я не нашел, и ничего что с ними связано.
и
scara_postgui.hal
Там всего 4 строчки.

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

Re: Все-таки SCARA

Сообщение nkp »

РЕКЛАМА писал(а):scara_sim_4.hal там много чего. но формул я не нашел, и ничего что с ними связано.
формулы в файле кинематики...
этот файл скомпилирован и находится в системе (скорей всего у тебя /usr/realtime-2.6.32-122-rtai/modules/linuxcnc/scarakins.ko)
его исходники:
(для просмотра содержимого нажмите на ссылку)

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

/*****************************************************************
* Description: scarakins.c
*   Kinematics for scara typed robots
*   Set the params using HAL to fit your robot
*
*   Derived from a work by Sagar Behere
*
* Author: Sagar Behere 
* License: GPL Version 2
* System: Linux
*
* Copyright (c) 2003 All rights reserved.
*
* Last change:
*******************************************************************
*/

#include "posemath.h"
#include "rtapi_math.h"
#include "kinematics.h"             /* decls for kinematicsForward, etc. */

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

struct scara_data {
    hal_float_t *d1, *d2, *d3, *d4, *d5, *d6;
} *haldata = 0;

/* key dimensions

   joint[0] = Entire arm rotates around a vertical axis at its inner end
		which is attached to the earth.  A value of zero means the
		inner arm is pointing along the X axis.
   D1 = Vertical distance from the ground plane to the center of the inner
		arm.
   D2 = Horizontal distance between joint[0] axis and joint[1] axis, ie.
		the length of the inner arm.
   joint[1] = Outer arm rotates around a vertical axis at its inner end
		which is attached to the outer end of the inner arm.  A
		value of zero means the outer arm is parallel to the
		inner arm (and extending outward).
   D3 = Vertical distance from the center of the inner arm to the center
		of the outer arm.  May be positive or negative depending
		on the structure of the robot.
   joint[2] = End effector slides along a vertical axis at the outer end
		of the outer arm.  A value of zero means the end effector
		is at the same height as the center of the outer arm, and
		positive values mean downward movement.
   D4 = Horizontal distance between joint[1] axis and joint[2] axis, ie.
		the length of the outer arm
   joint[3] = End effector rotates around the same vertical axis that it
		slides along.  A value of zero means that the tooltip (if
		offset from the axis) is pointing in the same direction
		as the centerline of the outer arm.
   D5 = Vertical distance from the end effector to the tooltip.  Positive
		means the tooltip is lower than the end effector, and is
		the normal case.
   D6 = Horizontal distance from the centerline of the end effector (and
		the joints 2 and 3 axis) and the tooltip.  Zero means the
		tooltip is on the centerline.  Non-zero values should be
		positive, if negative they introduce a 180 degree offset
		on the value of joint[3].
*/

#define D1 (*(haldata->d1))
#define D2 (*(haldata->d2))
#define D3 (*(haldata->d3))
#define D4 (*(haldata->d4))
#define D5 (*(haldata->d5))
#define D6 (*(haldata->d6))

/* joint[0], joint[1] and joint[3] are in degrees and joint[2] is in length units */
int kinematicsForward(const double * joint,
                      EmcPose * world,
                      const KINEMATICS_FORWARD_FLAGS * fflags,
                      KINEMATICS_INVERSE_FLAGS * iflags)
{
    double a0, a1, a3;
    double x, y, z, c;

/* convert joint angles to radians for sin() and cos() */

    a0 = joint[0] * ( PM_PI / 180 );
    a1 = joint[1] * ( PM_PI / 180 );
    a3 = joint[3] * ( PM_PI / 180 );
/* convert angles into world coords */

    a1 = a1 + a0;
    a3 = a3 + a1;

    x = D2*cos(a0) + D4*cos(a1) + D6*cos(a3);
    y = D2*sin(a0) + D4*sin(a1) + D6*sin(a3);
    z = D1 + D3 - joint[2] - D5;
    c = a3;
	
    *iflags = 0;
    if (joint[1] < 90)
	*iflags = 1;
	
    world->tran.x = x;
    world->tran.y = y;
    world->tran.z = z;
    world->c = c * 180 / PM_PI;
	
    world->a = joint[4];
    world->b = joint[5];
	
    return (0);
}

int kinematicsInverse(const EmcPose * world,
                      double * joint,
                      const KINEMATICS_INVERSE_FLAGS * iflags,
                      KINEMATICS_FORWARD_FLAGS * fflags)
{
    double a3;
    double q0, q1;
    double xt, yt, rsq, cc;
    double x, y, z, c;

    x = world->tran.x;
    y = world->tran.y;
    z = world->tran.z;
    c = world->c;

    /* convert degrees to radians */
    a3 = c * ( PM_PI / 180 );

    /* center of end effector (correct for D6) */
    xt = x - D6*cos(a3);
    yt = y - D6*sin(a3);

    /* horizontal distance (squared) from end effector centerline
	to main column centerline */
    rsq = xt*xt + yt*yt;
    /* joint 1 angle needed to make arm length match sqrt(rsq) */
    cc = (rsq - D2*D2 - D4*D4) / (2*D2*D4);
    if(cc < -1) cc = -1;
    if(cc > 1) cc = 1;
    q1 = acos(cc);

    if (*iflags)
	q1 = -q1;

    /* angle to end effector */
    q0 = atan2(yt, xt);

    /* end effector coords in inner arm coord system */
    xt = D2 + D4*cos(q1);
    yt = D4*sin(q1);

    /* inner arm angle */
    q0 = q0 - atan2(yt, xt);

    /* q0 and q1 are still in radians. convert them to degrees */
    q0 = q0 * (180 / PM_PI);
    q1 = q1 * (180 / PM_PI);

    joint[0] = q0;
    joint[1] = q1;
    joint[2] = D1 + D3 - D5 - z;
    joint[3] = c - ( q0 + q1);
    joint[4] = world->a;
    joint[5] = world->b;

    *fflags = 0;

    return (0);
}

int kinematicsHome(EmcPose * world,
                   double * joint,
                   KINEMATICS_FORWARD_FLAGS * fflags,
                   KINEMATICS_INVERSE_FLAGS * iflags)
{
  /* use joints, set world */
  return kinematicsForward(joint, world, fflags, iflags);
}

KINEMATICS_TYPE kinematicsType()
{
  return KINEMATICS_BOTH;
}

#define DEFAULT_D1 490
#define DEFAULT_D2 340
#define DEFAULT_D3  50
#define DEFAULT_D4 250
#define DEFAULT_D5  50
#define DEFAULT_D6  50

EXPORT_SYMBOL(kinematicsType);
EXPORT_SYMBOL(kinematicsForward);
EXPORT_SYMBOL(kinematicsInverse);
EXPORT_SYMBOL(kinematicsHome);

int comp_id;

int rtapi_app_main(void) {
    int res=0;
    
    comp_id = hal_init("scarakins");
    if (comp_id < 0) return comp_id;
    
    haldata = hal_malloc(sizeof(*haldata));
    if (!haldata) goto error;
    if((res = hal_pin_float_new("scarakins.D1", HAL_IO, &(haldata->d1), comp_id)) < 0) goto error;
    if((res = hal_pin_float_new("scarakins.D2", HAL_IO, &(haldata->d2), comp_id)) < 0) goto error;
    if((res = hal_pin_float_new("scarakins.D3", HAL_IO, &(haldata->d3), comp_id)) < 0) goto error;
    if((res = hal_pin_float_new("scarakins.D4", HAL_IO, &(haldata->d4), comp_id)) < 0) goto error;
    if((res = hal_pin_float_new("scarakins.D5", HAL_IO, &(haldata->d5), comp_id)) < 0) goto error;
    if((res = hal_pin_float_new("scarakins.D6", HAL_IO, &(haldata->d6), comp_id)) < 0) goto error;
    
    D1 = DEFAULT_D1;
    D2 = DEFAULT_D2;
    D3 = DEFAULT_D3;
    D4 = DEFAULT_D4;
    D5 = DEFAULT_D5;
    D6 = DEFAULT_D6;

    hal_ready(comp_id);
    return 0;
    
error:
    hal_exit(comp_id);
    return res;
}

void rtapi_app_exit(void) { hal_exit(comp_id); }
редактировать его способ есть - но думаю он не нужен нам будет...
РЕКЛАМА писал(а):Записал в первой, меняю цифры ничего не меняется, по крайней мере в симуляции.
скорей всего в симуляции мы ничего и не увидим...
(сейчас у себя попробую)
Аватара пользователя
РЕКЛАМА
Почётный участник
Почётный участник
Сообщения: 736
Зарегистрирован: 11 дек 2012, 21:46
Репутация: 80
Откуда: Брянск
Контактная информация:

Re: Все-таки SCARA

Сообщение РЕКЛАМА »

а где прописывать ускорения,лимиты и распиновку лпт?

И как всё-таки выкинуть 4 ось?
nkp
Мастер
Сообщения: 8340
Зарегистрирован: 28 ноя 2011, 00:25
Репутация: 1589
Контактная информация:

Re: Все-таки SCARA

Сообщение nkp »

кинематика работает и в симуляторе это тоже видно ...
=============
D1 - исходная высота по Z
РЕКЛАМА писал(а):И как всё-таки выкинуть 4 ось?
в ини и хал файлах(по ходу вытрем)
РЕКЛАМА писал(а):а где прописывать ускорения,лимиты и распиновку лпт?
ускорения прописываются в ini файле...

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

[TRAJ]
#+ machine specific settings
AXES =                  6
COORDINATES =           X Y Z C 
HOME = 			0 0 0 0 
LINEAR_UNITS =          mm
ANGULAR_UNITS =         degree
CYCLE_TIME =            0.010
DEFAULT_VELOCITY =      1.0
MAX_VELOCITY =          600.0
DEFAULT_ACCELERATION =  100.0
MAX_ACCELERATION =      200.0

###############################################################################
# Axes sections
###############################################################################

#+ First axis
[AXIS_0]
TYPE =                          ANGULAR
HOME =                          0.000
MAX_VELOCITY =                  30.0
MAX_ACCELERATION =              200.0
BACKLASH =                      0.000
INPUT_SCALE =                   4000  
OUTPUT_SCALE =                  1.000
MIN_LIMIT =                     -360.0
MAX_LIMIT =                     360.0
FERROR =                        2.000
MIN_FERROR =                    0.200
HOME_OFFSET =                   0.0
HOME_SEARCH_VEL =               0.0
HOME_LATCH_VEL =                0.0
HOME_USE_INDEX =                NO
HOME_IGNORE_LIMITS =            NO
HOME_SEQUENCE =                 0
это общие
DEFAULT_ACCELERATION = 100.0
MAX_ACCELERATION = 200.0
а дальше для каждой оси идут настройки
для X
#+ First axis
[AXIS_0]
...
...
nkp
Мастер
Сообщения: 8340
Зарегистрирован: 28 ноя 2011, 00:25
Репутация: 1589
Контактная информация:

Re: Все-таки SCARA

Сообщение nkp »

вот файлы с прописанным портом:
scara1.rar
(5.27 КБ) 343 скачивания
там в файле standard_pinout.hal есть распиновка под оси:
net 0step => parport.0.pin-03-out
net 0dir => parport.0.pin-02-out
net 1step => parport.0.pin-05-out
net 1dir => parport.0.pin-04-out
net 2step => parport.0.pin-07-out
net 2dir => parport.0.pin-06-out
надо поставить свои пины порта
==============
в этом конфиге вычислялась скорость из положения - не знаю пока - нужно ли это :thinking:
подтянутся знающие - подскажут))
Аватара пользователя
РЕКЛАМА
Почётный участник
Почётный участник
Сообщения: 736
Зарегистрирован: 11 дек 2012, 21:46
Репутация: 80
Откуда: Брянск
Контактная информация:

Re: Все-таки SCARA

Сообщение РЕКЛАМА »

Вставил файлы из архива. пересталошевелиться. при попытке крутить оси идет ошибка:
Вложения
Снимок-1.png (2331 просмотр) <a class='original' href='./download/file.php?id=38814&mode=view' target=_blank>Загрузить оригинал (198.37 КБ)</a>
Аватара пользователя
РЕКЛАМА
Почётный участник
Почётный участник
Сообщения: 736
Зарегистрирован: 11 дек 2012, 21:46
Репутация: 80
Откуда: Брянск
Контактная информация:

Re: Все-таки SCARA

Сообщение РЕКЛАМА »

имеет знаачеие что у меня более старая версия рограммы?
Аватара пользователя
РЕКЛАМА
Почётный участник
Почётный участник
Сообщения: 736
Зарегистрирован: 11 дек 2012, 21:46
Репутация: 80
Откуда: Брянск
Контактная информация:

Re: Все-таки SCARA

Сообщение РЕКЛАМА »

Переустановился по новой.
Теперь на Дебиане :shock:

Ошибка всё та-же. :cry:
Аватара пользователя
РЕКЛАМА
Почётный участник
Почётный участник
Сообщения: 736
Зарегистрирован: 11 дек 2012, 21:46
Репутация: 80
Откуда: Брянск
Контактная информация:

Re: Все-таки SCARA

Сообщение РЕКЛАМА »

Видимо не осилю.
Я не могу понять как хал и ини связаны друг с другом и самой программой.
со стандартными файлами все шевелится, размеры суставов в симуляции не меняются.
В тех что дал уважаемый nkp ничего не шевелится, выскакивает ошибка "joint 0(1.2..в зависимости от оси) following error", в режим координат не переключается, размеры суставов в симуляции не меняются.
Поиск по этой ошибке говорит что надо менять настройки "феррор", но изменение их ни на что не влияет.
При попытке менять файлы .ини или .хал по отдельности, не запускается с ошибкой.
С английским совсем плохо, переводчик помогает мало..
Аватара пользователя
PKM
Почётный участник
Почётный участник
Сообщения: 4263
Зарегистрирован: 31 мар 2011, 18:11
Репутация: 705
Настоящее имя: Андрей
Откуда: Украина
Контактная информация:

Re: Все-таки SCARA

Сообщение PKM »

Надо поставить в ини на все оси STEPGEN_MAXACCEL = 250
Аватара пользователя
РЕКЛАМА
Почётный участник
Почётный участник
Сообщения: 736
Зарегистрирован: 11 дек 2012, 21:46
Репутация: 80
Откуда: Брянск
Контактная информация:

Re: Все-таки SCARA

Сообщение РЕКЛАМА »

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

Re: Все-таки SCARA

Сообщение Serg »

Ошибка "joint N following error" в случае с шаговиками возникает только в одном случае - если разорвана связь между axis.N.motor-pos-cmd и axis.N.motor-pos-fb.
Я не Христос, рыбу не раздаю, но могу научить, как сделать удочку...
Аватара пользователя
РЕКЛАМА
Почётный участник
Почётный участник
Сообщения: 736
Зарегистрирован: 11 дек 2012, 21:46
Репутация: 80
Откуда: Брянск
Контактная информация:

Re: Все-таки SCARA

Сообщение РЕКЛАМА »

Как это проверить/иссправвить?
Вложения
45.png (2258 просмотров) <a class='original' href='./download/file.php?id=38854&mode=view' target=_blank>Загрузить оригинал (173.24 КБ)</a>
Аватара пользователя
Serg
Мастер
Сообщения: 21923
Зарегистрирован: 17 апр 2012, 14:58
Репутация: 5183
Заслуга: c781c134843e0c1a3de9
Настоящее имя: Сергей
Откуда: Москва
Контактная информация:

Re: Все-таки SCARA

Сообщение Serg »

Вопросом озадачил... Ну например в конфиг посмотреть... :)

Например вот этого глубокомысленного объявления я вообще ниасилил:

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

# loop position commands back to motion module feedback
net J0fb => axis.0.motor-pos-fb => axis.0.motor-pos-fb
net J1fb => axis.1.motor-pos-fb => axis.1.motor-pos-fb
net J2fb => axis.2.motor-pos-fb => axis.2.motor-pos-fb
net J3fb => axis.5.motor-pos-fb => axis.5.motor-pos-fb
В конфиге симулятора всё ведь было правильно...
P.S. Всем, начинающим осваивать LinuxCNC совет: обязательно осильте раздел в документации "HAL: the Hardware Abstract Layer" - сэкономите огромное количество времени себе и тем, кто вам может помочь...
Я не Христос, рыбу не раздаю, но могу научить, как сделать удочку...
Аватара пользователя
РЕКЛАМА
Почётный участник
Почётный участник
Сообщения: 736
Зарегистрирован: 11 дек 2012, 21:46
Репутация: 80
Откуда: Брянск
Контактная информация:

Re: Все-таки SCARA

Сообщение РЕКЛАМА »

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

Re: Все-таки SCARA

Сообщение Serg »

Можешь своими словами рассказать что делает эта строчка и для чего она?

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

net J0fb => axis.0.motor-pos-fb => axis.0.motor-pos-fb
Я не Христос, рыбу не раздаю, но могу научить, как сделать удочку...
Аватара пользователя
РЕКЛАМА
Почётный участник
Почётный участник
Сообщения: 736
Зарегистрирован: 11 дек 2012, 21:46
Репутация: 80
Откуда: Брянск
Контактная информация:

Re: Все-таки SCARA

Сообщение РЕКЛАМА »

прямо счас-нет.
я ни разу не прогрмист. механизмм я осилю. цифровое шамантво ммне пплохо поддается. слишком ммного иинформаии. а мозги уже старые.

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

Re: Все-таки SCARA

Сообщение Serg »

РЕКЛАМА писал(а): А как првильно?
Так, как было изначально в конфиге симулятора.
Я не Христос, рыбу не раздаю, но могу научить, как сделать удочку...
Аватара пользователя
РЕКЛАМА
Почётный участник
Почётный участник
Сообщения: 736
Зарегистрирован: 11 дек 2012, 21:46
Репутация: 80
Откуда: Брянск
Контактная информация:

Re: Все-таки SCARA

Сообщение РЕКЛАМА »

убрал хвосты по аналогии с первичным файлом. ничего не изменилось..
Ответить

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