final version

Dependencies:   HIDScope MODSERIAL QEI biquadFilter mbed

Fork of Project_script_union_final by Jorine Oosting

Committer:
MarijkeZondag
Date:
Thu Nov 01 17:29:06 2018 +0000
Revision:
28:5e54cd4525de
Parent:
27:fa493551be99
Child:
29:6cd4f5ac57c4
Werkende PID controller, Inversed kinematics zijn we nog niet helemaal zeker van.

Who changed what in which revision?

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