Robot kinematics model fully working

Dependencies:   mbed

Committer:
cmaas
Date:
Wed Oct 31 19:21:30 2018 +0000
Revision:
3:4055a919e936
Parent:
2:51c8b5d9cab0
correcte kinematics voor 3 motoren

Who changed what in which revision?

UserRevisionLine numberNew contents of line
cmaas 0:3325a6a3a912 1 // EMG naar hoek
cmaas 0:3325a6a3a912 2
cmaas 2:51c8b5d9cab0 3 #include "stdio.h" // for printng
cmaas 0:3325a6a3a912 4 #define _USE_MATH_DEFINES
cmaas 0:3325a6a3a912 5
cmaas 0:3325a6a3a912 6 #include <math.h>
cmaas 0:3325a6a3a912 7 #define M_PI 3.14159265358979323846 /* pi */
cmaas 0:3325a6a3a912 8
cmaas 0:3325a6a3a912 9 //defining constants
cmaas 0:3325a6a3a912 10 const float la = 0.256; // lengte actieve arm
cmaas 0:3325a6a3a912 11 const float lp = 0.21; // lengte passieve arm
cmaas 0:3325a6a3a912 12 const float rp = 0.052; // straal van midden end effector tot hoekpunt
cmaas 0:3325a6a3a912 13 const float rm = 0.23; // straal van global midden tot motor
cmaas 0:3325a6a3a912 14 const float a = 0.09; // zijde van de driehoek
cmaas 0:3325a6a3a912 15 const float xas = 0.40; // afstand van motor 1 tot motor 3
cmaas 0:3325a6a3a912 16 const float yas = 0.346; // afstand van xas tot motor 2
cmaas 0:3325a6a3a912 17 const float thetap = 0; // rotatiehoek van de end effector
cmaas 0:3325a6a3a912 18
cmaas 0:3325a6a3a912 19 //motor locatie
cmaas 0:3325a6a3a912 20 const int a1x = 0; //x locatie motor 1
cmaas 0:3325a6a3a912 21 const int a1y = 0; //y locatie motor 1
cmaas 0:3325a6a3a912 22 const float a2x = (0.5)*xas; // x locatie motor 2
cmaas 0:3325a6a3a912 23 const float a2y = yas; // y locatie motor 2
cmaas 0:3325a6a3a912 24 const float a3x = xas; // x locatie motor 3
cmaas 0:3325a6a3a912 25 const int a3y = 0; // y locatie motor 3
cmaas 0:3325a6a3a912 26
cmaas 0:3325a6a3a912 27 // script voor het bepalen van de desired position aan de hand van emg (1/0)
cmaas 0:3325a6a3a912 28
cmaas 0:3325a6a3a912 29 // Dit moet dus uit EMG script
cmaas 0:3325a6a3a912 30 int EMGxplus;
cmaas 0:3325a6a3a912 31 int EMGxmin ;
cmaas 0:3325a6a3a912 32 int EMGyplus;
cmaas 0:3325a6a3a912 33 int EMGymin ;
cmaas 0:3325a6a3a912 34
cmaas 0:3325a6a3a912 35 // Dit moet experimenteel geperfectioneerd worden
cmaas 0:3325a6a3a912 36 float tijdstap = 0.05; //nu wss heel langzaam, kan miss omhoog
cmaas 0:3325a6a3a912 37 float v = 0.1; // snelheid kan wss ook hoger
cmaas 0:3325a6a3a912 38
cmaas 0:3325a6a3a912 39 float px = 0.2; //starting x
cmaas 3:4055a919e936 40 float py = 0.155; // starting y+
cmaas 3:4055a919e936 41
cmaas 3:4055a919e936 42 // verschil horizontale as met de actieve arm
cmaas 3:4055a919e936 43 float da1 = 1.619685; // verschil a1 hoek en motor
cmaas 3:4055a919e936 44 float da2 = -0.609780;
cmaas 3:4055a919e936 45 float da3 = 3.372859;
cmaas 0:3325a6a3a912 46
cmaas 0:3325a6a3a912 47 // limits (since no forward kinematics)
cmaas 0:3325a6a3a912 48 float upperxlim = 0.36; //niet helemaal naar requierments ff kijken of ie groter kan
cmaas 0:3325a6a3a912 49 float lowerxlim = 0.04;
cmaas 0:3325a6a3a912 50 float upperylim = 0.30;
cmaas 0:3325a6a3a912 51 float lowerylim = 0.04;
cmaas 0:3325a6a3a912 52
cmaas 0:3325a6a3a912 53 // functie x positie
cmaas 0:3325a6a3a912 54 float positionx(int EMGxplus,int EMGxmin)
cmaas 0:3325a6a3a912 55 {
cmaas 0:3325a6a3a912 56 float EMGx = EMGxplus - EMGxmin;
cmaas 0:3325a6a3a912 57
cmaas 0:3325a6a3a912 58 float verplaatsingx = EMGx * tijdstap * v;
cmaas 0:3325a6a3a912 59 float pxnieuw = px + verplaatsingx;
cmaas 0:3325a6a3a912 60 // x limit
cmaas 0:3325a6a3a912 61 if (pxnieuw <= upperxlim && pxnieuw >= lowerxlim)
cmaas 0:3325a6a3a912 62 {
cmaas 0:3325a6a3a912 63 px = pxnieuw;
cmaas 0:3325a6a3a912 64 }
cmaas 0:3325a6a3a912 65 else
cmaas 0:3325a6a3a912 66 {
cmaas 0:3325a6a3a912 67 if (pxnieuw >= lowerxlim)
cmaas 0:3325a6a3a912 68 {
cmaas 0:3325a6a3a912 69 px = upperxlim;
cmaas 0:3325a6a3a912 70 }
cmaas 0:3325a6a3a912 71 else
cmaas 0:3325a6a3a912 72 {
cmaas 0:3325a6a3a912 73 px = lowerxlim;
cmaas 0:3325a6a3a912 74 }
cmaas 0:3325a6a3a912 75 }
cmaas 0:3325a6a3a912 76 printf("X eindpunt (%f) en verplaatsing: (%f)\n\r",px,verplaatsingx);
cmaas 0:3325a6a3a912 77 return px;
cmaas 0:3325a6a3a912 78 }
cmaas 0:3325a6a3a912 79
cmaas 0:3325a6a3a912 80 // functie y positie
cmaas 0:3325a6a3a912 81 float positiony(int EMGyplus,int EMGymin)
cmaas 0:3325a6a3a912 82 {
cmaas 0:3325a6a3a912 83 float EMGy = EMGyplus - EMGymin;
cmaas 0:3325a6a3a912 84
cmaas 0:3325a6a3a912 85 float verplaatsingy = EMGy * tijdstap * v;
cmaas 0:3325a6a3a912 86 float pynieuw = py + verplaatsingy;
cmaas 0:3325a6a3a912 87
cmaas 0:3325a6a3a912 88 // y limit
cmaas 0:3325a6a3a912 89 if (pynieuw <= upperylim && pynieuw >= lowerylim)
cmaas 0:3325a6a3a912 90 {
cmaas 0:3325a6a3a912 91 py = pynieuw;
cmaas 0:3325a6a3a912 92 }
cmaas 0:3325a6a3a912 93 else
cmaas 0:3325a6a3a912 94 {
cmaas 0:3325a6a3a912 95 if (pynieuw >= lowerylim)
cmaas 0:3325a6a3a912 96 {
cmaas 0:3325a6a3a912 97 py = upperylim;
cmaas 0:3325a6a3a912 98 }
cmaas 0:3325a6a3a912 99 else
cmaas 0:3325a6a3a912 100 {
cmaas 0:3325a6a3a912 101 py = lowerylim;
cmaas 0:3325a6a3a912 102 }
cmaas 0:3325a6a3a912 103 }
cmaas 0:3325a6a3a912 104 printf("Y eindpunt (%f) en verplaatsing: (%f) \n\r",py,verplaatsingy);
cmaas 0:3325a6a3a912 105 return (py);
cmaas 0:3325a6a3a912 106 }
cmaas 0:3325a6a3a912 107
cmaas 0:3325a6a3a912 108
cmaas 0:3325a6a3a912 109 // functie berekenen hoeken
cmaas 1:d45695ec7da9 110 // arm 1 --> reference angle motor 1
cmaas 0:3325a6a3a912 111 float hoek1(float px, float py) // input: ref x, ref y
cmaas 0:3325a6a3a912 112 {
cmaas 0:3325a6a3a912 113 float c1x = px - rp * cos(thetap +(M_PI/6)); // x locatie hoekpunt end-effector
cmaas 0:3325a6a3a912 114 float c1y = py - rp*sin(thetap+(M_PI/6)); // y locatie hoekpunt end-effector
cmaas 0:3325a6a3a912 115 float alpha1 = atan2((c1y-a1y),(c1x-a1x)); // hoek tussen horizontaal en lijn van motor naar bijbehorende end-effector punt
cmaas 0:3325a6a3a912 116 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
cmaas 3:4055a919e936 117 float a1 = alpha1 + psi1 - da1; //hoek tussen horizontaal en actieve arm
cmaas 0:3325a6a3a912 118 printf("arm 1 = %f \n\r",a1);
cmaas 0:3325a6a3a912 119 return a1;
cmaas 0:3325a6a3a912 120 }
cmaas 0:3325a6a3a912 121
cmaas 1:d45695ec7da9 122 // arm 2 --> reference angle motor 2
cmaas 0:3325a6a3a912 123 float hoek2(float px, float py)
cmaas 0:3325a6a3a912 124 {
cmaas 0:3325a6a3a912 125 float c2x = px - rp * cos(thetap -(M_PI/2));
cmaas 0:3325a6a3a912 126 float c2y = py - rp*sin(thetap-(M_PI/2));
cmaas 0:3325a6a3a912 127 float alpha2 = atan2((c2y-a2y),(c2x-a2x));
cmaas 0:3325a6a3a912 128 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) )));
cmaas 3:4055a919e936 129 float a2 = alpha2 + psi2 - da2;
cmaas 0:3325a6a3a912 130 printf("arm 2 = %f \n\r",a2);
cmaas 0:3325a6a3a912 131 return a2;
cmaas 0:3325a6a3a912 132 }
cmaas 0:3325a6a3a912 133
cmaas 1:d45695ec7da9 134 //arm 3 --> reference angle motor 3
cmaas 0:3325a6a3a912 135 float hoek3(float px, float py)
cmaas 0:3325a6a3a912 136 {
cmaas 0:3325a6a3a912 137 float c3x = px - rp * cos(thetap +(5*M_PI/6));
cmaas 0:3325a6a3a912 138 float c3y = py - rp*sin(thetap+(5*M_PI/6));
cmaas 0:3325a6a3a912 139 float alpha3 = atan2((c3y-a3y),(c3x-a3x));
cmaas 0:3325a6a3a912 140 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) )));
cmaas 3:4055a919e936 141 float a3 = alpha3 + psi3 - da3;
cmaas 0:3325a6a3a912 142 printf("arm 3 = %f \n\r",a3);
cmaas 0:3325a6a3a912 143 return a3;
cmaas 0:3325a6a3a912 144 }
cmaas 0:3325a6a3a912 145
cmaas 0:3325a6a3a912 146
cmaas 0:3325a6a3a912 147 // MAIN
cmaas 0:3325a6a3a912 148 int main()
cmaas 0:3325a6a3a912 149 {
cmaas 0:3325a6a3a912 150
cmaas 0:3325a6a3a912 151 // berekenen positie
cmaas 3:4055a919e936 152 float px = positionx(0,0); // EMG: +x, -x
cmaas 3:4055a919e936 153 float py = positiony(0,0); // EMG: +y, -y
cmaas 0:3325a6a3a912 154 printf("positie (%f,%f)\n\r",px,py);
cmaas 0:3325a6a3a912 155
cmaas 0:3325a6a3a912 156 // berekenen hoeken
cmaas 0:3325a6a3a912 157 float a1 = hoek1(px, py);
cmaas 0:3325a6a3a912 158 float a2 = hoek2(px, py);
cmaas 0:3325a6a3a912 159 float a3 = hoek3(px, py);
cmaas 0:3325a6a3a912 160
cmaas 0:3325a6a3a912 161 printf("hoek(%f,%f,%f)\n\r",a1,a2,a3);
cmaas 0:3325a6a3a912 162
cmaas 0:3325a6a3a912 163 return 0;
cmaas 0:3325a6a3a912 164
cmaas 0:3325a6a3a912 165 }