Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependencies: HIDScope MODSERIAL QEI biquadFilter mbed
main.cpp@3:4b6b3b5e3a1b, 2018-10-31 (annotated)
- Committer:
- cmaas
- Date:
- Wed Oct 31 15:35:56 2018 +0000
- Revision:
- 3:4b6b3b5e3a1b
- Parent:
- 2:44758d95cb0b
2 motors doesnt work
Who changed what in which revision?
| User | Revision | Line number | New 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 | 3:4b6b3b5e3a1b | 22 | |
| cmaas | 3:4b6b3b5e3a1b | 23 | DigitalOut directionpin1(D4); // motor 1 |
| cmaas | 3:4b6b3b5e3a1b | 24 | DigitalOut directionpin2(D7); // motor 2 |
| cmaas | 0:a6f2b6cc83ca | 25 | PwmOut pwmpin1(D6); // motor 1 |
| cmaas | 3:4b6b3b5e3a1b | 26 | PwmOut pwmpin2(D5); // motor 2 |
| cmaas | 0:a6f2b6cc83ca | 27 | |
| cmaas | 0:a6f2b6cc83ca | 28 | QEI encoder1 (D9, D8, NC, 8400, QEI::X4_ENCODING); |
| cmaas | 3:4b6b3b5e3a1b | 29 | QEI encoder2 (D11, D10, NC, 8400, QEI::X4_ENCODING); // motor 2 |
| cmaas | 0:a6f2b6cc83ca | 30 | MODSERIAL pc(USBTX, USBRX); |
| cmaas | 0:a6f2b6cc83ca | 31 | HIDScope scope(2); |
| cmaas | 0:a6f2b6cc83ca | 32 | |
| cmaas | 0:a6f2b6cc83ca | 33 | // TICKERS |
| cmaas | 0:a6f2b6cc83ca | 34 | Ticker ref_rot; |
| cmaas | 0:a6f2b6cc83ca | 35 | Ticker show_counts; |
| cmaas | 0:a6f2b6cc83ca | 36 | Ticker Scope_Data; |
| cmaas | 0:a6f2b6cc83ca | 37 | |
| cmaas | 0:a6f2b6cc83ca | 38 | //----------------GLOBALS-------------------------- |
| cmaas | 0:a6f2b6cc83ca | 39 | |
| cmaas | 0:a6f2b6cc83ca | 40 | // CONSTANTS PID CONTROLLER |
| cmaas | 0:a6f2b6cc83ca | 41 | double PI = M_PI;// CHANGE THIS INTO M_PI |
| cmaas | 2:44758d95cb0b | 42 | double Kp = 14; //200 , 50 |
| cmaas | 0:a6f2b6cc83ca | 43 | double Ki = 0; //1, 0.5 |
| cmaas | 2:44758d95cb0b | 44 | double Kd = 3; //200, 10 |
| cmaas | 0:a6f2b6cc83ca | 45 | double Ts = 0.1; // Sample time in seconds |
| cmaas | 0:a6f2b6cc83ca | 46 | double reference_rotation; //define as radians |
| cmaas | 3:4b6b3b5e3a1b | 47 | double countsToRadians = (2*PI)/8400; |
| cmaas | 0:a6f2b6cc83ca | 48 | double motor_position; |
| cmaas | 0:a6f2b6cc83ca | 49 | bool AlwaysTrue; |
| cmaas | 0:a6f2b6cc83ca | 50 | |
| cmaas | 0:a6f2b6cc83ca | 51 | //CONSTANTS KINEMATICS |
| cmaas | 0:a6f2b6cc83ca | 52 | // constants |
| cmaas | 0:a6f2b6cc83ca | 53 | const float la = 0.256; // lengte actieve arm |
| cmaas | 0:a6f2b6cc83ca | 54 | const float lp = 0.21; // lengte passieve arm |
| cmaas | 0:a6f2b6cc83ca | 55 | const float rp = 0.052; // straal van midden end effector tot hoekpunt |
| cmaas | 0:a6f2b6cc83ca | 56 | const float rm = 0.23; // straal van global midden tot motor |
| cmaas | 0:a6f2b6cc83ca | 57 | const float a = 0.09; // zijde van de driehoek |
| cmaas | 0:a6f2b6cc83ca | 58 | const float xas = 0.40; // afstand van motor 1 tot motor 3 |
| cmaas | 0:a6f2b6cc83ca | 59 | const float yas = 0.346; // afstand van xas tot motor 2 |
| cmaas | 0:a6f2b6cc83ca | 60 | const float thetap = 0; // rotatiehoek van de end effector |
| cmaas | 0:a6f2b6cc83ca | 61 | |
| cmaas | 0:a6f2b6cc83ca | 62 | // motor locatie |
| cmaas | 0:a6f2b6cc83ca | 63 | const int a1x = 0; //x locatie motor 1 |
| cmaas | 0:a6f2b6cc83ca | 64 | const int a1y = 0; //y locatie motor 1 |
| cmaas | 0:a6f2b6cc83ca | 65 | const float a2x = (0.5)*xas; // x locatie motor 2 |
| cmaas | 0:a6f2b6cc83ca | 66 | const float a2y = yas; // y locatie motor 2 |
| cmaas | 0:a6f2b6cc83ca | 67 | const float a3x = xas; // x locatie motor 3 |
| cmaas | 0:a6f2b6cc83ca | 68 | const int a3y = 0; // y locatie motor 3 |
| cmaas | 0:a6f2b6cc83ca | 69 | |
| cmaas | 0:a6f2b6cc83ca | 70 | // script voor het bepalen van de desired position aan de hand van emg (1/0) |
| cmaas | 0:a6f2b6cc83ca | 71 | |
| cmaas | 0:a6f2b6cc83ca | 72 | // EMG OUTPUT |
| cmaas | 0:a6f2b6cc83ca | 73 | int EMGxplus; |
| cmaas | 0:a6f2b6cc83ca | 74 | int EMGxmin ; |
| cmaas | 0:a6f2b6cc83ca | 75 | int EMGyplus; |
| cmaas | 0:a6f2b6cc83ca | 76 | int EMGymin ; |
| cmaas | 0:a6f2b6cc83ca | 77 | |
| cmaas | 0:a6f2b6cc83ca | 78 | // Dit moet experimenteel geperfectioneerd worden |
| cmaas | 0:a6f2b6cc83ca | 79 | float tijdstap = 0.05; //nu wss heel langzaam, kan miss omhoog |
| cmaas | 0:a6f2b6cc83ca | 80 | float v = 0.1; // snelheid kan wss ook hoger |
| cmaas | 0:a6f2b6cc83ca | 81 | |
| cmaas | 0:a6f2b6cc83ca | 82 | float px = 0.2; //starting x |
| cmaas | 0:a6f2b6cc83ca | 83 | float py = 0.155; // starting y |
| cmaas | 0:a6f2b6cc83ca | 84 | |
| cmaas | 0:a6f2b6cc83ca | 85 | // limits (since no forward kinematics) |
| cmaas | 0:a6f2b6cc83ca | 86 | float upperxlim = 0.36; //niet helemaal naar requierments ff kijken of ie groter kan |
| cmaas | 0:a6f2b6cc83ca | 87 | float lowerxlim = 0.04; |
| cmaas | 0:a6f2b6cc83ca | 88 | float upperylim = 0.30; |
| cmaas | 0:a6f2b6cc83ca | 89 | float lowerylim = 0.04; |
| cmaas | 0:a6f2b6cc83ca | 90 | |
| cmaas | 0:a6f2b6cc83ca | 91 | |
| cmaas | 0:a6f2b6cc83ca | 92 | //----------------FUNCTIONS-------------------------- |
| cmaas | 0:a6f2b6cc83ca | 93 | |
| cmaas | 0:a6f2b6cc83ca | 94 | // ~~~~~~~~~~~~~~ROBOT KINEMATICS ~~~~~~~~~~~~~~~~~~ |
| cmaas | 0:a6f2b6cc83ca | 95 | |
| cmaas | 0:a6f2b6cc83ca | 96 | // functie x positie |
| cmaas | 0:a6f2b6cc83ca | 97 | float positionx(int EMGxplus,int EMGxmin) |
| cmaas | 0:a6f2b6cc83ca | 98 | { |
| cmaas | 0:a6f2b6cc83ca | 99 | float EMGx = EMGxplus - EMGxmin; |
| cmaas | 0:a6f2b6cc83ca | 100 | |
| cmaas | 0:a6f2b6cc83ca | 101 | float verplaatsingx = EMGx * tijdstap * v; |
| cmaas | 0:a6f2b6cc83ca | 102 | float pxnieuw = px + verplaatsingx; |
| cmaas | 0:a6f2b6cc83ca | 103 | // x limit |
| cmaas | 0:a6f2b6cc83ca | 104 | if (pxnieuw <= upperxlim && pxnieuw >= lowerxlim) |
| cmaas | 0:a6f2b6cc83ca | 105 | { |
| cmaas | 0:a6f2b6cc83ca | 106 | px = pxnieuw; |
| cmaas | 0:a6f2b6cc83ca | 107 | } |
| cmaas | 0:a6f2b6cc83ca | 108 | else |
| cmaas | 0:a6f2b6cc83ca | 109 | { |
| cmaas | 0:a6f2b6cc83ca | 110 | if (pxnieuw >= lowerxlim) |
| cmaas | 0:a6f2b6cc83ca | 111 | { |
| cmaas | 0:a6f2b6cc83ca | 112 | px = upperxlim; |
| cmaas | 0:a6f2b6cc83ca | 113 | } |
| cmaas | 0:a6f2b6cc83ca | 114 | else |
| cmaas | 0:a6f2b6cc83ca | 115 | { |
| cmaas | 0:a6f2b6cc83ca | 116 | px = lowerxlim; |
| cmaas | 0:a6f2b6cc83ca | 117 | } |
| cmaas | 0:a6f2b6cc83ca | 118 | } |
| cmaas | 0:a6f2b6cc83ca | 119 | //printf("X eindpunt (%f) en verplaatsing: (%f)\n\r",px,verplaatsingx); |
| cmaas | 0:a6f2b6cc83ca | 120 | return px; |
| cmaas | 0:a6f2b6cc83ca | 121 | } |
| cmaas | 0:a6f2b6cc83ca | 122 | |
| cmaas | 0:a6f2b6cc83ca | 123 | |
| cmaas | 0:a6f2b6cc83ca | 124 | // functie y positie |
| cmaas | 0:a6f2b6cc83ca | 125 | float positiony(int EMGyplus,int EMGymin) |
| cmaas | 0:a6f2b6cc83ca | 126 | { |
| cmaas | 0:a6f2b6cc83ca | 127 | float EMGy = EMGyplus - EMGymin; |
| cmaas | 0:a6f2b6cc83ca | 128 | |
| cmaas | 0:a6f2b6cc83ca | 129 | float verplaatsingy = EMGy * tijdstap * v; |
| cmaas | 0:a6f2b6cc83ca | 130 | float pynieuw = py + verplaatsingy; |
| cmaas | 0:a6f2b6cc83ca | 131 | |
| cmaas | 0:a6f2b6cc83ca | 132 | // y limit |
| cmaas | 0:a6f2b6cc83ca | 133 | if (pynieuw <= upperylim && pynieuw >= lowerylim) |
| cmaas | 0:a6f2b6cc83ca | 134 | { |
| cmaas | 0:a6f2b6cc83ca | 135 | py = pynieuw; |
| cmaas | 0:a6f2b6cc83ca | 136 | } |
| cmaas | 0:a6f2b6cc83ca | 137 | else |
| cmaas | 0:a6f2b6cc83ca | 138 | { |
| cmaas | 0:a6f2b6cc83ca | 139 | if (pynieuw >= lowerylim) |
| cmaas | 0:a6f2b6cc83ca | 140 | { |
| cmaas | 0:a6f2b6cc83ca | 141 | py = upperylim; |
| cmaas | 0:a6f2b6cc83ca | 142 | } |
| cmaas | 0:a6f2b6cc83ca | 143 | else |
| cmaas | 0:a6f2b6cc83ca | 144 | { |
| cmaas | 0:a6f2b6cc83ca | 145 | py = lowerylim; |
| cmaas | 0:a6f2b6cc83ca | 146 | } |
| cmaas | 0:a6f2b6cc83ca | 147 | } |
| cmaas | 0:a6f2b6cc83ca | 148 | //printf("Y eindpunt (%f) en verplaatsing: (%f) \n\r",py,verplaatsingy); |
| cmaas | 0:a6f2b6cc83ca | 149 | return (py); |
| cmaas | 0:a6f2b6cc83ca | 150 | } |
| cmaas | 0:a6f2b6cc83ca | 151 | |
| cmaas | 0:a6f2b6cc83ca | 152 | |
| cmaas | 0:a6f2b6cc83ca | 153 | //~~~~~~~~~~~~CALCULATIING MOTOR ANGLES ~~~~~~~~ |
| cmaas | 0:a6f2b6cc83ca | 154 | // arm 1 --> reference angle motor 1 |
| cmaas | 0:a6f2b6cc83ca | 155 | float hoek1(float px, float py) // input: ref x, ref y |
| cmaas | 0:a6f2b6cc83ca | 156 | { |
| cmaas | 0:a6f2b6cc83ca | 157 | float c1x = px - rp * cos(thetap +(M_PI/6)); // x locatie hoekpunt end-effector |
| cmaas | 0:a6f2b6cc83ca | 158 | float c1y = py - rp*sin(thetap+(M_PI/6)); // y locatie hoekpunt end-effector |
| cmaas | 0:a6f2b6cc83ca | 159 | float alpha1 = atan2((c1y-a1y),(c1x-a1x)); // hoek tussen horizontaal en lijn van motor naar bijbehorende end-effector punt |
| cmaas | 0:a6f2b6cc83ca | 160 | 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 | 0:a6f2b6cc83ca | 161 | float a1 = alpha1 + psi1; //hoek tussen horizontaal en actieve arm |
| cmaas | 0:a6f2b6cc83ca | 162 | //printf("arm 1 = %f \n\r",a1); |
| cmaas | 0:a6f2b6cc83ca | 163 | return a1; |
| cmaas | 0:a6f2b6cc83ca | 164 | } |
| cmaas | 0:a6f2b6cc83ca | 165 | |
| cmaas | 0:a6f2b6cc83ca | 166 | // arm 2 --> reference angle motor 2 |
| cmaas | 0:a6f2b6cc83ca | 167 | float hoek2(float px, float py) |
| cmaas | 0:a6f2b6cc83ca | 168 | { |
| cmaas | 0:a6f2b6cc83ca | 169 | float c2x = px - rp * cos(thetap -(M_PI/2)); |
| cmaas | 0:a6f2b6cc83ca | 170 | float c2y = py - rp*sin(thetap-(M_PI/2)); |
| cmaas | 0:a6f2b6cc83ca | 171 | float alpha2 = atan2((c2y-a2y),(c2x-a2x)); |
| cmaas | 0:a6f2b6cc83ca | 172 | 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 | 0:a6f2b6cc83ca | 173 | float a2 = alpha2 + psi2; |
| cmaas | 0:a6f2b6cc83ca | 174 | //printf("arm 2 = %f \n\r",a2); |
| cmaas | 0:a6f2b6cc83ca | 175 | return a2; |
| cmaas | 0:a6f2b6cc83ca | 176 | } |
| cmaas | 0:a6f2b6cc83ca | 177 | |
| cmaas | 0:a6f2b6cc83ca | 178 | //arm 3 --> reference angle motor 3 |
| cmaas | 0:a6f2b6cc83ca | 179 | float hoek3(float px, float py) |
| cmaas | 0:a6f2b6cc83ca | 180 | { |
| cmaas | 0:a6f2b6cc83ca | 181 | float c3x = px - rp * cos(thetap +(5*M_PI/6)); |
| cmaas | 0:a6f2b6cc83ca | 182 | float c3y = py - rp*sin(thetap+(5*M_PI/6)); |
| cmaas | 0:a6f2b6cc83ca | 183 | float alpha3 = atan2((c3y-a3y),(c3x-a3x)); |
| cmaas | 0:a6f2b6cc83ca | 184 | 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 | 0:a6f2b6cc83ca | 185 | float a3 = alpha3 + psi3; |
| cmaas | 0:a6f2b6cc83ca | 186 | //printf("arm 3 = %f \n\r",a3); |
| cmaas | 0:a6f2b6cc83ca | 187 | return a3; |
| cmaas | 0:a6f2b6cc83ca | 188 | } |
| cmaas | 0:a6f2b6cc83ca | 189 | |
| cmaas | 0:a6f2b6cc83ca | 190 | // ~~~~~~~~~~~~~~PID CONTROLLER~~~~~~~~~~~~~~~~~~ |
| cmaas | 0:a6f2b6cc83ca | 191 | |
| cmaas | 0:a6f2b6cc83ca | 192 | double PID_controller(double error) |
| cmaas | 0:a6f2b6cc83ca | 193 | { |
| cmaas | 0:a6f2b6cc83ca | 194 | static double error_integral = 0; |
| cmaas | 0:a6f2b6cc83ca | 195 | static double error_prev = error; // initialization with this value only done once! |
| cmaas | 0:a6f2b6cc83ca | 196 | static BiQuad LowPassFilter(0.0640, 0.1279, 0.0640, -1.1683, 0.4241); |
| cmaas | 0:a6f2b6cc83ca | 197 | |
| cmaas | 0:a6f2b6cc83ca | 198 | // Proportional part: |
| cmaas | 0:a6f2b6cc83ca | 199 | double u_k = Kp * error; |
| cmaas | 0:a6f2b6cc83ca | 200 | |
| cmaas | 0:a6f2b6cc83ca | 201 | // Integral part |
| cmaas | 0:a6f2b6cc83ca | 202 | error_integral = error_integral + error * Ts; |
| cmaas | 0:a6f2b6cc83ca | 203 | double u_i = Ki * error_integral; |
| cmaas | 0:a6f2b6cc83ca | 204 | |
| cmaas | 0:a6f2b6cc83ca | 205 | // Derivative part |
| cmaas | 0:a6f2b6cc83ca | 206 | double error_derivative = (error - error_prev)/Ts; |
| cmaas | 0:a6f2b6cc83ca | 207 | double filtered_error_derivative = LowPassFilter.step(error_derivative); |
| cmaas | 0:a6f2b6cc83ca | 208 | double u_d = Kd * filtered_error_derivative; |
| cmaas | 0:a6f2b6cc83ca | 209 | error_prev = error; |
| cmaas | 0:a6f2b6cc83ca | 210 | |
| cmaas | 0:a6f2b6cc83ca | 211 | // Sum all parts and return it |
| cmaas | 0:a6f2b6cc83ca | 212 | return u_k + u_i + u_d; |
| cmaas | 0:a6f2b6cc83ca | 213 | } |
| cmaas | 0:a6f2b6cc83ca | 214 | |
| cmaas | 0:a6f2b6cc83ca | 215 | |
| cmaas | 0:a6f2b6cc83ca | 216 | // DIRECTON AND SPEED CONTROL |
| cmaas | 3:4b6b3b5e3a1b | 217 | void motor_control(double u_1, double u_2) |
| cmaas | 0:a6f2b6cc83ca | 218 | { |
| cmaas | 3:4b6b3b5e3a1b | 219 | directionpin1= u_1 > 0.0f; //eithertrueor false |
| cmaas | 3:4b6b3b5e3a1b | 220 | pwmpin1= fabs(u_1); //pwmduty cycle canonlybepositive, floatingpoint absolute value |
| cmaas | 3:4b6b3b5e3a1b | 221 | |
| cmaas | 3:4b6b3b5e3a1b | 222 | directionpin2= u_2 > 0.0f; //eithertrueor false |
| cmaas | 3:4b6b3b5e3a1b | 223 | pwmpin2= fabs(u_2); //pwmduty cycle canonlybepositive, floatingpoint absolute value |
| cmaas | 0:a6f2b6cc83ca | 224 | } |
| cmaas | 0:a6f2b6cc83ca | 225 | |
| cmaas | 0:a6f2b6cc83ca | 226 | |
| cmaas | 0:a6f2b6cc83ca | 227 | // CONTROLLING THE MOTOR |
| cmaas | 0:a6f2b6cc83ca | 228 | void Motor_mover() |
| cmaas | 0:a6f2b6cc83ca | 229 | { |
| cmaas | 3:4b6b3b5e3a1b | 230 | double motor_position1 = encoder1.getPulses(); //output in counts |
| cmaas | 3:4b6b3b5e3a1b | 231 | double reference_rotation1 = hoek2(px, py); |
| cmaas | 3:4b6b3b5e3a1b | 232 | double error_1 = reference_rotation1 - motor_position1*countsToRadians; |
| cmaas | 3:4b6b3b5e3a1b | 233 | double u_1 = PID_controller(error_1); |
| cmaas | 3:4b6b3b5e3a1b | 234 | |
| cmaas | 3:4b6b3b5e3a1b | 235 | double motor_position2 = encoder2.getPulses(); //output in counts |
| cmaas | 3:4b6b3b5e3a1b | 236 | double reference_rotation2 = hoek2(px, py); |
| cmaas | 3:4b6b3b5e3a1b | 237 | double error_2 = reference_rotation2 - motor_position2*countsToRadians; |
| cmaas | 3:4b6b3b5e3a1b | 238 | double u_2 = PID_controller(error_2); |
| cmaas | 3:4b6b3b5e3a1b | 239 | |
| cmaas | 3:4b6b3b5e3a1b | 240 | motor_control(u_1, u_2); |
| cmaas | 0:a6f2b6cc83ca | 241 | } |
| cmaas | 0:a6f2b6cc83ca | 242 | |
| cmaas | 0:a6f2b6cc83ca | 243 | //PRINT TICKER |
| cmaas | 0:a6f2b6cc83ca | 244 | void PrintFlag() |
| cmaas | 0:a6f2b6cc83ca | 245 | { |
| cmaas | 0:a6f2b6cc83ca | 246 | AlwaysTrue = true; |
| cmaas | 0:a6f2b6cc83ca | 247 | } |
| cmaas | 0:a6f2b6cc83ca | 248 | |
| cmaas | 0:a6f2b6cc83ca | 249 | // HIDSCOPE |
| cmaas | 0:a6f2b6cc83ca | 250 | void ScopeData() |
| cmaas | 0:a6f2b6cc83ca | 251 | { |
| cmaas | 0:a6f2b6cc83ca | 252 | double y = encoder1.getPulses(); |
| cmaas | 0:a6f2b6cc83ca | 253 | scope.set(0, y); |
| cmaas | 0:a6f2b6cc83ca | 254 | scope.send(); |
| cmaas | 0:a6f2b6cc83ca | 255 | } |
| cmaas | 0:a6f2b6cc83ca | 256 | |
| cmaas | 0:a6f2b6cc83ca | 257 | |
| cmaas | 0:a6f2b6cc83ca | 258 | //----------------------MAIN--------------------------------- |
| cmaas | 0:a6f2b6cc83ca | 259 | int main() |
| cmaas | 0:a6f2b6cc83ca | 260 | { |
| cmaas | 0:a6f2b6cc83ca | 261 | // ~~~~~~~~~~~~~~~~ INITIATING ~~~~~~~~~~~~ |
| cmaas | 0:a6f2b6cc83ca | 262 | pwmpin1.period_us(60); // setup motor |
| cmaas | 0:a6f2b6cc83ca | 263 | |
| cmaas | 0:a6f2b6cc83ca | 264 | // setup printing service |
| cmaas | 0:a6f2b6cc83ca | 265 | pc.baud(9600); |
| cmaas | 0:a6f2b6cc83ca | 266 | pc.printf("test"); |
| cmaas | 0:a6f2b6cc83ca | 267 | |
| cmaas | 0:a6f2b6cc83ca | 268 | // Tickers |
| cmaas | 0:a6f2b6cc83ca | 269 | //show_counts.attach(PrintFlag, 0.2); |
| cmaas | 0:a6f2b6cc83ca | 270 | ref_rot.attach(Motor_mover, 0.01); |
| cmaas | 0:a6f2b6cc83ca | 271 | Scope_Data.attach(ScopeData, 0.01); |
| cmaas | 0:a6f2b6cc83ca | 272 | |
| cmaas | 0:a6f2b6cc83ca | 273 | |
| cmaas | 2:44758d95cb0b | 274 | while(true){ |
| cmaas | 2:44758d95cb0b | 275 | |
| cmaas | 2:44758d95cb0b | 276 | |
| cmaas | 2:44758d95cb0b | 277 | if (button2 == false) |
| cmaas | 2:44758d95cb0b | 278 | { |
| cmaas | 2:44758d95cb0b | 279 | wait(0.05f); |
| cmaas | 2:44758d95cb0b | 280 | |
| cmaas | 2:44758d95cb0b | 281 | // berekenen positie |
| cmaas | 2:44758d95cb0b | 282 | float px = positionx(1,0); // EMG: +x, -x |
| cmaas | 2:44758d95cb0b | 283 | float py = positiony(1,0); // EMG: +y, -y |
| cmaas | 2:44758d95cb0b | 284 | //printf("positie (%f,%f)\n\r",px,py); |
| cmaas | 2:44758d95cb0b | 285 | } |
| cmaas | 0:a6f2b6cc83ca | 286 | |
| cmaas | 2:44758d95cb0b | 287 | if (button1 == false){ |
| cmaas | 2:44758d95cb0b | 288 | wait(0.05f); |
| cmaas | 2:44758d95cb0b | 289 | // berekenen positie |
| cmaas | 2:44758d95cb0b | 290 | float px = positionx(0,1); // EMG: +x, -x |
| cmaas | 2:44758d95cb0b | 291 | float py = positiony(0,1); // EMG: +y, -y |
| cmaas | 2:44758d95cb0b | 292 | //printf("positie (%f,%f)\n\r",px,py); |
| cmaas | 2:44758d95cb0b | 293 | } |
| cmaas | 2:44758d95cb0b | 294 | } |
| cmaas | 0:a6f2b6cc83ca | 295 | // berekenen hoeken |
| cmaas | 0:a6f2b6cc83ca | 296 | /* |
| cmaas | 0:a6f2b6cc83ca | 297 | float a1 = hoek1(px, py); |
| cmaas | 0:a6f2b6cc83ca | 298 | float a2 = hoek2(px, py); |
| cmaas | 0:a6f2b6cc83ca | 299 | float a3 = hoek3(px, py); |
| cmaas | 0:a6f2b6cc83ca | 300 | |
| cmaas | 0:a6f2b6cc83ca | 301 | printf("hoek(%f,%f,%f)\n\r",a1,a2,a3); |
| cmaas | 0:a6f2b6cc83ca | 302 | |
| cmaas | 0:a6f2b6cc83ca | 303 | return 0; |
| cmaas | 0:a6f2b6cc83ca | 304 | */ |
| cmaas | 0:a6f2b6cc83ca | 305 | } |
