Страница 3 из 10
Re: Настройка кинематики в EMC2
Добавлено: 14 ноя 2014, 21:55
sasha_89
вот что-то сделал я так понимаю скомпилировал:
Код: Выделить всё
sasha@sasha-desktop:/$ sudo apt-get install linuxcnc-dev
Чтение списков пакетов... Готово
Построение дерева зависимостей
Чтение информации о состоянии... Готово
Уже установлена самая новая версия linuxcnc-dev.
Следующие пакеты устанавливались автоматически и больше не требуются:
user-setup localechooser-data
Для их удаления используйте 'apt-get autoremove'.
обновлено 0, установлено 0 новых пакетов, для удаления отмечено 0 пакетов, и 235 пакетов не обновлено.
sasha@sasha-desktop:/$ cd /tmp
sasha@sasha-desktop:/tmp$ sudo comp --install angularkins.c
make KBUILD_EXTRA_SYMBOLS=/usr/realtime-2.6.32-122-rtai/modules/linuxcnc/Module.symvers -C /usr/src/linux-headers-2.6.32-122-rtai SUBDIRS=`pwd` CC=gcc V=0 modules
make[1]: Вход в каталог `/usr/src/linux-headers-2.6.32-122-rtai'
CC [M] /tmp/tmpgQZ32P/angularkins.o
Building modules, stage 2.
MODPOST 1 modules
CC /tmp/tmpgQZ32P/angularkins.mod.o
LD [M] /tmp/tmpgQZ32P/angularkins.ko
make[1]: Выход из каталога `/usr/src/linux-headers-2.6.32-122-rtai'
cp angularkins.ko /usr/realtime-2.6.32-122-rtai/modules/linuxcnc/
sasha@sasha-desktop:/tmp$
а дальше результатом есть файл angularkins.ko или как, что дальше нужна делать чтоб пробовать юзать робокопа,

подскажите я еще чайник в этом деле!

Re: Настройка кинематики в EMC2
Добавлено: 14 ноя 2014, 22:09
nkp
sasha_89 писал(а):что дальше нужна делать
ты выкладывал архив конфига ,который юзаешь...
там их два - какой работает на железе?
===============
по установке кинематики:
мне кажеться проще положить файл angularkins.c в домашнюю папку...
(ты еще его
много раз будешь редактировать и компилить)
потом открываешь терминал , никаких cd ,просто пишешь:
sudo comp --install angularkins.c
и всё
====================
я пробую сейчас "работу" кинематики с этим конфигом:
- 1.rar
- (3.96 КБ) 336 скачиваний
можешь его попробовать запустить...
==========
но у меня код кинематики пока такой:
Код: Выделить всё
/********************************************************************
* Description: angularkins.c
* Angular kinematics for 3 axis with angular axis along Z
*
* Derived from a work by Fred Proctor & Will Shackleford
*
* Author:
* License: GPL Version 2
* System: Linux
*
* Copyright (c) 2004 All rights reserved.
*
* Last change:
********************************************************************/
#include "posemath.h"
#include "hal.h"
#include "rtapi.h"
#include "rtapi_math.h"
#include "kinematics.h" /* sudo halcompile --install angularkins_1.c */
int kinematicsForward(const double *joints,
EmcPose * pos,
const KINEMATICS_FORWARD_FLAGS * fflags,
KINEMATICS_INVERSE_FLAGS * iflags)
{
pos->tran.x = joints[0];
pos->tran.y = joints[1];
pos->tran.z = joints[2];
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)
{
static double dx = 0 , dy = 0;
dx = pos->tran.x;
dy = pos->tran.y;
joints[4] = atan2(dx,dy)*(180.0/3.141592);
joints[0] = sqrt(pos->tran.x * pos->tran.x + pos->tran.y * pos->tran.y);
joints[1] = pos->tran.y;
joints[2] = pos->tran.z;
joints[3] = pos->a;
joints[5] = pos->c;
joints[6] = pos->u;
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_IDENTITY;
}
#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) {
comp_id = hal_init("angularkins");
if(comp_id > 0) {
hal_ready(comp_id);
return 0;
}
return comp_id;
}
void rtapi_app_exit(void) { hal_exit(comp_id); }
Re: Настройка кинематики в EMC2
Добавлено: 14 ноя 2014, 22:52
nkp
так вроде бы правильно отображает в dro:
Код: Выделить всё
int kinematicsForward(const double *joints,
EmcPose * pos,
const KINEMATICS_FORWARD_FLAGS * fflags,
KINEMATICS_INVERSE_FLAGS * iflags)
{
pos->tran.x = joints[0] * (sin(joints[4] * (PM_PI/180.0)));
pos->tran.y = joints[0] * (cos(joints[4] * (PM_PI/180.0)));
pos->tran.z = joints[2];
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;
}
Re: Настройка кинематики в EMC2
Добавлено: 16 ноя 2014, 22:18
sasha_89
дело вот в чем, я до конца не знаю как настраивать: начну сначала какой у меня уровень знаний и что я умею!
- установил Ubuntu 10.4
- запускаю в LinuxCNC конфигурацию stepper-xyza - и больше ничего не настраиваю машина сразу реагирует - ездит по осям - x,y,z. нужды в настройка пинов небыло а и знаю где настраивать каждую ось отдельно в текстовых файлах (вопрос ту ли я конфигурацию запускаю? )
- понял как нужно компилировать файл - sudo apt-get install linuxcnc-dev потом прописать директорию, где лежит файл потом - sudo comp --install angularkins.c (вопрос что нужно делать дальше - где то нужно прописывать в настройках этот файл чтоб LinuxCNC видел этот angularkins или как? )

