Casper Maas
/
Robot_Kinematics
Robot kinematics model fully working
main.cpp
- Committer:
- cmaas
- Date:
- 2018-10-31
- Revision:
- 3:4055a919e936
- Parent:
- 2:51c8b5d9cab0
File content as of revision 3:4055a919e936:
// EMG naar hoek #include "stdio.h" // for printng #define _USE_MATH_DEFINES #include <math.h> #define M_PI 3.14159265358979323846 /* pi */ //defining constants const float la = 0.256; // lengte actieve arm const float lp = 0.21; // lengte passieve arm const float rp = 0.052; // straal van midden end effector tot hoekpunt const float rm = 0.23; // straal van global midden tot motor const float a = 0.09; // zijde van de driehoek const float xas = 0.40; // afstand van motor 1 tot motor 3 const float yas = 0.346; // afstand van xas tot motor 2 const float thetap = 0; // rotatiehoek van de end effector //motor locatie const int a1x = 0; //x locatie motor 1 const int a1y = 0; //y locatie motor 1 const float a2x = (0.5)*xas; // x locatie motor 2 const float a2y = yas; // y locatie motor 2 const float a3x = xas; // x locatie motor 3 const int a3y = 0; // y locatie motor 3 // script voor het bepalen van de desired position aan de hand van emg (1/0) // Dit moet dus uit EMG script int EMGxplus; int EMGxmin ; int EMGyplus; int EMGymin ; // Dit moet experimenteel geperfectioneerd worden float tijdstap = 0.05; //nu wss heel langzaam, kan miss omhoog float v = 0.1; // snelheid kan wss ook hoger float px = 0.2; //starting x float py = 0.155; // starting y+ // verschil horizontale as met de actieve arm float da1 = 1.619685; // verschil a1 hoek en motor float da2 = -0.609780; float da3 = 3.372859; // limits (since no forward kinematics) float upperxlim = 0.36; //niet helemaal naar requierments ff kijken of ie groter kan float lowerxlim = 0.04; float upperylim = 0.30; float lowerylim = 0.04; // functie x positie float positionx(int EMGxplus,int EMGxmin) { float EMGx = EMGxplus - EMGxmin; float verplaatsingx = EMGx * tijdstap * v; float pxnieuw = px + verplaatsingx; // x limit if (pxnieuw <= upperxlim && pxnieuw >= lowerxlim) { px = pxnieuw; } else { if (pxnieuw >= lowerxlim) { px = upperxlim; } else { px = lowerxlim; } } printf("X eindpunt (%f) en verplaatsing: (%f)\n\r",px,verplaatsingx); return px; } // functie y positie float positiony(int EMGyplus,int EMGymin) { float EMGy = EMGyplus - EMGymin; float verplaatsingy = EMGy * tijdstap * v; float pynieuw = py + verplaatsingy; // y limit if (pynieuw <= upperylim && pynieuw >= lowerylim) { py = pynieuw; } else { if (pynieuw >= lowerylim) { py = upperylim; } else { py = lowerylim; } } printf("Y eindpunt (%f) en verplaatsing: (%f) \n\r",py,verplaatsingy); return (py); } // functie berekenen hoeken // arm 1 --> reference angle motor 1 float hoek1(float px, float py) // input: ref x, ref y { float c1x = px - rp * cos(thetap +(M_PI/6)); // x locatie hoekpunt end-effector float c1y = py - rp*sin(thetap+(M_PI/6)); // y locatie hoekpunt end-effector float alpha1 = atan2((c1y-a1y),(c1x-a1x)); // hoek tussen horizontaal en lijn van motor naar bijbehorende end-effector punt float psi1 = acos(( pow(la,2)-pow(lp,2)+pow((c1x-a1x),2)+pow((c1y-a1y),2))/(2*la*sqrt(pow ((c1x-a1x),2)+pow((c1y-a1y),2) ))); //Hoek tussen lijn van motor naar bijbehorende end=effector punt en actieve arm float a1 = alpha1 + psi1 - da1; //hoek tussen horizontaal en actieve arm printf("arm 1 = %f \n\r",a1); return a1; } // arm 2 --> reference angle motor 2 float hoek2(float px, float py) { float c2x = px - rp * cos(thetap -(M_PI/2)); float c2y = py - rp*sin(thetap-(M_PI/2)); float alpha2 = atan2((c2y-a2y),(c2x-a2x)); float psi2 = acos(( pow(la,2)-pow(lp,2)+pow((c2x-a2x),2)+pow((c2y-a2y),2))/(2*la*sqrt(pow ((c2x-a2x),2)+pow((c2y-a2y),2) ))); float a2 = alpha2 + psi2 - da2; printf("arm 2 = %f \n\r",a2); return a2; } //arm 3 --> reference angle motor 3 float hoek3(float px, float py) { float c3x = px - rp * cos(thetap +(5*M_PI/6)); float c3y = py - rp*sin(thetap+(5*M_PI/6)); float alpha3 = atan2((c3y-a3y),(c3x-a3x)); float psi3 = acos(( pow(la,2)-pow(lp,2)+pow((c3x-a3x),2)+pow((c3y-a3y),2))/(2*la*sqrt(pow ((c3x-a3x),2)+pow((c3y-a3y),2) ))); float a3 = alpha3 + psi3 - da3; printf("arm 3 = %f \n\r",a3); return a3; } // MAIN int main() { // berekenen positie float px = positionx(0,0); // EMG: +x, -x float py = positiony(0,0); // EMG: +y, -y printf("positie (%f,%f)\n\r",px,py); // berekenen hoeken float a1 = hoek1(px, py); float a2 = hoek2(px, py); float a3 = hoek3(px, py); printf("hoek(%f,%f,%f)\n\r",a1,a2,a3); return 0; }