Robot kinematics model fully working
Embed:
(wiki syntax)
Show/hide line numbers
main.cpp
00001 // EMG naar hoek 00002 00003 #include "stdio.h" // for printng 00004 #define _USE_MATH_DEFINES 00005 00006 #include <math.h> 00007 #define M_PI 3.14159265358979323846 /* pi */ 00008 00009 //defining constants 00010 const float la = 0.256; // lengte actieve arm 00011 const float lp = 0.21; // lengte passieve arm 00012 const float rp = 0.052; // straal van midden end effector tot hoekpunt 00013 const float rm = 0.23; // straal van global midden tot motor 00014 const float a = 0.09; // zijde van de driehoek 00015 const float xas = 0.40; // afstand van motor 1 tot motor 3 00016 const float yas = 0.346; // afstand van xas tot motor 2 00017 const float thetap = 0; // rotatiehoek van de end effector 00018 00019 //motor locatie 00020 const int a1x = 0; //x locatie motor 1 00021 const int a1y = 0; //y locatie motor 1 00022 const float a2x = (0.5)*xas; // x locatie motor 2 00023 const float a2y = yas; // y locatie motor 2 00024 const float a3x = xas; // x locatie motor 3 00025 const int a3y = 0; // y locatie motor 3 00026 00027 // script voor het bepalen van de desired position aan de hand van emg (1/0) 00028 00029 // Dit moet dus uit EMG script 00030 int EMGxplus; 00031 int EMGxmin ; 00032 int EMGyplus; 00033 int EMGymin ; 00034 00035 // Dit moet experimenteel geperfectioneerd worden 00036 float tijdstap = 0.05; //nu wss heel langzaam, kan miss omhoog 00037 float v = 0.1; // snelheid kan wss ook hoger 00038 00039 float px = 0.2; //starting x 00040 float py = 0.155; // starting y+ 00041 00042 // verschil horizontale as met de actieve arm 00043 float da1 = 1.619685; // verschil a1 hoek en motor 00044 float da2 = -0.609780; 00045 float da3 = 3.372859; 00046 00047 // limits (since no forward kinematics) 00048 float upperxlim = 0.36; //niet helemaal naar requierments ff kijken of ie groter kan 00049 float lowerxlim = 0.04; 00050 float upperylim = 0.30; 00051 float lowerylim = 0.04; 00052 00053 // functie x positie 00054 float positionx(int EMGxplus,int EMGxmin) 00055 { 00056 float EMGx = EMGxplus - EMGxmin; 00057 00058 float verplaatsingx = EMGx * tijdstap * v; 00059 float pxnieuw = px + verplaatsingx; 00060 // x limit 00061 if (pxnieuw <= upperxlim && pxnieuw >= lowerxlim) 00062 { 00063 px = pxnieuw; 00064 } 00065 else 00066 { 00067 if (pxnieuw >= lowerxlim) 00068 { 00069 px = upperxlim; 00070 } 00071 else 00072 { 00073 px = lowerxlim; 00074 } 00075 } 00076 printf("X eindpunt (%f) en verplaatsing: (%f)\n\r",px,verplaatsingx); 00077 return px; 00078 } 00079 00080 // functie y positie 00081 float positiony(int EMGyplus,int EMGymin) 00082 { 00083 float EMGy = EMGyplus - EMGymin; 00084 00085 float verplaatsingy = EMGy * tijdstap * v; 00086 float pynieuw = py + verplaatsingy; 00087 00088 // y limit 00089 if (pynieuw <= upperylim && pynieuw >= lowerylim) 00090 { 00091 py = pynieuw; 00092 } 00093 else 00094 { 00095 if (pynieuw >= lowerylim) 00096 { 00097 py = upperylim; 00098 } 00099 else 00100 { 00101 py = lowerylim; 00102 } 00103 } 00104 printf("Y eindpunt (%f) en verplaatsing: (%f) \n\r",py,verplaatsingy); 00105 return (py); 00106 } 00107 00108 00109 // functie berekenen hoeken 00110 // arm 1 --> reference angle motor 1 00111 float hoek1(float px, float py) // input: ref x, ref y 00112 { 00113 float c1x = px - rp * cos(thetap +(M_PI/6)); // x locatie hoekpunt end-effector 00114 float c1y = py - rp*sin(thetap+(M_PI/6)); // y locatie hoekpunt end-effector 00115 float alpha1 = atan2((c1y-a1y),(c1x-a1x)); // hoek tussen horizontaal en lijn van motor naar bijbehorende end-effector punt 00116 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 00117 float a1 = alpha1 + psi1 - da1; //hoek tussen horizontaal en actieve arm 00118 printf("arm 1 = %f \n\r",a1); 00119 return a1; 00120 } 00121 00122 // arm 2 --> reference angle motor 2 00123 float hoek2(float px, float py) 00124 { 00125 float c2x = px - rp * cos(thetap -(M_PI/2)); 00126 float c2y = py - rp*sin(thetap-(M_PI/2)); 00127 float alpha2 = atan2((c2y-a2y),(c2x-a2x)); 00128 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) ))); 00129 float a2 = alpha2 + psi2 - da2; 00130 printf("arm 2 = %f \n\r",a2); 00131 return a2; 00132 } 00133 00134 //arm 3 --> reference angle motor 3 00135 float hoek3(float px, float py) 00136 { 00137 float c3x = px - rp * cos(thetap +(5*M_PI/6)); 00138 float c3y = py - rp*sin(thetap+(5*M_PI/6)); 00139 float alpha3 = atan2((c3y-a3y),(c3x-a3x)); 00140 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) ))); 00141 float a3 = alpha3 + psi3 - da3; 00142 printf("arm 3 = %f \n\r",a3); 00143 return a3; 00144 } 00145 00146 00147 // MAIN 00148 int main() 00149 { 00150 00151 // berekenen positie 00152 float px = positionx(0,0); // EMG: +x, -x 00153 float py = positiony(0,0); // EMG: +y, -y 00154 printf("positie (%f,%f)\n\r",px,py); 00155 00156 // berekenen hoeken 00157 float a1 = hoek1(px, py); 00158 float a2 = hoek2(px, py); 00159 float a3 = hoek3(px, py); 00160 00161 printf("hoek(%f,%f,%f)\n\r",a1,a2,a3); 00162 00163 return 0; 00164 00165 }
Generated on Wed Jul 20 2022 01:48:02 by
1.7.2