подскажите пожалуйста по пунктам как верно нужно делать всю процедуру настройки до мелочи - спасибо
Re: Настройка кинематики в EMC2
Добавлено: 16 ноя 2014, 22:44
nkp
sasha_89 писал(а):подскажите пожалуйста по пунктам как верно нужно делать всю процедуру настройки до мелочи
"до мелочи" сразу в одном посте наверно не получится...
для начала возьми проверенный код кинематики :
Код: Выделить всё
/********************************************************************
* Description: angularkins.c
* Angular kinematics for 3 axis with angular axis along Z
*
* Derived from a work by Fred Proctor & Will Shackleford
*
* Author:
* License: GPL Version 2
* System: Linux
*
* Copyright (c) 2004 All rights reserved.
*
* Last change:
********************************************************************/
#include "posemath.h"
#include "hal.h"
#include "rtapi.h"
#include "rtapi_math.h"
#include "kinematics.h"
int kinematicsForward(const double *joints,
EmcPose * pos,
const KINEMATICS_FORWARD_FLAGS * fflags,
KINEMATICS_INVERSE_FLAGS * iflags)
{
pos->tran.x = joints[0] * (sin(joints[4] * (PM_PI/180.0)));
pos->tran.y = joints[0] * (cos(joints[4] * (PM_PI/180.0)));
pos->tran.z = joints[2];
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)
{
static double dx = 0 , dy = 0;
dx = pos->tran.x;
dy = pos->tran.y;
joints[4] = atan2(dx,dy)*(180.0/PM_PI);
joints[0] = sqrt(pos->tran.x * pos->tran.x + pos->tran.y * pos->tran.y);
joints[1] = pos->tran.y;
joints[2] = pos->tran.z;
joints[3] = pos->a;
joints[5] = pos->c;
joints[6] = pos->u;
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_IDENTITY;
}
#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) {
comp_id = hal_init("angularkins");
if(comp_id > 0) {
hal_ready(comp_id);
return 0;
}
return comp_id;
}
void rtapi_app_exit(void) { hal_exit(comp_id); }
установи ее(кинематику) как ты уже делал...
---------------
в своем файле stepper_xyza.hal поменяй строку
loadrt trivkins
на
loadrt angularkins
и пробуй запускать...
ошибки выкладывай сюда...
постепенно всё решим

