Cinematica diretta e inversa

Sezione dedicata a Linuxcnc
Rispondi
ross
Member
Member
Messaggi: 351
Iscritto il: mercoledì 3 agosto 2011, 23:16
Località: Macerata (MC)

Cinematica diretta e inversa

Messaggio da ross » venerdì 2 maggio 2014, 22:48

Buona sera a tutti,
vorrei condividere con voi la mia esperienza riguardo alla modifica della cinematica diretta e inversa di una normale macchina a controllo numerico cartesiana a 3 assi che ho progettato e costruito.
Nel mio caso specifico ho modificato il file trivkins.c inserendo delle formule matematiche per risolvere un problema di rettilineità degli assi XY, a causa della loro lunghezza. L'asse Y, in particolare, tende ad flettersi quando tutto il carro contenente l'asse Z, le valvole e altre diavolerie arriva a metà corsa. E' una questione di peso, in sostanza.
Dato che non volevo modificare l'originale trivkins.c ho optato per trivkinsr.c, aggiungendo una "r".
Il file è scritto in linguaggio C e ovviamente occorre seguire le regole basilari della programmazione.
Matematicamente parlando la modifica della cinematica consiste nel correggere l'asse Z quando il carro percorre gli assi XY, ho utilizzato la funzione seno unita alla lunghezza degli assi per ottenere la correzione pari a 0 alle estremità (Y0 e Y1985, sempre nel mio caso) e la massima correzione impostabile quando il carro sta a metà corsa, Y992.5.
La stessa cosa viene fatta tenendo conto anche dell'asse X ma in questo caso, quando X0 la correzione è 0 mentre a X massima (860) la correzione è massima.
Sfruttando la funzione seno, a 0° è 0 a 90° è 1 e a 180° ritorna a 0 che moltiplicato per il coefficiente freccia massima di flessione mi da la cercata correzione.
Il kfzx e il kfzy li ho misurati muovendo gli assi della macchina e utilizzando l'originaria cinematica trivkins.c.
Le correzioni derivate dagli assi XY, sommandole, mi agiscono sull'asse Z, correggendolo.

Codice: Seleziona tutto

/********************************************************************
* Descrizione: trivkinsr.c
*   Trivial kinematics R per macchina a 3 assi cartesiani XYZ
*
*   Derivato da "trivkins.c"
*
* Author: Rossano F.
* License: GPL Version 2
* System: Linux
*    
* Copyright (c) 2014 All rights reserved.
*
* Last change:
* rev.1.1 30-04-2014 - correzione su Z per rettilineità asse Y
* kfzx = la freccia massima di flessione dell'asse X, in mm
* kfzy = la freccia massima di flessione dell'asse Y, in mm
* axmax è Pigreco/il campo di lavoro dell'asse X della macchina 
* aymax è Pigreco/il campo di lavoro dell'asse Y della macchina 
* la funzione seno usa i radianti e non i gradi
* xmax e ymax sono i limiti della macchina.
* sudo comp --install trivkinsr.c (il file deve stare nella home)
********************************************************************/

#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 kfzx=1;
    double xmax=860;
    double kfzy=3;
    double ymax=1985;
    double axmax=(3.141592654/2)/xmax;
    double alpha;
    double aymax=3.141592654/ymax;
    double beta;
    alpha=axmax*joints[0];
    beta=aymax*joints[1];
    pos->tran.x = joints[0];
    pos->tran.y = joints[1];
    pos->tran.z = joints[2]-kfzx*sin(alpha)-kfzy*sin(beta);
    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 kfzx=1;
    double xmax=860;
    double kfzy=3;
    double ymax=1985;
    double axmax=(3.141592654/2)/xmax;
    double alpha;
    double aymax=3.141592654/ymax;
    double beta;
    alpha=axmax*pos->tran.x;
    beta=aymax*pos->tran.y;
    joints[0] = pos->tran.x;
    joints[1] = pos->tran.y;
    joints[2] = pos->tran.z+kfzx*sin(alpha)+kfzy*sin(beta);
    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_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("trivkinsr");
    if(comp_id > 0) {
	hal_ready(comp_id);
	return 0;
    }
    return comp_id;
}

void rtapi_app_exit(void) { hal_exit(comp_id); }
Da notare l'aggiunta #include "rtapi_math.h" per poter usare la funzione seno e l'ultimo blocco di istruzioni, contiene la riga "comp_id = hal_init("trivkinsr");" e se ci fate caso tra le virgolette c'è il nome del file a cui ho aggiunto la "r", senza il nuovo componente non viene riconosciuto una volta chiamato dal file hal della configurazione della macchina con il solito loadrt.

Cinematica diretta:
conoscendo joint[0] e joint[1] ottengo Z.

Codice: Seleziona tutto

pos->tran.z = joints[2]-kfzx*sin(alpha)-kfzy*sin(beta);
Cinematica indiretta:
conoscendo pos->tran.x e pos->tran.y ottengo joints[2].

Codice: Seleziona tutto

joints[2] = pos->tran.z+kfzx*sin(alpha)+kfzy*sin(beta);
Tutto il sistema modificato funziona egregiamente, l'ho testato un paio d'ore fa ..prima di scrivere una cavolata :D

C'è solo una cosa che non mi torna, come mai quando muovo gli assi XY con i tasti della tastiera l'asse Z non viene corretto? In mdi, come in auto, va benissimo e in genere, per questa macchina cn non dovrei usare il jog, è solo per curiosità.

Aggiungo anche che sono molto soddisfatto di aver scelto Linuxcnc per il controllo numerico, dubito che altri software possono arrivare a tanto.

Grazie.
Ross

Avatar utente
Zebrauno
God
God
Messaggi: 9670
Iscritto il: venerdì 18 settembre 2009, 18:24
Località: Savigliano/Torino
Contatta:

Re: Cinematica diretta e inversa

Messaggio da Zebrauno » sabato 3 maggio 2014, 12:08

Mi piace sia l'approccio che lo svolgimento =D> , ho scorso il codice velocemente e non ho visto formule per applicare la teoria della trave (equazione della linea elastica riferita alla tua struttura etc.).

Hai gia' verificato in modo empirico se le correzioni nel codice ottengono risultati coerenti anche nella realta?

Ho affrontato lo stesso problema su un altro controllo, Kflop, e per verificare tutto scandisco una linea di punti sopra un piano di riscontro, in modo da vedere anche gli errori di linearita' che dipendono dal montaggio degli scorrimenti.

Ottimo lavoro, da seguire.

ciao

ross
Member
Member
Messaggi: 351
Iscritto il: mercoledì 3 agosto 2011, 23:16
Località: Macerata (MC)

Re: Cinematica diretta e inversa

Messaggio da ross » sabato 3 maggio 2014, 18:23

Grazie.
Si ho verificato fisicamente ed ho ottenuto il risultato che cercavo.
Tramite la semplice comparazione con un oggetto di spessore definito ho verificato col metodo pratico "passa non passa" poiché non mi occorre una grossa precisione, diciamo +/-0.25mm sono più che sufficienti per il lavoro che svolge.

Ciao
Ross

Rispondi

Torna a “Linuxcnc”