working PID + Kinematics + Motorcontrol

Dependencies:   HIDScope MODSERIAL QEI biquadFilter mbed

Committer:
cmaas
Date:
Wed Oct 31 23:05:26 2018 +0000
Revision:
8:cfe7ad86837c
Parent:
7:83a69ca630bc
Child:
9:59dc4c12e4ee
volledig functioneel

Who changed what in which revision?

UserRevisionLine numberNew contents of line
cmaas 0:a6f2b6cc83ca 1 // KINEMATICS + PID + MOTOR CONTROL
cmaas 0:a6f2b6cc83ca 2
cmaas 0:a6f2b6cc83ca 3 //----------------~INITIATING-------------------------
cmaas 0:a6f2b6cc83ca 4 #include "mbed.h"
cmaas 0:a6f2b6cc83ca 5
cmaas 0:a6f2b6cc83ca 6 // KINEMATICS -- DEPENDENCIES
cmaas 0:a6f2b6cc83ca 7 #include "stdio.h"
cmaas 0:a6f2b6cc83ca 8 #define _USE_MATH_DEFINES
cmaas 0:a6f2b6cc83ca 9 #include <math.h>
cmaas 0:a6f2b6cc83ca 10 #define M_PI 3.14159265358979323846 /* pi */
cmaas 0:a6f2b6cc83ca 11
cmaas 0:a6f2b6cc83ca 12 // PID CONTROLLER -- DEPENDENCIES
cmaas 0:a6f2b6cc83ca 13 #include "BiQuad.h"
cmaas 0:a6f2b6cc83ca 14 #include "QEI.h"
cmaas 0:a6f2b6cc83ca 15 #include "MODSERIAL.h"
cmaas 0:a6f2b6cc83ca 16 #include "HIDScope.h"
cmaas 0:a6f2b6cc83ca 17 //#include "Math.h"
cmaas 0:a6f2b6cc83ca 18
cmaas 0:a6f2b6cc83ca 19 // PID CONTROLLER -- PIN DEFENITIONS
cmaas 0:a6f2b6cc83ca 20 AnalogIn button2(A4);
cmaas 2:44758d95cb0b 21 AnalogIn button1(A3);
cmaas 4:85770b268599 22
cmaas 0:a6f2b6cc83ca 23 DigitalOut directionpin1(D7); // motor 1
cmaas 4:85770b268599 24 DigitalOut directionpin2(D4); // motor 2
cmaas 5:a54ea6514bc5 25 DigitalOut directionpin3(D13); // motor 3
cmaas 0:a6f2b6cc83ca 26 PwmOut pwmpin1(D6); // motor 1
cmaas 4:85770b268599 27 PwmOut pwmpin2(D5); // motor 2
cmaas 5:a54ea6514bc5 28 PwmOut pwmpin3(D12); // motor 3
cmaas 0:a6f2b6cc83ca 29
cmaas 0:a6f2b6cc83ca 30 QEI encoder1 (D9, D8, NC, 8400, QEI::X4_ENCODING);
cmaas 4:85770b268599 31 QEI encoder2 (D11, D10, NC, 8400, QEI::X4_ENCODING); // motor 2
cmaas 5:a54ea6514bc5 32 QEI encoder3 (D3, D2, NC, 8400, QEI::X4_ENCODING); // motor 3
cmaas 0:a6f2b6cc83ca 33 MODSERIAL pc(USBTX, USBRX);
cmaas 0:a6f2b6cc83ca 34 HIDScope scope(2);
cmaas 0:a6f2b6cc83ca 35
cmaas 0:a6f2b6cc83ca 36 // TICKERS
cmaas 0:a6f2b6cc83ca 37 Ticker ref_rot;
cmaas 0:a6f2b6cc83ca 38 Ticker show_counts;
cmaas 0:a6f2b6cc83ca 39 Ticker Scope_Data;
cmaas 0:a6f2b6cc83ca 40
cmaas 0:a6f2b6cc83ca 41 //----------------GLOBALS--------------------------
cmaas 0:a6f2b6cc83ca 42
cmaas 0:a6f2b6cc83ca 43 // CONSTANTS PID CONTROLLER
cmaas 0:a6f2b6cc83ca 44 double PI = M_PI;// CHANGE THIS INTO M_PI
cmaas 2:44758d95cb0b 45 double Kp = 14; //200 , 50
cmaas 0:a6f2b6cc83ca 46 double Ki = 0; //1, 0.5
cmaas 2:44758d95cb0b 47 double Kd = 3; //200, 10
cmaas 0:a6f2b6cc83ca 48 double Ts = 0.1; // Sample time in seconds
cmaas 0:a6f2b6cc83ca 49 double reference_rotation; //define as radians
cmaas 0:a6f2b6cc83ca 50 double motor_position;
cmaas 0:a6f2b6cc83ca 51 bool AlwaysTrue;
cmaas 0:a6f2b6cc83ca 52
cmaas 0:a6f2b6cc83ca 53 //CONSTANTS KINEMATICS
cmaas 0:a6f2b6cc83ca 54 // constants
cmaas 0:a6f2b6cc83ca 55 const float la = 0.256; // lengte actieve arm
cmaas 0:a6f2b6cc83ca 56 const float lp = 0.21; // lengte passieve arm
cmaas 0:a6f2b6cc83ca 57 const float rp = 0.052; // straal van midden end effector tot hoekpunt
cmaas 0:a6f2b6cc83ca 58 const float rm = 0.23; // straal van global midden tot motor
cmaas 0:a6f2b6cc83ca 59 const float a = 0.09; // zijde van de driehoek
cmaas 0:a6f2b6cc83ca 60 const float xas = 0.40; // afstand van motor 1 tot motor 3
cmaas 0:a6f2b6cc83ca 61 const float yas = 0.346; // afstand van xas tot motor 2
cmaas 0:a6f2b6cc83ca 62 const float thetap = 0; // rotatiehoek van de end effector
cmaas 0:a6f2b6cc83ca 63
cmaas 6:6545e197858a 64
cmaas 0:a6f2b6cc83ca 65 // motor locatie
cmaas 0:a6f2b6cc83ca 66 const int a1x = 0; //x locatie motor 1
cmaas 0:a6f2b6cc83ca 67 const int a1y = 0; //y locatie motor 1
cmaas 0:a6f2b6cc83ca 68 const float a2x = (0.5)*xas; // x locatie motor 2
cmaas 0:a6f2b6cc83ca 69 const float a2y = yas; // y locatie motor 2
cmaas 0:a6f2b6cc83ca 70 const float a3x = xas; // x locatie motor 3
cmaas 0:a6f2b6cc83ca 71 const int a3y = 0; // y locatie motor 3
cmaas 0:a6f2b6cc83ca 72
cmaas 0:a6f2b6cc83ca 73 // script voor het bepalen van de desired position aan de hand van emg (1/0)
cmaas 0:a6f2b6cc83ca 74
cmaas 0:a6f2b6cc83ca 75 // EMG OUTPUT
cmaas 0:a6f2b6cc83ca 76 int EMGxplus;
cmaas 0:a6f2b6cc83ca 77 int EMGxmin ;
cmaas 0:a6f2b6cc83ca 78 int EMGyplus;
cmaas 0:a6f2b6cc83ca 79 int EMGymin ;
cmaas 0:a6f2b6cc83ca 80
cmaas 0:a6f2b6cc83ca 81 // Dit moet experimenteel geperfectioneerd worden
cmaas 8:cfe7ad86837c 82 float tijdstap = 0.005; //nu wss heel langzaam, kan miss omhoog KEER V GEEFT VERANDERING IN POSITIE
cmaas 0:a6f2b6cc83ca 83 float v = 0.1; // snelheid kan wss ook hoger
cmaas 0:a6f2b6cc83ca 84
cmaas 8:cfe7ad86837c 85 float px = 0.2; //starting x // BOUNDARIES
cmaas 8:cfe7ad86837c 86 float py = 0.155; // starting y // BOUNDARIES
cmaas 0:a6f2b6cc83ca 87
cmaas 6:6545e197858a 88 // verschil horizontale as met de actieve arm
cmaas 6:6545e197858a 89 float da1 = 1.619685; // verschil a1 hoek en motor
cmaas 6:6545e197858a 90 float da2 = -0.609780;
cmaas 6:6545e197858a 91 float da3 = 3.372859;
cmaas 6:6545e197858a 92
cmaas 0:a6f2b6cc83ca 93 // limits (since no forward kinematics)
cmaas 8:cfe7ad86837c 94 float upperxlim = 0.25; //36, 0.04, 0.315, -0.085niet helemaal naar requierments ff kijken of ie groter kan
cmaas 8:cfe7ad86837c 95 float lowerxlim = 0.15;
cmaas 8:cfe7ad86837c 96 float upperylim = 0.20;
cmaas 8:cfe7ad86837c 97 float lowerylim = 0.10;
cmaas 0:a6f2b6cc83ca 98
cmaas 0:a6f2b6cc83ca 99
cmaas 0:a6f2b6cc83ca 100 //----------------FUNCTIONS--------------------------
cmaas 0:a6f2b6cc83ca 101
cmaas 0:a6f2b6cc83ca 102 // ~~~~~~~~~~~~~~ROBOT KINEMATICS ~~~~~~~~~~~~~~~~~~
cmaas 0:a6f2b6cc83ca 103
cmaas 0:a6f2b6cc83ca 104 // functie x positie
cmaas 0:a6f2b6cc83ca 105 float positionx(int EMGxplus,int EMGxmin)
cmaas 0:a6f2b6cc83ca 106 {
cmaas 0:a6f2b6cc83ca 107 float EMGx = EMGxplus - EMGxmin;
cmaas 0:a6f2b6cc83ca 108
cmaas 0:a6f2b6cc83ca 109 float verplaatsingx = EMGx * tijdstap * v;
cmaas 0:a6f2b6cc83ca 110 float pxnieuw = px + verplaatsingx;
cmaas 0:a6f2b6cc83ca 111 // x limit
cmaas 0:a6f2b6cc83ca 112 if (pxnieuw <= upperxlim && pxnieuw >= lowerxlim)
cmaas 0:a6f2b6cc83ca 113 {
cmaas 0:a6f2b6cc83ca 114 px = pxnieuw;
cmaas 0:a6f2b6cc83ca 115 }
cmaas 0:a6f2b6cc83ca 116 else
cmaas 0:a6f2b6cc83ca 117 {
cmaas 0:a6f2b6cc83ca 118 if (pxnieuw >= lowerxlim)
cmaas 0:a6f2b6cc83ca 119 {
cmaas 0:a6f2b6cc83ca 120 px = upperxlim;
cmaas 0:a6f2b6cc83ca 121 }
cmaas 0:a6f2b6cc83ca 122 else
cmaas 0:a6f2b6cc83ca 123 {
cmaas 0:a6f2b6cc83ca 124 px = lowerxlim;
cmaas 0:a6f2b6cc83ca 125 }
cmaas 0:a6f2b6cc83ca 126 }
cmaas 0:a6f2b6cc83ca 127 //printf("X eindpunt (%f) en verplaatsing: (%f)\n\r",px,verplaatsingx);
cmaas 0:a6f2b6cc83ca 128 return px;
cmaas 0:a6f2b6cc83ca 129 }
cmaas 0:a6f2b6cc83ca 130
cmaas 0:a6f2b6cc83ca 131
cmaas 0:a6f2b6cc83ca 132 // functie y positie
cmaas 0:a6f2b6cc83ca 133 float positiony(int EMGyplus,int EMGymin)
cmaas 0:a6f2b6cc83ca 134 {
cmaas 0:a6f2b6cc83ca 135 float EMGy = EMGyplus - EMGymin;
cmaas 0:a6f2b6cc83ca 136
cmaas 0:a6f2b6cc83ca 137 float verplaatsingy = EMGy * tijdstap * v;
cmaas 0:a6f2b6cc83ca 138 float pynieuw = py + verplaatsingy;
cmaas 0:a6f2b6cc83ca 139
cmaas 0:a6f2b6cc83ca 140 // y limit
cmaas 0:a6f2b6cc83ca 141 if (pynieuw <= upperylim && pynieuw >= lowerylim)
cmaas 0:a6f2b6cc83ca 142 {
cmaas 0:a6f2b6cc83ca 143 py = pynieuw;
cmaas 0:a6f2b6cc83ca 144 }
cmaas 0:a6f2b6cc83ca 145 else
cmaas 0:a6f2b6cc83ca 146 {
cmaas 0:a6f2b6cc83ca 147 if (pynieuw >= lowerylim)
cmaas 0:a6f2b6cc83ca 148 {
cmaas 0:a6f2b6cc83ca 149 py = upperylim;
cmaas 0:a6f2b6cc83ca 150 }
cmaas 0:a6f2b6cc83ca 151 else
cmaas 0:a6f2b6cc83ca 152 {
cmaas 0:a6f2b6cc83ca 153 py = lowerylim;
cmaas 0:a6f2b6cc83ca 154 }
cmaas 0:a6f2b6cc83ca 155 }
cmaas 0:a6f2b6cc83ca 156 //printf("Y eindpunt (%f) en verplaatsing: (%f) \n\r",py,verplaatsingy);
cmaas 0:a6f2b6cc83ca 157 return (py);
cmaas 0:a6f2b6cc83ca 158 }
cmaas 0:a6f2b6cc83ca 159
cmaas 0:a6f2b6cc83ca 160
cmaas 0:a6f2b6cc83ca 161 //~~~~~~~~~~~~CALCULATIING MOTOR ANGLES ~~~~~~~~
cmaas 0:a6f2b6cc83ca 162 // arm 1 --> reference angle motor 1
cmaas 0:a6f2b6cc83ca 163 float hoek1(float px, float py) // input: ref x, ref y
cmaas 0:a6f2b6cc83ca 164 {
cmaas 0:a6f2b6cc83ca 165 float c1x = px - rp * cos(thetap +(M_PI/6)); // x locatie hoekpunt end-effector
cmaas 0:a6f2b6cc83ca 166 float c1y = py - rp*sin(thetap+(M_PI/6)); // y locatie hoekpunt end-effector
cmaas 0:a6f2b6cc83ca 167 float alpha1 = atan2((c1y-a1y),(c1x-a1x)); // hoek tussen horizontaal en lijn van motor naar bijbehorende end-effector punt
cmaas 0:a6f2b6cc83ca 168 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 6:6545e197858a 169 float a1 = alpha1 + psi1 - da1; //hoek tussen horizontaal en actieve arm
cmaas 7:83a69ca630bc 170 //printf("arm 1 = %f \n\r",a1);
cmaas 0:a6f2b6cc83ca 171 return a1;
cmaas 0:a6f2b6cc83ca 172 }
cmaas 0:a6f2b6cc83ca 173
cmaas 0:a6f2b6cc83ca 174 // arm 2 --> reference angle motor 2
cmaas 0:a6f2b6cc83ca 175 float hoek2(float px, float py)
cmaas 0:a6f2b6cc83ca 176 {
cmaas 0:a6f2b6cc83ca 177 float c2x = px - rp * cos(thetap -(M_PI/2));
cmaas 0:a6f2b6cc83ca 178 float c2y = py - rp*sin(thetap-(M_PI/2));
cmaas 0:a6f2b6cc83ca 179 float alpha2 = atan2((c2y-a2y),(c2x-a2x));
cmaas 0:a6f2b6cc83ca 180 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 6:6545e197858a 181 float a2 = alpha2 + psi2 - da2;
cmaas 7:83a69ca630bc 182 //printf("arm 2 = %f \n\r",a2);
cmaas 0:a6f2b6cc83ca 183 return a2;
cmaas 0:a6f2b6cc83ca 184 }
cmaas 0:a6f2b6cc83ca 185
cmaas 0:a6f2b6cc83ca 186 //arm 3 --> reference angle motor 3
cmaas 0:a6f2b6cc83ca 187 float hoek3(float px, float py)
cmaas 0:a6f2b6cc83ca 188 {
cmaas 0:a6f2b6cc83ca 189 float c3x = px - rp * cos(thetap +(5*M_PI/6));
cmaas 0:a6f2b6cc83ca 190 float c3y = py - rp*sin(thetap+(5*M_PI/6));
cmaas 0:a6f2b6cc83ca 191 float alpha3 = atan2((c3y-a3y),(c3x-a3x));
cmaas 0:a6f2b6cc83ca 192 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 6:6545e197858a 193 float a3 = alpha3 + psi3 - da3;
cmaas 7:83a69ca630bc 194 //printf("arm 3 = %f \n\r",a3);
cmaas 0:a6f2b6cc83ca 195 return a3;
cmaas 0:a6f2b6cc83ca 196 }
cmaas 0:a6f2b6cc83ca 197
cmaas 0:a6f2b6cc83ca 198 // ~~~~~~~~~~~~~~PID CONTROLLER~~~~~~~~~~~~~~~~~~
cmaas 0:a6f2b6cc83ca 199
cmaas 0:a6f2b6cc83ca 200 double PID_controller(double error)
cmaas 0:a6f2b6cc83ca 201 {
cmaas 0:a6f2b6cc83ca 202 static double error_integral = 0;
cmaas 0:a6f2b6cc83ca 203 static double error_prev = error; // initialization with this value only done once!
cmaas 0:a6f2b6cc83ca 204 static BiQuad LowPassFilter(0.0640, 0.1279, 0.0640, -1.1683, 0.4241);
cmaas 0:a6f2b6cc83ca 205
cmaas 0:a6f2b6cc83ca 206 // Proportional part:
cmaas 0:a6f2b6cc83ca 207 double u_k = Kp * error;
cmaas 0:a6f2b6cc83ca 208
cmaas 0:a6f2b6cc83ca 209 // Integral part
cmaas 0:a6f2b6cc83ca 210 error_integral = error_integral + error * Ts;
cmaas 0:a6f2b6cc83ca 211 double u_i = Ki * error_integral;
cmaas 0:a6f2b6cc83ca 212
cmaas 0:a6f2b6cc83ca 213 // Derivative part
cmaas 0:a6f2b6cc83ca 214 double error_derivative = (error - error_prev)/Ts;
cmaas 0:a6f2b6cc83ca 215 double filtered_error_derivative = LowPassFilter.step(error_derivative);
cmaas 0:a6f2b6cc83ca 216 double u_d = Kd * filtered_error_derivative;
cmaas 0:a6f2b6cc83ca 217 error_prev = error;
cmaas 0:a6f2b6cc83ca 218
cmaas 0:a6f2b6cc83ca 219 // Sum all parts and return it
cmaas 0:a6f2b6cc83ca 220 return u_k + u_i + u_d;
cmaas 0:a6f2b6cc83ca 221 }
cmaas 0:a6f2b6cc83ca 222
cmaas 0:a6f2b6cc83ca 223
cmaas 0:a6f2b6cc83ca 224 // DIRECTON AND SPEED CONTROL
cmaas 0:a6f2b6cc83ca 225 void moter_control(double u)
cmaas 0:a6f2b6cc83ca 226 {
cmaas 0:a6f2b6cc83ca 227 directionpin1= u > 0.0f; //eithertrueor false
cmaas 0:a6f2b6cc83ca 228 pwmpin1= fabs(u); //pwmduty cycle canonlybepositive, floatingpoint absolute value
cmaas 0:a6f2b6cc83ca 229 }
cmaas 0:a6f2b6cc83ca 230
cmaas 5:a54ea6514bc5 231 void moter2_control(double u)
cmaas 5:a54ea6514bc5 232 {
cmaas 5:a54ea6514bc5 233 directionpin2= u > 0.0f; //eithertrueor false
cmaas 5:a54ea6514bc5 234 pwmpin2= fabs(u); //pwmduty cycle canonlybepositive, floatingpoint absolute value
cmaas 5:a54ea6514bc5 235 }
cmaas 5:a54ea6514bc5 236
cmaas 5:a54ea6514bc5 237 void moter3_control(double u)
cmaas 5:a54ea6514bc5 238 {
cmaas 5:a54ea6514bc5 239 directionpin3= u > 0.0f; //eithertrueor false
cmaas 5:a54ea6514bc5 240 pwmpin3 = fabs(u); //pwmduty cycle canonlybepositive, floatingpoint absolute value
cmaas 5:a54ea6514bc5 241 }
cmaas 0:a6f2b6cc83ca 242
cmaas 0:a6f2b6cc83ca 243 // CONTROLLING THE MOTOR
cmaas 0:a6f2b6cc83ca 244 void Motor_mover()
cmaas 0:a6f2b6cc83ca 245 {
cmaas 0:a6f2b6cc83ca 246 double motor_position = encoder1.getPulses(); //output in counts
cmaas 8:cfe7ad86837c 247 double reference_rotation = hoek1(px, py);
cmaas 0:a6f2b6cc83ca 248 double error = reference_rotation - motor_position*(2*PI)/8400;
cmaas 0:a6f2b6cc83ca 249 double u = PID_controller(error);
cmaas 0:a6f2b6cc83ca 250 moter_control(u);
cmaas 5:a54ea6514bc5 251
cmaas 5:a54ea6514bc5 252 double motor_position2 = encoder2.getPulses(); //output in counts
cmaas 5:a54ea6514bc5 253 double reference_rotation2 = hoek2(px, py);
cmaas 5:a54ea6514bc5 254 double error_2 = reference_rotation2 - motor_position2*(2*PI)/8400;
cmaas 5:a54ea6514bc5 255 double u_2 = PID_controller(error_2);
cmaas 5:a54ea6514bc5 256 moter2_control(u_2);
cmaas 5:a54ea6514bc5 257
cmaas 5:a54ea6514bc5 258 double motor_position3 = encoder3.getPulses(); //output in counts
cmaas 8:cfe7ad86837c 259 double reference_rotation3 = hoek3(px, py);
cmaas 5:a54ea6514bc5 260 double error_3 = reference_rotation3 - motor_position3*(2*PI)/8400;
cmaas 5:a54ea6514bc5 261 double u_3 = PID_controller(error_3);
cmaas 5:a54ea6514bc5 262 moter3_control(u_3);
cmaas 5:a54ea6514bc5 263
cmaas 5:a54ea6514bc5 264
cmaas 0:a6f2b6cc83ca 265 }
cmaas 0:a6f2b6cc83ca 266
cmaas 0:a6f2b6cc83ca 267 //PRINT TICKER
cmaas 0:a6f2b6cc83ca 268 void PrintFlag()
cmaas 0:a6f2b6cc83ca 269 {
cmaas 0:a6f2b6cc83ca 270 AlwaysTrue = true;
cmaas 0:a6f2b6cc83ca 271 }
cmaas 0:a6f2b6cc83ca 272
cmaas 0:a6f2b6cc83ca 273 // HIDSCOPE
cmaas 0:a6f2b6cc83ca 274 void ScopeData()
cmaas 0:a6f2b6cc83ca 275 {
cmaas 0:a6f2b6cc83ca 276 double y = encoder1.getPulses();
cmaas 0:a6f2b6cc83ca 277 scope.set(0, y);
cmaas 0:a6f2b6cc83ca 278 scope.send();
cmaas 0:a6f2b6cc83ca 279 }
cmaas 0:a6f2b6cc83ca 280
cmaas 0:a6f2b6cc83ca 281
cmaas 0:a6f2b6cc83ca 282 //----------------------MAIN---------------------------------
cmaas 0:a6f2b6cc83ca 283 int main()
cmaas 0:a6f2b6cc83ca 284 {
cmaas 0:a6f2b6cc83ca 285 // ~~~~~~~~~~~~~~~~ INITIATING ~~~~~~~~~~~~
cmaas 0:a6f2b6cc83ca 286 pwmpin1.period_us(60); // setup motor
cmaas 0:a6f2b6cc83ca 287
cmaas 0:a6f2b6cc83ca 288 // setup printing service
cmaas 0:a6f2b6cc83ca 289 pc.baud(9600);
cmaas 0:a6f2b6cc83ca 290 pc.printf("test");
cmaas 0:a6f2b6cc83ca 291
cmaas 0:a6f2b6cc83ca 292 // Tickers
cmaas 0:a6f2b6cc83ca 293 //show_counts.attach(PrintFlag, 0.2);
cmaas 8:cfe7ad86837c 294 ref_rot.attach(Motor_mover, 0.001);
cmaas 4:85770b268599 295 //Scope_Data.attach(ScopeData, 0.01);
cmaas 0:a6f2b6cc83ca 296
cmaas 0:a6f2b6cc83ca 297
cmaas 2:44758d95cb0b 298 while(true){
cmaas 2:44758d95cb0b 299
cmaas 2:44758d95cb0b 300
cmaas 2:44758d95cb0b 301 if (button2 == false)
cmaas 2:44758d95cb0b 302 {
cmaas 8:cfe7ad86837c 303 wait(0.01f);
cmaas 2:44758d95cb0b 304
cmaas 2:44758d95cb0b 305 // berekenen positie
cmaas 2:44758d95cb0b 306 float px = positionx(1,0); // EMG: +x, -x
cmaas 2:44758d95cb0b 307 float py = positiony(1,0); // EMG: +y, -y
cmaas 2:44758d95cb0b 308 //printf("positie (%f,%f)\n\r",px,py);
cmaas 2:44758d95cb0b 309 }
cmaas 0:a6f2b6cc83ca 310
cmaas 2:44758d95cb0b 311 if (button1 == false){
cmaas 8:cfe7ad86837c 312 wait(0.01f);
cmaas 2:44758d95cb0b 313 // berekenen positie
cmaas 2:44758d95cb0b 314 float px = positionx(0,1); // EMG: +x, -x
cmaas 2:44758d95cb0b 315 float py = positiony(0,1); // EMG: +y, -y
cmaas 2:44758d95cb0b 316 //printf("positie (%f,%f)\n\r",px,py);
cmaas 2:44758d95cb0b 317 }
cmaas 2:44758d95cb0b 318 }
cmaas 0:a6f2b6cc83ca 319 // berekenen hoeken
cmaas 0:a6f2b6cc83ca 320 /*
cmaas 0:a6f2b6cc83ca 321 float a1 = hoek1(px, py);
cmaas 0:a6f2b6cc83ca 322 float a2 = hoek2(px, py);
cmaas 0:a6f2b6cc83ca 323 float a3 = hoek3(px, py);
cmaas 0:a6f2b6cc83ca 324
cmaas 7:83a69ca630bc 325 //printf("hoek(%f,%f,%f)\n\r",a1,a2,a3);
cmaas 0:a6f2b6cc83ca 326
cmaas 0:a6f2b6cc83ca 327 return 0;
cmaas 0:a6f2b6cc83ca 328 */
cmaas 0:a6f2b6cc83ca 329 }