RKI aangepast 10:02
Dependencies: HIDScope MODSERIAL QEI biquadFilter mbed
Fork of Project_script_union by
main.cpp@31:0418ce58af56, 2018-11-01 (annotated)
- Committer:
- MarijkeZondag
- Date:
- Thu Nov 01 18:04:50 2018 +0000
- Revision:
- 31:0418ce58af56
- Parent:
- 30:f04a35f2a06d
- Child:
- 32:56a8bd82e971
zonder error;
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
vsluiter | 0:c8f15874531b | 1 | #include "mbed.h" |
vsluiter | 0:c8f15874531b | 2 | #include "MODSERIAL.h" |
MarijkeZondag | 10:39ec51206c8b | 3 | #include "BiQuad.h" |
MarijkeZondag | 10:39ec51206c8b | 4 | #include "HIDScope.h" |
MarijkeZondag | 10:39ec51206c8b | 5 | #include <math.h> |
MarijkeZondag | 28:5e54cd4525de | 6 | #include "QEI.h" |
vsluiter | 0:c8f15874531b | 7 | |
MarijkeZondag | 22:5d956c93b3ae | 8 | //ATTENTION: set mBed to version 151 |
MarijkeZondag | 22:5d956c93b3ae | 9 | // set QEI to version 0, (gebruiken wij (nog) niet, is voor encoder) |
MarijkeZondag | 22:5d956c93b3ae | 10 | // set MODSERIAL to version 44 |
MarijkeZondag | 22:5d956c93b3ae | 11 | // set HIDScope to version 7 |
MarijkeZondag | 22:5d956c93b3ae | 12 | // set biquadFilter to version 7 |
MarijkeZondag | 10:39ec51206c8b | 13 | |
MarijkeZondag | 22:5d956c93b3ae | 14 | AnalogIn emg0_in (A0); //First raw EMG signal input |
MarijkeZondag | 22:5d956c93b3ae | 15 | AnalogIn emg1_in (A1); //Second raw EMG signal input |
MarijkeZondag | 22:5d956c93b3ae | 16 | AnalogIn emg2_in (A2); //Third raw EMG signal input |
MarijkeZondag | 22:5d956c93b3ae | 17 | |
MarijkeZondag | 26:ac5656aa35c7 | 18 | InterruptIn button1 (D10); |
MarijkeZondag | 16:5f7196ddc77b | 19 | InterruptIn button2 (D11); |
MarijkeZondag | 6:f4bbb73f3989 | 20 | |
MarijkeZondag | 28:5e54cd4525de | 21 | DigitalOut directionpin1 (D4); |
MarijkeZondag | 28:5e54cd4525de | 22 | DigitalOut directionpin2 (D7); |
MarijkeZondag | 26:ac5656aa35c7 | 23 | |
MarijkeZondag | 28:5e54cd4525de | 24 | PwmOut pwmpin1 (D5); |
MarijkeZondag | 28:5e54cd4525de | 25 | PwmOut pwmpin2 (D6); |
MarijkeZondag | 22:5d956c93b3ae | 26 | |
MarijkeZondag | 17:741798018c0d | 27 | DigitalOut ledr (LED_RED); |
MarijkeZondag | 17:741798018c0d | 28 | DigitalOut ledb (LED_BLUE); |
MarijkeZondag | 17:741798018c0d | 29 | DigitalOut ledg (LED_GREEN); |
MarijkeZondag | 13:a3d4b4daf5b4 | 30 | |
MarijkeZondag | 9:c722418997b5 | 31 | |
MarijkeZondag | 23:97a976a8f0fc | 32 | MODSERIAL pc(USBTX, USBRX); //Serial communication to see if the code works step by step, turn on if hidscope is off |
MarijkeZondag | 28:5e54cd4525de | 33 | QEI encoder2 (D9, D8, NC, 8400,QEI::X4_ENCODING); |
MarijkeZondag | 28:5e54cd4525de | 34 | QEI encoder1 (D12, D13, NC, 8400,QEI::X4_ENCODING); |
MarijkeZondag | 6:f4bbb73f3989 | 35 | |
MarijkeZondag | 23:97a976a8f0fc | 36 | //HIDScope scope( 6 ); //HIDScope set to 3x2 channels for 3 muscles, raw data + filtered |
vsluiter | 0:c8f15874531b | 37 | |
MarijkeZondag | 22:5d956c93b3ae | 38 | //Tickers |
MarijkeZondag | 28:5e54cd4525de | 39 | Ticker func_tick; |
MarijkeZondag | 28:5e54cd4525de | 40 | Ticker movag_tick; |
MarijkeZondag | 30:f04a35f2a06d | 41 | Ticker emg_tick; |
MarijkeZondag | 30:f04a35f2a06d | 42 | Ticker print_tick; |
MarijkeZondag | 30:f04a35f2a06d | 43 | |
MarijkeZondag | 9:c722418997b5 | 44 | |
MarijkeZondag | 9:c722418997b5 | 45 | //Global variables |
MarijkeZondag | 30:f04a35f2a06d | 46 | const float T = 0.002f; //Ticker period EMG, engine control |
MarijkeZondag | 30:f04a35f2a06d | 47 | const float T2 = 0.2f; //Ticker print function |
MarijkeZondag | 10:39ec51206c8b | 48 | |
MarijkeZondag | 13:a3d4b4daf5b4 | 49 | //EMG filter |
MarijkeZondag | 22:5d956c93b3ae | 50 | double emg0_filt, emg1_filt, emg2_filt; //Variables for filtered EMG data channel 0, 1 and 2 |
MarijkeZondag | 22:5d956c93b3ae | 51 | double emg0_raw, emg1_raw, emg2_raw; |
MarijkeZondag | 22:5d956c93b3ae | 52 | double emg0_filt_x, emg1_filt_x, emg2_filt_x; |
MarijkeZondag | 22:5d956c93b3ae | 53 | const int windowsize = 150; //Size of the array over which the moving average (MovAg) is calculated. (random number) |
MarijkeZondag | 13:a3d4b4daf5b4 | 54 | double sum, sum1, sum2, sum3; //variables used to sum elements in array |
MarijkeZondag | 22:5d956c93b3ae | 55 | double StoreArray0[windowsize], StoreArray1[windowsize], StoreArray2[windowsize]; //Empty arrays to calculate MoveAg |
MarijkeZondag | 22:5d956c93b3ae | 56 | double movAg0, movAg1, movAg2; //outcome of MovAg (moet dit een array zijn??) |
MarijkeZondag | 13:a3d4b4daf5b4 | 57 | |
MarijkeZondag | 22:5d956c93b3ae | 58 | //Calibration variables |
MarijkeZondag | 22:5d956c93b3ae | 59 | int x = -1; //Start switch, colour LED is blue. |
MarijkeZondag | 22:5d956c93b3ae | 60 | int emg_cal = 0; //if emg_cal is set to 1, motors can begin to work in this code (!!) |
MarijkeZondag | 22:5d956c93b3ae | 61 | const int sizeCal = 1500; //size of the dataset used for calibration, eerst 2000 |
MarijkeZondag | 22:5d956c93b3ae | 62 | double StoreCal0[sizeCal], StoreCal1[sizeCal], StoreCal2[sizeCal]; //arrays to put the dataset of the calibration in |
MarijkeZondag | 22:5d956c93b3ae | 63 | double Mean0,Mean1,Mean2; //average of maximum tightening |
MarijkeZondag | 22:5d956c93b3ae | 64 | double Threshold0, Threshold1, Threshold2; |
MarijkeZondag | 13:a3d4b4daf5b4 | 65 | |
MarijkeZondag | 22:5d956c93b3ae | 66 | //Biquad //Variables for the biquad band filters (alle 3 dezelfde maar je kan niet 3x 'emg0band' aanroepen ofzo) |
MarijkeZondag | 22:5d956c93b3ae | 67 | BiQuadChain emg0filter; |
MarijkeZondag | 10:39ec51206c8b | 68 | BiQuad emg0band1( 7.29441e-01, -1.89276e-08, -7.29450e-01, -1.64507e-01, -7.26543e-01 ); |
MarijkeZondag | 10:39ec51206c8b | 69 | BiQuad emg0band2( 1.00000e+00, 1.99999e+00, 9.99994e-01, 1.72349e+00, 7.79616e-01 ); |
MarijkeZondag | 10:39ec51206c8b | 70 | BiQuad emg0band3( 1.00000e+00, -1.99999e+00, 9.99994e-01, -1.93552e+00, 9.39358e-01 ); |
MarijkeZondag | 22:5d956c93b3ae | 71 | BiQuad notch1( 9.91104e-01, -1.60364e+00, 9.91104e-01, -1.60364e+00, 9.82207e-01 ); //Notch filter biquad coefficients |
MarijkeZondag | 10:39ec51206c8b | 72 | |
MarijkeZondag | 22:5d956c93b3ae | 73 | BiQuadChain emg1filter; |
MarijkeZondag | 10:39ec51206c8b | 74 | BiQuad emg1band1( 7.29441e-01, -1.89276e-08, -7.29450e-01, -1.64507e-01, -7.26543e-01 ); |
MarijkeZondag | 10:39ec51206c8b | 75 | BiQuad emg1band2( 1.00000e+00, 1.99999e+00, 9.99994e-01, 1.72349e+00, 7.79616e-01 ); |
MarijkeZondag | 10:39ec51206c8b | 76 | BiQuad emg1band3( 1.00000e+00, -1.99999e+00, 9.99994e-01, -1.93552e+00, 9.39358e-01 ); |
MarijkeZondag | 22:5d956c93b3ae | 77 | BiQuad notch2( 9.91104e-01, -1.60364e+00, 9.91104e-01, -1.60364e+00, 9.82207e-01 ); //Notch filter |
MarijkeZondag | 10:39ec51206c8b | 78 | |
MarijkeZondag | 22:5d956c93b3ae | 79 | BiQuadChain emg2filter; |
MarijkeZondag | 10:39ec51206c8b | 80 | BiQuad emg2band1( 7.29441e-01, -1.89276e-08, -7.29450e-01, -1.64507e-01, -7.26543e-01 ); |
MarijkeZondag | 10:39ec51206c8b | 81 | BiQuad emg2band2( 1.00000e+00, 1.99999e+00, 9.99994e-01, 1.72349e+00, 7.79616e-01 ); |
MarijkeZondag | 10:39ec51206c8b | 82 | BiQuad emg2band3( 1.00000e+00, -1.99999e+00, 9.99994e-01, -1.93552e+00, 9.39358e-01 ); |
MarijkeZondag | 14:fa09dae67390 | 83 | BiQuad notch3( 9.91104e-01, -1.60364e+00, 9.91104e-01, -1.60364e+00, 9.82207e-01 ); //Notch filter |
MarijkeZondag | 10:39ec51206c8b | 84 | |
MarijkeZondag | 26:ac5656aa35c7 | 85 | // Inverse Kinematica variables |
Marle | 25:bbef09ff226b | 86 | const double L1 = 0.208; // Hoogte van tafel tot joint 1 |
MarijkeZondag | 28:5e54cd4525de | 87 | //const double L2 = 0.288; // Hoogte van tafel tot joint 2 |
Marle | 25:bbef09ff226b | 88 | const double L3 = 0.212; // Lengte van de arm |
Marle | 25:bbef09ff226b | 89 | const double L4 = 0.089; // Afstand van achterkant base tot joint 1 |
MarijkeZondag | 28:5e54cd4525de | 90 | //const double L5 = 0.030; // Afstand van joint 1 naar joint 2 |
Marle | 25:bbef09ff226b | 91 | const double r_trans = 0.035; // Kan gebruikt worden om om te rekenen van translation naar shaft rotation |
Marle | 25:bbef09ff226b | 92 | |
Marle | 25:bbef09ff226b | 93 | // Variërende variabelen inverse kinematics: |
MarijkeZondag | 28:5e54cd4525de | 94 | double q1ref = 0.0; // Huidige motorhoek van joint 1 zoals bepaald uit referentiesignaal --> checken of het goede type is |
MarijkeZondag | 28:5e54cd4525de | 95 | double q2ref = 0.0; // Huidige motorhoek van joint 2 zoals bepaald uit referentiesignaal --> checken of het goede type is |
Marle | 25:bbef09ff226b | 96 | double v_x; // Desired velocity end effector in x direction --> Determined by EMG signals |
Marle | 25:bbef09ff226b | 97 | double v_y; // Desired velocity end effector in y direction --> Determined by EMG signals |
Marle | 25:bbef09ff226b | 98 | |
Marle | 25:bbef09ff226b | 99 | double Lq1; // Translatieafstand als gevolg van motor rotation joint 1 |
Marle | 25:bbef09ff226b | 100 | double Cq2; // Joint angle of the system (corrected for gear ratio 1:5) |
Marle | 25:bbef09ff226b | 101 | |
MarijkeZondag | 28:5e54cd4525de | 102 | double q1_dot=0.0; // Benodigde hoeksnelheid van motor 1 om v_des te bereiken |
MarijkeZondag | 28:5e54cd4525de | 103 | double q2_dot=0.0; // Benodigde hoeksnelheid van motor 2 om v_des te bereiken |
Marle | 25:bbef09ff226b | 104 | |
MarijkeZondag | 28:5e54cd4525de | 105 | double q1_ii=0.0; // Reference signal for motorangle q1ref |
MarijkeZondag | 28:5e54cd4525de | 106 | double q2_ii=0.0; // Reference signal for motorangle q2ref |
Marle | 25:bbef09ff226b | 107 | |
MarijkeZondag | 26:ac5656aa35c7 | 108 | //Variables PID controller |
MarijkeZondag | 26:ac5656aa35c7 | 109 | double PI = 3.14159; |
MarijkeZondag | 30:f04a35f2a06d | 110 | double Kp1 = 20.0; //Motor 1 |
MarijkeZondag | 26:ac5656aa35c7 | 111 | double Ki1 = 1.02; |
MarijkeZondag | 28:5e54cd4525de | 112 | double Kd1 = 1.0; |
MarijkeZondag | 26:ac5656aa35c7 | 113 | double encoder_radians1=0; |
MarijkeZondag | 28:5e54cd4525de | 114 | double err_integral1 = 0; |
MarijkeZondag | 28:5e54cd4525de | 115 | double err_prev1, err_prev2; |
MarijkeZondag | 28:5e54cd4525de | 116 | double err1, err2; |
MarijkeZondag | 30:f04a35f2a06d | 117 | BiQuad LowPassFilterDer1( 1.12160e-01, 1.12160e-01, 0.00000e+00, -7.75680e-01, 0.00000e+00 ); //sample frequency 500 Hz, cutoff 20Hz low pass |
Marle | 25:bbef09ff226b | 118 | |
MarijkeZondag | 30:f04a35f2a06d | 119 | double Kp2 = 20.0; //Motor 2 |
MarijkeZondag | 26:ac5656aa35c7 | 120 | double Ki2 = 1.02; |
MarijkeZondag | 28:5e54cd4525de | 121 | double Kd2 = 1.0; |
MarijkeZondag | 26:ac5656aa35c7 | 122 | double encoder_radians2=0; |
MarijkeZondag | 28:5e54cd4525de | 123 | double err_integral2 = 0; |
MarijkeZondag | 28:5e54cd4525de | 124 | double u1, u2; |
MarijkeZondag | 30:f04a35f2a06d | 125 | BiQuad LowPassFilterDer2( 1.12160e-01, 1.12160e-01, 0.00000e+00, -7.75680e-01, 0.00000e+00 ); |
MarijkeZondag | 26:ac5656aa35c7 | 126 | |
MarijkeZondag | 28:5e54cd4525de | 127 | |
MarijkeZondag | 26:ac5656aa35c7 | 128 | //--------------Functions----------------------------------------------------------------------------------------------------------------------------// |
MarijkeZondag | 26:ac5656aa35c7 | 129 | |
MarijkeZondag | 26:ac5656aa35c7 | 130 | |
MarijkeZondag | 26:ac5656aa35c7 | 131 | //------------------ Filter EMG + Calibration EMG --------------------------------// |
MarijkeZondag | 26:ac5656aa35c7 | 132 | |
MarijkeZondag | 13:a3d4b4daf5b4 | 133 | void switch_to_calibrate() |
MarijkeZondag | 13:a3d4b4daf5b4 | 134 | { |
MarijkeZondag | 22:5d956c93b3ae | 135 | x++; //Every time function gets called, x increases. Every button press --> new calibration state. |
MarijkeZondag | 22:5d956c93b3ae | 136 | //Starts with x = -1. So when function gets called 1 time, x = 0. In the end, x = 4 will reset to -1. |
MarijkeZondag | 22:5d956c93b3ae | 137 | |
MarijkeZondag | 13:a3d4b4daf5b4 | 138 | if(x==0) //If x = 0, led is red |
MarijkeZondag | 13:a3d4b4daf5b4 | 139 | { |
MarijkeZondag | 17:741798018c0d | 140 | ledr = 0; |
MarijkeZondag | 17:741798018c0d | 141 | ledb = 1; |
MarijkeZondag | 17:741798018c0d | 142 | ledg = 1; |
MarijkeZondag | 13:a3d4b4daf5b4 | 143 | } |
MarijkeZondag | 13:a3d4b4daf5b4 | 144 | else if (x==1) //If x = 1, led is blue |
MarijkeZondag | 13:a3d4b4daf5b4 | 145 | { |
MarijkeZondag | 17:741798018c0d | 146 | ledr = 1; |
MarijkeZondag | 17:741798018c0d | 147 | ledb = 0; |
MarijkeZondag | 17:741798018c0d | 148 | ledg = 1; |
MarijkeZondag | 13:a3d4b4daf5b4 | 149 | } |
MarijkeZondag | 22:5d956c93b3ae | 150 | else if (x==2) //If x = 2, led is green |
MarijkeZondag | 13:a3d4b4daf5b4 | 151 | { |
MarijkeZondag | 17:741798018c0d | 152 | ledr = 1; |
MarijkeZondag | 17:741798018c0d | 153 | ledb = 1; |
MarijkeZondag | 17:741798018c0d | 154 | ledg = 0; |
MarijkeZondag | 13:a3d4b4daf5b4 | 155 | } |
MarijkeZondag | 22:5d956c93b3ae | 156 | else //If x = 3 or 4, led is white |
MarijkeZondag | 13:a3d4b4daf5b4 | 157 | { |
MarijkeZondag | 17:741798018c0d | 158 | ledr = 0; |
MarijkeZondag | 17:741798018c0d | 159 | ledb = 0; |
MarijkeZondag | 17:741798018c0d | 160 | ledg = 0; |
MarijkeZondag | 13:a3d4b4daf5b4 | 161 | } |
MarijkeZondag | 13:a3d4b4daf5b4 | 162 | |
MarijkeZondag | 22:5d956c93b3ae | 163 | if(x==4) //Reset back to x = -1 |
MarijkeZondag | 13:a3d4b4daf5b4 | 164 | { |
MarijkeZondag | 16:5f7196ddc77b | 165 | x = -1; |
MarijkeZondag | 23:97a976a8f0fc | 166 | emg_cal=0; //reset, motors off |
MarijkeZondag | 13:a3d4b4daf5b4 | 167 | } |
MarijkeZondag | 13:a3d4b4daf5b4 | 168 | } |
MarijkeZondag | 13:a3d4b4daf5b4 | 169 | |
MarijkeZondag | 13:a3d4b4daf5b4 | 170 | |
MarijkeZondag | 13:a3d4b4daf5b4 | 171 | void calibrate(void) |
MarijkeZondag | 12:eaed305a76c3 | 172 | { |
MarijkeZondag | 13:a3d4b4daf5b4 | 173 | switch(x) |
MarijkeZondag | 13:a3d4b4daf5b4 | 174 | { |
MarijkeZondag | 22:5d956c93b3ae | 175 | case 0: //If calibration state 0: |
MarijkeZondag | 13:a3d4b4daf5b4 | 176 | { |
MarijkeZondag | 13:a3d4b4daf5b4 | 177 | sum = 0.0; |
MarijkeZondag | 22:5d956c93b3ae | 178 | for(int j = 0; j<=sizeCal-1; j++) //Array filled with datapoints from the EMGfilter signal of muscle 0 |
MarijkeZondag | 13:a3d4b4daf5b4 | 179 | { |
MarijkeZondag | 22:5d956c93b3ae | 180 | StoreCal0[j] = emg0_filt; |
MarijkeZondag | 13:a3d4b4daf5b4 | 181 | sum+=StoreCal0[j]; |
MarijkeZondag | 22:5d956c93b3ae | 182 | wait(0.001f); //Does there need to be a wait? |
MarijkeZondag | 13:a3d4b4daf5b4 | 183 | } |
MarijkeZondag | 22:5d956c93b3ae | 184 | Mean0 = sum/sizeCal; //Calculate mean of the datapoints in the calibration set (2000 samples) |
MarijkeZondag | 23:97a976a8f0fc | 185 | Threshold0 = Mean0/2; //Threshold calculation = 0.5*mean |
MarijkeZondag | 22:5d956c93b3ae | 186 | break; //Stop. Threshold is calculated, we will use this further in the code |
MarijkeZondag | 13:a3d4b4daf5b4 | 187 | } |
MarijkeZondag | 22:5d956c93b3ae | 188 | case 1: //If calibration state 1: |
MarijkeZondag | 13:a3d4b4daf5b4 | 189 | { |
MarijkeZondag | 22:5d956c93b3ae | 190 | sum = 0.0; |
MarijkeZondag | 22:5d956c93b3ae | 191 | for(int j = 0; j<=sizeCal-1; j++) //Array filled with datapoints from the EMGfilter signal of muscle 1 |
MarijkeZondag | 13:a3d4b4daf5b4 | 192 | { |
MarijkeZondag | 22:5d956c93b3ae | 193 | StoreCal1[j] = emg1_filt; |
MarijkeZondag | 13:a3d4b4daf5b4 | 194 | sum+=StoreCal1[j]; |
MarijkeZondag | 21:1da43fdbd254 | 195 | wait(0.001f); |
MarijkeZondag | 13:a3d4b4daf5b4 | 196 | } |
MarijkeZondag | 13:a3d4b4daf5b4 | 197 | Mean1 = sum/sizeCal; |
MarijkeZondag | 23:97a976a8f0fc | 198 | Threshold1 = Mean1/2; |
MarijkeZondag | 13:a3d4b4daf5b4 | 199 | break; |
MarijkeZondag | 13:a3d4b4daf5b4 | 200 | } |
MarijkeZondag | 22:5d956c93b3ae | 201 | case 2: //If calibration state 2: |
MarijkeZondag | 13:a3d4b4daf5b4 | 202 | { |
MarijkeZondag | 13:a3d4b4daf5b4 | 203 | sum = 0.0; |
MarijkeZondag | 22:5d956c93b3ae | 204 | for(int j = 0; j<=sizeCal-1; j++) //Array filled with datapoints from the EMGfilter signal of muscle 2 |
MarijkeZondag | 13:a3d4b4daf5b4 | 205 | { |
MarijkeZondag | 23:97a976a8f0fc | 206 | StoreCal2[j] = emg2_filt; |
MarijkeZondag | 13:a3d4b4daf5b4 | 207 | sum+=StoreCal2[j]; |
MarijkeZondag | 21:1da43fdbd254 | 208 | wait(0.001f); |
MarijkeZondag | 13:a3d4b4daf5b4 | 209 | } |
MarijkeZondag | 13:a3d4b4daf5b4 | 210 | Mean2 = sum/sizeCal; |
MarijkeZondag | 23:97a976a8f0fc | 211 | Threshold2 = Mean2/2; |
MarijkeZondag | 13:a3d4b4daf5b4 | 212 | break; |
MarijkeZondag | 13:a3d4b4daf5b4 | 213 | } |
MarijkeZondag | 22:5d956c93b3ae | 214 | case 3: //EMG is calibrated, robot can be set to Home position. |
MarijkeZondag | 13:a3d4b4daf5b4 | 215 | { |
MarijkeZondag | 22:5d956c93b3ae | 216 | emg_cal = 1; //This is the setting for which the motors can begin turning in this code (!!) |
MarijkeZondag | 27:fa493551be99 | 217 | |
MarijkeZondag | 21:1da43fdbd254 | 218 | wait(0.001f); |
MarijkeZondag | 13:a3d4b4daf5b4 | 219 | break; |
MarijkeZondag | 13:a3d4b4daf5b4 | 220 | } |
MarijkeZondag | 22:5d956c93b3ae | 221 | default: //Ensures nothing happens if x is not 0,1 or 2. |
MarijkeZondag | 13:a3d4b4daf5b4 | 222 | { |
MarijkeZondag | 13:a3d4b4daf5b4 | 223 | break; |
MarijkeZondag | 13:a3d4b4daf5b4 | 224 | } |
MarijkeZondag | 13:a3d4b4daf5b4 | 225 | } |
MarijkeZondag | 12:eaed305a76c3 | 226 | } |
MarijkeZondag | 28:5e54cd4525de | 227 | |
MarijkeZondag | 28:5e54cd4525de | 228 | void EMGFilter0() |
MarijkeZondag | 28:5e54cd4525de | 229 | { |
MarijkeZondag | 28:5e54cd4525de | 230 | emg0_raw = emg0_in.read(); //give name to raw EMG0 data |
MarijkeZondag | 28:5e54cd4525de | 231 | emg0_filt_x = emg0filter.step(emg0_raw); //Use biquad chain to filter raw EMG data |
MarijkeZondag | 28:5e54cd4525de | 232 | emg0_filt = abs(emg0_filt_x); //rectifier. LET OP: volgorde filter: band-notch-rectifier. Eerst band-rect-notch, stel er komt iets raars uit, dan Notch uit de biquad chain halen en aparte chain voor aanmaken. |
MarijkeZondag | 28:5e54cd4525de | 233 | } |
MarijkeZondag | 28:5e54cd4525de | 234 | |
MarijkeZondag | 28:5e54cd4525de | 235 | void EMGFilter1() |
MarijkeZondag | 28:5e54cd4525de | 236 | { |
MarijkeZondag | 28:5e54cd4525de | 237 | emg1_raw = emg1_in.read(); //give name to raw EMG1 data |
MarijkeZondag | 28:5e54cd4525de | 238 | emg1_filt_x = emg1filter.step(emg1_raw); //Use biquad chain to filter raw EMG data |
MarijkeZondag | 28:5e54cd4525de | 239 | emg1_filt = abs(emg1_filt_x); //rectifier. LET OP: volgorde filter: band-notch-rectifier. Eerst band-rect-notch. |
MarijkeZondag | 28:5e54cd4525de | 240 | } |
MarijkeZondag | 28:5e54cd4525de | 241 | |
MarijkeZondag | 28:5e54cd4525de | 242 | void EMGFilter2() |
MarijkeZondag | 28:5e54cd4525de | 243 | { |
MarijkeZondag | 28:5e54cd4525de | 244 | emg2_raw = emg2_in.read(); //Give name to raw EMG1 data |
MarijkeZondag | 28:5e54cd4525de | 245 | emg2_filt_x = emg2filter.step(emg2_raw); //Use biquad chain to filter raw EMG data |
MarijkeZondag | 28:5e54cd4525de | 246 | emg2_filt = abs(emg2_filt_x); //Rectifier. LET OP: volgorde filter: band-notch-rectifier. |
MarijkeZondag | 28:5e54cd4525de | 247 | } |
MarijkeZondag | 28:5e54cd4525de | 248 | |
MarijkeZondag | 28:5e54cd4525de | 249 | void MovAg() //Calculate moving average (MovAg), klopt nog niet!! |
MarijkeZondag | 28:5e54cd4525de | 250 | { |
MarijkeZondag | 28:5e54cd4525de | 251 | for (int i = windowsize-1; i>=0; i--) //Make arrays for the last datapoints of the filtered signals |
MarijkeZondag | 28:5e54cd4525de | 252 | { |
MarijkeZondag | 28:5e54cd4525de | 253 | StoreArray0[i] = StoreArray0[i-1]; //Shifts the i'th element one place to the right, this makes it "rolling or moving" average. |
MarijkeZondag | 28:5e54cd4525de | 254 | StoreArray1[i] = StoreArray1[i-1]; |
MarijkeZondag | 28:5e54cd4525de | 255 | StoreArray2[i] = StoreArray2[i-1]; |
MarijkeZondag | 28:5e54cd4525de | 256 | } |
MarijkeZondag | 28:5e54cd4525de | 257 | |
MarijkeZondag | 28:5e54cd4525de | 258 | StoreArray0[0] = emg0_filt; //Stores the latest datapoint of the filtered signal in the first element of the array |
MarijkeZondag | 28:5e54cd4525de | 259 | StoreArray1[0] = emg1_filt; |
MarijkeZondag | 28:5e54cd4525de | 260 | StoreArray2[0] = emg2_filt; |
MarijkeZondag | 28:5e54cd4525de | 261 | |
MarijkeZondag | 28:5e54cd4525de | 262 | sum1 = 0.0; |
MarijkeZondag | 28:5e54cd4525de | 263 | sum2 = 0.0; |
MarijkeZondag | 28:5e54cd4525de | 264 | sum3 = 0.0; |
MarijkeZondag | 28:5e54cd4525de | 265 | |
MarijkeZondag | 28:5e54cd4525de | 266 | for(int a = 0; a<= windowsize-1; a++) //Sums the elements in the arrays |
MarijkeZondag | 28:5e54cd4525de | 267 | { |
MarijkeZondag | 28:5e54cd4525de | 268 | sum1 += StoreArray0[a]; |
MarijkeZondag | 28:5e54cd4525de | 269 | sum2 += StoreArray1[a]; |
MarijkeZondag | 28:5e54cd4525de | 270 | sum3 += StoreArray2[a]; |
MarijkeZondag | 28:5e54cd4525de | 271 | } |
MarijkeZondag | 28:5e54cd4525de | 272 | |
MarijkeZondag | 28:5e54cd4525de | 273 | movAg0 = sum1/windowsize; //calculates an average in the array |
MarijkeZondag | 28:5e54cd4525de | 274 | movAg1 = sum2/windowsize; |
MarijkeZondag | 28:5e54cd4525de | 275 | movAg2 = sum3/windowsize; |
MarijkeZondag | 28:5e54cd4525de | 276 | //serial getallen sturen, als het 1 getal is gaat hier wat fout, als het een reeks is dan gaat er bij de input naar HIDscope wat fout. |
MarijkeZondag | 28:5e54cd4525de | 277 | } |
MarijkeZondag | 28:5e54cd4525de | 278 | |
MarijkeZondag | 28:5e54cd4525de | 279 | void emg_filtered() //Call all filter functions |
MarijkeZondag | 28:5e54cd4525de | 280 | { |
MarijkeZondag | 28:5e54cd4525de | 281 | EMGFilter0(); |
MarijkeZondag | 28:5e54cd4525de | 282 | EMGFilter1(); |
MarijkeZondag | 28:5e54cd4525de | 283 | EMGFilter2(); |
MarijkeZondag | 28:5e54cd4525de | 284 | } |
MarijkeZondag | 28:5e54cd4525de | 285 | |
MarijkeZondag | 26:ac5656aa35c7 | 286 | /* |
MarijkeZondag | 22:5d956c93b3ae | 287 | void HIDScope_sample() |
MarijkeZondag | 22:5d956c93b3ae | 288 | { |
MarijkeZondag | 26:ac5656aa35c7 | 289 | scope.set(0,emg0_raw); |
MarijkeZondag | 26:ac5656aa35c7 | 290 | scope.set(1,emg0_filt); |
MarijkeZondag | 26:ac5656aa35c7 | 291 | scope.set(1,movAg0); //als moving average werkt |
MarijkeZondag | 26:ac5656aa35c7 | 292 | scope.set(2,emg1_raw); |
MarijkeZondag | 26:ac5656aa35c7 | 293 | scope.set(3,emg1_filt); |
MarijkeZondag | 26:ac5656aa35c7 | 294 | scope.set(3,movAg1); //als moving average werkt |
MarijkeZondag | 26:ac5656aa35c7 | 295 | scope.set(4,emg2_raw); |
MarijkeZondag | 26:ac5656aa35c7 | 296 | scope.set(5,emg2_filt); |
MarijkeZondag | 26:ac5656aa35c7 | 297 | scope.set(5,movAg2); //als moving average werkt |
MarijkeZondag | 22:5d956c93b3ae | 298 | |
MarijkeZondag | 26:ac5656aa35c7 | 299 | scope.send(); //Send data to HIDScope server |
MarijkeZondag | 22:5d956c93b3ae | 300 | } |
MarijkeZondag | 26:ac5656aa35c7 | 301 | */ |
MarijkeZondag | 8:895d941a5910 | 302 | |
MarijkeZondag | 28:5e54cd4525de | 303 | |
MarijkeZondag | 28:5e54cd4525de | 304 | //---------PID controller 1 + 2 + motor control 1 & 2-----------------------------------------------------------// |
MarijkeZondag | 28:5e54cd4525de | 305 | void PID_control1() |
MarijkeZondag | 28:5e54cd4525de | 306 | { |
MarijkeZondag | 28:5e54cd4525de | 307 | //pc.printf("ik doe het, PDI \n\r"); |
MarijkeZondag | 28:5e54cd4525de | 308 | |
MarijkeZondag | 28:5e54cd4525de | 309 | // Proportional part: |
MarijkeZondag | 28:5e54cd4525de | 310 | double u_k1 = Kp1 * err1; |
MarijkeZondag | 28:5e54cd4525de | 311 | |
MarijkeZondag | 28:5e54cd4525de | 312 | //Integral part |
MarijkeZondag | 28:5e54cd4525de | 313 | err_integral1 = err_integral1 + err1 * T; |
MarijkeZondag | 28:5e54cd4525de | 314 | double u_i1 = Ki1 * err_integral1; |
MarijkeZondag | 28:5e54cd4525de | 315 | |
MarijkeZondag | 28:5e54cd4525de | 316 | // Derivative part |
MarijkeZondag | 28:5e54cd4525de | 317 | double err_derivative1 = (err1 - err_prev1)/T; |
MarijkeZondag | 28:5e54cd4525de | 318 | double filtered_err_derivative1 = LowPassFilterDer1.step(err_derivative1); |
MarijkeZondag | 28:5e54cd4525de | 319 | double u_d1 = Kd1 * filtered_err_derivative1; |
MarijkeZondag | 28:5e54cd4525de | 320 | err_prev1 = err1; |
MarijkeZondag | 28:5e54cd4525de | 321 | |
MarijkeZondag | 28:5e54cd4525de | 322 | |
MarijkeZondag | 28:5e54cd4525de | 323 | // Sum all parts and return it |
MarijkeZondag | 28:5e54cd4525de | 324 | u1 = u_k1 + u_i1 + u_d1; |
MarijkeZondag | 28:5e54cd4525de | 325 | } |
MarijkeZondag | 28:5e54cd4525de | 326 | |
MarijkeZondag | 28:5e54cd4525de | 327 | void PID_control2() |
MarijkeZondag | 28:5e54cd4525de | 328 | { |
MarijkeZondag | 28:5e54cd4525de | 329 | //pc.printf("ik doe het, PDI \n\r"); |
MarijkeZondag | 28:5e54cd4525de | 330 | |
MarijkeZondag | 28:5e54cd4525de | 331 | // Proportional part: |
MarijkeZondag | 28:5e54cd4525de | 332 | double u_k2 = Kp2 * err2; |
MarijkeZondag | 28:5e54cd4525de | 333 | |
MarijkeZondag | 28:5e54cd4525de | 334 | //Integral part |
MarijkeZondag | 28:5e54cd4525de | 335 | err_integral2 = err_integral2 + err2 * T; |
MarijkeZondag | 28:5e54cd4525de | 336 | double u_i2 = Ki2 * err_integral2; |
MarijkeZondag | 28:5e54cd4525de | 337 | |
MarijkeZondag | 28:5e54cd4525de | 338 | // Derivative part |
MarijkeZondag | 28:5e54cd4525de | 339 | double err_derivative2 = (err2 - err_prev2)/T; |
MarijkeZondag | 28:5e54cd4525de | 340 | double filtered_err_derivative2 = LowPassFilterDer2.step(err_derivative2); |
MarijkeZondag | 28:5e54cd4525de | 341 | double u_d2 = Kd2 * filtered_err_derivative2; |
MarijkeZondag | 28:5e54cd4525de | 342 | err_prev2 = err2; |
MarijkeZondag | 28:5e54cd4525de | 343 | |
MarijkeZondag | 28:5e54cd4525de | 344 | |
MarijkeZondag | 28:5e54cd4525de | 345 | // Sum all parts and return it |
MarijkeZondag | 28:5e54cd4525de | 346 | u2 = u_k2 + u_i2 + u_d2; |
MarijkeZondag | 28:5e54cd4525de | 347 | } |
MarijkeZondag | 28:5e54cd4525de | 348 | |
MarijkeZondag | 28:5e54cd4525de | 349 | void engine_control1() //Engine 1 is translational engine, connected with left side pins |
MarijkeZondag | 28:5e54cd4525de | 350 | { |
MarijkeZondag | 28:5e54cd4525de | 351 | //pc.printf("ik doe het, engine control 1\n\r"); |
MarijkeZondag | 28:5e54cd4525de | 352 | encoder_radians1 = (double)encoder1.getPulses()*(2.0*PI)/8400.0; |
MarijkeZondag | 28:5e54cd4525de | 353 | //pc.printf("encoder1 %f \n\r", (float)encoder1.getPulses()); |
MarijkeZondag | 28:5e54cd4525de | 354 | //pc.printf("encoder_radians1 %f \n\r",(float) encoder_radians1); |
MarijkeZondag | 28:5e54cd4525de | 355 | err1 = q1ref - encoder_radians1; |
MarijkeZondag | 28:5e54cd4525de | 356 | //pc.printf("err1 = %f\n\r",err1); |
MarijkeZondag | 28:5e54cd4525de | 357 | PID_control1(); //PID controller function call |
MarijkeZondag | 28:5e54cd4525de | 358 | |
MarijkeZondag | 28:5e54cd4525de | 359 | //pc.printf("u1 = %f\n\r",u1); |
MarijkeZondag | 28:5e54cd4525de | 360 | |
MarijkeZondag | 28:5e54cd4525de | 361 | //if(encoder1.getPulses()<12000 && encoder1.getPulses()>-1) //limits translation in counts, eerst 12600 |
MarijkeZondag | 28:5e54cd4525de | 362 | //{ |
MarijkeZondag | 28:5e54cd4525de | 363 | pwmpin1 = fabs(u1); //u_total moet nog geschaald worden om in de motor gevoerd te worden!!! |
MarijkeZondag | 28:5e54cd4525de | 364 | directionpin1.write(u1<0); |
MarijkeZondag | 28:5e54cd4525de | 365 | //} |
MarijkeZondag | 28:5e54cd4525de | 366 | //else |
MarijkeZondag | 28:5e54cd4525de | 367 | // { |
MarijkeZondag | 28:5e54cd4525de | 368 | // pwmpin1 = 0; |
MarijkeZondag | 28:5e54cd4525de | 369 | // } |
MarijkeZondag | 28:5e54cd4525de | 370 | } |
MarijkeZondag | 28:5e54cd4525de | 371 | |
MarijkeZondag | 28:5e54cd4525de | 372 | void engine_control2() //Engine 2 is rotational engine, connected with right side wires |
MarijkeZondag | 28:5e54cd4525de | 373 | { |
MarijkeZondag | 28:5e54cd4525de | 374 | encoder_radians2 = (float)encoder2.getPulses()*(2.0*PI)/8400.0; |
MarijkeZondag | 28:5e54cd4525de | 375 | //pc.printf("encoder2 %f \n\r",(float)encoder2.getPulses()); |
MarijkeZondag | 28:5e54cd4525de | 376 | //pc.printf("encoder_radians2 %f \n\r",(float)encoder_radians2); |
MarijkeZondag | 28:5e54cd4525de | 377 | err2 = q2ref - encoder_radians2; |
MarijkeZondag | 28:5e54cd4525de | 378 | //pc.printf("err2 = %f\n\r",err2); |
MarijkeZondag | 28:5e54cd4525de | 379 | PID_control2(); //PID controller function call |
MarijkeZondag | 28:5e54cd4525de | 380 | //pc.printf("u2 = %f\n\r",u2); |
MarijkeZondag | 28:5e54cd4525de | 381 | |
MarijkeZondag | 28:5e54cd4525de | 382 | //if(encoder2.getPulses()<-5250 && encoder2.getPulses()>5250) //limits rotation, in counts |
MarijkeZondag | 28:5e54cd4525de | 383 | // { |
MarijkeZondag | 28:5e54cd4525de | 384 | pwmpin2 = fabs(u2); //u_total moet nog geschaald worden om in de motor gevoerd te worden!!! |
MarijkeZondag | 28:5e54cd4525de | 385 | directionpin2.write(u2>0); |
MarijkeZondag | 28:5e54cd4525de | 386 | // } |
MarijkeZondag | 28:5e54cd4525de | 387 | //else |
MarijkeZondag | 28:5e54cd4525de | 388 | // { |
MarijkeZondag | 28:5e54cd4525de | 389 | // pwmpin2 = 0; |
MarijkeZondag | 28:5e54cd4525de | 390 | // } |
MarijkeZondag | 28:5e54cd4525de | 391 | } |
MarijkeZondag | 28:5e54cd4525de | 392 | |
MarijkeZondag | 26:ac5656aa35c7 | 393 | //------------------ Inversed Kinematics --------------------------------// |
MarijkeZondag | 8:895d941a5910 | 394 | |
Marle | 25:bbef09ff226b | 395 | void inverse_kinematics() |
Marle | 25:bbef09ff226b | 396 | { |
MarijkeZondag | 28:5e54cd4525de | 397 | |
MarijkeZondag | 28:5e54cd4525de | 398 | //pc.printf("v_x is %f en v_y is %f\n\r",v_x, v_y); |
MarijkeZondag | 28:5e54cd4525de | 399 | |
Marle | 25:bbef09ff226b | 400 | Lq1 = q1ref*r_trans; |
Marle | 25:bbef09ff226b | 401 | Cq2 = q2ref/5.0; |
Marle | 25:bbef09ff226b | 402 | |
MarijkeZondag | 28:5e54cd4525de | 403 | q1_dot = v_x + (v_y*(L1 + L3*sin(Cq2)))/(L4 + Lq1 + L3*cos(Cq2)); //RKI systeem |
MarijkeZondag | 28:5e54cd4525de | 404 | q2_dot = v_y/(L4 + Lq1 + L3*cos(Cq2)); // |
Marle | 25:bbef09ff226b | 405 | |
MarijkeZondag | 28:5e54cd4525de | 406 | q1_ii = q1ref + (q1_dot/r_trans)*T; //Omgezet naar motorhoeken |
MarijkeZondag | 28:5e54cd4525de | 407 | q2_ii = q2ref + (q2_dot*5.0)*T; |
Marle | 25:bbef09ff226b | 408 | |
Marle | 25:bbef09ff226b | 409 | q1ref = q1_ii; |
Marle | 25:bbef09ff226b | 410 | q2ref = q2_ii; |
MarijkeZondag | 27:fa493551be99 | 411 | |
MarijkeZondag | 28:5e54cd4525de | 412 | |
MarijkeZondag | 28:5e54cd4525de | 413 | //pc.printf("q1ref is %f en q2ref is %f\n\r",q1ref, q2ref); |
MarijkeZondag | 28:5e54cd4525de | 414 | |
MarijkeZondag | 28:5e54cd4525de | 415 | |
MarijkeZondag | 28:5e54cd4525de | 416 | //start_control = 1; |
MarijkeZondag | 28:5e54cd4525de | 417 | engine_control1(); |
MarijkeZondag | 28:5e54cd4525de | 418 | engine_control2(); |
Marle | 25:bbef09ff226b | 419 | } |
Marle | 25:bbef09ff226b | 420 | |
Marle | 25:bbef09ff226b | 421 | void v_des_calculate_qref() |
MarijkeZondag | 23:97a976a8f0fc | 422 | { |
MarijkeZondag | 30:f04a35f2a06d | 423 | while(emg_cal==1) //After calibration is finished, emg_cal will be 1. Otherwise 0. |
MarijkeZondag | 16:5f7196ddc77b | 424 | { |
MarijkeZondag | 30:f04a35f2a06d | 425 | if(movAg1>Threshold1 && movAg0<Threshold0) //If the filtered EMG signal of muscle 1 is higher than the threshold and the switch is off (movAg0) |
MarijkeZondag | 16:5f7196ddc77b | 426 | { |
MarijkeZondag | 30:f04a35f2a06d | 427 | v_x = 0.5; //movement in +x direction |
MarijkeZondag | 28:5e54cd4525de | 428 | v_y = 0.0; |
MarijkeZondag | 28:5e54cd4525de | 429 | |
MarijkeZondag | 30:f04a35f2a06d | 430 | ledr = 0; //red |
Marle | 25:bbef09ff226b | 431 | ledb = 1; |
Marle | 25:bbef09ff226b | 432 | ledg = 1; |
MarijkeZondag | 16:5f7196ddc77b | 433 | } |
MarijkeZondag | 30:f04a35f2a06d | 434 | else if(movAg2>Threshold2 && movAg0<Threshold0) //If the filtered EMG signal of muscle 2 is higher than the threshold and the switch is off (movAg0) |
MarijkeZondag | 16:5f7196ddc77b | 435 | { |
MarijkeZondag | 30:f04a35f2a06d | 436 | v_y = 0.5; //Movement in +y direction |
MarijkeZondag | 28:5e54cd4525de | 437 | v_x = 0.0; |
MarijkeZondag | 28:5e54cd4525de | 438 | |
MarijkeZondag | 30:f04a35f2a06d | 439 | ledr = 1; //Green |
Marle | 25:bbef09ff226b | 440 | ledb = 1; |
Marle | 25:bbef09ff226b | 441 | ledg = 0; |
MarijkeZondag | 24:6d63ad38fef7 | 442 | } |
Marle | 25:bbef09ff226b | 443 | |
MarijkeZondag | 30:f04a35f2a06d | 444 | else if(movAg0>Threshold0 && movAg1>Threshold1) //If the filtered EMG signal of muscle 1 is higher than the threshold and the switch is on (movAg0) |
MarijkeZondag | 24:6d63ad38fef7 | 445 | { |
MarijkeZondag | 30:f04a35f2a06d | 446 | v_y = 0.0; //Movement in -x direction |
MarijkeZondag | 30:f04a35f2a06d | 447 | v_x = -0.5; |
MarijkeZondag | 28:5e54cd4525de | 448 | |
MarijkeZondag | 30:f04a35f2a06d | 449 | ledr = 0; //Purple |
Marle | 25:bbef09ff226b | 450 | ledb = 0; |
MarijkeZondag | 30:f04a35f2a06d | 451 | ledg = 1; |
MarijkeZondag | 30:f04a35f2a06d | 452 | } |
MarijkeZondag | 28:5e54cd4525de | 453 | |
MarijkeZondag | 30:f04a35f2a06d | 454 | else if(movAg0>Threshold0 && movAg2>Threshold2) //If the filtered EMG signal of muscle 2 is higher than the threshold and the switch is on (movAg0) |
MarijkeZondag | 30:f04a35f2a06d | 455 | { |
MarijkeZondag | 30:f04a35f2a06d | 456 | v_y = -0.5; //Movement in -y direction |
MarijkeZondag | 30:f04a35f2a06d | 457 | v_x = 0.0; |
MarijkeZondag | 30:f04a35f2a06d | 458 | |
MarijkeZondag | 30:f04a35f2a06d | 459 | ledr = 1; //Blue |
MarijkeZondag | 30:f04a35f2a06d | 460 | ledb = 0; |
MarijkeZondag | 30:f04a35f2a06d | 461 | ledg = 1; |
MarijkeZondag | 30:f04a35f2a06d | 462 | } |
MarijkeZondag | 30:f04a35f2a06d | 463 | else //If not higher than any threshold, motors will not turn at all |
Marle | 25:bbef09ff226b | 464 | { |
Marle | 25:bbef09ff226b | 465 | v_x = 0; |
Marle | 25:bbef09ff226b | 466 | v_y = 0; |
MarijkeZondag | 28:5e54cd4525de | 467 | |
MarijkeZondag | 30:f04a35f2a06d | 468 | ledr = 0; //White |
MarijkeZondag | 24:6d63ad38fef7 | 469 | ledb = 0; |
MarijkeZondag | 24:6d63ad38fef7 | 470 | ledg = 0; |
MarijkeZondag | 24:6d63ad38fef7 | 471 | } |
MarijkeZondag | 27:fa493551be99 | 472 | |
MarijkeZondag | 30:f04a35f2a06d | 473 | inverse_kinematics(); //Call inverse kinematics function |
MarijkeZondag | 27:fa493551be99 | 474 | |
MarijkeZondag | 28:5e54cd4525de | 475 | break; |
MarijkeZondag | 23:97a976a8f0fc | 476 | } |
MarijkeZondag | 26:ac5656aa35c7 | 477 | } |
MarijkeZondag | 26:ac5656aa35c7 | 478 | |
MarijkeZondag | 30:f04a35f2a06d | 479 | void printFunction() |
MarijkeZondag | 30:f04a35f2a06d | 480 | { |
MarijkeZondag | 30:f04a35f2a06d | 481 | pc.printf("Movag0 = %f , Movag1 = %f, Movag2 = %f \n\r",movAg0, movAg1, movAg2); |
MarijkeZondag | 30:f04a35f2a06d | 482 | pc.printf("Thresh0 = %f , Thresh1 = %f, Thresh2 = %f \n\r",Threshold0, Threshold1, Threshold2); |
MarijkeZondag | 30:f04a35f2a06d | 483 | } |
MarijkeZondag | 30:f04a35f2a06d | 484 | |
MarijkeZondag | 26:ac5656aa35c7 | 485 | |
MarijkeZondag | 26:ac5656aa35c7 | 486 | |
MarijkeZondag | 26:ac5656aa35c7 | 487 | //------------------ Start main function --------------------------// |
MarijkeZondag | 26:ac5656aa35c7 | 488 | |
MarijkeZondag | 26:ac5656aa35c7 | 489 | |
MarijkeZondag | 23:97a976a8f0fc | 490 | int main() |
MarijkeZondag | 23:97a976a8f0fc | 491 | { |
MarijkeZondag | 23:97a976a8f0fc | 492 | pc.baud(115200); |
MarijkeZondag | 30:f04a35f2a06d | 493 | pc.printf("Hello World!\r\n"); //Serial communication only works if hidscope is turned off. |
MarijkeZondag | 30:f04a35f2a06d | 494 | pwmpin1.period_us(60); //60 microseconds PWM period, 16.7 kHz |
MarijkeZondag | 23:97a976a8f0fc | 495 | |
MarijkeZondag | 23:97a976a8f0fc | 496 | emg0filter.add( &emg0band1 ).add( &emg0band2 ).add( &emg0band3 ).add( ¬ch1 ); //attach biquad elements to chain |
MarijkeZondag | 23:97a976a8f0fc | 497 | emg1filter.add( &emg1band1 ).add( &emg1band2 ).add( &emg1band3 ).add( ¬ch2 ); |
MarijkeZondag | 23:97a976a8f0fc | 498 | emg2filter.add( &emg2band1 ).add( &emg2band2 ).add( &emg2band3 ).add( ¬ch3 ); |
MarijkeZondag | 10:39ec51206c8b | 499 | |
MarijkeZondag | 30:f04a35f2a06d | 500 | emg_tick.attach(&emg_filtered,T); //EMG signals filtered + moving average every T sec. |
MarijkeZondag | 28:5e54cd4525de | 501 | movag_tick.attach(&MovAg,T); |
MarijkeZondag | 30:f04a35f2a06d | 502 | func_tick.attach(&v_des_calculate_qref,T); //v_des determined every T |
MarijkeZondag | 30:f04a35f2a06d | 503 | print_tick.attach(&printFunction,T2); |
MarijkeZondag | 30:f04a35f2a06d | 504 | // HIDScope_tick.attach(&HIDScope_sample,T); //EMG signals raw + filtered to HIDScope every T sec. |
MarijkeZondag | 28:5e54cd4525de | 505 | |
MarijkeZondag | 30:f04a35f2a06d | 506 | button1.rise(switch_to_calibrate); //Switch state of calibration (which muscle) |
MarijkeZondag | 30:f04a35f2a06d | 507 | //wait(0.2f); //Wait to avoid bouncing of button |
MarijkeZondag | 30:f04a35f2a06d | 508 | button2.rise(calibrate); //Calibrate threshold for 3 muscles |
MarijkeZondag | 30:f04a35f2a06d | 509 | //wait(0.2f); //Wait to avoid bouncing of button |
MarijkeZondag | 28:5e54cd4525de | 510 | |
MarijkeZondag | 23:97a976a8f0fc | 511 | while(true) |
MarijkeZondag | 23:97a976a8f0fc | 512 | { |
MarijkeZondag | 30:f04a35f2a06d | 513 | ; |
MarijkeZondag | 23:97a976a8f0fc | 514 | } |
vsluiter | 0:c8f15874531b | 515 | } |