Bipod setup
06 Aug 2010 08:44 #3603
by dab77
Bipod setup was created by dab77
Hallo everyone,
I'm trying to setup an inverted bipod, for studying purpose.
looked around for a lot, but still I didn't get to the point.
I'm trying to modify the file tripodkins.c to have my_bipod.c to compile, but I'm not sure if what I changed is ok.
I've read about in later versions of EMC2 there was a bipod.c already in ..src/emc/kinematics, but now there's not anymore.
do someone have this file to give me, or can tell me where to find it? ..so i can compare and find out any error.
thanks, dab.
I'm trying to setup an inverted bipod, for studying purpose.
looked around for a lot, but still I didn't get to the point.
I'm trying to modify the file tripodkins.c to have my_bipod.c to compile, but I'm not sure if what I changed is ok.
I've read about in later versions of EMC2 there was a bipod.c already in ..src/emc/kinematics, but now there's not anymore.
do someone have this file to give me, or can tell me where to find it? ..so i can compare and find out any error.
thanks, dab.
Please Log in or Create an account to join the conversation.
- step4linux
- Offline
- Elite Member
Less
More
- Posts: 163
- Thank you received: 5
06 Aug 2010 10:47 #3605
by step4linux
Replied by step4linux on topic Re:Bipod setup
you may want to look here for a bipod example:
www.linuxcnc.org/docview/html//motion_kinematics.html
www.linuxcnc.org/docview/html//motion_kinematics.html
Please Log in or Create an account to join the conversation.
09 Aug 2010 08:08 #3643
by dab77
Replied by dab77 on topic Re:Bipod setup
Hi step4linux, and thank you for replying.
in a lot of thread there is a suggestion to read that link, so i found it and read it already many times, and if also i found it very interesting, it doesn't help much, because doesn't tell you how to write the .c kins.
I did modify the file trivkins.cand compiled in this way:
then when compiling:
then when i run the machine in joint mode it's all ok, then i zero my axes, but when i try to change into world mode i have this error (in the terminal):
Can you help me?
in a lot of thread there is a suggestion to read that link, so i found it and read it already many times, and if also i found it very interesting, it doesn't help much, because doesn't tell you how to write the .c kins.
I did modify the file trivkins.cand compiled in this way:
********************************************************************/
#include "kinematics.h" /* these decls */
#include "rtapi_math.h"
int kinematicsForward(const double *joints,
EmcPose * pos,
const KINEMATICS_FORWARD_FLAGS * fflags,
KINEMATICS_INVERSE_FLAGS * iflags)
{ double Bx = 800;
double AD2 = joints[0] * joints[0];
double BD2 = joints[1] * joints[1];
double x = (AD2 - BD2 + Bx * Bx) / (2 * Bx);
double y2 = AD2 - x * x;
if(y2 < 0) return -1;
pos->tran.x = x;
pos->tran.y = sqrt(y2);
return 0;
}
int kinematicsInverse(const EmcPose * pos,
double *joints,
const KINEMATICS_INVERSE_FLAGS * iflags,
KINEMATICS_FORWARD_FLAGS * fflags)
{ double Bx = 800;
double x2 = pos->tran.x * pos->tran.x;
double y2 = pos->tran.y * pos->tran.y;
double xx2 = (Bx - pos->tran.x) * (Bx - pos->tran.x);
joints[0] = sqrt(x2 + y2);
joints[1] = sqrt(xx2 + y2);
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("trivkins");
if(comp_id > 0) {
hal_ready(comp_id);
return 0;
}
return comp_id;
}
void rtapi_app_exit(void) { hal_exit(comp_id); }
then when compiling:
dab-cnc@dab-cnc-desktop:~$ sudo comp --compile trivkins.c
make -C /usr/src/linux-headers-2.6.24-16-rtai SUBDIRS=`pwd` CC=gcc V=0 -o /Module.symvers modules
make[1]: ingresso nella directory «/usr/src/linux-headers-2.6.24-16-rtai»
CC [M] /tmp/tmp04BYj4/trivkins.o
Building modules, stage 2.
MODPOST 1 modules
WARNING: "hal_init" [/tmp/tmp04BYj4/trivkins.ko] undefined!
WARNING: "hal_exit" [/tmp/tmp04BYj4/trivkins.ko] undefined!
WARNING: "hal_ready" [/tmp/tmp04BYj4/trivkins.ko] undefined!
CC /tmp/tmp04BYj4/trivkins.mod.o
LD [M] /tmp/tmp04BYj4/trivkins.ko
make[1]: uscita dalla directory «/usr/src/linux-headers-2.6.24-16-rtai»
dab-cnc@dab-cnc-desktop:~$ sudo cp trivkins.ko /usr/realtime-2.6.24-16-rtai/modules/emc2/
dab-cnc@dab-cnc-desktop:~$
then when i run the machine in joint mode it's all ok, then i zero my axes, but when i try to change into world mode i have this error (in the terminal):
dab-cnc@dab-cnc-desktop:~$ emc /home/dab-cnc/emc2/configs/Prova_Bipod/Prova_Bipod.ini
EMC2 - 2.4.3
Machine configuration directory is '/home/dab-cnc/emc2/configs/Prova_Bipod'
Machine configuration file is 'Prova_Bipod.ini'
Starting EMC2...
*********************************WARN_ONCE*********************************
File r300_render.c function r300Fallback line 470
Software fallback:ctx->Line.StippleFlag
***************************************************************************
[b]joint 1 following error
emc/task/taskintf.cc 611: Error on axis 1, command number 111[/b]
Shutting down and cleaning up EMC2...
Cleanup done
dab-cnc@dab-cnc-desktop:~$
Can you help me?
Please Log in or Create an account to join the conversation.
- step4linux
- Offline
- Elite Member
Less
More
- Posts: 163
- Thank you received: 5
09 Aug 2010 08:37 - 09 Aug 2010 08:47 #3644
by step4linux
Replied by step4linux on topic Re:Bipod setup
hi dab,
I did a dualbipod, and started like you did with trivkins.
You can find it here code.google.com/p/emc2hotwinch/ .
From your code two things I see:
1. You must insert the name of your own kinematics here, instead of trivkins:
comp_id = hal_init("trivkins");
EDIT: okay I have seen you still use the the name trivkins for your own kinematics
2. you should leave all the simple equations in the code, like
joints[2] = pos.tran->z
etc
pos.tran->z = joints[2]
etc
for all joints and all axis.
EDIT: of course except for those you have your own equation.
Gerd
I did a dualbipod, and started like you did with trivkins.
You can find it here code.google.com/p/emc2hotwinch/ .
From your code two things I see:
1. You must insert the name of your own kinematics here, instead of trivkins:
comp_id = hal_init("trivkins");
EDIT: okay I have seen you still use the the name trivkins for your own kinematics
2. you should leave all the simple equations in the code, like
joints[2] = pos.tran->z
etc
pos.tran->z = joints[2]
etc
for all joints and all axis.
EDIT: of course except for those you have your own equation.
Gerd
Last edit: 09 Aug 2010 08:47 by step4linux.
Please Log in or Create an account to join the conversation.
09 Aug 2010 09:42 #3647
by dab77
Replied by dab77 on topic Re:Bipod setup
ok, i'm trying to replace the other axes kins.
thanks!
thanks!
Please Log in or Create an account to join the conversation.
09 Aug 2010 09:46 #3648
by dab77
Replied by dab77 on topic Re:Bipod setup
mmmmh.. no. isn't going to work.
it return the same error.
code now is:
any other idea?
it return the same error.
code now is:
#include "kinematics.h" /* these decls */
#include "rtapi_math.h"
int kinematicsForward(const double *joints,
EmcPose * pos,
const KINEMATICS_FORWARD_FLAGS * fflags,
KINEMATICS_INVERSE_FLAGS * iflags)
{ double Bx = 800;
double AD2 = joints[0] * joints[0];
double BD2 = joints[1] * joints[1];
double x = (AD2 - BD2 + Bx * Bx) / (2 * Bx);
double y2 = AD2 - x * x;
if(y2 < 0) return -1;
pos->tran.x = x;
pos->tran.y = sqrt(y2);
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 Bx = 800;
double x2 = pos->tran.x * pos->tran.x;
double y2 = pos->tran.y * pos->tran.y;
double xx2 = (Bx - pos->tran.x) * (Bx - pos->tran.x);
joints[0] = sqrt(x2 + y2);
joints[1] = sqrt(xx2 + y2);
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("trivkins");
if(comp_id > 0) {
hal_ready(comp_id);
return 0;
}
return comp_id;
}
void rtapi_app_exit(void) { hal_exit(comp_id); }
any other idea?
Please Log in or Create an account to join the conversation.
Time to create page: 0.177 seconds