final version

Dependencies:   HIDScope MODSERIAL QEI biquadFilter mbed

Fork of Project_script_union_final by Jorine Oosting

Committer:
MarijkeZondag
Date:
Tue Nov 06 14:31:52 2018 +0000
Revision:
38:f45aa515f625
Parent:
37:c7ca9bc29d20
final script;

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"
MarijkeZondag 38:f45aa515f625 7 //
MarijkeZondag 22:5d956c93b3ae 8 //ATTENTION: set mBed to version 151
JorineOosting 36:650a9245bc44 9 // set QEI to version 0
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 37:c7ca9bc29d20 14 AnalogIn emg0_in (A0); //First raw EMG signal input: calve muscle
MarijkeZondag 37:c7ca9bc29d20 15 AnalogIn emg1_in (A1); //Second raw EMG signal input: biceps muscle 1
MarijkeZondag 37:c7ca9bc29d20 16 AnalogIn emg2_in (A2); //Third raw EMG signal input: biceps muscle 2
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
JorineOosting 36:650a9245bc44 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 37:c7ca9bc29d20 36 //--------------Tickers------------------------------------------------------------------------------------------------------------------------------//
vsluiter 0:c8f15874531b 37
MarijkeZondag 28:5e54cd4525de 38 Ticker func_tick;
MarijkeZondag 28:5e54cd4525de 39 Ticker movag_tick;
MarijkeZondag 30:f04a35f2a06d 40 Ticker emg_tick;
MarijkeZondag 30:f04a35f2a06d 41 Ticker print_tick;
MarijkeZondag 30:f04a35f2a06d 42
MarijkeZondag 37:c7ca9bc29d20 43
MarijkeZondag 37:c7ca9bc29d20 44 //--------------Global Variables---------------------------------------------------------------------------------------------------------------------//
JorineOosting 36:650a9245bc44 45
JorineOosting 36:650a9245bc44 46 //Ticker frequencies
MarijkeZondag 35:63c890ac71ff 47 const float T = 0.002f; //Ticker period EMG, engine control
MarijkeZondag 35:63c890ac71ff 48 const float T2 = 0.2f; //Ticker print function
MarijkeZondag 10:39ec51206c8b 49
MarijkeZondag 13:a3d4b4daf5b4 50 //EMG filter
MarijkeZondag 22:5d956c93b3ae 51 double emg0_filt, emg1_filt, emg2_filt; //Variables for filtered EMG data channel 0, 1 and 2
MarijkeZondag 22:5d956c93b3ae 52 double emg0_raw, emg1_raw, emg2_raw;
MarijkeZondag 22:5d956c93b3ae 53 double emg0_filt_x, emg1_filt_x, emg2_filt_x;
MarijkeZondag 35:63c890ac71ff 54 const int windowsize = 150; //Size of the array over which the moving average (MovAg) is calculated
JorineOosting 36:650a9245bc44 55 double sum, sum1, sum2, sum3; //Variables used to sum elements in array
JorineOosting 36:650a9245bc44 56 double StoreArray0[windowsize], StoreArray1[windowsize], StoreArray2[windowsize]; //Empty arrays to calculate MovAg
MarijkeZondag 35:63c890ac71ff 57 double movAg0, movAg1, movAg2; //Outcome of MovAg
MarijkeZondag 13:a3d4b4daf5b4 58
MarijkeZondag 22:5d956c93b3ae 59 //Calibration variables
MarijkeZondag 22:5d956c93b3ae 60 int x = -1; //Start switch, colour LED is blue.
MarijkeZondag 35:63c890ac71ff 61 int emg_cal = 0; //If emg_cal is set to 1, motors can begin to work in this code
MarijkeZondag 35:63c890ac71ff 62 const int sizeCal = 1500; //Size of the dataset used for calibration
MarijkeZondag 35:63c890ac71ff 63 double StoreCal0[sizeCal], StoreCal1[sizeCal], StoreCal2[sizeCal]; //Arrays to put the dataset of the calibration in
JorineOosting 36:650a9245bc44 64 double Mean0,Mean1,Mean2; //Average of maximum contraction: Threshold values
MarijkeZondag 22:5d956c93b3ae 65 double Threshold0, Threshold1, Threshold2;
MarijkeZondag 13:a3d4b4daf5b4 66
MarijkeZondag 35:63c890ac71ff 67 //Biquad //Variables for the biquad band filters
MarijkeZondag 22:5d956c93b3ae 68 BiQuadChain emg0filter;
MarijkeZondag 10:39ec51206c8b 69 BiQuad emg0band1( 7.29441e-01, -1.89276e-08, -7.29450e-01, -1.64507e-01, -7.26543e-01 );
MarijkeZondag 10:39ec51206c8b 70 BiQuad emg0band2( 1.00000e+00, 1.99999e+00, 9.99994e-01, 1.72349e+00, 7.79616e-01 );
MarijkeZondag 10:39ec51206c8b 71 BiQuad emg0band3( 1.00000e+00, -1.99999e+00, 9.99994e-01, -1.93552e+00, 9.39358e-01 );
MarijkeZondag 35:63c890ac71ff 72 BiQuad notch1( 9.91104e-01, -1.60364e+00, 9.91104e-01, -1.60364e+00, 9.82207e-01 ); //Notch filter biquad coefficients
MarijkeZondag 10:39ec51206c8b 73
MarijkeZondag 22:5d956c93b3ae 74 BiQuadChain emg1filter;
MarijkeZondag 10:39ec51206c8b 75 BiQuad emg1band1( 7.29441e-01, -1.89276e-08, -7.29450e-01, -1.64507e-01, -7.26543e-01 );
MarijkeZondag 10:39ec51206c8b 76 BiQuad emg1band2( 1.00000e+00, 1.99999e+00, 9.99994e-01, 1.72349e+00, 7.79616e-01 );
MarijkeZondag 10:39ec51206c8b 77 BiQuad emg1band3( 1.00000e+00, -1.99999e+00, 9.99994e-01, -1.93552e+00, 9.39358e-01 );
MarijkeZondag 35:63c890ac71ff 78 BiQuad notch2( 9.91104e-01, -1.60364e+00, 9.91104e-01, -1.60364e+00, 9.82207e-01 );
MarijkeZondag 10:39ec51206c8b 79
MarijkeZondag 22:5d956c93b3ae 80 BiQuadChain emg2filter;
MarijkeZondag 10:39ec51206c8b 81 BiQuad emg2band1( 7.29441e-01, -1.89276e-08, -7.29450e-01, -1.64507e-01, -7.26543e-01 );
MarijkeZondag 10:39ec51206c8b 82 BiQuad emg2band2( 1.00000e+00, 1.99999e+00, 9.99994e-01, 1.72349e+00, 7.79616e-01 );
MarijkeZondag 10:39ec51206c8b 83 BiQuad emg2band3( 1.00000e+00, -1.99999e+00, 9.99994e-01, -1.93552e+00, 9.39358e-01 );
MarijkeZondag 35:63c890ac71ff 84 BiQuad notch3( 9.91104e-01, -1.60364e+00, 9.91104e-01, -1.60364e+00, 9.82207e-01 );
MarijkeZondag 10:39ec51206c8b 85
Marle 25:bbef09ff226b 86
MarijkeZondag 26:ac5656aa35c7 87 //Variables PID controller
MarijkeZondag 35:63c890ac71ff 88 double PI = 3.14159; //Pi value
Marle 25:bbef09ff226b 89
MarijkeZondag 35:63c890ac71ff 90 double Kp1 = 20.0; //Proportional gain motor 1
MarijkeZondag 35:63c890ac71ff 91 double Ki1 = 1.02; //Integrative term motor 1
MarijkeZondag 35:63c890ac71ff 92 double Kd1 = 1.0; //Differential term motor 1
MarijkeZondag 35:63c890ac71ff 93 double encoder_radians1=0; //Inital encoder value motor 1
MarijkeZondag 35:63c890ac71ff 94 double err_integral1 = 0; //Initial error integral value motor 1
MarijkeZondag 35:63c890ac71ff 95 double err_prev1, err_prev2; //Variables called previous error motor 1 and motor 2
JorineOosting 36:650a9245bc44 96 double err1, err2; //Variables called current error motor 1 and motor 2
JorineOosting 36:650a9245bc44 97 BiQuad LowPassFilterDer1( 1.12160e-01, 1.12160e-01, 0.00000e+00, -7.75680e-01, 0.00000e+00 ); //Lowpass differential term: Sample frequency 500 Hz, cutoff 20Hz low pass
MarijkeZondag 35:63c890ac71ff 98
MarijkeZondag 35:63c890ac71ff 99 double Kp2 = 20.0; / //Motor 2
MarijkeZondag 26:ac5656aa35c7 100 double Ki2 = 1.02;
MarijkeZondag 28:5e54cd4525de 101 double Kd2 = 1.0;
MarijkeZondag 26:ac5656aa35c7 102 double encoder_radians2=0;
MarijkeZondag 28:5e54cd4525de 103 double err_integral2 = 0;
MarijkeZondag 28:5e54cd4525de 104 double u1, u2;
MarijkeZondag 30:f04a35f2a06d 105 BiQuad LowPassFilterDer2( 1.12160e-01, 1.12160e-01, 0.00000e+00, -7.75680e-01, 0.00000e+00 );
MarijkeZondag 26:ac5656aa35c7 106
MarijkeZondag 32:56a8bd82e971 107 // Inverse Kinematica variables
JorineOosting 36:650a9245bc44 108 //const double L1 = 0.208; //Height of the base assembly
JorineOosting 36:650a9245bc44 109 //const double L2 = 0.288; //Height of joint 2
JorineOosting 36:650a9245bc44 110 const double L3 = 0.212; //Length of the rotating arm
JorineOosting 36:650a9245bc44 111 const double r_trans = 0.035; //Radius of translational gear
MarijkeZondag 32:56a8bd82e971 112
MarijkeZondag 32:56a8bd82e971 113 // Variërende variabelen inverse kinematics:
JorineOosting 36:650a9245bc44 114 double q1ref = 0.0; //Current motor angle of joint 1, initial value = 0
JorineOosting 36:650a9245bc44 115 double q2ref = 0.0; //Current motor angle of joint 2, initial value = 0
JorineOosting 36:650a9245bc44 116 double v_x; //Desired velocity of end effector in x direction --> Determined by EMG signals
JorineOosting 36:650a9245bc44 117 double v_y; //Desired velocity of end effector in y direction --> Determined by EMG signals
MarijkeZondag 32:56a8bd82e971 118
JorineOosting 36:650a9245bc44 119 double q1_dot=0.0; //Required angular velocity of motor 1 to reach v_des
JorineOosting 36:650a9245bc44 120 double q2_dot=0.0; //Required angular velocity of motor 2 to reach v_des
MarijkeZondag 32:56a8bd82e971 121
JorineOosting 36:650a9245bc44 122 double q1_ii=0.0; //New reference angle for joint 1, becomes new q1ref
JorineOosting 36:650a9245bc44 123 double q2_ii=0.0; //New reference angke for joint 2, becomes new q2ref
MarijkeZondag 32:56a8bd82e971 124
JorineOosting 36:650a9245bc44 125 double q1_motor; //Reference motor angle 1, input PID control
JorineOosting 36:650a9245bc44 126 double q2_motor; //Reference motor angle 2, input PID control
MarijkeZondag 28:5e54cd4525de 127
MarijkeZondag 26:ac5656aa35c7 128 //--------------Functions----------------------------------------------------------------------------------------------------------------------------//
MarijkeZondag 26:ac5656aa35c7 129
MarijkeZondag 26:ac5656aa35c7 130
MarijkeZondag 35:63c890ac71ff 131 //------------------ Filter EMG + Calibration EMG --------------------------------------------------------------------------------------------------//
MarijkeZondag 26:ac5656aa35c7 132
MarijkeZondag 13:a3d4b4daf5b4 133 void switch_to_calibrate()
MarijkeZondag 13:a3d4b4daf5b4 134 {
MarijkeZondag 35:63c890ac71ff 135 //Every time function gets called, x increases. Every button press --> new calibration state.
MarijkeZondag 35:63c890ac71ff 136 //Starts with x = -1. So when function gets called 1 time, x = 0. In the end, x = 4 will reset to -1.
MarijkeZondag 35:63c890ac71ff 137
MarijkeZondag 35:63c890ac71ff 138 x++;
MarijkeZondag 35:63c890ac71ff 139
MarijkeZondag 22:5d956c93b3ae 140
MarijkeZondag 35:63c890ac71ff 141 if(x==0) //If x = 0, led is red
MarijkeZondag 13:a3d4b4daf5b4 142 {
MarijkeZondag 17:741798018c0d 143 ledr = 0;
MarijkeZondag 17:741798018c0d 144 ledb = 1;
MarijkeZondag 17:741798018c0d 145 ledg = 1;
MarijkeZondag 13:a3d4b4daf5b4 146 }
MarijkeZondag 35:63c890ac71ff 147 else if (x==1) //If x = 1, led is blue
MarijkeZondag 13:a3d4b4daf5b4 148 {
MarijkeZondag 17:741798018c0d 149 ledr = 1;
MarijkeZondag 17:741798018c0d 150 ledb = 0;
MarijkeZondag 17:741798018c0d 151 ledg = 1;
MarijkeZondag 13:a3d4b4daf5b4 152 }
MarijkeZondag 35:63c890ac71ff 153 else if (x==2) //If x = 2, led is green
MarijkeZondag 13:a3d4b4daf5b4 154 {
MarijkeZondag 17:741798018c0d 155 ledr = 1;
MarijkeZondag 17:741798018c0d 156 ledb = 1;
MarijkeZondag 17:741798018c0d 157 ledg = 0;
MarijkeZondag 13:a3d4b4daf5b4 158 }
MarijkeZondag 35:63c890ac71ff 159 else //If x = 3 or 4, led is white
MarijkeZondag 13:a3d4b4daf5b4 160 {
MarijkeZondag 17:741798018c0d 161 ledr = 0;
MarijkeZondag 17:741798018c0d 162 ledb = 0;
MarijkeZondag 17:741798018c0d 163 ledg = 0;
MarijkeZondag 13:a3d4b4daf5b4 164 }
MarijkeZondag 13:a3d4b4daf5b4 165
MarijkeZondag 35:63c890ac71ff 166 if(x==4) //Reset back to x = -1
MarijkeZondag 13:a3d4b4daf5b4 167 {
MarijkeZondag 16:5f7196ddc77b 168 x = -1;
MarijkeZondag 35:63c890ac71ff 169 emg_cal=0; //Reset, motors off
MarijkeZondag 13:a3d4b4daf5b4 170 }
MarijkeZondag 13:a3d4b4daf5b4 171 }
MarijkeZondag 13:a3d4b4daf5b4 172
MarijkeZondag 13:a3d4b4daf5b4 173
MarijkeZondag 13:a3d4b4daf5b4 174 void calibrate(void)
MarijkeZondag 12:eaed305a76c3 175 {
MarijkeZondag 13:a3d4b4daf5b4 176 switch(x)
MarijkeZondag 13:a3d4b4daf5b4 177 {
MarijkeZondag 35:63c890ac71ff 178 case 0: //If calibration state 0:
MarijkeZondag 13:a3d4b4daf5b4 179 {
MarijkeZondag 13:a3d4b4daf5b4 180 sum = 0.0;
MarijkeZondag 35:63c890ac71ff 181 for(int j = 0; j<=sizeCal-1; j++) //Array filled with datapoints from the EMGfilter signal of muscle 0
MarijkeZondag 13:a3d4b4daf5b4 182 {
MarijkeZondag 22:5d956c93b3ae 183 StoreCal0[j] = emg0_filt;
MarijkeZondag 13:a3d4b4daf5b4 184 sum+=StoreCal0[j];
MarijkeZondag 35:63c890ac71ff 185 wait(0.001f);
MarijkeZondag 13:a3d4b4daf5b4 186 }
MarijkeZondag 35:63c890ac71ff 187 Mean0 = sum/sizeCal; //Calculate mean of the datapoints in the calibration set
JorineOosting 36:650a9245bc44 188 Threshold0 = Mean0*0.5; //Threshold calculation calve = 0.5*mean
MarijkeZondag 35:63c890ac71ff 189 break; //Stop. Threshold is calculated.
MarijkeZondag 13:a3d4b4daf5b4 190 }
MarijkeZondag 35:63c890ac71ff 191 case 1: //If calibration state 1:
MarijkeZondag 13:a3d4b4daf5b4 192 {
MarijkeZondag 22:5d956c93b3ae 193 sum = 0.0;
MarijkeZondag 35:63c890ac71ff 194 for(int j = 0; j<=sizeCal-1; j++) //Array filled with datapoints from the EMGfilter signal of muscle 1
MarijkeZondag 13:a3d4b4daf5b4 195 {
MarijkeZondag 22:5d956c93b3ae 196 StoreCal1[j] = emg1_filt;
MarijkeZondag 13:a3d4b4daf5b4 197 sum+=StoreCal1[j];
MarijkeZondag 21:1da43fdbd254 198 wait(0.001f);
MarijkeZondag 13:a3d4b4daf5b4 199 }
MarijkeZondag 13:a3d4b4daf5b4 200 Mean1 = sum/sizeCal;
MarijkeZondag 23:97a976a8f0fc 201 Threshold1 = Mean1/2;
MarijkeZondag 13:a3d4b4daf5b4 202 break;
MarijkeZondag 35:63c890ac71ff 203 }
MarijkeZondag 35:63c890ac71ff 204 case 2: //If calibration state 2:
MarijkeZondag 13:a3d4b4daf5b4 205 {
MarijkeZondag 13:a3d4b4daf5b4 206 sum = 0.0;
MarijkeZondag 35:63c890ac71ff 207 for(int j = 0; j<=sizeCal-1; j++) //Array filled with datapoints from the EMGfilter signal of muscle 2
MarijkeZondag 13:a3d4b4daf5b4 208 {
MarijkeZondag 23:97a976a8f0fc 209 StoreCal2[j] = emg2_filt;
MarijkeZondag 13:a3d4b4daf5b4 210 sum+=StoreCal2[j];
MarijkeZondag 21:1da43fdbd254 211 wait(0.001f);
MarijkeZondag 13:a3d4b4daf5b4 212 }
MarijkeZondag 13:a3d4b4daf5b4 213 Mean2 = sum/sizeCal;
MarijkeZondag 23:97a976a8f0fc 214 Threshold2 = Mean2/2;
MarijkeZondag 13:a3d4b4daf5b4 215 break;
MarijkeZondag 13:a3d4b4daf5b4 216 }
MarijkeZondag 35:63c890ac71ff 217 case 3: //EMG is calibrated, robot can be set to Home position.
MarijkeZondag 13:a3d4b4daf5b4 218 {
MarijkeZondag 35:63c890ac71ff 219 emg_cal = 1; //This is the setting for which the motors can begin turning in this code
MarijkeZondag 27:fa493551be99 220
MarijkeZondag 21:1da43fdbd254 221 wait(0.001f);
MarijkeZondag 13:a3d4b4daf5b4 222 break;
MarijkeZondag 13:a3d4b4daf5b4 223 }
MarijkeZondag 35:63c890ac71ff 224 default: //Ensures nothing happens if x is not 0,1 or 2
MarijkeZondag 13:a3d4b4daf5b4 225 {
MarijkeZondag 13:a3d4b4daf5b4 226 break;
MarijkeZondag 13:a3d4b4daf5b4 227 }
MarijkeZondag 13:a3d4b4daf5b4 228 }
MarijkeZondag 12:eaed305a76c3 229 }
MarijkeZondag 28:5e54cd4525de 230
MarijkeZondag 28:5e54cd4525de 231 void EMGFilter0()
MarijkeZondag 28:5e54cd4525de 232 {
MarijkeZondag 35:63c890ac71ff 233 emg0_raw = emg0_in.read(); //Give name to raw EMG0 data
MarijkeZondag 35:63c890ac71ff 234 emg0_filt_x = emg0filter.step(emg0_raw); //Use biquad chain to filter raw EMG data
MarijkeZondag 35:63c890ac71ff 235 emg0_filt = abs(emg0_filt_x); //Rectifier
MarijkeZondag 28:5e54cd4525de 236 }
MarijkeZondag 28:5e54cd4525de 237
MarijkeZondag 28:5e54cd4525de 238 void EMGFilter1()
MarijkeZondag 28:5e54cd4525de 239 {
MarijkeZondag 35:63c890ac71ff 240 emg1_raw = emg1_in.read(); //Give name to raw EMG1 data
MarijkeZondag 35:63c890ac71ff 241 emg1_filt_x = emg1filter.step(emg1_raw); //Use biquad chain to filter raw EMG data
MarijkeZondag 35:63c890ac71ff 242 emg1_filt = abs(emg1_filt_x); //Rectifier
MarijkeZondag 28:5e54cd4525de 243 }
MarijkeZondag 28:5e54cd4525de 244
MarijkeZondag 28:5e54cd4525de 245 void EMGFilter2()
MarijkeZondag 28:5e54cd4525de 246 {
MarijkeZondag 35:63c890ac71ff 247 emg2_raw = emg2_in.read(); //Give name to raw EMG1 data
MarijkeZondag 35:63c890ac71ff 248 emg2_filt_x = emg2filter.step(emg2_raw); //Use biquad chain to filter raw EMG data
MarijkeZondag 35:63c890ac71ff 249 emg2_filt = abs(emg2_filt_x); //Rectifier
MarijkeZondag 28:5e54cd4525de 250 }
MarijkeZondag 28:5e54cd4525de 251
MarijkeZondag 35:63c890ac71ff 252 void MovAg() //Calculate moving average (MovAg)
MarijkeZondag 28:5e54cd4525de 253 {
MarijkeZondag 35:63c890ac71ff 254 for (int i = windowsize-1; i>=0; i--) //Make arrays for the last datapoints of the filtered signals
MarijkeZondag 28:5e54cd4525de 255 {
MarijkeZondag 35:63c890ac71ff 256 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 257 StoreArray1[i] = StoreArray1[i-1];
MarijkeZondag 28:5e54cd4525de 258 StoreArray2[i] = StoreArray2[i-1];
MarijkeZondag 28:5e54cd4525de 259 }
MarijkeZondag 28:5e54cd4525de 260
MarijkeZondag 35:63c890ac71ff 261 StoreArray0[0] = emg0_filt; //Stores the latest datapoint of the filtered signal in the first element of the array
MarijkeZondag 28:5e54cd4525de 262 StoreArray1[0] = emg1_filt;
MarijkeZondag 28:5e54cd4525de 263 StoreArray2[0] = emg2_filt;
MarijkeZondag 28:5e54cd4525de 264
MarijkeZondag 28:5e54cd4525de 265 sum1 = 0.0;
MarijkeZondag 28:5e54cd4525de 266 sum2 = 0.0;
MarijkeZondag 28:5e54cd4525de 267 sum3 = 0.0;
MarijkeZondag 28:5e54cd4525de 268
MarijkeZondag 35:63c890ac71ff 269 for(int a = 0; a<= windowsize-1; a++) //Sums the elements in the arrays
MarijkeZondag 28:5e54cd4525de 270 {
MarijkeZondag 28:5e54cd4525de 271 sum1 += StoreArray0[a];
MarijkeZondag 28:5e54cd4525de 272 sum2 += StoreArray1[a];
MarijkeZondag 28:5e54cd4525de 273 sum3 += StoreArray2[a];
MarijkeZondag 28:5e54cd4525de 274 }
MarijkeZondag 28:5e54cd4525de 275
JorineOosting 36:650a9245bc44 276 movAg0 = sum1/windowsize; //Calculates an average in the array
MarijkeZondag 28:5e54cd4525de 277 movAg1 = sum2/windowsize;
MarijkeZondag 28:5e54cd4525de 278 movAg2 = sum3/windowsize;
MarijkeZondag 28:5e54cd4525de 279 }
MarijkeZondag 28:5e54cd4525de 280
MarijkeZondag 35:63c890ac71ff 281 void emg_filtered() //Call all filter functions
MarijkeZondag 28:5e54cd4525de 282 {
MarijkeZondag 28:5e54cd4525de 283 EMGFilter0();
MarijkeZondag 28:5e54cd4525de 284 EMGFilter1();
MarijkeZondag 28:5e54cd4525de 285 EMGFilter2();
MarijkeZondag 28:5e54cd4525de 286 }
MarijkeZondag 28:5e54cd4525de 287
MarijkeZondag 35:63c890ac71ff 288 //---------PID controller 1 + 2 + motor control 1 & 2-----------------------------------------------------------------------------------------------//
MarijkeZondag 28:5e54cd4525de 289 void PID_control1()
MarijkeZondag 28:5e54cd4525de 290 {
MarijkeZondag 28:5e54cd4525de 291 // Proportional part:
MarijkeZondag 35:63c890ac71ff 292 double u_k1 = Kp1 * err1; //Proportional gain times calculated error
MarijkeZondag 28:5e54cd4525de 293
MarijkeZondag 28:5e54cd4525de 294 //Integral part
MarijkeZondag 35:63c890ac71ff 295 err_integral1 = err_integral1 + err1 * T; //Adds the error*T
MarijkeZondag 35:63c890ac71ff 296 double u_i1 = Ki1 * err_integral1; //Integral term times the integral
MarijkeZondag 28:5e54cd4525de 297
MarijkeZondag 28:5e54cd4525de 298 // Derivative part
JorineOosting 36:650a9245bc44 299 double err_derivative1 = (err1 - err_prev1)/T; //Error - previous error /T
MarijkeZondag 35:63c890ac71ff 300 double filtered_err_derivative1 = LowPassFilterDer1.step(err_derivative1); //Filter the derivative term for stabilization
MarijkeZondag 35:63c890ac71ff 301 double u_d1 = Kd1 * filtered_err_derivative1; //Derivative term times the derivative error
MarijkeZondag 35:63c890ac71ff 302 err_prev1 = err1; //Sets the current error to previous error (remember)
MarijkeZondag 28:5e54cd4525de 303
MarijkeZondag 35:63c890ac71ff 304 // Sum all parts and return it
MarijkeZondag 35:63c890ac71ff 305 u1 = u_k1 + u_i1 + u_d1;
MarijkeZondag 28:5e54cd4525de 306 }
MarijkeZondag 28:5e54cd4525de 307
MarijkeZondag 28:5e54cd4525de 308 void PID_control2()
MarijkeZondag 28:5e54cd4525de 309 {
MarijkeZondag 28:5e54cd4525de 310 // Proportional part:
MarijkeZondag 28:5e54cd4525de 311 double u_k2 = Kp2 * err2;
MarijkeZondag 28:5e54cd4525de 312
MarijkeZondag 28:5e54cd4525de 313 //Integral part
MarijkeZondag 28:5e54cd4525de 314 err_integral2 = err_integral2 + err2 * T;
MarijkeZondag 28:5e54cd4525de 315 double u_i2 = Ki2 * err_integral2;
MarijkeZondag 28:5e54cd4525de 316
MarijkeZondag 28:5e54cd4525de 317 // Derivative part
MarijkeZondag 28:5e54cd4525de 318 double err_derivative2 = (err2 - err_prev2)/T;
MarijkeZondag 28:5e54cd4525de 319 double filtered_err_derivative2 = LowPassFilterDer2.step(err_derivative2);
MarijkeZondag 28:5e54cd4525de 320 double u_d2 = Kd2 * filtered_err_derivative2;
MarijkeZondag 28:5e54cd4525de 321 err_prev2 = err2;
MarijkeZondag 28:5e54cd4525de 322
MarijkeZondag 35:63c890ac71ff 323 // Sum all parts and return it
MarijkeZondag 28:5e54cd4525de 324 u2 = u_k2 + u_i2 + u_d2;
MarijkeZondag 28:5e54cd4525de 325 }
JorineOosting 36:650a9245bc44 326 void engine_control1() //Engine 1 is translational joint, connected with left side pins
MarijkeZondag 28:5e54cd4525de 327 {
MarijkeZondag 28:5e54cd4525de 328 encoder_radians1 = (double)encoder1.getPulses()*(2.0*PI)/8400.0;
JorineOosting 36:650a9245bc44 329 err1 = q1_motor - encoder_radians1; //Calculate error between reference angle 1 and current angle 1
MarijkeZondag 35:63c890ac71ff 330 PID_control1(); //PID 1 controller function call
JorineOosting 36:650a9245bc44 331 pwmpin1 = fabs(u1); //Set speed motor 1
JorineOosting 36:650a9245bc44 332 directionpin1.write(u1<0); //Set direction motor 1
MarijkeZondag 28:5e54cd4525de 333 }
MarijkeZondag 28:5e54cd4525de 334
JorineOosting 36:650a9245bc44 335 void engine_control2() //Engine 2 is rotational joint, connected with right side wires
MarijkeZondag 28:5e54cd4525de 336 {
MarijkeZondag 28:5e54cd4525de 337 encoder_radians2 = (float)encoder2.getPulses()*(2.0*PI)/8400.0;
JorineOosting 36:650a9245bc44 338 err2 = q2_motor - encoder_radians2; //Calculate error between reference angle 2 and current angle 2
MarijkeZondag 35:63c890ac71ff 339 PID_control2(); //PID 2 controller function call
JorineOosting 36:650a9245bc44 340 pwmpin2 = fabs(u2); //Set speed motor 2
JorineOosting 36:650a9245bc44 341 directionpin2.write(u2>0); //Set direction motor 2
MarijkeZondag 28:5e54cd4525de 342 }
MarijkeZondag 28:5e54cd4525de 343
Esmee 33:976be2825a23 344
MarijkeZondag 35:63c890ac71ff 345 //------------------ Inversed Kinematics -----------------------------------------------------------------------------------------------------------//
MarijkeZondag 8:895d941a5910 346
Marle 25:bbef09ff226b 347 void inverse_kinematics()
Esmee 34:b8b18ba0c336 348 {
Marle 25:bbef09ff226b 349
MarijkeZondag 35:63c890ac71ff 350 q1_dot = (v_x*cos(q2ref) + v_y*sin(q2ref))/cos(q2ref); //Calculate desired angular velocity of motor 1
MarijkeZondag 35:63c890ac71ff 351 q2_dot = v_y/(L3*cos(q2ref)); //Calculate desired angular velocity of motor 2
MarijkeZondag 35:63c890ac71ff 352
JorineOosting 36:650a9245bc44 353 q1_ii = q1ref + q1_dot*T; //Calculate new reference angle of joint 1, from current angle and desired angular velocity times ticker time
JorineOosting 36:650a9245bc44 354 q2_ii = q2ref + q2_dot*T; //Calculate new reference angle of joint 2, from current angle and desired angular velocity times ticker time
Marle 25:bbef09ff226b 355
JorineOosting 36:650a9245bc44 356 q1ref = q1_ii; //Replace qref by newly calculated reference angle
JorineOosting 36:650a9245bc44 357 q2ref = q2_ii;
MarijkeZondag 32:56a8bd82e971 358
JorineOosting 36:650a9245bc44 359 q1_motor = -q1ref/r_trans; //Calculate reference motor angle 1, corrected for translational joint --> input PID control
JorineOosting 36:650a9245bc44 360 q2_motor = q2ref*5.0; //Calculate reference motor angle 2, corrected for gear ratio 1:5 ---> input PID control
MarijkeZondag 28:5e54cd4525de 361
MarijkeZondag 35:63c890ac71ff 362 engine_control1(); //Call engine_control 1 function
MarijkeZondag 35:63c890ac71ff 363 engine_control2(); //Call engine_control 2 function
Esmee 33:976be2825a23 364
Marle 25:bbef09ff226b 365 }
Marle 25:bbef09ff226b 366
Marle 25:bbef09ff226b 367 void v_des_calculate_qref()
MarijkeZondag 23:97a976a8f0fc 368 {
MarijkeZondag 35:63c890ac71ff 369 while(emg_cal==1) //After calibration is finished, emg_cal will be 1. Otherwise 0.
MarijkeZondag 16:5f7196ddc77b 370 {
MarijkeZondag 35:63c890ac71ff 371 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 372 {
JorineOosting 36:650a9245bc44 373 v_y = 0.0;
MarijkeZondag 35:63c890ac71ff 374 v_x = 0.05; //Movement in +x direction
JorineOosting 36:650a9245bc44 375
MarijkeZondag 35:63c890ac71ff 376 ledr = 0; //Led is red
Marle 25:bbef09ff226b 377 ledb = 1;
Marle 25:bbef09ff226b 378 ledg = 1;
MarijkeZondag 16:5f7196ddc77b 379 }
MarijkeZondag 35:63c890ac71ff 380 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 381 {
MarijkeZondag 35:63c890ac71ff 382 v_y = 0.05; //Movement in +y direction
MarijkeZondag 28:5e54cd4525de 383 v_x = 0.0;
MarijkeZondag 28:5e54cd4525de 384
MarijkeZondag 35:63c890ac71ff 385 ledr = 1; //Led is green
Marle 25:bbef09ff226b 386 ledb = 1;
Marle 25:bbef09ff226b 387 ledg = 0;
MarijkeZondag 24:6d63ad38fef7 388 }
Marle 25:bbef09ff226b 389
MarijkeZondag 35:63c890ac71ff 390 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 391 {
MarijkeZondag 35:63c890ac71ff 392 v_y = 0.0; //Movement in -x direction
Esmee 33:976be2825a23 393 v_x = -0.05;
MarijkeZondag 28:5e54cd4525de 394
MarijkeZondag 35:63c890ac71ff 395 ledr = 0; //Led is purple
Marle 25:bbef09ff226b 396 ledb = 0;
MarijkeZondag 30:f04a35f2a06d 397 ledg = 1;
MarijkeZondag 30:f04a35f2a06d 398 }
MarijkeZondag 28:5e54cd4525de 399
MarijkeZondag 35:63c890ac71ff 400 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 401 {
MarijkeZondag 35:63c890ac71ff 402 v_y = -0.05; //Movement in -y direction
MarijkeZondag 30:f04a35f2a06d 403 v_x = 0.0;
MarijkeZondag 30:f04a35f2a06d 404
MarijkeZondag 35:63c890ac71ff 405 ledr = 1; //Led is blue
MarijkeZondag 30:f04a35f2a06d 406 ledb = 0;
MarijkeZondag 30:f04a35f2a06d 407 ledg = 1;
MarijkeZondag 30:f04a35f2a06d 408 }
MarijkeZondag 35:63c890ac71ff 409 else //If not higher than any threshold, motors will not turn at all
Marle 25:bbef09ff226b 410 {
Marle 25:bbef09ff226b 411 v_x = 0;
Marle 25:bbef09ff226b 412 v_y = 0;
MarijkeZondag 28:5e54cd4525de 413
MarijkeZondag 35:63c890ac71ff 414 ledr = 0; //Led is white
MarijkeZondag 24:6d63ad38fef7 415 ledb = 0;
MarijkeZondag 24:6d63ad38fef7 416 ledg = 0;
MarijkeZondag 24:6d63ad38fef7 417 }
MarijkeZondag 27:fa493551be99 418
MarijkeZondag 35:63c890ac71ff 419 inverse_kinematics(); //Call inverse kinematics function
MarijkeZondag 27:fa493551be99 420
MarijkeZondag 28:5e54cd4525de 421 break;
MarijkeZondag 23:97a976a8f0fc 422 }
MarijkeZondag 26:ac5656aa35c7 423 }
MarijkeZondag 26:ac5656aa35c7 424
MarijkeZondag 35:63c890ac71ff 425 //------------------ Start main function -----------------------------------------------------------------------------------------------------------//
MarijkeZondag 26:ac5656aa35c7 426
MarijkeZondag 23:97a976a8f0fc 427 int main()
MarijkeZondag 23:97a976a8f0fc 428 {
MarijkeZondag 35:63c890ac71ff 429 pwmpin1.period_us(60); //60 microseconds PWM period, 16.7 kHz
MarijkeZondag 23:97a976a8f0fc 430
MarijkeZondag 35:63c890ac71ff 431 emg0filter.add( &emg0band1 ).add( &emg0band2 ).add( &emg0band3 ).add( &notch1 ); //Attach biquad elements to chain
MarijkeZondag 23:97a976a8f0fc 432 emg1filter.add( &emg1band1 ).add( &emg1band2 ).add( &emg1band3 ).add( &notch2 );
MarijkeZondag 23:97a976a8f0fc 433 emg2filter.add( &emg2band1 ).add( &emg2band2 ).add( &emg2band3 ).add( &notch3 );
MarijkeZondag 10:39ec51206c8b 434
MarijkeZondag 35:63c890ac71ff 435 emg_tick.attach(&emg_filtered,T); //EMG signals filtered + moving average every T sec.
MarijkeZondag 28:5e54cd4525de 436 movag_tick.attach(&MovAg,T);
MarijkeZondag 35:63c890ac71ff 437 func_tick.attach(&v_des_calculate_qref,T); //v_des determined every T
MarijkeZondag 28:5e54cd4525de 438
MarijkeZondag 35:63c890ac71ff 439 button1.rise(switch_to_calibrate); //Switch state of calibration (which muscle)
MarijkeZondag 35:63c890ac71ff 440 button2.rise(calibrate); //Calibrate threshold for 3 muscles
MarijkeZondag 28:5e54cd4525de 441
MarijkeZondag 23:97a976a8f0fc 442 while(true)
MarijkeZondag 23:97a976a8f0fc 443 {
MarijkeZondag 30:f04a35f2a06d 444 ;
MarijkeZondag 23:97a976a8f0fc 445 }
vsluiter 0:c8f15874531b 446 }