Re: Настройка кинематики в EMC2
Добавлено: 17 ноя 2014, 09:25
Nick
Только ось поворотную надо будет подключать к axis.4."..."
Re: Настройка кинематики в EMC2
Добавлено: 17 ноя 2014, 09:41
nkp
Nick писал(а):олько ось поворотную надо будет подключать к axis.4."..."
наверно для начинающего проще будет в файле кинематики пока поправить
joints[4] на
joints[3]
(с учетом того,что у тс железо более менее уже работает с конфигом)
========
правда такой вопрос:
с переустановкой убунты конфиг юзаешь все тот же?
(как я писал - этот конфиг с устаревшим синтаксисом - его (синтаксис) на сегодня уже не пользуют)
Re: Настройка кинематики в EMC2
Добавлено: 17 ноя 2014, 10:14
sasha_89
нет - новый с нуля что создался при первом запуске EMC!
Re: Настройка кинематики в EMC2
Добавлено: 17 ноя 2014, 10:23
nkp
sasha_89 писал(а):нет - новый с нуля что создался при первом запуске EMC!
он тоже рабртает ? (в смысле железяка управляется им?)
если он отличается - выкладывай его сюда...
Re: Настройка кинематики в EMC2
Добавлено: 17 ноя 2014, 10:33
sasha_89
да работает также!
Re: Настройка кинематики в EMC2
Добавлено: 17 ноя 2014, 10:34
Nick
А как у тебя выглядит angularkins.c?
Re: Настройка кинематики в EMC2
Добавлено: 17 ноя 2014, 10:41
nkp
кинематику смотрю ты прописал...
но наверно она пока не работает так как надо...
просто у тебя поворотка прописана на 3-ю ось(net Apos-cmd => stepgen.3.position-cmd)
а в кинематике поворотка - 4-я ось(joints[4])
============
то есть тебе нужно или в файле править , или в кинематике...
легче для проверки в кинематике:
Код: Выделить всё
/********************************************************************
* Description: angularkins.c
* Angular kinematics for 3 axis with angular axis along Z
*
* Derived from a work by Fred Proctor & Will Shackleford
*
* Author:
* License: GPL Version 2
* System: Linux
*
* Copyright (c) 2004 All rights reserved.
*
* Last change:
********************************************************************/
#include "posemath.h"
#include "hal.h"
#include "rtapi.h"
#include "rtapi_math.h"
#include "kinematics.h"
int kinematicsForward(const double *joints,
EmcPose * pos,
const KINEMATICS_FORWARD_FLAGS * fflags,
KINEMATICS_INVERSE_FLAGS * iflags)
{
pos->tran.x = joints[0] * (sin(joints[3] * (PM_PI/180.0)));
pos->tran.y = joints[0] * (cos(joints[3] * (PM_PI/180.0)));
pos->tran.z = joints[2];
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)
{
static double dx = 0 , dy = 0 , A = 0;
dx = pos->tran.x;
dy = pos->tran.y;
A = atan2(dx,dy);
joints[3] = A * (180.0/PM_PI);
joints[0] = sqrt(pos->tran.x * pos->tran.x + pos->tran.y * pos->tran.y);
joints[1] = pos->tran.y;
joints[2] = pos->tran.z;
joints[3] = pos->a;
joints[5] = pos->c;
joints[6] = pos->u;
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_IDENTITY;
}
#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) {
comp_id = hal_init("angularkins");
if(comp_id > 0) {
hal_ready(comp_id);
return 0;
}
return comp_id;
}
void rtapi_app_exit(void) { hal_exit(comp_id); }
===============
может я пишу ,а ты уже всё это сделал

