Tommie Verouden / Mbed 2 deprecated StateMachine

Dependencies:   biquadFilter FastPWM MODSERIAL QEI mbed

Committer:
tverouden
Date:
Thu Nov 01 14:12:29 2018 +0000
Revision:
32:a00ff9898574
Parent:
25:ac139331fe51
Child:
33:44ba3c159f54
Merge version 1

Who changed what in which revision?

UserRevisionLine numberNew contents of line
tverouden 0:c0c35b95765f 1 // ≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡ PREPARATION ≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡
tverouden 0:c0c35b95765f 2 // Libraries
tverouden 0:c0c35b95765f 3 #include "mbed.h"
tverouden 2:d70795e4e0bf 4 #include "BiQuad.h"
tverouden 0:c0c35b95765f 5 #include "FastPWM.h"
tverouden 0:c0c35b95765f 6 #include "MODSERIAL.h"
efvanmarrewijk 25:ac139331fe51 7 #include "QEI.h"
EvaKrolis 13:4ba8f63e6ff4 8 #include <algorithm>
EvaKrolis 14:2c0bf576a0e7 9 #define PI 3.14159265
tverouden 0:c0c35b95765f 10
tverouden 8:8cef1050ebd9 11 // LEDs
tverouden 23:e282bdb9e9b7 12 DigitalOut ledRed(LED_RED,1); // red LED K64F
tverouden 23:e282bdb9e9b7 13 DigitalOut ledGreen(LED_GREEN,1); // green LED K64F
tverouden 23:e282bdb9e9b7 14 DigitalOut ledBlue(LED_BLUE,1); // blue LED K64F
tverouden 8:8cef1050ebd9 15
tverouden 23:e282bdb9e9b7 16 Ticker blinkTimer; // LED ticker
tverouden 8:8cef1050ebd9 17
tverouden 8:8cef1050ebd9 18 // Buttons/inputs
tverouden 23:e282bdb9e9b7 19 InterruptIn buttonBio1(D0); // button 1 BioRobotics shield
tverouden 23:e282bdb9e9b7 20 InterruptIn buttonBio2(D1); // button 2 BioRobotics shield
tverouden 23:e282bdb9e9b7 21 InterruptIn buttonEmergency(SW2); // emergency button on K64F
tverouden 24:0abc564349e1 22 InterruptIn buttonHome(SW3); // button on K64F
tverouden 0:c0c35b95765f 23
efvanmarrewijk 25:ac139331fe51 24 // Potmeters
efvanmarrewijk 25:ac139331fe51 25 AnalogIn pot1(A1);
efvanmarrewijk 25:ac139331fe51 26 AnalogIn pot2(A2);
efvanmarrewijk 25:ac139331fe51 27
efvanmarrewijk 25:ac139331fe51 28 // Motor pins input
efvanmarrewijk 25:ac139331fe51 29 DigitalIn pin8(D8); // Encoder L B
efvanmarrewijk 25:ac139331fe51 30 DigitalIn pin9(D9); // Encoder L A
efvanmarrewijk 25:ac139331fe51 31 DigitalIn pin10(D10); // Encoder R B
efvanmarrewijk 25:ac139331fe51 32 DigitalIn pin11(D11); // Encoder R A
efvanmarrewijk 25:ac139331fe51 33 DigitalIn pin12(D12); // Encoder F B
efvanmarrewijk 25:ac139331fe51 34 DigitalIn pin13(D13); // Encoder F A
tverouden 8:8cef1050ebd9 35
efvanmarrewijk 25:ac139331fe51 36 // Motor pins output
efvanmarrewijk 25:ac139331fe51 37 DigitalOut pin2(D2); // Motor F direction = motor flip
efvanmarrewijk 25:ac139331fe51 38 FastPWM pin3(A5); // Motor F pwm = motor flip
efvanmarrewijk 25:ac139331fe51 39 DigitalOut pin4(D4); // Motor R direction = motor right
efvanmarrewijk 25:ac139331fe51 40 FastPWM pin5(D5); // Motor R pwm = motor right
efvanmarrewijk 25:ac139331fe51 41 FastPWM pin6(D6); // Motor L pwm = motor left
tverouden 32:a00ff9898574 42 DigitalOut pin7(D7); // Motor L direction = motor left
efvanmarrewijk 25:ac139331fe51 43
efvanmarrewijk 25:ac139331fe51 44 // Utilisation of libraries
tverouden 32:a00ff9898574 45 MODSERIAL pc(USBTX, USBRX); // communication with pc
efvanmarrewijk 25:ac139331fe51 46 QEI encoderL(D9,D8,NC,4200); // Encoder input of motor L
efvanmarrewijk 25:ac139331fe51 47 QEI encoderR(D10,D11,NC,4200); // Encoder input of motor R
efvanmarrewijk 25:ac139331fe51 48 QEI encoderF(D12,D13,NC,4200); // Encoder input of motor F
efvanmarrewijk 25:ac139331fe51 49 Ticker motorL;
efvanmarrewijk 25:ac139331fe51 50 Ticker motorR;
efvanmarrewijk 25:ac139331fe51 51 Ticker motorF;
tverouden 4:5ce2c8864908 52
tverouden 0:c0c35b95765f 53 // Define & initialise state machine
efvanmarrewijk 25:ac139331fe51 54 const float dt = 0.02f
tverouden 11:2d1dfebae948 55 enum states { calibratingMotors, calibratingEMG,
tverouden 17:b04e1938491a 56 homing, reading, operating, failing, demoing
tverouden 2:d70795e4e0bf 57 };
tverouden 23:e282bdb9e9b7 58 states currentState = calibratingMotors; // start in waiting mode
tverouden 23:e282bdb9e9b7 59 bool changeState = true; // initialise the first state
tverouden 2:d70795e4e0bf 60
tverouden 23:e282bdb9e9b7 61 Ticker stateTimer; // state machine ticker
tverouden 19:2797bb471f9f 62
EvaKrolis 14:2c0bf576a0e7 63 //------------------------ Parameters for the EMG ----------------------------
tverouden 3:9c63fc5f157e 64
tverouden 23:e282bdb9e9b7 65 // EMG inputs
tverouden 23:e282bdb9e9b7 66 AnalogIn EMG0In(A0); // EMG input 0
tverouden 23:e282bdb9e9b7 67 AnalogIn EMG1In(A1); // EMG input 1
EvaKrolis 13:4ba8f63e6ff4 68
tverouden 23:e282bdb9e9b7 69 // Timers
tverouden 23:e282bdb9e9b7 70 Ticker ReadUseEMG0_timer; // Timer to read, filter and use the EMG
tverouden 23:e282bdb9e9b7 71 Ticker EMGCalibration0_timer; // Timer for the calibration of the EMG
tverouden 23:e282bdb9e9b7 72 Ticker FindMax0_timer; // Timer for finding the max muscle
tverouden 23:e282bdb9e9b7 73 Ticker ReadUseEMG1_timer; // Timer to read, filter and use the EMG
tverouden 23:e282bdb9e9b7 74 Ticker EMGCalibration1_timer; // Timer for the calibration of the EMG
tverouden 23:e282bdb9e9b7 75 Ticker FindMax1_timer; // Timer for finding the max muscle
tverouden 23:e282bdb9e9b7 76 Ticker SwitchState_timer; // Timer to switch from the Calibration to the working mode
EvaKrolis 13:4ba8f63e6ff4 77
tverouden 23:e282bdb9e9b7 78 // Constants
tverouden 23:e282bdb9e9b7 79 const int Length = 10000; // Length of the array for the calibration
tverouden 23:e282bdb9e9b7 80 const int Parts = 50; // Mean average filter over 50 values
EvaKrolis 13:4ba8f63e6ff4 81
tverouden 23:e282bdb9e9b7 82 // Parameters for the first EMG signal
tverouden 23:e282bdb9e9b7 83 float EMG0; // float for EMG input
tverouden 23:e282bdb9e9b7 84 float EMG0filt; // float for filtered EMG
tverouden 23:e282bdb9e9b7 85 float EMG0filtArray[Parts]; // Array for the filtered array
tverouden 23:e282bdb9e9b7 86 float EMG0Average; // float for the value after Moving Average Filter
tverouden 23:e282bdb9e9b7 87 float Sum0 = 0; // Sum0 for the moving average filter
tverouden 23:e282bdb9e9b7 88 float EMG0Calibrate[Length]; // Array for the calibration
tverouden 23:e282bdb9e9b7 89 int ReadCal0 = 0; // Integer to read over the calibration array
tverouden 23:e282bdb9e9b7 90 float MaxValue0 = 0; // float to save the max muscle
tverouden 23:e282bdb9e9b7 91 float Threshold0 = 0; // Threshold for the first EMG signal
EvaKrolis 13:4ba8f63e6ff4 92
tverouden 23:e282bdb9e9b7 93 // Parameters for the second EMG signal
tverouden 23:e282bdb9e9b7 94 float EMG1; // float for EMG input
tverouden 23:e282bdb9e9b7 95 float EMG1filt; // float for filtered EMG
tverouden 23:e282bdb9e9b7 96 float EMG1filtArray[Parts]; // Array for the filtered array
tverouden 23:e282bdb9e9b7 97 float EMG1Average; // float for the value after Moving Average Filter
tverouden 23:e282bdb9e9b7 98 float Sum1 = 0; // Sum0 for the moving average filter
tverouden 23:e282bdb9e9b7 99 float EMG1Calibrate[Length]; // Array for the calibration
tverouden 23:e282bdb9e9b7 100 int ReadCal1 = 0; // Integer to read over the calibration array
tverouden 23:e282bdb9e9b7 101 float MaxValue1 = 0; // float to save the max muscle
tverouden 23:e282bdb9e9b7 102 float Threshold1 = 0; // Threshold for the second EMG signal
EvaKrolis 13:4ba8f63e6ff4 103
EvaKrolis 13:4ba8f63e6ff4 104 //Filter variables
EvaKrolis 13:4ba8f63e6ff4 105 BiQuad Notch50_0(0.7887,0,0.7887,0,0.5774); //Make Notch filter around 50 Hz
tverouden 23:e282bdb9e9b7 106 BiQuad Notch50_1(0.7887,0,0.7887,0,0.5774); // Make Notch filter around 50 Hz
EvaKrolis 13:4ba8f63e6ff4 107 BiQuad High0(0.8006,-1.6012,0.8006,-1.561,0.6414); //Make high-pass filter
EvaKrolis 13:4ba8f63e6ff4 108 BiQuad High1(0.8006,-1.6012,0.8006,-1.561,0.6414); //Make high-pass filter
EvaKrolis 13:4ba8f63e6ff4 109 BiQuadChain filter0; //Make chain of filters for the first EMG signal
EvaKrolis 13:4ba8f63e6ff4 110 BiQuadChain filter1; //Make chain of filters for the second EMG signal
EvaKrolis 13:4ba8f63e6ff4 111
EvaKrolis 13:4ba8f63e6ff4 112 //Bool for movement
EvaKrolis 13:4ba8f63e6ff4 113 bool xMove = false; //Bool for the x-movement
EvaKrolis 13:4ba8f63e6ff4 114 bool yMove = false; //Bool for the y-movement
tverouden 3:9c63fc5f157e 115
EvaKrolis 14:2c0bf576a0e7 116 // -------------------- Parameters for the kinematics -------------------------
EvaKrolis 14:2c0bf576a0e7 117
EvaKrolis 14:2c0bf576a0e7 118 //Constants
EvaKrolis 14:2c0bf576a0e7 119 const double ll = 230; //Length of the lower arm
EvaKrolis 14:2c0bf576a0e7 120 const double lu = 198; //Length of the upper arm
EvaKrolis 14:2c0bf576a0e7 121 const double lb = 50; //Length of the part between the upper arms
EvaKrolis 14:2c0bf576a0e7 122 const double le = 79; //Length of the end-effector beam
EvaKrolis 14:2c0bf576a0e7 123 const double xbase = 450-lb; //Length between the motors
EvaKrolis 14:2c0bf576a0e7 124
EvaKrolis 14:2c0bf576a0e7 125 //General parameters
EvaKrolis 14:2c0bf576a0e7 126 double theta1 = PI*0.49; //Angle of the left motor
EvaKrolis 14:2c0bf576a0e7 127 double theta4 = PI*0.49; //Angle of the right motor
EvaKrolis 14:2c0bf576a0e7 128 double thetaflip = 0; //Angle of the flipping motor
EvaKrolis 14:2c0bf576a0e7 129 double prefx; //Desired x velocity
EvaKrolis 14:2c0bf576a0e7 130 double prefy; //Desired y velocity "
EvaKrolis 14:2c0bf576a0e7 131 double deltat = 0.01; //Time step (dependent on sample frequency)
EvaKrolis 14:2c0bf576a0e7 132
EvaKrolis 14:2c0bf576a0e7 133 //Kinematics parameters for x
EvaKrolis 14:2c0bf576a0e7 134 double xendsum;
EvaKrolis 14:2c0bf576a0e7 135 double xendsqrt1;
EvaKrolis 14:2c0bf576a0e7 136 double xendsqrt2;
EvaKrolis 14:2c0bf576a0e7 137 double xend;
EvaKrolis 14:2c0bf576a0e7 138 double jacobiana;
EvaKrolis 14:2c0bf576a0e7 139 double jacobianc;
EvaKrolis 14:2c0bf576a0e7 140
EvaKrolis 14:2c0bf576a0e7 141 //Kinematics parameters for y
EvaKrolis 14:2c0bf576a0e7 142 double yendsum;
EvaKrolis 14:2c0bf576a0e7 143 double yendsqrt1;
EvaKrolis 14:2c0bf576a0e7 144 double yendsqrt2;
EvaKrolis 14:2c0bf576a0e7 145 double yend;
EvaKrolis 14:2c0bf576a0e7 146 double jacobianb;
EvaKrolis 14:2c0bf576a0e7 147 double jacobiand;
EvaKrolis 14:2c0bf576a0e7 148
EvaKrolis 14:2c0bf576a0e7 149 //Tickers
EvaKrolis 14:2c0bf576a0e7 150 Ticker kin; //Timer for calculating x,y,theta1,theta4
EvaKrolis 14:2c0bf576a0e7 151 Ticker simulateval; //Timer that prints the values for x,y, and angles
EvaKrolis 14:2c0bf576a0e7 152
EvaKrolis 14:2c0bf576a0e7 153 // ---------------------- Parameters for the motors ---------------------------
EvaKrolis 14:2c0bf576a0e7 154
efvanmarrewijk 25:ac139331fe51 155
efvanmarrewijk 25:ac139331fe51 156
tverouden 4:5ce2c8864908 157 // ≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡ FUNCTIONS ≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡
tverouden 6:f32352bc5078 158 // ============================ GENERAL FUNCTIONS =============================
tverouden 6:f32352bc5078 159 void stopProgram(void)
tverouden 6:f32352bc5078 160 {
tverouden 6:f32352bc5078 161 // Error message
tverouden 6:f32352bc5078 162 pc.printf("[ERROR] emergency button pressed\r\n");
tverouden 6:f32352bc5078 163 currentState = failing; // change to state
tverouden 6:f32352bc5078 164 changeState = true; // next loop, switch states
tverouden 6:f32352bc5078 165 }
tverouden 8:8cef1050ebd9 166
tverouden 15:6566c5dedeeb 167 void blinkLedRed(void)
tverouden 15:6566c5dedeeb 168 {
tverouden 15:6566c5dedeeb 169 ledRed =! ledRed; // toggle LED
tverouden 10:584b7d2c2d63 170 }
tverouden 15:6566c5dedeeb 171 void blinkLedGreen(void)
tverouden 15:6566c5dedeeb 172 {
tverouden 15:6566c5dedeeb 173 ledGreen =! ledGreen; // toggle LED
tverouden 15:6566c5dedeeb 174 }
tverouden 15:6566c5dedeeb 175 void blinkLedBlue(void)
tverouden 15:6566c5dedeeb 176 {
tverouden 15:6566c5dedeeb 177 ledBlue =! ledBlue; // toggle LED
tverouden 15:6566c5dedeeb 178 }
tverouden 15:6566c5dedeeb 179
tverouden 4:5ce2c8864908 180 // ============================= EMG FUNCTIONS ===============================
tverouden 4:5ce2c8864908 181
EvaKrolis 13:4ba8f63e6ff4 182 //Function to read and filter the EMG
EvaKrolis 13:4ba8f63e6ff4 183 void ReadUseEMG0(){
EvaKrolis 13:4ba8f63e6ff4 184 for(int i = Parts ; i > 0 ; i--){ //Make a first in, first out array
EvaKrolis 13:4ba8f63e6ff4 185 EMG0filtArray[i] = EMG0filtArray[i-1]; //Every value moves one up
EvaKrolis 13:4ba8f63e6ff4 186 }
EvaKrolis 13:4ba8f63e6ff4 187
EvaKrolis 13:4ba8f63e6ff4 188 Sum0 = 0;
EvaKrolis 13:4ba8f63e6ff4 189 EMG0 = EMG0In; //Save EMG input in float
EvaKrolis 13:4ba8f63e6ff4 190 EMG0filt = filter0.step(EMG0); //Filter the signal
EvaKrolis 13:4ba8f63e6ff4 191 EMG0filt = abs(EMG0filt); //Take the absolute value
EvaKrolis 13:4ba8f63e6ff4 192 EMG0filtArray[0] = EMG0filt; //Save the filtered signal on the first place in the array
EvaKrolis 13:4ba8f63e6ff4 193
EvaKrolis 13:4ba8f63e6ff4 194 for(int i = 0 ; i < Parts ; i++){ //Moving Average filter
EvaKrolis 13:4ba8f63e6ff4 195 Sum0 += EMG0filtArray[i]; //Sum the new value and the previous 49
EvaKrolis 13:4ba8f63e6ff4 196 }
EvaKrolis 13:4ba8f63e6ff4 197 EMG0Average = (float)Sum0/Parts; //Divide the sum by 50
EvaKrolis 13:4ba8f63e6ff4 198
EvaKrolis 13:4ba8f63e6ff4 199 if (EMG0Average > Threshold0){ //If the value is higher than the threshold value
EvaKrolis 13:4ba8f63e6ff4 200 xMove = true; //Set movement to true
EvaKrolis 13:4ba8f63e6ff4 201 }
EvaKrolis 13:4ba8f63e6ff4 202 else{
EvaKrolis 13:4ba8f63e6ff4 203 xMove = false; //Otherwise set movement to false
EvaKrolis 13:4ba8f63e6ff4 204 }
EvaKrolis 13:4ba8f63e6ff4 205 }
EvaKrolis 13:4ba8f63e6ff4 206
EvaKrolis 13:4ba8f63e6ff4 207 //Function to read and filter the EMG
EvaKrolis 13:4ba8f63e6ff4 208 void ReadUseEMG1(){
EvaKrolis 13:4ba8f63e6ff4 209 for(int i = Parts ; i > 0 ; i--){ //Make a first in, first out array
EvaKrolis 13:4ba8f63e6ff4 210 EMG1filtArray[i] = EMG1filtArray[i-1]; //Every value moves one up
EvaKrolis 13:4ba8f63e6ff4 211 }
EvaKrolis 13:4ba8f63e6ff4 212
EvaKrolis 13:4ba8f63e6ff4 213 Sum1 = 0;
EvaKrolis 13:4ba8f63e6ff4 214 EMG1 = EMG1In; //Save EMG input in float
EvaKrolis 13:4ba8f63e6ff4 215 EMG1filt = filter1.step(EMG1); //Filter the signal
EvaKrolis 13:4ba8f63e6ff4 216 EMG1filt = abs(EMG1filt); //Take the absolute value
EvaKrolis 13:4ba8f63e6ff4 217 EMG1filtArray[0] = EMG1filt; //Save the filtered signal on the first place in the array
EvaKrolis 13:4ba8f63e6ff4 218
EvaKrolis 13:4ba8f63e6ff4 219 for(int i = 0 ; i < Parts ; i++){ //Moving Average filter
EvaKrolis 13:4ba8f63e6ff4 220 Sum1 += EMG1filtArray[i]; //Sum the new value and the previous 49
EvaKrolis 13:4ba8f63e6ff4 221 }
EvaKrolis 13:4ba8f63e6ff4 222 EMG1Average = (float)Sum1/Parts; //Divide the sum by 50
EvaKrolis 13:4ba8f63e6ff4 223
EvaKrolis 13:4ba8f63e6ff4 224 if (EMG1Average > Threshold1){ //If the value is higher than the threshold value
EvaKrolis 13:4ba8f63e6ff4 225 yMove = true; //Set y movement to true
EvaKrolis 13:4ba8f63e6ff4 226 }
EvaKrolis 13:4ba8f63e6ff4 227 else{
EvaKrolis 13:4ba8f63e6ff4 228 yMove = false; //Otherwise set y movement to false
EvaKrolis 13:4ba8f63e6ff4 229 }
EvaKrolis 13:4ba8f63e6ff4 230 }
EvaKrolis 13:4ba8f63e6ff4 231
EvaKrolis 13:4ba8f63e6ff4 232 //Function to make an array during the calibration
EvaKrolis 13:4ba8f63e6ff4 233 void CalibrateEMG0(){
EvaKrolis 13:4ba8f63e6ff4 234 for(int i = Parts ; i > 0 ; i--){ //Make a first in, first out array
EvaKrolis 13:4ba8f63e6ff4 235 EMG0filtArray[i] = EMG0filtArray[i-1]; //Every value moves one up
EvaKrolis 13:4ba8f63e6ff4 236 }
EvaKrolis 13:4ba8f63e6ff4 237
EvaKrolis 13:4ba8f63e6ff4 238 Sum0 = 0;
EvaKrolis 13:4ba8f63e6ff4 239 EMG0 = EMG0In; //Save EMG input in float
EvaKrolis 13:4ba8f63e6ff4 240 EMG0filt = filter0.step(EMG0); //Filter the signal
EvaKrolis 13:4ba8f63e6ff4 241 EMG0filt = abs(EMG0filt); //Take the absolute value
EvaKrolis 13:4ba8f63e6ff4 242 EMG0filtArray[0] = EMG0filt; //Save the filtered signal on the first place in the array
EvaKrolis 13:4ba8f63e6ff4 243
EvaKrolis 13:4ba8f63e6ff4 244 for(int i = 0 ; i < Parts ; i++){ //Moving Average filter
EvaKrolis 13:4ba8f63e6ff4 245 Sum0 += EMG0filtArray[i]; //Sum the new value and the previous 49
EvaKrolis 13:4ba8f63e6ff4 246 }
EvaKrolis 13:4ba8f63e6ff4 247 EMG0Calibrate[ReadCal0] = (float)Sum0/Parts; //Divide the sum by 50
EvaKrolis 13:4ba8f63e6ff4 248
EvaKrolis 13:4ba8f63e6ff4 249 ReadCal0++;
EvaKrolis 13:4ba8f63e6ff4 250 }
EvaKrolis 13:4ba8f63e6ff4 251
EvaKrolis 13:4ba8f63e6ff4 252 //Function to make an array during the calibration
EvaKrolis 13:4ba8f63e6ff4 253 void CalibrateEMG1(){
EvaKrolis 13:4ba8f63e6ff4 254 for(int i = Parts ; i > 0 ; i--){ //Make a first in, first out array
EvaKrolis 13:4ba8f63e6ff4 255 EMG1filtArray[i] = EMG1filtArray[i-1]; //Every value moves one up
EvaKrolis 13:4ba8f63e6ff4 256 }
EvaKrolis 13:4ba8f63e6ff4 257
EvaKrolis 13:4ba8f63e6ff4 258 Sum1 = 0;
EvaKrolis 13:4ba8f63e6ff4 259 EMG1 = EMG1In; //Save EMG input in float
EvaKrolis 13:4ba8f63e6ff4 260 EMG1filt = filter1.step(EMG1); //Filter the signal
EvaKrolis 13:4ba8f63e6ff4 261 EMG1filt = abs(EMG1filt); //Take the absolute value
EvaKrolis 13:4ba8f63e6ff4 262 EMG1filtArray[0] = EMG1filt; //Save the filtered signal on the first place in the array
EvaKrolis 13:4ba8f63e6ff4 263
EvaKrolis 13:4ba8f63e6ff4 264 for(int i = 0 ; i < Parts ; i++){ //Moving Average filter
EvaKrolis 13:4ba8f63e6ff4 265 Sum1 += EMG1filtArray[i]; //Sum the new value and the previous 49
EvaKrolis 13:4ba8f63e6ff4 266 }
EvaKrolis 13:4ba8f63e6ff4 267 EMG1Calibrate[ReadCal1] = (float)Sum1/Parts; //Divide the sum by 50
EvaKrolis 13:4ba8f63e6ff4 268
EvaKrolis 13:4ba8f63e6ff4 269 ReadCal1++;
EvaKrolis 13:4ba8f63e6ff4 270 }
EvaKrolis 13:4ba8f63e6ff4 271
EvaKrolis 13:4ba8f63e6ff4 272 //Function to find the max value during the calibration
EvaKrolis 13:4ba8f63e6ff4 273 void FindMax0(){
EvaKrolis 13:4ba8f63e6ff4 274 MaxValue0 = *max_element(EMG0Calibrate+500,EMG0Calibrate+Length); //Find max value, but discard the first 100 values
EvaKrolis 13:4ba8f63e6ff4 275 Threshold0 = 0.30f*MaxValue0; //The threshold is a percentage of the max value
EvaKrolis 13:4ba8f63e6ff4 276 pc.printf("The calibration value of the first EMG is %f.\n\r The threshold is %f. \n\r",MaxValue0,Threshold0); //Print the max value and the threshold
EvaKrolis 13:4ba8f63e6ff4 277 FindMax0_timer.detach(); //Detach the timer, so you only use this once
EvaKrolis 13:4ba8f63e6ff4 278 }
EvaKrolis 13:4ba8f63e6ff4 279
EvaKrolis 13:4ba8f63e6ff4 280 //Function to find the max value during the calibration
EvaKrolis 13:4ba8f63e6ff4 281 void FindMax1(){
EvaKrolis 13:4ba8f63e6ff4 282 MaxValue1 = *max_element(EMG1Calibrate+500,EMG1Calibrate+Length); //Find max value, but discard the first 100 values
EvaKrolis 13:4ba8f63e6ff4 283 Threshold1 = 0.30f*MaxValue1; //The threshold is a percentage of the max value
EvaKrolis 13:4ba8f63e6ff4 284 pc.printf("The calibration value of the second EMG is %f.\n\r The threshold is %f. \n\r",MaxValue1,Threshold1); //Print the Max value and the threshold
EvaKrolis 13:4ba8f63e6ff4 285 FindMax1_timer.detach(); //Detach the timer, so you only use this once
EvaKrolis 13:4ba8f63e6ff4 286 }
tverouden 4:5ce2c8864908 287
tverouden 12:323ac4e27a0d 288 // ========================= KINEMATICS FUNCTIONS ============================
tverouden 12:323ac4e27a0d 289
EvaKrolis 14:2c0bf576a0e7 290 // Function to calculate the inverse kinematics
EvaKrolis 14:2c0bf576a0e7 291 void inverse(double prex, double prey)
EvaKrolis 14:2c0bf576a0e7 292 {
EvaKrolis 14:2c0bf576a0e7 293 /*
EvaKrolis 14:2c0bf576a0e7 294 qn = qn-1 + (jacobian^-1)*dPref/dt *deltaT
EvaKrolis 14:2c0bf576a0e7 295 ofwel
EvaKrolis 14:2c0bf576a0e7 296 thetai+1 = thetai +(jacobian)^-1*vector(deltaX, DeltaY)
EvaKrolis 14:2c0bf576a0e7 297 waar Pref = emg signaal
EvaKrolis 14:2c0bf576a0e7 298 */ //achtergrondinfo hierboven...
EvaKrolis 14:2c0bf576a0e7 299 //
EvaKrolis 14:2c0bf576a0e7 300
EvaKrolis 14:2c0bf576a0e7 301 theta1 += (prefx*jacobiana+jacobianb*prey)*deltat; //theta 1 is zichzelf plus wat hier staat (is kinematics)
EvaKrolis 14:2c0bf576a0e7 302 theta4 += (prefx*jacobianc+jacobiand*prey)*deltat;//" "
EvaKrolis 14:2c0bf576a0e7 303 //Hier worden xend en yend doorgerekend, die formules kan je overslaan
EvaKrolis 14:2c0bf576a0e7 304 xendsum = lb + xbase +ll*(cos(theta1) - cos(theta4));
EvaKrolis 14:2c0bf576a0e7 305 xendsqrt1 = 2*sqrt(-xbase*xbase/4 + lu*lu + ll*(xbase*(cos(theta1)+cos(theta4))/2) -ll*(1+ cos(theta1+theta4)))*(-sin(theta1)+sin(theta4));
EvaKrolis 14:2c0bf576a0e7 306 xendsqrt2 = sqrt(pow((-xbase/ll+cos(theta1)+cos(theta4)),2)+ pow(sin(theta1) - sin(theta4),2));
EvaKrolis 14:2c0bf576a0e7 307 xend = (xendsum + xendsqrt1/xendsqrt2)/2;
EvaKrolis 14:2c0bf576a0e7 308 //hieronder rekenen we yendeffector door;
EvaKrolis 14:2c0bf576a0e7 309 yendsum = -le + ll/2*(sin(theta1)+sin(theta4));
EvaKrolis 14:2c0bf576a0e7 310 yendsqrt1 = (-xbase/ll + cos(theta1)+cos(theta4))*sqrt(-xbase*xbase/4 + lu*lu + ll/2*(xbase*(cos(theta1)+cos(theta4))- ll*(1+cos(theta1+theta4))));
EvaKrolis 14:2c0bf576a0e7 311 yendsqrt2 = sqrt(pow((-xbase/ll + cos(theta1)+ cos(theta4)),2)+ pow((sin(theta1)-sin(theta4)),2));
EvaKrolis 14:2c0bf576a0e7 312 yend = (yendsum + yendsqrt1/yendsqrt2);
EvaKrolis 14:2c0bf576a0e7 313
EvaKrolis 14:2c0bf576a0e7 314 }
EvaKrolis 14:2c0bf576a0e7 315
EvaKrolis 14:2c0bf576a0e7 316 // Function for the Jacobian
EvaKrolis 14:2c0bf576a0e7 317 void kinematics()
EvaKrolis 14:2c0bf576a0e7 318 {
EvaKrolis 14:2c0bf576a0e7 319
EvaKrolis 14:2c0bf576a0e7 320 jacobiana = (500*(-(((-(xbase/ll) + cos(theta1) + cos(theta4))*sqrt(-pow(xbase,2)/4. + pow(lu,2) + (ll*(xbase*(cos(theta1) + cos(theta4)) - ll*(1 + cos(theta1 + theta4))))/2.))/
EvaKrolis 14:2c0bf576a0e7 321 sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2))) - (ll*(sin(theta1) + sin(theta4)))/2. +
EvaKrolis 14:2c0bf576a0e7 322 ((-xbase + ll*(cos(theta1) + cos(0.002 + theta4)))*sqrt(-pow(xbase,2)/4. + pow(lu,2) + (ll*(xbase*(cos(theta1) + cos(0.002 + theta4)) - ll*(1 + cos(0.002 + theta1 + theta4))))/2.))/
EvaKrolis 14:2c0bf576a0e7 323 (ll*sqrt(pow(-(xbase/ll) + cos(theta1) + cos(0.002 + theta4),2) + pow(sin(theta1) - sin(0.002 + theta4),2))) + (ll*(sin(theta1) + sin(0.002 + theta4)))/2.))/
EvaKrolis 14:2c0bf576a0e7 324 (-125000*(-(((-(xbase/ll) + cos(theta1) + cos(theta4))*sqrt(-pow(xbase,2)/4. + pow(lu,2) + (ll*(xbase*(cos(theta1) + cos(theta4)) - ll*(1 + cos(theta1 + theta4))))/2.))/
EvaKrolis 14:2c0bf576a0e7 325 sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2))) +
EvaKrolis 14:2c0bf576a0e7 326 ((-xbase + ll*(cos(0.002 + theta1) + cos(theta4)))*sqrt(-pow(xbase,2)/4. + pow(lu,2) + (ll*(xbase*(cos(0.002 + theta1) + cos(theta4)) - ll*(1 + cos(0.002 + theta1 + theta4))))/2.))/
EvaKrolis 14:2c0bf576a0e7 327 (ll*sqrt(pow(-(xbase/ll) + cos(0.002 + theta1) + cos(theta4),2) + pow(sin(0.002 + theta1) - sin(theta4),2))) - (ll*(sin(theta1) + sin(theta4)))/2. + (ll*(sin(0.002 + theta1) + sin(theta4)))/2.)*
EvaKrolis 14:2c0bf576a0e7 328 (ll*(-cos(theta1) + cos(theta4)) + ll*(cos(theta1) - cos(0.002 + theta4)) + (sqrt(-pow(xbase,2) - 2*pow(ll,2) + 4*pow(lu,2) + 2*xbase*ll*cos(theta1) + 2*xbase*ll*cos(theta4) - 2*pow(ll,2)*cos(theta1 + theta4))*
EvaKrolis 14:2c0bf576a0e7 329 (sin(theta1) - sin(theta4)))/sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2)) +
EvaKrolis 14:2c0bf576a0e7 330 (sqrt(-pow(xbase,2) - 2*pow(ll,2) + 4*pow(lu,2) + 2*xbase*ll*cos(theta1) + 2*xbase*ll*cos(0.002 + theta4) - 2*pow(ll,2)*cos(0.002 + theta1 + theta4))*(-sin(theta1) + sin(0.002 + theta4)))/
EvaKrolis 14:2c0bf576a0e7 331 sqrt(pow(-(xbase/ll) + cos(theta1) + cos(0.002 + theta4),2) + pow(sin(theta1) - sin(0.002 + theta4),2))) +
EvaKrolis 14:2c0bf576a0e7 332 125000*(ll*(cos(0.002 + theta1) - cos(theta4)) + ll*(-cos(theta1) + cos(theta4)) + (sqrt(-pow(xbase,2) - 2*pow(ll,2) + 4*pow(lu,2) + 2*xbase*ll*cos(theta1) + 2*xbase*ll*cos(theta4) - 2*pow(ll,2)*cos(theta1 + theta4))*
EvaKrolis 14:2c0bf576a0e7 333 (sin(theta1) - sin(theta4)))/sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2)) +
EvaKrolis 14:2c0bf576a0e7 334 (sqrt(-pow(xbase,2) - 2*pow(ll,2) + 4*pow(lu,2) + 2*xbase*ll*cos(0.002 + theta1) + 2*xbase*ll*cos(theta4) - 2*pow(ll,2)*cos(0.002 + theta1 + theta4))*(-sin(0.002 + theta1) + sin(theta4)))/
EvaKrolis 14:2c0bf576a0e7 335 sqrt(pow(-(xbase/ll) + cos(0.002 + theta1) + cos(theta4),2) + pow(sin(0.002 + theta1) - sin(theta4),2)))*
EvaKrolis 14:2c0bf576a0e7 336 (-(((-(xbase/ll) + cos(theta1) + cos(theta4))*sqrt(-pow(xbase,2)/4. + pow(lu,2) + (ll*(xbase*(cos(theta1) + cos(theta4)) - ll*(1 + cos(theta1 + theta4))))/2.))/
EvaKrolis 14:2c0bf576a0e7 337 sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2))) - (ll*(sin(theta1) + sin(theta4)))/2. +
EvaKrolis 14:2c0bf576a0e7 338 ((-xbase + ll*(cos(theta1) + cos(0.002 + theta4)))*sqrt(-pow(xbase,2)/4. + pow(lu,2) + (ll*(xbase*(cos(theta1) + cos(0.002 + theta4)) - ll*(1 + cos(0.002 + theta1 + theta4))))/2.))/
EvaKrolis 14:2c0bf576a0e7 339 (ll*sqrt(pow(-(xbase/ll) + cos(theta1) + cos(0.002 + theta4),2) + pow(sin(theta1) - sin(0.002 + theta4),2))) + (ll*(sin(theta1) + sin(0.002 + theta4)))/2.));
EvaKrolis 14:2c0bf576a0e7 340
EvaKrolis 14:2c0bf576a0e7 341 jacobianb = (-250*(ll*(-cos(theta1) + cos(theta4)) + ll*(cos(theta1) - cos(0.002 + theta4)) + (sqrt(-pow(xbase,2) - 2*pow(ll,2) + 4*pow(lu,2) + 2*xbase*ll*cos(theta1) + 2*xbase*ll*cos(theta4) - 2*pow(ll,2)*cos(theta1 + theta4))*
EvaKrolis 14:2c0bf576a0e7 342 (sin(theta1) - sin(theta4)))/sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2)) +
EvaKrolis 14:2c0bf576a0e7 343 (sqrt(-pow(xbase,2) - 2*pow(ll,2) + 4*pow(lu,2) + 2*xbase*ll*cos(theta1) + 2*xbase*ll*cos(0.002 + theta4) - 2*pow(ll,2)*cos(0.002 + theta1 + theta4))*(-sin(theta1) + sin(0.002 + theta4)))/
EvaKrolis 14:2c0bf576a0e7 344 sqrt(pow(-(xbase/ll) + cos(theta1) + cos(0.002 + theta4),2) + pow(sin(theta1) - sin(0.002 + theta4),2))))/
EvaKrolis 14:2c0bf576a0e7 345 (-125000*(-(((-(xbase/ll) + cos(theta1) + cos(theta4))*sqrt(-pow(xbase,2)/4. + pow(lu,2) + (ll*(xbase*(cos(theta1) + cos(theta4)) - ll*(1 + cos(theta1 + theta4))))/2.))/
EvaKrolis 14:2c0bf576a0e7 346 sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2))) +
EvaKrolis 14:2c0bf576a0e7 347 ((-xbase + ll*(cos(0.002 + theta1) + cos(theta4)))*sqrt(-pow(xbase,2)/4. + pow(lu,2) + (ll*(xbase*(cos(0.002 + theta1) + cos(theta4)) - ll*(1 + cos(0.002 + theta1 + theta4))))/2.))/
EvaKrolis 14:2c0bf576a0e7 348 (ll*sqrt(pow(-(xbase/ll) + cos(0.002 + theta1) + cos(theta4),2) + pow(sin(0.002 + theta1) - sin(theta4),2))) - (ll*(sin(theta1) + sin(theta4)))/2. + (ll*(sin(0.002 + theta1) + sin(theta4)))/2.)*
EvaKrolis 14:2c0bf576a0e7 349 (ll*(-cos(theta1) + cos(theta4)) + ll*(cos(theta1) - cos(0.002 + theta4)) + (sqrt(-pow(xbase,2) - 2*pow(ll,2) + 4*pow(lu,2) + 2*xbase*ll*cos(theta1) + 2*xbase*ll*cos(theta4) - 2*pow(ll,2)*cos(theta1 + theta4))*
EvaKrolis 14:2c0bf576a0e7 350 (sin(theta1) - sin(theta4)))/sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2)) +
EvaKrolis 14:2c0bf576a0e7 351 (sqrt(-pow(xbase,2) - 2*pow(ll,2) + 4*pow(lu,2) + 2*xbase*ll*cos(theta1) + 2*xbase*ll*cos(0.002 + theta4) - 2*pow(ll,2)*cos(0.002 + theta1 + theta4))*(-sin(theta1) + sin(0.002 + theta4)))/
EvaKrolis 14:2c0bf576a0e7 352 sqrt(pow(-(xbase/ll) + cos(theta1) + cos(0.002 + theta4),2) + pow(sin(theta1) - sin(0.002 + theta4),2))) +
EvaKrolis 14:2c0bf576a0e7 353 125000*(ll*(cos(0.002 + theta1) - cos(theta4)) + ll*(-cos(theta1) + cos(theta4)) + (sqrt(-pow(xbase,2) - 2*pow(ll,2) + 4*pow(lu,2) + 2*xbase*ll*cos(theta1) + 2*xbase*ll*cos(theta4) - 2*pow(ll,2)*cos(theta1 + theta4))*
EvaKrolis 14:2c0bf576a0e7 354 (sin(theta1) - sin(theta4)))/sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2)) +
EvaKrolis 14:2c0bf576a0e7 355 (sqrt(-pow(xbase,2) - 2*pow(ll,2) + 4*pow(lu,2) + 2*xbase*ll*cos(0.002 + theta1) + 2*xbase*ll*cos(theta4) - 2*pow(ll,2)*cos(0.002 + theta1 + theta4))*(-sin(0.002 + theta1) + sin(theta4)))/
EvaKrolis 14:2c0bf576a0e7 356 sqrt(pow(-(xbase/ll) + cos(0.002 + theta1) + cos(theta4),2) + pow(sin(0.002 + theta1) - sin(theta4),2)))*
EvaKrolis 14:2c0bf576a0e7 357 (-(((-(xbase/ll) + cos(theta1) + cos(theta4))*sqrt(-pow(xbase,2)/4. + pow(lu,2) + (ll*(xbase*(cos(theta1) + cos(theta4)) - ll*(1 + cos(theta1 + theta4))))/2.))/
EvaKrolis 14:2c0bf576a0e7 358 sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2))) - (ll*(sin(theta1) + sin(theta4)))/2. +
EvaKrolis 14:2c0bf576a0e7 359 ((-xbase + ll*(cos(theta1) + cos(0.002 + theta4)))*sqrt(-pow(xbase,2)/4. + pow(lu,2) + (ll*(xbase*(cos(theta1) + cos(0.002 + theta4)) - ll*(1 + cos(0.002 + theta1 + theta4))))/2.))/
EvaKrolis 14:2c0bf576a0e7 360 (ll*sqrt(pow(-(xbase/ll) + cos(theta1) + cos(0.002 + theta4),2) + pow(sin(theta1) - sin(0.002 + theta4),2))) + (ll*(sin(theta1) + sin(0.002 + theta4)))/2.));
EvaKrolis 14:2c0bf576a0e7 361
EvaKrolis 14:2c0bf576a0e7 362 jacobianc = (-500*(-(((-(xbase/ll) + cos(theta1) + cos(theta4))*sqrt(-pow(xbase,2)/4. + pow(lu,2) + (ll*(xbase*(cos(theta1) + cos(theta4)) - ll*(1 + cos(theta1 + theta4))))/2.))/
EvaKrolis 14:2c0bf576a0e7 363 sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2))) +
EvaKrolis 14:2c0bf576a0e7 364 ((-xbase + ll*(cos(0.002 + theta1) + cos(theta4)))*sqrt(-pow(xbase,2)/4. + pow(lu,2) + (ll*(xbase*(cos(0.002 + theta1) + cos(theta4)) - ll*(1 + cos(0.002 + theta1 + theta4))))/2.))/
EvaKrolis 14:2c0bf576a0e7 365 (ll*sqrt(pow(-(xbase/ll) + cos(0.002 + theta1) + cos(theta4),2) + pow(sin(0.002 + theta1) - sin(theta4),2))) - (ll*(sin(theta1) + sin(theta4)))/2. + (ll*(sin(0.002 + theta1) + sin(theta4)))/2.))/
EvaKrolis 14:2c0bf576a0e7 366 (-125000*(-(((-(xbase/ll) + cos(theta1) + cos(theta4))*sqrt(-pow(xbase,2)/4. + pow(lu,2) + (ll*(xbase*(cos(theta1) + cos(theta4)) - ll*(1 + cos(theta1 + theta4))))/2.))/
EvaKrolis 14:2c0bf576a0e7 367 sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2))) +
EvaKrolis 14:2c0bf576a0e7 368 ((-xbase + ll*(cos(0.002 + theta1) + cos(theta4)))*sqrt(-pow(xbase,2)/4. + pow(lu,2) + (ll*(xbase*(cos(0.002 + theta1) + cos(theta4)) - ll*(1 + cos(0.002 + theta1 + theta4))))/2.))/
EvaKrolis 14:2c0bf576a0e7 369 (ll*sqrt(pow(-(xbase/ll) + cos(0.002 + theta1) + cos(theta4),2) + pow(sin(0.002 + theta1) - sin(theta4),2))) - (ll*(sin(theta1) + sin(theta4)))/2. + (ll*(sin(0.002 + theta1) + sin(theta4)))/2.)*
EvaKrolis 14:2c0bf576a0e7 370 (ll*(-cos(theta1) + cos(theta4)) + ll*(cos(theta1) - cos(0.002 + theta4)) + (sqrt(-pow(xbase,2) - 2*pow(ll,2) + 4*pow(lu,2) + 2*xbase*ll*cos(theta1) + 2*xbase*ll*cos(theta4) - 2*pow(ll,2)*cos(theta1 + theta4))*
EvaKrolis 14:2c0bf576a0e7 371 (sin(theta1) - sin(theta4)))/sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2)) +
EvaKrolis 14:2c0bf576a0e7 372 (sqrt(-pow(xbase,2) - 2*pow(ll,2) + 4*pow(lu,2) + 2*xbase*ll*cos(theta1) + 2*xbase*ll*cos(0.002 + theta4) - 2*pow(ll,2)*cos(0.002 + theta1 + theta4))*(-sin(theta1) + sin(0.002 + theta4)))/
EvaKrolis 14:2c0bf576a0e7 373 sqrt(pow(-(xbase/ll) + cos(theta1) + cos(0.002 + theta4),2) + pow(sin(theta1) - sin(0.002 + theta4),2))) +
EvaKrolis 14:2c0bf576a0e7 374 125000*(ll*(cos(0.002 + theta1) - cos(theta4)) + ll*(-cos(theta1) + cos(theta4)) + (sqrt(-pow(xbase,2) - 2*pow(ll,2) + 4*pow(lu,2) + 2*xbase*ll*cos(theta1) + 2*xbase*ll*cos(theta4) - 2*pow(ll,2)*cos(theta1 + theta4))*
EvaKrolis 14:2c0bf576a0e7 375 (sin(theta1) - sin(theta4)))/sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2)) +
EvaKrolis 14:2c0bf576a0e7 376 (sqrt(-pow(xbase,2) - 2*pow(ll,2) + 4*pow(lu,2) + 2*xbase*ll*cos(0.002 + theta1) + 2*xbase*ll*cos(theta4) - 2*pow(ll,2)*cos(0.002 + theta1 + theta4))*(-sin(0.002 + theta1) + sin(theta4)))/
EvaKrolis 14:2c0bf576a0e7 377 sqrt(pow(-(xbase/ll) + cos(0.002 + theta1) + cos(theta4),2) + pow(sin(0.002 + theta1) - sin(theta4),2)))*
EvaKrolis 14:2c0bf576a0e7 378 (-(((-(xbase/ll) + cos(theta1) + cos(theta4))*sqrt(-pow(xbase,2)/4. + pow(lu,2) + (ll*(xbase*(cos(theta1) + cos(theta4)) - ll*(1 + cos(theta1 + theta4))))/2.))/
EvaKrolis 14:2c0bf576a0e7 379 sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2))) - (ll*(sin(theta1) + sin(theta4)))/2. +
EvaKrolis 14:2c0bf576a0e7 380 ((-xbase + ll*(cos(theta1) + cos(0.002 + theta4)))*sqrt(-pow(xbase,2)/4. + pow(lu,2) + (ll*(xbase*(cos(theta1) + cos(0.002 + theta4)) - ll*(1 + cos(0.002 + theta1 + theta4))))/2.))/
EvaKrolis 14:2c0bf576a0e7 381 (ll*sqrt(pow(-(xbase/ll) + cos(theta1) + cos(0.002 + theta4),2) + pow(sin(theta1) - sin(0.002 + theta4),2))) + (ll*(sin(theta1) + sin(0.002 + theta4)))/2.));
EvaKrolis 14:2c0bf576a0e7 382
EvaKrolis 14:2c0bf576a0e7 383 jacobiand = (250*(ll*(cos(0.002 + theta1) - cos(theta4)) + ll*(-cos(theta1) + cos(theta4)) + (sqrt(-pow(xbase,2) - 2*pow(ll,2) + 4*pow(lu,2) + 2*xbase*ll*cos(theta1) + 2*xbase*ll*cos(theta4) - 2*pow(ll,2)*cos(theta1 + theta4))*
EvaKrolis 14:2c0bf576a0e7 384 (sin(theta1) - sin(theta4)))/sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2)) +
EvaKrolis 14:2c0bf576a0e7 385 (sqrt(-pow(xbase,2) - 2*pow(ll,2) + 4*pow(lu,2) + 2*xbase*ll*cos(0.002 + theta1) + 2*xbase*ll*cos(theta4) - 2*pow(ll,2)*cos(0.002 + theta1 + theta4))*(-sin(0.002 + theta1) + sin(theta4)))/
EvaKrolis 14:2c0bf576a0e7 386 sqrt(pow(-(xbase/ll) + cos(0.002 + theta1) + cos(theta4),2) + pow(sin(0.002 + theta1) - sin(theta4),2))))/
EvaKrolis 14:2c0bf576a0e7 387 (-125000*(-(((-(xbase/ll) + cos(theta1) + cos(theta4))*sqrt(-pow(xbase,2)/4. + pow(lu,2) + (ll*(xbase*(cos(theta1) + cos(theta4)) - ll*(1 + cos(theta1 + theta4))))/2.))/
EvaKrolis 14:2c0bf576a0e7 388 sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2))) +
EvaKrolis 14:2c0bf576a0e7 389 ((-xbase + ll*(cos(0.002 + theta1) + cos(theta4)))*sqrt(-pow(xbase,2)/4. + pow(lu,2) + (ll*(xbase*(cos(0.002 + theta1) + cos(theta4)) - ll*(1 + cos(0.002 + theta1 + theta4))))/2.))/
EvaKrolis 14:2c0bf576a0e7 390 (ll*sqrt(pow(-(xbase/ll) + cos(0.002 + theta1) + cos(theta4),2) + pow(sin(0.002 + theta1) - sin(theta4),2))) - (ll*(sin(theta1) + sin(theta4)))/2. + (ll*(sin(0.002 + theta1) + sin(theta4)))/2.)*
EvaKrolis 14:2c0bf576a0e7 391 (ll*(-cos(theta1) + cos(theta4)) + ll*(cos(theta1) - cos(0.002 + theta4)) + (sqrt(-pow(xbase,2) - 2*pow(ll,2) + 4*pow(lu,2) + 2*xbase*ll*cos(theta1) + 2*xbase*ll*cos(theta4) - 2*pow(ll,2)*cos(theta1 + theta4))*
EvaKrolis 14:2c0bf576a0e7 392 (sin(theta1) - sin(theta4)))/sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2)) +
EvaKrolis 14:2c0bf576a0e7 393 (sqrt(-pow(xbase,2) - 2*pow(ll,2) + 4*pow(lu,2) + 2*xbase*ll*cos(theta1) + 2*xbase*ll*cos(0.002 + theta4) - 2*pow(ll,2)*cos(0.002 + theta1 + theta4))*(-sin(theta1) + sin(0.002 + theta4)))/
EvaKrolis 14:2c0bf576a0e7 394 sqrt(pow(-(xbase/ll) + cos(theta1) + cos(0.002 + theta4),2) + pow(sin(theta1) - sin(0.002 + theta4),2))) +
EvaKrolis 14:2c0bf576a0e7 395 125000*(ll*(cos(0.002 + theta1) - cos(theta4)) + ll*(-cos(theta1) + cos(theta4)) + (sqrt(-pow(xbase,2) - 2*pow(ll,2) + 4*pow(lu,2) + 2*xbase*ll*cos(theta1) + 2*xbase*ll*cos(theta4) - 2*pow(ll,2)*cos(theta1 + theta4))*
EvaKrolis 14:2c0bf576a0e7 396 (sin(theta1) - sin(theta4)))/sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2)) +
EvaKrolis 14:2c0bf576a0e7 397 (sqrt(-pow(xbase,2) - 2*pow(ll,2) + 4*pow(lu,2) + 2*xbase*ll*cos(0.002 + theta1) + 2*xbase*ll*cos(theta4) - 2*pow(ll,2)*cos(0.002 + theta1 + theta4))*(-sin(0.002 + theta1) + sin(theta4)))/
EvaKrolis 14:2c0bf576a0e7 398 sqrt(pow(-(xbase/ll) + cos(0.002 + theta1) + cos(theta4),2) + pow(sin(0.002 + theta1) - sin(theta4),2)))*
EvaKrolis 14:2c0bf576a0e7 399 (-(((-(xbase/ll) + cos(theta1) + cos(theta4))*sqrt(-pow(xbase,2)/4. + pow(lu,2) + (ll*(xbase*(cos(theta1) + cos(theta4)) - ll*(1 + cos(theta1 + theta4))))/2.))/
EvaKrolis 14:2c0bf576a0e7 400 sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2))) - (ll*(sin(theta1) + sin(theta4)))/2. +
EvaKrolis 14:2c0bf576a0e7 401 ((-xbase + ll*(cos(theta1) + cos(0.002 + theta4)))*sqrt(-pow(xbase,2)/4. + pow(lu,2) + (ll*(xbase*(cos(theta1) + cos(0.002 + theta4)) - ll*(1 + cos(0.002 + theta1 + theta4))))/2.))/
EvaKrolis 14:2c0bf576a0e7 402 (ll*sqrt(pow(-(xbase/ll) + cos(theta1) + cos(0.002 + theta4),2) + pow(sin(theta1) - sin(0.002 + theta4),2))) + (ll*(sin(theta1) + sin(0.002 + theta4)))/2.));
EvaKrolis 14:2c0bf576a0e7 403
EvaKrolis 14:2c0bf576a0e7 404 prefx = 1*xMove; //If the EMG is true, the x will move with 1
EvaKrolis 14:2c0bf576a0e7 405 prefy = 1*yMove; //If the EMG is true, the y will move with 1
EvaKrolis 14:2c0bf576a0e7 406 inverse(prefx, prefy);
EvaKrolis 14:2c0bf576a0e7 407 }
tverouden 12:323ac4e27a0d 408
efvanmarrewijk 25:ac139331fe51 409 // ============================ MOTOR FUNCTIONS ===============================
efvanmarrewijk 25:ac139331fe51 410 // angleDesired now defined as angle of potmeter and not the angle as output from the kinematics
efvanmarrewijk 25:ac139331fe51 411 // So, the angleDesired needs to be defined again and the part in which the potmeter value is calculated needs to be commented
efvanmarrewijk 25:ac139331fe51 412
efvanmarrewijk 25:ac139331fe51 413 // ------------------------ General motor functions ----------------------------
efvanmarrewijk 25:ac139331fe51 414 int countsInputL() // Gets the counts from encoder 1
efvanmarrewijk 25:ac139331fe51 415 { int countsL;
efvanmarrewijk 25:ac139331fe51 416 countsL = encoderL.getPulses();
efvanmarrewijk 25:ac139331fe51 417 return countsL;
efvanmarrewijk 25:ac139331fe51 418 }
efvanmarrewijk 25:ac139331fe51 419 int countsInputR() // Gets the counts from encoder 2
efvanmarrewijk 25:ac139331fe51 420 { int countsR;
efvanmarrewijk 25:ac139331fe51 421 countsR = encoderR.getPulses();
efvanmarrewijk 25:ac139331fe51 422 return countsR;
efvanmarrewijk 25:ac139331fe51 423 }
efvanmarrewijk 25:ac139331fe51 424 int countsInputF() // Gets the counts from encoder 3
efvanmarrewijk 25:ac139331fe51 425 { int countsF;
efvanmarrewijk 25:ac139331fe51 426 countsF = encoderF.getPulses();
efvanmarrewijk 25:ac139331fe51 427 return countsF;
efvanmarrewijk 25:ac139331fe51 428 }
efvanmarrewijk 25:ac139331fe51 429
efvanmarrewijk 25:ac139331fe51 430 float angleCurrent(float counts) // Calculates the current angle of the motor (between -2*PI to 2*PI) based on the counts from the encoder
efvanmarrewijk 25:ac139331fe51 431 { float angle = ((float)counts*2.0f*PI)/countsRad;
efvanmarrewijk 25:ac139331fe51 432 while (angle > 2.0f*PI)
efvanmarrewijk 25:ac139331fe51 433 { angle = angle-2.0f*PI;
efvanmarrewijk 25:ac139331fe51 434 }
efvanmarrewijk 25:ac139331fe51 435 while (angle < -2.0f*PI)
efvanmarrewijk 25:ac139331fe51 436 { angle = angle+2.0f*PI;
efvanmarrewijk 25:ac139331fe51 437 }
efvanmarrewijk 25:ac139331fe51 438 return angle;
efvanmarrewijk 25:ac139331fe51 439 }
efvanmarrewijk 25:ac139331fe51 440
efvanmarrewijk 25:ac139331fe51 441 float errorCalc(float angleReference,float angleCurrent) // Calculates the error of the system, based on the current angle and the reference value
efvanmarrewijk 25:ac139331fe51 442 { float error = angleReference - angleCurrent;
efvanmarrewijk 25:ac139331fe51 443 return error;
efvanmarrewijk 25:ac139331fe51 444 }
efvanmarrewijk 25:ac139331fe51 445
efvanmarrewijk 25:ac139331fe51 446 // ------------------------- MOTOR FUNCTIONS FOR MOTOR LEFT --------------------
efvanmarrewijk 25:ac139331fe51 447 float PIDControllerL(float angleReference,float angleCurrent) // PID controller for the motors, based on the reference value and the current angle of the motor
efvanmarrewijk 25:ac139331fe51 448 { float Kp = 19.24f;
efvanmarrewijk 25:ac139331fe51 449 float Ki = 1.02f;
efvanmarrewijk 25:ac139331fe51 450 float Kd = 0.827f;
efvanmarrewijk 25:ac139331fe51 451 float error = errorCalc(angleReference,angleCurrent);
efvanmarrewijk 25:ac139331fe51 452 static float errorIntegralL = 0.0;
efvanmarrewijk 25:ac139331fe51 453 static float errorPreviousL = error; // initialization with this value only done once!
efvanmarrewijk 25:ac139331fe51 454 static BiQuad PIDFilterL(0.0640, 0.1279, 0.0640, -1.1683, 0.4241);
efvanmarrewijk 25:ac139331fe51 455 // Proportional part:
efvanmarrewijk 25:ac139331fe51 456 float u_k = Kp * error;
efvanmarrewijk 25:ac139331fe51 457 // Integral part
efvanmarrewijk 25:ac139331fe51 458 errorIntegralL = errorIntegralL + error * dt;
efvanmarrewijk 25:ac139331fe51 459 float u_i = Ki * errorIntegralL;
efvanmarrewijk 25:ac139331fe51 460 // Derivative part
efvanmarrewijk 25:ac139331fe51 461 float errorDerivative = (error - errorPreviousL)/dt;
efvanmarrewijk 25:ac139331fe51 462 float errorDerivativeFiltered = PIDFilterL.step(errorDerivative);
efvanmarrewijk 25:ac139331fe51 463 float u_d = Kd * errorDerivativeFiltered;
efvanmarrewijk 25:ac139331fe51 464 errorPreviousL = error;
efvanmarrewijk 25:ac139331fe51 465 // Sum all parts and return it
efvanmarrewijk 25:ac139331fe51 466 return u_k + u_i + u_d;
efvanmarrewijk 25:ac139331fe51 467 }
efvanmarrewijk 25:ac139331fe51 468
efvanmarrewijk 25:ac139331fe51 469 float angleDesiredL() // Sets the desired angle for the controller dependent on the scaled angle of potmeter 1
efvanmarrewijk 25:ac139331fe51 470 { float angle = (pot1*2.0f*PI)-PI;
efvanmarrewijk 25:ac139331fe51 471 return angle;
efvanmarrewijk 25:ac139331fe51 472 }
efvanmarrewijk 25:ac139331fe51 473
efvanmarrewijk 25:ac139331fe51 474 float countsCalibrCalcL(int countsOffsetL)
efvanmarrewijk 25:ac139331fe51 475 {
efvanmarrewijk 25:ac139331fe51 476 countsCalibratedL = countsL - countsOffsetL + countsCalibration;
efvanmarrewijk 25:ac139331fe51 477 return countsCalibratedL;
efvanmarrewijk 25:ac139331fe51 478 }
EvaKrolis 13:4ba8f63e6ff4 479
efvanmarrewijk 25:ac139331fe51 480 void calibrationL() // Partially the same as motorTurnL, only with potmeter input
efvanmarrewijk 25:ac139331fe51 481 // How it works: manually turn motor using potmeters until the robot arm touches the bookholder.
efvanmarrewijk 25:ac139331fe51 482 // This program sets the counts from the motor to the reference counts (an angle of PI/4.0)
efvanmarrewijk 25:ac139331fe51 483 // Do this for every motor and after calibrated all motors, press a button
efvanmarrewijk 25:ac139331fe51 484 { float angleReferenceL = angleDesiredL(); // insert kinematics output here instead of angleDesiredL()
efvanmarrewijk 25:ac139331fe51 485 angleReferenceL = -angleReferenceL; // different minus sign per motor
efvanmarrewijk 25:ac139331fe51 486 angleCurrentL = angleCurrent(countsL); // different minus sign per motor
efvanmarrewijk 25:ac139331fe51 487 errorL = errorCalc(angleReferenceL,angleCurrentL); // same for every motor
efvanmarrewijk 25:ac139331fe51 488
efvanmarrewijk 25:ac139331fe51 489 if (fabs(errorL) >= 0.01f)
efvanmarrewijk 25:ac139331fe51 490 { float PIDControlL = PIDControllerL(angleReferenceL,angleCurrentL); // same for every motor
efvanmarrewijk 25:ac139331fe51 491 pin6 = fabs(PIDControlL); // different pins for every motor
efvanmarrewijk 25:ac139331fe51 492 pin7 = PIDControlL > 0.0f; // different pins for every motor
efvanmarrewijk 25:ac139331fe51 493 }
efvanmarrewijk 25:ac139331fe51 494 else if (fabs(errorL) < 0.01f)
efvanmarrewijk 25:ac139331fe51 495 { int countsOffsetL = countsL;
efvanmarrewijk 25:ac139331fe51 496 countsCalibrCalcL(countsOffsetL);
efvanmarrewijk 25:ac139331fe51 497 pin6 = 0.0f;
efvanmarrewijk 25:ac139331fe51 498 // BUTTON PRESS: TO NEXT STATE
efvanmarrewijk 25:ac139331fe51 499 }
efvanmarrewijk 25:ac139331fe51 500 }
efvanmarrewijk 25:ac139331fe51 501
efvanmarrewijk 25:ac139331fe51 502 void motorTurnL() // main function for movement of motor 1, all above functions with an extra tab are called
efvanmarrewijk 25:ac139331fe51 503 {
efvanmarrewijk 25:ac139331fe51 504 float angleReferenceL = angleDesiredL(); // insert kinematics output here instead of angleDesiredL()
efvanmarrewijk 25:ac139331fe51 505 angleReferenceL = -angleReferenceL; // different minus sign per motor
efvanmarrewijk 25:ac139331fe51 506 int countsL = countsInputL(); // different encoder pins per motor
efvanmarrewijk 25:ac139331fe51 507 angleCurrentL = angleCurrent(countsCalibratedL); // different minus sign per motor
efvanmarrewijk 25:ac139331fe51 508 errorCalibratedL = errorCalc(angleReferenceL,angleCurrentL); // same for every motor
efvanmarrewijk 25:ac139331fe51 509
efvanmarrewijk 25:ac139331fe51 510 float PIDControlL = PIDControllerL(angleReferenceL,angleCurrentL); // same for every motor
efvanmarrewijk 25:ac139331fe51 511 pin6 = fabs(PIDControlL); // different pins for every motor
efvanmarrewijk 25:ac139331fe51 512 pin7 = PIDControlL > 0.0f; // different pins for every motor
efvanmarrewijk 25:ac139331fe51 513 }
efvanmarrewijk 25:ac139331fe51 514
efvanmarrewijk 25:ac139331fe51 515 // ------------------------ MOTOR FUNCTIONS FOR MOTOR RIGHT --------------------
efvanmarrewijk 25:ac139331fe51 516 float PIDControllerR(float angleReference,float angleCurrent) // PID controller for the motors, based on the reference value and the current angle of the motor
efvanmarrewijk 25:ac139331fe51 517 { float Kp = 19.24f;
efvanmarrewijk 25:ac139331fe51 518 float Ki = 1.02f;
efvanmarrewijk 25:ac139331fe51 519 float Kd = 0.827f;
efvanmarrewijk 25:ac139331fe51 520 float error = errorCalc(angleReference,angleCurrent);
efvanmarrewijk 25:ac139331fe51 521 static float errorIntegralR = 0.0;
efvanmarrewijk 25:ac139331fe51 522 static float errorPreviousR = error; // initialization with this value only done once!
efvanmarrewijk 25:ac139331fe51 523 static BiQuad PIDFilterR(0.0640, 0.1279, 0.0640, -1.1683, 0.4241);
efvanmarrewijk 25:ac139331fe51 524 // Proportional part:
efvanmarrewijk 25:ac139331fe51 525 float u_k = Kp * error;
efvanmarrewijk 25:ac139331fe51 526 // Integral part
efvanmarrewijk 25:ac139331fe51 527 errorIntegralR = errorIntegralR + error * dt;
efvanmarrewijk 25:ac139331fe51 528 float u_i = Ki * errorIntegralR;
efvanmarrewijk 25:ac139331fe51 529 // Derivative part
efvanmarrewijk 25:ac139331fe51 530 float errorDerivative = (error - errorPreviousR)/dt;
efvanmarrewijk 25:ac139331fe51 531 float errorDerivativeFiltered = PIDFilterR.step(errorDerivative);
efvanmarrewijk 25:ac139331fe51 532 float u_d = Kd * errorDerivativeFiltered;
efvanmarrewijk 25:ac139331fe51 533 errorPreviousR = error;
efvanmarrewijk 25:ac139331fe51 534 // Sum all parts and return it
efvanmarrewijk 25:ac139331fe51 535 return u_k + u_i + u_d;
efvanmarrewijk 25:ac139331fe51 536 }
efvanmarrewijk 25:ac139331fe51 537
efvanmarrewijk 25:ac139331fe51 538 float angleDesiredR() // Sets the desired angle for the controller dependent on the scaled angle of potmeter 1
efvanmarrewijk 25:ac139331fe51 539 { float angle = (pot1*2.0f*PI)-PI;
efvanmarrewijk 25:ac139331fe51 540 return angle;
efvanmarrewijk 25:ac139331fe51 541 }
efvanmarrewijk 25:ac139331fe51 542
efvanmarrewijk 25:ac139331fe51 543 float countsCalibrCalcR(int countsOffsetR)
efvanmarrewijk 25:ac139331fe51 544 {
efvanmarrewijk 25:ac139331fe51 545 countsCalibratedR = countsR - countsOffsetR + countsCalibration;
efvanmarrewijk 25:ac139331fe51 546 return countsCalibratedR;
efvanmarrewijk 25:ac139331fe51 547 }
efvanmarrewijk 25:ac139331fe51 548
efvanmarrewijk 25:ac139331fe51 549 void calibrationR() // Partially the same as motorTurnR, only with potmeter input
efvanmarrewijk 25:ac139331fe51 550 // How it works: manually turn motor using potmeters until the robot arm touches the bookholder.
efvanmarrewijk 25:ac139331fe51 551 // This program sets the counts from the motor to the reference counts (an angle of PI/4.0)
efvanmarrewijk 25:ac139331fe51 552 // Do this for every motor and after calibrated all motors, press a button
efvanmarrewijk 25:ac139331fe51 553 { float angleReferenceR = angleDesiredR(); // insert kinematics output here instead of angleDesiredR()
efvanmarrewijk 25:ac139331fe51 554 angleReferenceR = -angleReferenceR; // different minus sign per motor
efvanmarrewijk 25:ac139331fe51 555 angleCurrentR = angleCurrent(countsR); // different minus sign per motor
efvanmarrewijk 25:ac139331fe51 556 errorR = errorCalc(angleReferenceR,angleCurrentR); // same for every motor
efvanmarrewijk 25:ac139331fe51 557
efvanmarrewijk 25:ac139331fe51 558 if (fabs(errorR) >= 0.01f)
efvanmarrewijk 25:ac139331fe51 559 { float PIDControlR = PIDControllerR(angleReferenceR,angleCurrentR); // same for every motor
efvanmarrewijk 25:ac139331fe51 560 pin6 = fabs(PIDControlR); // different pins for every motor
efvanmarrewijk 25:ac139331fe51 561 pin7 = PIDControlR > 0.0f; // different pins for every motor
efvanmarrewijk 25:ac139331fe51 562 }
efvanmarrewijk 25:ac139331fe51 563 else if (fabs(errorR) < 0.01f)
efvanmarrewijk 25:ac139331fe51 564 { int countsOffsetR = countsR;
efvanmarrewijk 25:ac139331fe51 565 countsCalibrCalcR(countsOffsetR);
efvanmarrewijk 25:ac139331fe51 566 pin6 = 0.0f;
efvanmarrewijk 25:ac139331fe51 567 // BUTTON PRESS: NAAR VOLGENDE STATE
efvanmarrewijk 25:ac139331fe51 568 }
efvanmarrewijk 25:ac139331fe51 569 }
efvanmarrewijk 25:ac139331fe51 570
efvanmarrewijk 25:ac139331fe51 571 void motorTurnR() // main function for movement of motor 1, all above functions with an extra tab are called
efvanmarrewijk 25:ac139331fe51 572 {
efvanmarrewijk 25:ac139331fe51 573 float angleReferenceR = angleDesiredR(); // insert kinematics output here instead of angleDesiredR()
efvanmarrewijk 25:ac139331fe51 574 angleReferenceR = -angleReferenceR; // different minus sign per motor
efvanmarrewijk 25:ac139331fe51 575 int countsR = countsInputR(); // different encoder pins per motor
efvanmarrewijk 25:ac139331fe51 576 angleCurrentR = angleCurrent(countsCalibratedR); // different minus sign per motor
efvanmarrewijk 25:ac139331fe51 577 errorCalibratedR = errorCalc(angleReferenceR,angleCurrentR); // same for every motor
efvanmarrewijk 25:ac139331fe51 578
efvanmarrewijk 25:ac139331fe51 579 float PIDControlR = PIDControllerR(angleReferenceR,angleCurrentR); // same for every motor
efvanmarrewijk 25:ac139331fe51 580 pin6 = fabs(PIDControlR); // different pins for every motor
efvanmarrewijk 25:ac139331fe51 581 pin7 = PIDControlR > 0.0f; // different pins for every motor
efvanmarrewijk 25:ac139331fe51 582 }
efvanmarrewijk 25:ac139331fe51 583
efvanmarrewijk 25:ac139331fe51 584 // ------------------------- MOTOR FUNCTIONS FOR MOTOR FLIP --------------------
efvanmarrewijk 25:ac139331fe51 585 // Not yet implemented
EvaKrolis 13:4ba8f63e6ff4 586
tverouden 2:d70795e4e0bf 587 // ≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡ STATE MACHINE ≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡
tverouden 15:6566c5dedeeb 588 void stateMachine(void)
tverouden 3:9c63fc5f157e 589 {
tverouden 24:0abc564349e1 590 switch (currentState) { // determine which state Odin is in
tverouden 3:9c63fc5f157e 591
tverouden 4:5ce2c8864908 592 // ========================= MOTOR CALIBRATION MODE ==========================
tverouden 4:5ce2c8864908 593 case calibratingMotors:
tverouden 4:5ce2c8864908 594 // ------------------------- initialisation --------------------------
tverouden 4:5ce2c8864908 595 if (changeState) { // when entering the state
tverouden 15:6566c5dedeeb 596 pc.printf("[MODE] calibrating motors...\r\n");
tverouden 5:04b26b2f536a 597 // print current state
tverouden 4:5ce2c8864908 598 changeState = false; // stay in this state
tverouden 4:5ce2c8864908 599
tverouden 4:5ce2c8864908 600 // Actions when entering state
tverouden 15:6566c5dedeeb 601 ledRed = 1; // cyan-green blinking LED
tverouden 15:6566c5dedeeb 602 ledGreen = 0;
tverouden 15:6566c5dedeeb 603 ledBlue = 0;
tverouden 15:6566c5dedeeb 604 blinkTimer.attach(&blinkLedBlue,0.5);
tverouden 4:5ce2c8864908 605
tverouden 4:5ce2c8864908 606 }
tverouden 4:5ce2c8864908 607 // ----------------------------- action ------------------------------
tverouden 5:04b26b2f536a 608 // Actions for each loop iteration
tverouden 5:04b26b2f536a 609 /* */
tverouden 4:5ce2c8864908 610
tverouden 4:5ce2c8864908 611 // --------------------------- transition ----------------------------
tverouden 24:0abc564349e1 612 // Transition condition: when all motor errors smaller than 0.01,
tverouden 24:0abc564349e1 613 // start calibrating EMG
tverouden 23:e282bdb9e9b7 614 if (errorMotorL < 0.01 && errorMotorR < 0.01
tverouden 24:0abc564349e1 615 && errorMotorF < 0.01 && buttonHome == false) {
tverouden 24:0abc564349e1 616
tverouden 23:e282bdb9e9b7 617 // Actions when leaving state
tverouden 23:e282bdb9e9b7 618 blinkTimer.detach();
tverouden 23:e282bdb9e9b7 619
tverouden 23:e282bdb9e9b7 620 currentState = calibratingEMG; // change to state
tverouden 23:e282bdb9e9b7 621 changeState = true; // next loop, switch states
tverouden 23:e282bdb9e9b7 622 }
tverouden 5:04b26b2f536a 623
tverouden 4:5ce2c8864908 624 break; // end case
tverouden 4:5ce2c8864908 625
tverouden 7:ef5966469621 626 // =========================== EMG CALIBRATION MODE ===========================
tverouden 7:ef5966469621 627 case calibratingEMG:
tverouden 4:5ce2c8864908 628 // ------------------------- initialisation --------------------------
tverouden 3:9c63fc5f157e 629 if (changeState) { // when entering the state
tverouden 21:fbd900a55877 630 pc.printf("[MODE] calibrating EMG...\r\n");
tverouden 5:04b26b2f536a 631 // print current state
tverouden 4:5ce2c8864908 632 changeState = false; // stay in this state
tverouden 4:5ce2c8864908 633
tverouden 4:5ce2c8864908 634 // Actions when entering state
tverouden 15:6566c5dedeeb 635 ledRed = 1; // cyan-blue blinking LED
tverouden 15:6566c5dedeeb 636 ledGreen = 0;
tverouden 15:6566c5dedeeb 637 ledBlue = 0;
tverouden 15:6566c5dedeeb 638 blinkTimer.attach(&blinkLedGreen,0.5);
tverouden 15:6566c5dedeeb 639
tverouden 4:5ce2c8864908 640
tverouden 4:5ce2c8864908 641 }
tverouden 4:5ce2c8864908 642 // ----------------------------- action ------------------------------
tverouden 5:04b26b2f536a 643 // Actions for each loop iteration
tverouden 5:04b26b2f536a 644 /* */
tverouden 4:5ce2c8864908 645
tverouden 4:5ce2c8864908 646 // --------------------------- transition ----------------------------
tverouden 24:0abc564349e1 647 // Transition condition: after 20 sec in state
tverouden 24:0abc564349e1 648 if (1) { // CONDITION -> Eva, hoe moet ik de 20 seconden regelen?
tverouden 4:5ce2c8864908 649 // Actions when leaving state
tverouden 15:6566c5dedeeb 650 blinkTimer.detach();
tverouden 5:04b26b2f536a 651
tverouden 4:5ce2c8864908 652 currentState = homing; // change to state
tverouden 4:5ce2c8864908 653 changeState = true; // next loop, switch states
tverouden 5:04b26b2f536a 654 }
tverouden 5:04b26b2f536a 655 break; // end case
tverouden 4:5ce2c8864908 656
tverouden 4:5ce2c8864908 657 // ============================== HOMING MODE ================================
tverouden 4:5ce2c8864908 658 case homing:
tverouden 24:0abc564349e1 659 // ------------------------- initialisation --------------------------
tverouden 4:5ce2c8864908 660 if (changeState) { // when entering the state
tverouden 4:5ce2c8864908 661 pc.printf("[MODE] homing...\r\n");
tverouden 5:04b26b2f536a 662 // print current state
tverouden 4:5ce2c8864908 663 changeState = false; // stay in this state
tverouden 4:5ce2c8864908 664
tverouden 4:5ce2c8864908 665
tverouden 4:5ce2c8864908 666 // Actions when entering state
tverouden 15:6566c5dedeeb 667 ledRed = 1; // cyan LED on
tverouden 15:6566c5dedeeb 668 ledGreen = 0;
tverouden 15:6566c5dedeeb 669 ledBlue = 0;
tverouden 4:5ce2c8864908 670
tverouden 4:5ce2c8864908 671 }
tverouden 4:5ce2c8864908 672 // ----------------------------- action ------------------------------
tverouden 5:04b26b2f536a 673 // Actions for each loop iteration
tverouden 5:04b26b2f536a 674 /* */
tverouden 4:5ce2c8864908 675
tverouden 24:0abc564349e1 676 // --------------------------- transition ----------------------------
tverouden 24:0abc564349e1 677 // Transition condition #1: with button press, enter demo mode,
tverouden 24:0abc564349e1 678 // but only when velocity == 0
tverouden 24:0abc564349e1 679 if (errorMotorL < 0.01 && errorMotorR < 0.01
tverouden 24:0abc564349e1 680 && errorMotorF < 0.01 && buttonBio1 == true) {
tverouden 24:0abc564349e1 681 // Actions when leaving state
tverouden 24:0abc564349e1 682 /* */
tverouden 24:0abc564349e1 683
tverouden 24:0abc564349e1 684 currentState = reading; // change to state
tverouden 24:0abc564349e1 685 changeState = true; // next loop, switch states
tverouden 24:0abc564349e1 686 }
tverouden 24:0abc564349e1 687 // Transition condition #2: with button press, enter operation mode
tverouden 24:0abc564349e1 688 // but only when velocity == 0
tverouden 24:0abc564349e1 689 if (errorMotorL < 0.01 && errorMotorR < 0.01
tverouden 24:0abc564349e1 690 && errorMotorF < 0.01 && buttonBio2 == true) {
tverouden 4:5ce2c8864908 691 // Actions when leaving state
tverouden 4:5ce2c8864908 692 /* */
tverouden 5:04b26b2f536a 693
tverouden 4:5ce2c8864908 694 currentState = demoing; // change to state
tverouden 4:5ce2c8864908 695 changeState = true; // next loop, switch states
tverouden 4:5ce2c8864908 696 }
tverouden 4:5ce2c8864908 697 break; // end case
tverouden 4:5ce2c8864908 698
tverouden 24:0abc564349e1 699 // ============================== READING MODE ===============================
tverouden 17:b04e1938491a 700 case reading:
tverouden 17:b04e1938491a 701 // ------------------------- initialisation --------------------------
tverouden 17:b04e1938491a 702 if (changeState) { // when entering the state
tverouden 17:b04e1938491a 703 pc.printf("[MODE] reading...\r\n");
tverouden 17:b04e1938491a 704 // print current state
tverouden 17:b04e1938491a 705 changeState = false; // stay in this state
tverouden 17:b04e1938491a 706
tverouden 17:b04e1938491a 707 // Actions when entering state
tverouden 17:b04e1938491a 708 ledRed = 1; // blue LED on
tverouden 17:b04e1938491a 709 ledGreen = 1;
tverouden 17:b04e1938491a 710 ledBlue = 0;
tverouden 24:0abc564349e1 711
tverouden 24:0abc564349e1 712 // TERUGKLAPPEN
tverouden 17:b04e1938491a 713
tverouden 17:b04e1938491a 714 }
tverouden 17:b04e1938491a 715 // ----------------------------- action ------------------------------
tverouden 17:b04e1938491a 716 // Actions for each loop iteration
tverouden 17:b04e1938491a 717 /* */
tverouden 17:b04e1938491a 718
tverouden 17:b04e1938491a 719 // --------------------------- transition ----------------------------
tverouden 24:0abc564349e1 720 // Transition condition #1: when EMG signal detected, enter reading
tverouden 24:0abc564349e1 721 // mode
tverouden 24:0abc564349e1 722 if (moving_average(EMG1 > threshold_value || // Namen variabelen?
tverouden 24:0abc564349e1 723 moving_average(EMG2 > threshold_value) {
tverouden 24:0abc564349e1 724 // Actions when leaving state
tverouden 24:0abc564349e1 725 /* */
tverouden 24:0abc564349e1 726
tverouden 24:0abc564349e1 727 currentState = reading; // change to state
tverouden 24:0abc564349e1 728 changeState = true; // next loop, switch states
tverouden 24:0abc564349e1 729 }
tverouden 24:0abc564349e1 730 // Transition condition #2: with button press, back to homing mode
tverouden 24:0abc564349e1 731 if (buttonHome == false) {
tverouden 24:0abc564349e1 732 // Actions when leaving state
tverouden 17:b04e1938491a 733 /* */
tverouden 17:b04e1938491a 734
tverouden 17:b04e1938491a 735 currentState = homing; // change to state
tverouden 17:b04e1938491a 736 changeState = true; // next loop, switch states
tverouden 17:b04e1938491a 737 }
tverouden 17:b04e1938491a 738 break; // end case
tverouden 17:b04e1938491a 739
tverouden 4:5ce2c8864908 740 // ============================= OPERATING MODE ==============================
tverouden 4:5ce2c8864908 741 case operating:
tverouden 4:5ce2c8864908 742 // ------------------------- initialisation --------------------------
tverouden 4:5ce2c8864908 743 if (changeState) { // when entering the state
tverouden 4:5ce2c8864908 744 pc.printf("[MODE] operating...\r\n");
tverouden 5:04b26b2f536a 745 // print current state
tverouden 5:04b26b2f536a 746 changeState = false; // stay in this state
tverouden 5:04b26b2f536a 747
tverouden 5:04b26b2f536a 748 // Actions when entering state
tverouden 15:6566c5dedeeb 749 ledRed = 1; // blue fast blinking LED
tverouden 15:6566c5dedeeb 750 ledGreen = 1;
tverouden 15:6566c5dedeeb 751 ledBlue = 1;
tverouden 15:6566c5dedeeb 752 blinkTimer.attach(&blinkLedBlue,0.25);
tverouden 5:04b26b2f536a 753
tverouden 5:04b26b2f536a 754 }
tverouden 5:04b26b2f536a 755 // ----------------------------- action ------------------------------
tverouden 5:04b26b2f536a 756 // Actions for each loop iteration
tverouden 5:04b26b2f536a 757 /* */
tverouden 5:04b26b2f536a 758
tverouden 5:04b26b2f536a 759 // --------------------------- transition ----------------------------
tverouden 24:0abc564349e1 760 // Transition condition: when path is over, back to reading mode
tverouden 24:0abc564349e1 761 if (errorMotorL < 0.01 && errorMotorR < 0.01) {
tverouden 5:04b26b2f536a 762 // Actions when leaving state
tverouden 15:6566c5dedeeb 763 blinkTimer.detach();
tverouden 5:04b26b2f536a 764
tverouden 24:0abc564349e1 765 currentState = reading; // change to state
tverouden 5:04b26b2f536a 766 changeState = true; // next loop, switch states
tverouden 5:04b26b2f536a 767 }
tverouden 5:04b26b2f536a 768 break; // end case
tverouden 5:04b26b2f536a 769
tverouden 5:04b26b2f536a 770 // ============================== DEMOING MODE ===============================
tverouden 5:04b26b2f536a 771 case demoing:
tverouden 5:04b26b2f536a 772 // ------------------------- initialisation --------------------------
tverouden 5:04b26b2f536a 773 if (changeState) { // when entering the state
tverouden 5:04b26b2f536a 774 pc.printf("[MODE] demoing...\r\n");
tverouden 5:04b26b2f536a 775 // print current state
tverouden 5:04b26b2f536a 776 changeState = false; // stay in this state
tverouden 5:04b26b2f536a 777
tverouden 5:04b26b2f536a 778 // Actions when entering state
tverouden 15:6566c5dedeeb 779 ledRed = 0; // yellow LED on
tverouden 15:6566c5dedeeb 780 ledGreen = 0;
tverouden 15:6566c5dedeeb 781 ledBlue = 1;
tverouden 5:04b26b2f536a 782
tverouden 5:04b26b2f536a 783 }
tverouden 5:04b26b2f536a 784 // ----------------------------- action ------------------------------
tverouden 5:04b26b2f536a 785 // Actions for each loop iteration
tverouden 5:04b26b2f536a 786 /* */
tverouden 5:04b26b2f536a 787
tverouden 5:04b26b2f536a 788 // --------------------------- transition ----------------------------
tverouden 24:0abc564349e1 789 // Transition condition: with button press, back to homing mode
tverouden 24:0abc564349e1 790 if (buttonHome == false) {
tverouden 5:04b26b2f536a 791 // Actions when leaving state
tverouden 5:04b26b2f536a 792 /* */
tverouden 5:04b26b2f536a 793
tverouden 5:04b26b2f536a 794 currentState = homing; // change to state
tverouden 5:04b26b2f536a 795 changeState = true; // next loop, switch states
tverouden 5:04b26b2f536a 796 }
tverouden 5:04b26b2f536a 797 break; // end case
tverouden 5:04b26b2f536a 798
tverouden 5:04b26b2f536a 799 // =============================== FAILING MODE ================================
tverouden 5:04b26b2f536a 800 case failing:
tverouden 24:0abc564349e1 801 changeState = false; // stay in this state
tverouden 3:9c63fc5f157e 802
tverouden 3:9c63fc5f157e 803 // Actions when entering state
tverouden 20:cf673a2cbc60 804 ledRed = 0; // red LED on
tverouden 20:cf673a2cbc60 805 ledGreen = 1;
tverouden 6:f32352bc5078 806 ledBlue = 1;
tverouden 4:5ce2c8864908 807
tverouden 24:0abc564349e1 808 // pin3 = 0; // all motor forces to zero // Pins nog niet gedefiniëerd
tverouden 6:f32352bc5078 809 // pin5 = 0;
tverouden 6:f32352bc5078 810 // pin6 = 0;
tverouden 20:cf673a2cbc60 811 exit (0); // stop all current functions
tverouden 4:5ce2c8864908 812 break; // end case
tverouden 4:5ce2c8864908 813
tverouden 4:5ce2c8864908 814 // ============================== DEFAULT MODE =================================
tverouden 3:9c63fc5f157e 815 default:
tverouden 4:5ce2c8864908 816 // ---------------------------- enter failing mode -----------------------------
tverouden 4:5ce2c8864908 817 currentState = failing; // change to state
tverouden 4:5ce2c8864908 818 changeState = true; // next loop, switch states
tverouden 4:5ce2c8864908 819 // print current state
tverouden 4:5ce2c8864908 820 pc.printf("[ERROR] unknown or unimplemented state reached\r\n");
tverouden 3:9c63fc5f157e 821
tverouden 4:5ce2c8864908 822 } // end switch
tverouden 4:5ce2c8864908 823 } // end stateMachine
tverouden 3:9c63fc5f157e 824
tverouden 3:9c63fc5f157e 825
tverouden 2:d70795e4e0bf 826
tverouden 2:d70795e4e0bf 827 // ≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡ MAIN LOOP ≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡
tverouden 2:d70795e4e0bf 828
tverouden 3:9c63fc5f157e 829 int main()
tverouden 3:9c63fc5f157e 830 {
tverouden 8:8cef1050ebd9 831 // ================================ EMERGENCY ================================
tverouden 15:6566c5dedeeb 832 //If the emergency button is pressed, stop program via failing state
tverouden 24:0abc564349e1 833 buttonEmergency.rise(stopProgram); // Automatische triggers voor failure mode? -> ook error message in andere functies plaatsen!
tverouden 15:6566c5dedeeb 834
tverouden 19:2797bb471f9f 835 // ============================= PC-COMMUNICATION =============================
tverouden 19:2797bb471f9f 836 pc.baud(115200); // communication with terminal
tverouden 19:2797bb471f9f 837 pc.printf("\n\n[START] starting O.D.I.N\r\n");
tverouden 6:f32352bc5078 838
efvanmarrewijk 25:ac139331fe51 839 // ============================= PIN DEFINE PERIOD ============================
efvanmarrewijk 25:ac139331fe51 840 // If you give a period on one pin, c++ gives all pins this period
efvanmarrewijk 25:ac139331fe51 841 pin3.period_us(15);
efvanmarrewijk 25:ac139331fe51 842
tverouden 2:d70795e4e0bf 843 // ==================================== LOOP ===================================
tverouden 24:0abc564349e1 844 // run state machine at 500 Hz
efvanmarrewijk 25:ac139331fe51 845 stateTimer.attach(&stateMachine,dt);
tverouden 2:d70795e4e0bf 846 }