working PID + Kinematics + Motorcontrol

Dependencies:   HIDScope MODSERIAL QEI biquadFilter mbed

Committer:
cmaas
Date:
Thu Nov 01 15:37:21 2018 +0000
Revision:
9:59dc4c12e4ee
Parent:
8:cfe7ad86837c
Boundaries added - safe to use

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