Re: Настройка кинематики в EMC2
Добавлено: 17 ноя 2014, 10:48
nkp
кстати - по поводу ручных перемещений(не глянул в других файлах кинематик - мож уже так сделано))
в main наверно можно засунуть условие :
если ручной режим - одни функции прямой и обратной кинематики...
для других режимов - другие("теперешние"))
может через #define ...
=========
ps
глянул - можно проще ,как в tangentkins:
(для просмотра содержимого нажмите на ссылку)Код: Выделить всё
#include "kinematics.h" /* these decls */
#include "hal.h"
#include "rtapi_math.h"
static PmCartesian old; // sudo comp --install tangentkins.c
typedef struct { hal_bit_t *pin_auto ;} tangentkins_hal_t;
tangentkins_hal_t *data;
int kinematicsForward(const double *joints,
EmcPose * pos,
const KINEMATICS_FORWARD_FLAGS * fflags,
KINEMATICS_INVERSE_FLAGS * iflags)
{
pos->tran.x = joints[0];
pos->tran.y = joints[1];
pos->tran.z = joints[2];
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)
{
static double dx = 0, dy = 0, A = 0;
if (*data->pin_auto){
if (dx != 0 || dy != 0) {
A = atan2(dx, dy)*(180.0/3.141592);
}
}else{
A=pos->a;
}
joints[0] = pos->tran.x / cos(A);
joints[1] = pos->tran.y;
joints[2] = pos->tran.z;
joints[3] = A;
joints[4] = pos->b;
joints[5] = pos->c;
joints[6] = pos->u;
joints[7] = pos->v;
joints[8] = pos->w;
old.x = pos->tran.x; // store previous value here to exclude kins-based movements
old.y = pos->tran.y;
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) {
comp_id = hal_init("tangentkins");
if(comp_id > 0) {
data = hal_malloc(sizeof(tangentkins_hal_t));
if(hal_pin_bit_new("tangentkins.auto", HAL_IN, &(data->pin_auto), comp_id) < 0 ){
rtapi_print("Failed to create pin in tangentkins");
return -EINVAL;
}
hal_ready(comp_id);
return 0;
}
return comp_id;
}
void rtapi_app_exit(void) { hal_exit(comp_id); }
а в hal:
Код: Выделить всё
loadrt not
addf not.0 servo-thread
net not_in not.0.in halui.mode.is-manual
net tkins_auto not.0.out tangentkins.auto
Re: Настройка кинематики в EMC2
Добавлено: 19 ноя 2014, 17:34
sasha_89
как сделать инверсию оси У?
Re: Настройка кинематики в EMC2
Добавлено: 19 ноя 2014, 18:39
Nick
Scale поставить меньше 0 или сделать invert на пине dir.
Re: Настройка кинематики в EMC2
Добавлено: 25 ноя 2014, 21:53
sasha_89
Настроил каждую ось и ездит в милиметрах! компилирую, меняю loadrt - trivkins на angularkins. Запускаю но работает как на - trivkins, только что увидел что нужно било сделать:
кинематику смотрю ты прописал...
но наверно она пока не работает так как надо...
просто у тебя поворотка прописана на 3-ю ось(net Apos-cmd => stepgen.3.position-cmd)
а в кинематике поворотка - 4-я ось(joints[4])
============
то есть тебе нужно или в файле править , или в кинематике...
легче для проверки в кинематике:
Код: Выделить всё
КОД: ВЫДЕЛИТЬ ВСЁ • РАЗВЕРНУТЬ
/********************************************************************
* Description: angularkins.c
* Angular kinematics for 3 axis with angular axis along Z
*
* Derived from a work by Fred Proctor & Will Shackleford
*
* Author:
* License: GPL Version 2
* System: Linux
*
* Copyright (c) 2004 All rights reserved.
*
* Last change:
********************************************************************/
#include "posemath.h"
#include "hal.h"
#include "rtapi.h"
#include "rtapi_math.h"
#include "kinematics.h"
int kinematicsForward(const double *joints,
EmcPose * pos,
const KINEMATICS_FORWARD_FLAGS * fflags,
KINEMATICS_INVERSE_FLAGS * iflags)
{
pos->tran.x = joints[0] * (sin(joints[3] * (PM_PI/180.0)));
pos->tran.y = joints[0] * (cos(joints[3] * (PM_PI/180.0)));
pos->tran.z = joints[2];
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)
{
static double dx = 0 , dy = 0 , A = 0;
dx = pos->tran.x;
dy = pos->tran.y;
A = atan2(dx,dy);
joints[3] = A * (180.0/PM_PI);
joints[0] = sqrt(pos->tran.x * pos->tran.x + pos->tran.y * pos->tran.y);
joints[1] = pos->tran.y;
joints[2] = pos->tran.z;
joints[3] = pos->a;
joints[5] = pos->c;
joints[6] = pos->u;
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_IDENTITY;
}
#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) {
comp_id = hal_init("angularkins");
if(comp_id > 0) {
hal_ready(comp_id);
return 0;
}
return comp_id;
}
void rtapi_app_exit(void) { hal_exit(comp_id); }
у меня кинематика така -
Код: Выделить всё
/********************************************************************
* Description: angularkins.c
* Angular kinematics for 3 axis with angular axis along Z
*
* Derived from a work by Fred Proctor & Will Shackleford
*
* Author:
* License: GPL Version 2
* System: Linux
*
* Copyright (c) 2004 All rights reserved.
*
* Last change:
********************************************************************/
#include "posemath.h"
#include "hal.h"
#include "rtapi.h"
#include "rtapi_math.h"
#include "kinematics.h"
int kinematicsForward(const double *joints,
EmcPose * pos,
const KINEMATICS_FORWARD_FLAGS * fflags,
KINEMATICS_INVERSE_FLAGS * iflags)
{
pos->tran.x = joints[0] * (sin(joints[4] * (PM_PI/180.0)));
pos->tran.y = joints[0] * (cos(joints[4] * (PM_PI/180.0)));
pos->tran.z = joints[2];
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)
{
static double dx = 0 , dy = 0;
dx = pos->tran.x;
dy = pos->tran.y;
joints[4] = atan2(dx,dy)*(180.0/PM_PI);
joints[0] = sqrt(pos->tran.x * pos->tran.x + pos->tran.y * pos->tran.y);
joints[1] = pos->tran.y;
joints[2] = pos->tran.z;
joints[3] = pos->a;
joints[5] = pos->c;
joints[6] = pos->u;
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_IDENTITY;
}
#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) {
comp_id = hal_init("angularkins");
if(comp_id > 0) {
hal_ready(comp_id);
return 0;
}
return comp_id;
}
void rtapi_app_exit(void) { hal_exit(comp_id); }
из за этого не работает не считаєт ?
а ище компилировал єтот тоже не работает, а работает как на - trivkins:
Код: Выделить всё
/********************************************************************
* Description: rotatekins.c
* Simple example kinematics for a rotary table in software
*
* Derived from a work by Fred Proctor & Will Shackleford
*
* Author: Chris Radek
* License: GPL Version 2
* System: Linux
*
* Copyright (c) 2006 All rights reserved.
*
********************************************************************/
#include "rtapi_math.h"
#include "kinematics.h" /* these decls */
int kinematicsForward(const double *joints,
EmcPose * pos,
const KINEMATICS_FORWARD_FLAGS * fflags,
KINEMATICS_INVERSE_FLAGS * iflags)
{
double c_rad = -joints[5]*M_PI/180;
pos->tran.x = joints[0] * cos(c_rad) - joints[1] * sin(c_rad);
pos->tran.y = joints[0] * sin(c_rad) + joints[1] * cos(c_rad);
pos->tran.z = joints[2];
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)
{
double c_rad = pos->c*M_PI/180;
joints[0] = pos->tran.x * cos(c_rad) - pos->tran.y * sin(c_rad);
joints[1] = pos->tran.x * sin(c_rad) + pos->tran.y * cos(c_rad);
joints[2] = pos->tran.z;
joints[3] = pos->a;
joints[4] = pos->b;
joints[5] = pos->c;
joints[6] = pos->u;
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) {
comp_id = hal_init("rotatekins");
if(comp_id > 0) {
hal_ready(comp_id);
return 0;
}
return comp_id;
}
void rtapi_app_exit(void) { hal_exit(comp_id); }
Re: Настройка кинематики в EMC2
Добавлено: 25 ноя 2014, 22:42
nkp
sasha_89 писал(а):только что увидел что нужно било сделать:
пробовал как
здесь написано???
Re: Настройка кинематики в EMC2
Добавлено: 26 ноя 2014, 01:13
sasha_89
завтра буду пробовать! а в целом так и настраивається?
Re: Настройка кинематики в EMC2
Добавлено: 26 ноя 2014, 01:18
nkp
sasha_89 писал(а):а в целом так и настраивається?
не очень понятен твой вопрос...
=============
там по ссылке код файла кинематики с исправленой осью вращения...
тебе стоит просто установить ее как раньше ты делал(sudo comp --install angularkins.c)
Re: Настройка кинематики в EMC2
Добавлено: 26 ноя 2014, 01:25
sasha_89
я в том смысле что компилирую меняю loadrt - trivkins на angularkins и смотрю что вышло? или есть еще где то что прописывать?