Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependencies: biquadFilter FastPWM MODSERIAL QEI mbed
main.cpp@35:3c937770aa41, 2018-11-01 (annotated)
- Committer:
- efvanmarrewijk
- Date:
- Thu Nov 01 14:26:16 2018 +0000
- Revision:
- 35:3c937770aa41
- Parent:
- 34:fb6889c5ca22
- Child:
- 37:317e14b9d551
Motor flip code added
Who changed what in which revision?
| User | Revision | Line number | New 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 | 26:247be0bea9b1 | 54 | const float dt = 0.002f; |
| 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 --------------------------- |
| efvanmarrewijk | 26:247be0bea9b1 | 154 | const float countsRad = 4200.0f; |
| efvanmarrewijk | 26:247be0bea9b1 | 155 | int countsL; |
| efvanmarrewijk | 26:247be0bea9b1 | 156 | int countsR; |
| efvanmarrewijk | 26:247be0bea9b1 | 157 | int countsF; |
| efvanmarrewijk | 26:247be0bea9b1 | 158 | int countsCalibratedL; |
| efvanmarrewijk | 26:247be0bea9b1 | 159 | int countsCalibratedR; |
| efvanmarrewijk | 26:247be0bea9b1 | 160 | int countsCalibratedF; |
| efvanmarrewijk | 26:247be0bea9b1 | 161 | float angleCurrentL; |
| efvanmarrewijk | 26:247be0bea9b1 | 162 | float angleCurrentR; |
| efvanmarrewijk | 26:247be0bea9b1 | 163 | float angleCurrentF; |
| efvanmarrewijk | 26:247be0bea9b1 | 164 | float errorL; |
| efvanmarrewijk | 26:247be0bea9b1 | 165 | float errorR; |
| efvanmarrewijk | 26:247be0bea9b1 | 166 | float errorF; |
| efvanmarrewijk | 26:247be0bea9b1 | 167 | float errorCalibratedL; |
| efvanmarrewijk | 26:247be0bea9b1 | 168 | float errorCalibratedR; |
| efvanmarrewijk | 26:247be0bea9b1 | 169 | float errorCalibratedF; |
| EvaKrolis | 14:2c0bf576a0e7 | 170 | |
| efvanmarrewijk | 26:247be0bea9b1 | 171 | int countsCalibration = 4200/4; |
| efvanmarrewijk | 25:ac139331fe51 | 172 | |
| tverouden | 4:5ce2c8864908 | 173 | // ≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡ FUNCTIONS ≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡ |
| tverouden | 6:f32352bc5078 | 174 | // ============================ GENERAL FUNCTIONS ============================= |
| tverouden | 6:f32352bc5078 | 175 | void stopProgram(void) |
| tverouden | 6:f32352bc5078 | 176 | { |
| tverouden | 6:f32352bc5078 | 177 | // Error message |
| tverouden | 6:f32352bc5078 | 178 | pc.printf("[ERROR] emergency button pressed\r\n"); |
| tverouden | 6:f32352bc5078 | 179 | currentState = failing; // change to state |
| tverouden | 6:f32352bc5078 | 180 | changeState = true; // next loop, switch states |
| tverouden | 6:f32352bc5078 | 181 | } |
| tverouden | 8:8cef1050ebd9 | 182 | |
| tverouden | 15:6566c5dedeeb | 183 | void blinkLedRed(void) |
| tverouden | 15:6566c5dedeeb | 184 | { |
| tverouden | 15:6566c5dedeeb | 185 | ledRed =! ledRed; // toggle LED |
| tverouden | 10:584b7d2c2d63 | 186 | } |
| tverouden | 15:6566c5dedeeb | 187 | void blinkLedGreen(void) |
| tverouden | 15:6566c5dedeeb | 188 | { |
| tverouden | 15:6566c5dedeeb | 189 | ledGreen =! ledGreen; // toggle LED |
| tverouden | 15:6566c5dedeeb | 190 | } |
| tverouden | 15:6566c5dedeeb | 191 | void blinkLedBlue(void) |
| tverouden | 15:6566c5dedeeb | 192 | { |
| tverouden | 15:6566c5dedeeb | 193 | ledBlue =! ledBlue; // toggle LED |
| tverouden | 15:6566c5dedeeb | 194 | } |
| tverouden | 15:6566c5dedeeb | 195 | |
| tverouden | 4:5ce2c8864908 | 196 | // ============================= EMG FUNCTIONS =============================== |
| tverouden | 4:5ce2c8864908 | 197 | |
| EvaKrolis | 13:4ba8f63e6ff4 | 198 | //Function to read and filter the EMG |
| EvaKrolis | 13:4ba8f63e6ff4 | 199 | void ReadUseEMG0(){ |
| EvaKrolis | 13:4ba8f63e6ff4 | 200 | for(int i = Parts ; i > 0 ; i--){ //Make a first in, first out array |
| EvaKrolis | 13:4ba8f63e6ff4 | 201 | EMG0filtArray[i] = EMG0filtArray[i-1]; //Every value moves one up |
| EvaKrolis | 13:4ba8f63e6ff4 | 202 | } |
| EvaKrolis | 13:4ba8f63e6ff4 | 203 | |
| EvaKrolis | 13:4ba8f63e6ff4 | 204 | Sum0 = 0; |
| EvaKrolis | 13:4ba8f63e6ff4 | 205 | EMG0 = EMG0In; //Save EMG input in float |
| EvaKrolis | 13:4ba8f63e6ff4 | 206 | EMG0filt = filter0.step(EMG0); //Filter the signal |
| EvaKrolis | 13:4ba8f63e6ff4 | 207 | EMG0filt = abs(EMG0filt); //Take the absolute value |
| EvaKrolis | 13:4ba8f63e6ff4 | 208 | EMG0filtArray[0] = EMG0filt; //Save the filtered signal on the first place in the array |
| EvaKrolis | 13:4ba8f63e6ff4 | 209 | |
| EvaKrolis | 13:4ba8f63e6ff4 | 210 | for(int i = 0 ; i < Parts ; i++){ //Moving Average filter |
| EvaKrolis | 13:4ba8f63e6ff4 | 211 | Sum0 += EMG0filtArray[i]; //Sum the new value and the previous 49 |
| EvaKrolis | 13:4ba8f63e6ff4 | 212 | } |
| EvaKrolis | 13:4ba8f63e6ff4 | 213 | EMG0Average = (float)Sum0/Parts; //Divide the sum by 50 |
| EvaKrolis | 13:4ba8f63e6ff4 | 214 | |
| EvaKrolis | 13:4ba8f63e6ff4 | 215 | if (EMG0Average > Threshold0){ //If the value is higher than the threshold value |
| EvaKrolis | 13:4ba8f63e6ff4 | 216 | xMove = true; //Set movement to true |
| EvaKrolis | 13:4ba8f63e6ff4 | 217 | } |
| EvaKrolis | 13:4ba8f63e6ff4 | 218 | else{ |
| EvaKrolis | 13:4ba8f63e6ff4 | 219 | xMove = false; //Otherwise set movement to false |
| EvaKrolis | 13:4ba8f63e6ff4 | 220 | } |
| EvaKrolis | 13:4ba8f63e6ff4 | 221 | } |
| EvaKrolis | 13:4ba8f63e6ff4 | 222 | |
| EvaKrolis | 13:4ba8f63e6ff4 | 223 | //Function to read and filter the EMG |
| EvaKrolis | 13:4ba8f63e6ff4 | 224 | void ReadUseEMG1(){ |
| EvaKrolis | 13:4ba8f63e6ff4 | 225 | for(int i = Parts ; i > 0 ; i--){ //Make a first in, first out array |
| EvaKrolis | 13:4ba8f63e6ff4 | 226 | EMG1filtArray[i] = EMG1filtArray[i-1]; //Every value moves one up |
| EvaKrolis | 13:4ba8f63e6ff4 | 227 | } |
| EvaKrolis | 13:4ba8f63e6ff4 | 228 | |
| EvaKrolis | 13:4ba8f63e6ff4 | 229 | Sum1 = 0; |
| EvaKrolis | 13:4ba8f63e6ff4 | 230 | EMG1 = EMG1In; //Save EMG input in float |
| EvaKrolis | 13:4ba8f63e6ff4 | 231 | EMG1filt = filter1.step(EMG1); //Filter the signal |
| EvaKrolis | 13:4ba8f63e6ff4 | 232 | EMG1filt = abs(EMG1filt); //Take the absolute value |
| EvaKrolis | 13:4ba8f63e6ff4 | 233 | EMG1filtArray[0] = EMG1filt; //Save the filtered signal on the first place in the array |
| EvaKrolis | 13:4ba8f63e6ff4 | 234 | |
| EvaKrolis | 13:4ba8f63e6ff4 | 235 | for(int i = 0 ; i < Parts ; i++){ //Moving Average filter |
| EvaKrolis | 13:4ba8f63e6ff4 | 236 | Sum1 += EMG1filtArray[i]; //Sum the new value and the previous 49 |
| EvaKrolis | 13:4ba8f63e6ff4 | 237 | } |
| EvaKrolis | 13:4ba8f63e6ff4 | 238 | EMG1Average = (float)Sum1/Parts; //Divide the sum by 50 |
| EvaKrolis | 13:4ba8f63e6ff4 | 239 | |
| EvaKrolis | 13:4ba8f63e6ff4 | 240 | if (EMG1Average > Threshold1){ //If the value is higher than the threshold value |
| EvaKrolis | 13:4ba8f63e6ff4 | 241 | yMove = true; //Set y movement to true |
| EvaKrolis | 13:4ba8f63e6ff4 | 242 | } |
| EvaKrolis | 13:4ba8f63e6ff4 | 243 | else{ |
| EvaKrolis | 13:4ba8f63e6ff4 | 244 | yMove = false; //Otherwise set y movement to false |
| EvaKrolis | 13:4ba8f63e6ff4 | 245 | } |
| EvaKrolis | 13:4ba8f63e6ff4 | 246 | } |
| EvaKrolis | 13:4ba8f63e6ff4 | 247 | |
| EvaKrolis | 13:4ba8f63e6ff4 | 248 | //Function to make an array during the calibration |
| EvaKrolis | 13:4ba8f63e6ff4 | 249 | void CalibrateEMG0(){ |
| EvaKrolis | 13:4ba8f63e6ff4 | 250 | for(int i = Parts ; i > 0 ; i--){ //Make a first in, first out array |
| EvaKrolis | 13:4ba8f63e6ff4 | 251 | EMG0filtArray[i] = EMG0filtArray[i-1]; //Every value moves one up |
| EvaKrolis | 13:4ba8f63e6ff4 | 252 | } |
| EvaKrolis | 13:4ba8f63e6ff4 | 253 | |
| EvaKrolis | 13:4ba8f63e6ff4 | 254 | Sum0 = 0; |
| EvaKrolis | 13:4ba8f63e6ff4 | 255 | EMG0 = EMG0In; //Save EMG input in float |
| EvaKrolis | 13:4ba8f63e6ff4 | 256 | EMG0filt = filter0.step(EMG0); //Filter the signal |
| EvaKrolis | 13:4ba8f63e6ff4 | 257 | EMG0filt = abs(EMG0filt); //Take the absolute value |
| EvaKrolis | 13:4ba8f63e6ff4 | 258 | EMG0filtArray[0] = EMG0filt; //Save the filtered signal on the first place in the array |
| EvaKrolis | 13:4ba8f63e6ff4 | 259 | |
| EvaKrolis | 13:4ba8f63e6ff4 | 260 | for(int i = 0 ; i < Parts ; i++){ //Moving Average filter |
| EvaKrolis | 13:4ba8f63e6ff4 | 261 | Sum0 += EMG0filtArray[i]; //Sum the new value and the previous 49 |
| EvaKrolis | 13:4ba8f63e6ff4 | 262 | } |
| EvaKrolis | 13:4ba8f63e6ff4 | 263 | EMG0Calibrate[ReadCal0] = (float)Sum0/Parts; //Divide the sum by 50 |
| EvaKrolis | 13:4ba8f63e6ff4 | 264 | |
| EvaKrolis | 13:4ba8f63e6ff4 | 265 | ReadCal0++; |
| EvaKrolis | 13:4ba8f63e6ff4 | 266 | } |
| EvaKrolis | 13:4ba8f63e6ff4 | 267 | |
| EvaKrolis | 13:4ba8f63e6ff4 | 268 | //Function to make an array during the calibration |
| EvaKrolis | 13:4ba8f63e6ff4 | 269 | void CalibrateEMG1(){ |
| EvaKrolis | 13:4ba8f63e6ff4 | 270 | for(int i = Parts ; i > 0 ; i--){ //Make a first in, first out array |
| EvaKrolis | 13:4ba8f63e6ff4 | 271 | EMG1filtArray[i] = EMG1filtArray[i-1]; //Every value moves one up |
| EvaKrolis | 13:4ba8f63e6ff4 | 272 | } |
| EvaKrolis | 13:4ba8f63e6ff4 | 273 | |
| EvaKrolis | 13:4ba8f63e6ff4 | 274 | Sum1 = 0; |
| EvaKrolis | 13:4ba8f63e6ff4 | 275 | EMG1 = EMG1In; //Save EMG input in float |
| EvaKrolis | 13:4ba8f63e6ff4 | 276 | EMG1filt = filter1.step(EMG1); //Filter the signal |
| EvaKrolis | 13:4ba8f63e6ff4 | 277 | EMG1filt = abs(EMG1filt); //Take the absolute value |
| EvaKrolis | 13:4ba8f63e6ff4 | 278 | EMG1filtArray[0] = EMG1filt; //Save the filtered signal on the first place in the array |
| EvaKrolis | 13:4ba8f63e6ff4 | 279 | |
| EvaKrolis | 13:4ba8f63e6ff4 | 280 | for(int i = 0 ; i < Parts ; i++){ //Moving Average filter |
| EvaKrolis | 13:4ba8f63e6ff4 | 281 | Sum1 += EMG1filtArray[i]; //Sum the new value and the previous 49 |
| EvaKrolis | 13:4ba8f63e6ff4 | 282 | } |
| EvaKrolis | 13:4ba8f63e6ff4 | 283 | EMG1Calibrate[ReadCal1] = (float)Sum1/Parts; //Divide the sum by 50 |
| EvaKrolis | 13:4ba8f63e6ff4 | 284 | |
| EvaKrolis | 13:4ba8f63e6ff4 | 285 | ReadCal1++; |
| EvaKrolis | 13:4ba8f63e6ff4 | 286 | } |
| EvaKrolis | 13:4ba8f63e6ff4 | 287 | |
| EvaKrolis | 13:4ba8f63e6ff4 | 288 | //Function to find the max value during the calibration |
| EvaKrolis | 13:4ba8f63e6ff4 | 289 | void FindMax0(){ |
| EvaKrolis | 13:4ba8f63e6ff4 | 290 | MaxValue0 = *max_element(EMG0Calibrate+500,EMG0Calibrate+Length); //Find max value, but discard the first 100 values |
| EvaKrolis | 13:4ba8f63e6ff4 | 291 | Threshold0 = 0.30f*MaxValue0; //The threshold is a percentage of the max value |
| EvaKrolis | 13:4ba8f63e6ff4 | 292 | 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 | 293 | FindMax0_timer.detach(); //Detach the timer, so you only use this once |
| EvaKrolis | 13:4ba8f63e6ff4 | 294 | } |
| EvaKrolis | 13:4ba8f63e6ff4 | 295 | |
| EvaKrolis | 13:4ba8f63e6ff4 | 296 | //Function to find the max value during the calibration |
| EvaKrolis | 13:4ba8f63e6ff4 | 297 | void FindMax1(){ |
| EvaKrolis | 13:4ba8f63e6ff4 | 298 | MaxValue1 = *max_element(EMG1Calibrate+500,EMG1Calibrate+Length); //Find max value, but discard the first 100 values |
| EvaKrolis | 13:4ba8f63e6ff4 | 299 | Threshold1 = 0.30f*MaxValue1; //The threshold is a percentage of the max value |
| EvaKrolis | 13:4ba8f63e6ff4 | 300 | 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 | 301 | FindMax1_timer.detach(); //Detach the timer, so you only use this once |
| EvaKrolis | 13:4ba8f63e6ff4 | 302 | } |
| tverouden | 4:5ce2c8864908 | 303 | |
| tverouden | 12:323ac4e27a0d | 304 | // ========================= KINEMATICS FUNCTIONS ============================ |
| tverouden | 12:323ac4e27a0d | 305 | |
| EvaKrolis | 14:2c0bf576a0e7 | 306 | // Function to calculate the inverse kinematics |
| EvaKrolis | 14:2c0bf576a0e7 | 307 | void inverse(double prex, double prey) |
| EvaKrolis | 14:2c0bf576a0e7 | 308 | { |
| EvaKrolis | 14:2c0bf576a0e7 | 309 | /* |
| EvaKrolis | 14:2c0bf576a0e7 | 310 | qn = qn-1 + (jacobian^-1)*dPref/dt *deltaT |
| EvaKrolis | 14:2c0bf576a0e7 | 311 | ofwel |
| EvaKrolis | 14:2c0bf576a0e7 | 312 | thetai+1 = thetai +(jacobian)^-1*vector(deltaX, DeltaY) |
| EvaKrolis | 14:2c0bf576a0e7 | 313 | waar Pref = emg signaal |
| EvaKrolis | 14:2c0bf576a0e7 | 314 | */ //achtergrondinfo hierboven... |
| EvaKrolis | 14:2c0bf576a0e7 | 315 | // |
| EvaKrolis | 14:2c0bf576a0e7 | 316 | |
| EvaKrolis | 14:2c0bf576a0e7 | 317 | theta1 += (prefx*jacobiana+jacobianb*prey)*deltat; //theta 1 is zichzelf plus wat hier staat (is kinematics) |
| EvaKrolis | 14:2c0bf576a0e7 | 318 | theta4 += (prefx*jacobianc+jacobiand*prey)*deltat;//" " |
| EvaKrolis | 14:2c0bf576a0e7 | 319 | //Hier worden xend en yend doorgerekend, die formules kan je overslaan |
| EvaKrolis | 14:2c0bf576a0e7 | 320 | xendsum = lb + xbase +ll*(cos(theta1) - cos(theta4)); |
| EvaKrolis | 14:2c0bf576a0e7 | 321 | 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 | 322 | xendsqrt2 = sqrt(pow((-xbase/ll+cos(theta1)+cos(theta4)),2)+ pow(sin(theta1) - sin(theta4),2)); |
| EvaKrolis | 14:2c0bf576a0e7 | 323 | xend = (xendsum + xendsqrt1/xendsqrt2)/2; |
| EvaKrolis | 14:2c0bf576a0e7 | 324 | //hieronder rekenen we yendeffector door; |
| EvaKrolis | 14:2c0bf576a0e7 | 325 | yendsum = -le + ll/2*(sin(theta1)+sin(theta4)); |
| EvaKrolis | 14:2c0bf576a0e7 | 326 | 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 | 327 | yendsqrt2 = sqrt(pow((-xbase/ll + cos(theta1)+ cos(theta4)),2)+ pow((sin(theta1)-sin(theta4)),2)); |
| EvaKrolis | 14:2c0bf576a0e7 | 328 | yend = (yendsum + yendsqrt1/yendsqrt2); |
| EvaKrolis | 14:2c0bf576a0e7 | 329 | |
| EvaKrolis | 14:2c0bf576a0e7 | 330 | } |
| EvaKrolis | 14:2c0bf576a0e7 | 331 | |
| EvaKrolis | 14:2c0bf576a0e7 | 332 | // Function for the Jacobian |
| EvaKrolis | 14:2c0bf576a0e7 | 333 | void kinematics() |
| EvaKrolis | 14:2c0bf576a0e7 | 334 | { |
| EvaKrolis | 14:2c0bf576a0e7 | 335 | |
| EvaKrolis | 14:2c0bf576a0e7 | 336 | 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 | 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 | (-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 | 341 | sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2))) + |
| EvaKrolis | 14:2c0bf576a0e7 | 342 | ((-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 | 343 | (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 | 344 | (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 | 345 | (sin(theta1) - sin(theta4)))/sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2)) + |
| EvaKrolis | 14:2c0bf576a0e7 | 346 | (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 | 347 | sqrt(pow(-(xbase/ll) + cos(theta1) + cos(0.002 + theta4),2) + pow(sin(theta1) - sin(0.002 + theta4),2))) + |
| EvaKrolis | 14:2c0bf576a0e7 | 348 | 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 | 349 | (sin(theta1) - sin(theta4)))/sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2)) + |
| EvaKrolis | 14:2c0bf576a0e7 | 350 | (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 | 351 | sqrt(pow(-(xbase/ll) + cos(0.002 + theta1) + cos(theta4),2) + pow(sin(0.002 + theta1) - sin(theta4),2)))* |
| EvaKrolis | 14:2c0bf576a0e7 | 352 | (-(((-(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 | 353 | sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2))) - (ll*(sin(theta1) + sin(theta4)))/2. + |
| EvaKrolis | 14:2c0bf576a0e7 | 354 | ((-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 | 355 | (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 | 356 | |
| EvaKrolis | 14:2c0bf576a0e7 | 357 | 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 | 358 | (sin(theta1) - sin(theta4)))/sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2)) + |
| EvaKrolis | 14:2c0bf576a0e7 | 359 | (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 | 360 | sqrt(pow(-(xbase/ll) + cos(theta1) + cos(0.002 + theta4),2) + pow(sin(theta1) - sin(0.002 + theta4),2))))/ |
| EvaKrolis | 14:2c0bf576a0e7 | 361 | (-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 | 362 | sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2))) + |
| EvaKrolis | 14:2c0bf576a0e7 | 363 | ((-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 | 364 | (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 | 365 | (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 | 366 | (sin(theta1) - sin(theta4)))/sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2)) + |
| EvaKrolis | 14:2c0bf576a0e7 | 367 | (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 | 368 | sqrt(pow(-(xbase/ll) + cos(theta1) + cos(0.002 + theta4),2) + pow(sin(theta1) - sin(0.002 + theta4),2))) + |
| EvaKrolis | 14:2c0bf576a0e7 | 369 | 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 | 370 | (sin(theta1) - sin(theta4)))/sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2)) + |
| EvaKrolis | 14:2c0bf576a0e7 | 371 | (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 | 372 | sqrt(pow(-(xbase/ll) + cos(0.002 + theta1) + cos(theta4),2) + pow(sin(0.002 + theta1) - sin(theta4),2)))* |
| EvaKrolis | 14:2c0bf576a0e7 | 373 | (-(((-(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 | 374 | sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2))) - (ll*(sin(theta1) + sin(theta4)))/2. + |
| EvaKrolis | 14:2c0bf576a0e7 | 375 | ((-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 | 376 | (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 | 377 | |
| EvaKrolis | 14:2c0bf576a0e7 | 378 | 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 | 379 | sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2))) + |
| EvaKrolis | 14:2c0bf576a0e7 | 380 | ((-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 | 381 | (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 | 382 | (-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 | 383 | sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2))) + |
| EvaKrolis | 14:2c0bf576a0e7 | 384 | ((-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 | 385 | (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 | 386 | (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 | 387 | (sin(theta1) - sin(theta4)))/sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2)) + |
| EvaKrolis | 14:2c0bf576a0e7 | 388 | (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 | 389 | sqrt(pow(-(xbase/ll) + cos(theta1) + cos(0.002 + theta4),2) + pow(sin(theta1) - sin(0.002 + theta4),2))) + |
| EvaKrolis | 14:2c0bf576a0e7 | 390 | 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 | 391 | (sin(theta1) - sin(theta4)))/sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2)) + |
| EvaKrolis | 14:2c0bf576a0e7 | 392 | (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 | 393 | sqrt(pow(-(xbase/ll) + cos(0.002 + theta1) + cos(theta4),2) + pow(sin(0.002 + theta1) - sin(theta4),2)))* |
| EvaKrolis | 14:2c0bf576a0e7 | 394 | (-(((-(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 | 395 | sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2))) - (ll*(sin(theta1) + sin(theta4)))/2. + |
| EvaKrolis | 14:2c0bf576a0e7 | 396 | ((-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 | 397 | (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 | 398 | |
| EvaKrolis | 14:2c0bf576a0e7 | 399 | 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 | 400 | (sin(theta1) - sin(theta4)))/sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2)) + |
| EvaKrolis | 14:2c0bf576a0e7 | 401 | (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 | 402 | sqrt(pow(-(xbase/ll) + cos(0.002 + theta1) + cos(theta4),2) + pow(sin(0.002 + theta1) - sin(theta4),2))))/ |
| EvaKrolis | 14:2c0bf576a0e7 | 403 | (-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 | 404 | sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2))) + |
| EvaKrolis | 14:2c0bf576a0e7 | 405 | ((-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 | 406 | (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 | 407 | (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 | 408 | (sin(theta1) - sin(theta4)))/sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2)) + |
| EvaKrolis | 14:2c0bf576a0e7 | 409 | (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 | 410 | sqrt(pow(-(xbase/ll) + cos(theta1) + cos(0.002 + theta4),2) + pow(sin(theta1) - sin(0.002 + theta4),2))) + |
| EvaKrolis | 14:2c0bf576a0e7 | 411 | 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 | 412 | (sin(theta1) - sin(theta4)))/sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2)) + |
| EvaKrolis | 14:2c0bf576a0e7 | 413 | (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 | 414 | sqrt(pow(-(xbase/ll) + cos(0.002 + theta1) + cos(theta4),2) + pow(sin(0.002 + theta1) - sin(theta4),2)))* |
| EvaKrolis | 14:2c0bf576a0e7 | 415 | (-(((-(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 | 416 | sqrt(pow(-(xbase/ll) + cos(theta1) + cos(theta4),2) + pow(sin(theta1) - sin(theta4),2))) - (ll*(sin(theta1) + sin(theta4)))/2. + |
| EvaKrolis | 14:2c0bf576a0e7 | 417 | ((-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 | 418 | (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 | 419 | |
| EvaKrolis | 14:2c0bf576a0e7 | 420 | prefx = 1*xMove; //If the EMG is true, the x will move with 1 |
| EvaKrolis | 14:2c0bf576a0e7 | 421 | prefy = 1*yMove; //If the EMG is true, the y will move with 1 |
| EvaKrolis | 14:2c0bf576a0e7 | 422 | inverse(prefx, prefy); |
| EvaKrolis | 14:2c0bf576a0e7 | 423 | } |
| tverouden | 12:323ac4e27a0d | 424 | |
| efvanmarrewijk | 25:ac139331fe51 | 425 | // ============================ MOTOR FUNCTIONS =============================== |
| efvanmarrewijk | 25:ac139331fe51 | 426 | // angleDesired now defined as angle of potmeter and not the angle as output from the kinematics |
| efvanmarrewijk | 25:ac139331fe51 | 427 | // 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 | 428 | |
| efvanmarrewijk | 25:ac139331fe51 | 429 | // ------------------------ General motor functions ---------------------------- |
| efvanmarrewijk | 25:ac139331fe51 | 430 | int countsInputL() // Gets the counts from encoder 1 |
| efvanmarrewijk | 25:ac139331fe51 | 431 | { int countsL; |
| efvanmarrewijk | 25:ac139331fe51 | 432 | countsL = encoderL.getPulses(); |
| efvanmarrewijk | 25:ac139331fe51 | 433 | return countsL; |
| efvanmarrewijk | 25:ac139331fe51 | 434 | } |
| efvanmarrewijk | 25:ac139331fe51 | 435 | int countsInputR() // Gets the counts from encoder 2 |
| efvanmarrewijk | 25:ac139331fe51 | 436 | { int countsR; |
| efvanmarrewijk | 25:ac139331fe51 | 437 | countsR = encoderR.getPulses(); |
| efvanmarrewijk | 25:ac139331fe51 | 438 | return countsR; |
| efvanmarrewijk | 25:ac139331fe51 | 439 | } |
| efvanmarrewijk | 25:ac139331fe51 | 440 | int countsInputF() // Gets the counts from encoder 3 |
| efvanmarrewijk | 25:ac139331fe51 | 441 | { int countsF; |
| efvanmarrewijk | 25:ac139331fe51 | 442 | countsF = encoderF.getPulses(); |
| efvanmarrewijk | 25:ac139331fe51 | 443 | return countsF; |
| efvanmarrewijk | 25:ac139331fe51 | 444 | } |
| efvanmarrewijk | 25:ac139331fe51 | 445 | |
| efvanmarrewijk | 25:ac139331fe51 | 446 | 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 | 447 | { float angle = ((float)counts*2.0f*PI)/countsRad; |
| efvanmarrewijk | 25:ac139331fe51 | 448 | while (angle > 2.0f*PI) |
| efvanmarrewijk | 25:ac139331fe51 | 449 | { angle = angle-2.0f*PI; |
| efvanmarrewijk | 25:ac139331fe51 | 450 | } |
| efvanmarrewijk | 25:ac139331fe51 | 451 | while (angle < -2.0f*PI) |
| efvanmarrewijk | 25:ac139331fe51 | 452 | { angle = angle+2.0f*PI; |
| efvanmarrewijk | 25:ac139331fe51 | 453 | } |
| efvanmarrewijk | 25:ac139331fe51 | 454 | return angle; |
| efvanmarrewijk | 25:ac139331fe51 | 455 | } |
| efvanmarrewijk | 25:ac139331fe51 | 456 | |
| efvanmarrewijk | 25:ac139331fe51 | 457 | float errorCalc(float angleReference,float angleCurrent) // Calculates the error of the system, based on the current angle and the reference value |
| efvanmarrewijk | 25:ac139331fe51 | 458 | { float error = angleReference - angleCurrent; |
| efvanmarrewijk | 25:ac139331fe51 | 459 | return error; |
| efvanmarrewijk | 25:ac139331fe51 | 460 | } |
| efvanmarrewijk | 25:ac139331fe51 | 461 | |
| efvanmarrewijk | 25:ac139331fe51 | 462 | // ------------------------- MOTOR FUNCTIONS FOR MOTOR LEFT -------------------- |
| efvanmarrewijk | 25:ac139331fe51 | 463 | 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 | 464 | { float Kp = 19.24f; |
| efvanmarrewijk | 25:ac139331fe51 | 465 | float Ki = 1.02f; |
| efvanmarrewijk | 25:ac139331fe51 | 466 | float Kd = 0.827f; |
| efvanmarrewijk | 25:ac139331fe51 | 467 | float error = errorCalc(angleReference,angleCurrent); |
| efvanmarrewijk | 25:ac139331fe51 | 468 | static float errorIntegralL = 0.0; |
| efvanmarrewijk | 25:ac139331fe51 | 469 | static float errorPreviousL = error; // initialization with this value only done once! |
| efvanmarrewijk | 25:ac139331fe51 | 470 | static BiQuad PIDFilterL(0.0640, 0.1279, 0.0640, -1.1683, 0.4241); |
| efvanmarrewijk | 25:ac139331fe51 | 471 | // Proportional part: |
| efvanmarrewijk | 25:ac139331fe51 | 472 | float u_k = Kp * error; |
| efvanmarrewijk | 25:ac139331fe51 | 473 | // Integral part |
| efvanmarrewijk | 25:ac139331fe51 | 474 | errorIntegralL = errorIntegralL + error * dt; |
| efvanmarrewijk | 25:ac139331fe51 | 475 | float u_i = Ki * errorIntegralL; |
| efvanmarrewijk | 25:ac139331fe51 | 476 | // Derivative part |
| efvanmarrewijk | 25:ac139331fe51 | 477 | float errorDerivative = (error - errorPreviousL)/dt; |
| efvanmarrewijk | 25:ac139331fe51 | 478 | float errorDerivativeFiltered = PIDFilterL.step(errorDerivative); |
| efvanmarrewijk | 25:ac139331fe51 | 479 | float u_d = Kd * errorDerivativeFiltered; |
| efvanmarrewijk | 25:ac139331fe51 | 480 | errorPreviousL = error; |
| efvanmarrewijk | 25:ac139331fe51 | 481 | // Sum all parts and return it |
| efvanmarrewijk | 25:ac139331fe51 | 482 | return u_k + u_i + u_d; |
| efvanmarrewijk | 25:ac139331fe51 | 483 | } |
| efvanmarrewijk | 25:ac139331fe51 | 484 | |
| efvanmarrewijk | 25:ac139331fe51 | 485 | float angleDesiredL() // Sets the desired angle for the controller dependent on the scaled angle of potmeter 1 |
| efvanmarrewijk | 25:ac139331fe51 | 486 | { float angle = (pot1*2.0f*PI)-PI; |
| efvanmarrewijk | 25:ac139331fe51 | 487 | return angle; |
| efvanmarrewijk | 25:ac139331fe51 | 488 | } |
| efvanmarrewijk | 25:ac139331fe51 | 489 | |
| efvanmarrewijk | 25:ac139331fe51 | 490 | float countsCalibrCalcL(int countsOffsetL) |
| efvanmarrewijk | 25:ac139331fe51 | 491 | { |
| efvanmarrewijk | 25:ac139331fe51 | 492 | countsCalibratedL = countsL - countsOffsetL + countsCalibration; |
| efvanmarrewijk | 25:ac139331fe51 | 493 | return countsCalibratedL; |
| efvanmarrewijk | 25:ac139331fe51 | 494 | } |
| EvaKrolis | 13:4ba8f63e6ff4 | 495 | |
| efvanmarrewijk | 25:ac139331fe51 | 496 | void calibrationL() // Partially the same as motorTurnL, only with potmeter input |
| efvanmarrewijk | 25:ac139331fe51 | 497 | // How it works: manually turn motor using potmeters until the robot arm touches the bookholder. |
| efvanmarrewijk | 25:ac139331fe51 | 498 | // This program sets the counts from the motor to the reference counts (an angle of PI/4.0) |
| efvanmarrewijk | 25:ac139331fe51 | 499 | // Do this for every motor and after calibrated all motors, press a button |
| efvanmarrewijk | 25:ac139331fe51 | 500 | { float angleReferenceL = angleDesiredL(); // insert kinematics output here instead of angleDesiredL() |
| efvanmarrewijk | 25:ac139331fe51 | 501 | angleReferenceL = -angleReferenceL; // different minus sign per motor |
| efvanmarrewijk | 25:ac139331fe51 | 502 | angleCurrentL = angleCurrent(countsL); // different minus sign per motor |
| efvanmarrewijk | 25:ac139331fe51 | 503 | errorL = errorCalc(angleReferenceL,angleCurrentL); // same for every motor |
| efvanmarrewijk | 25:ac139331fe51 | 504 | |
| efvanmarrewijk | 25:ac139331fe51 | 505 | if (fabs(errorL) >= 0.01f) |
| efvanmarrewijk | 25:ac139331fe51 | 506 | { float PIDControlL = PIDControllerL(angleReferenceL,angleCurrentL); // same for every motor |
| efvanmarrewijk | 25:ac139331fe51 | 507 | pin6 = fabs(PIDControlL); // different pins for every motor |
| efvanmarrewijk | 25:ac139331fe51 | 508 | pin7 = PIDControlL > 0.0f; // different pins for every motor |
| efvanmarrewijk | 25:ac139331fe51 | 509 | } |
| efvanmarrewijk | 25:ac139331fe51 | 510 | else if (fabs(errorL) < 0.01f) |
| efvanmarrewijk | 25:ac139331fe51 | 511 | { int countsOffsetL = countsL; |
| efvanmarrewijk | 25:ac139331fe51 | 512 | countsCalibrCalcL(countsOffsetL); |
| efvanmarrewijk | 25:ac139331fe51 | 513 | pin6 = 0.0f; |
| efvanmarrewijk | 25:ac139331fe51 | 514 | // BUTTON PRESS: TO NEXT STATE |
| efvanmarrewijk | 25:ac139331fe51 | 515 | } |
| efvanmarrewijk | 25:ac139331fe51 | 516 | } |
| efvanmarrewijk | 25:ac139331fe51 | 517 | |
| efvanmarrewijk | 25:ac139331fe51 | 518 | void motorTurnL() // main function for movement of motor 1, all above functions with an extra tab are called |
| efvanmarrewijk | 25:ac139331fe51 | 519 | { |
| efvanmarrewijk | 25:ac139331fe51 | 520 | float angleReferenceL = angleDesiredL(); // insert kinematics output here instead of angleDesiredL() |
| efvanmarrewijk | 25:ac139331fe51 | 521 | angleReferenceL = -angleReferenceL; // different minus sign per motor |
| efvanmarrewijk | 25:ac139331fe51 | 522 | int countsL = countsInputL(); // different encoder pins per motor |
| efvanmarrewijk | 25:ac139331fe51 | 523 | angleCurrentL = angleCurrent(countsCalibratedL); // different minus sign per motor |
| efvanmarrewijk | 25:ac139331fe51 | 524 | errorCalibratedL = errorCalc(angleReferenceL,angleCurrentL); // same for every motor |
| efvanmarrewijk | 25:ac139331fe51 | 525 | |
| efvanmarrewijk | 25:ac139331fe51 | 526 | float PIDControlL = PIDControllerL(angleReferenceL,angleCurrentL); // same for every motor |
| efvanmarrewijk | 25:ac139331fe51 | 527 | pin6 = fabs(PIDControlL); // different pins for every motor |
| efvanmarrewijk | 25:ac139331fe51 | 528 | pin7 = PIDControlL > 0.0f; // different pins for every motor |
| efvanmarrewijk | 25:ac139331fe51 | 529 | } |
| efvanmarrewijk | 25:ac139331fe51 | 530 | |
| efvanmarrewijk | 25:ac139331fe51 | 531 | // ------------------------ MOTOR FUNCTIONS FOR MOTOR RIGHT -------------------- |
| efvanmarrewijk | 25:ac139331fe51 | 532 | 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 | 533 | { float Kp = 19.24f; |
| efvanmarrewijk | 25:ac139331fe51 | 534 | float Ki = 1.02f; |
| efvanmarrewijk | 25:ac139331fe51 | 535 | float Kd = 0.827f; |
| efvanmarrewijk | 25:ac139331fe51 | 536 | float error = errorCalc(angleReference,angleCurrent); |
| efvanmarrewijk | 25:ac139331fe51 | 537 | static float errorIntegralR = 0.0; |
| efvanmarrewijk | 25:ac139331fe51 | 538 | static float errorPreviousR = error; // initialization with this value only done once! |
| efvanmarrewijk | 25:ac139331fe51 | 539 | static BiQuad PIDFilterR(0.0640, 0.1279, 0.0640, -1.1683, 0.4241); |
| efvanmarrewijk | 25:ac139331fe51 | 540 | // Proportional part: |
| efvanmarrewijk | 25:ac139331fe51 | 541 | float u_k = Kp * error; |
| efvanmarrewijk | 25:ac139331fe51 | 542 | // Integral part |
| efvanmarrewijk | 25:ac139331fe51 | 543 | errorIntegralR = errorIntegralR + error * dt; |
| efvanmarrewijk | 25:ac139331fe51 | 544 | float u_i = Ki * errorIntegralR; |
| efvanmarrewijk | 25:ac139331fe51 | 545 | // Derivative part |
| efvanmarrewijk | 25:ac139331fe51 | 546 | float errorDerivative = (error - errorPreviousR)/dt; |
| efvanmarrewijk | 25:ac139331fe51 | 547 | float errorDerivativeFiltered = PIDFilterR.step(errorDerivative); |
| efvanmarrewijk | 25:ac139331fe51 | 548 | float u_d = Kd * errorDerivativeFiltered; |
| efvanmarrewijk | 25:ac139331fe51 | 549 | errorPreviousR = error; |
| efvanmarrewijk | 25:ac139331fe51 | 550 | // Sum all parts and return it |
| efvanmarrewijk | 25:ac139331fe51 | 551 | return u_k + u_i + u_d; |
| efvanmarrewijk | 25:ac139331fe51 | 552 | } |
| efvanmarrewijk | 25:ac139331fe51 | 553 | |
| efvanmarrewijk | 25:ac139331fe51 | 554 | float angleDesiredR() // Sets the desired angle for the controller dependent on the scaled angle of potmeter 1 |
| efvanmarrewijk | 25:ac139331fe51 | 555 | { float angle = (pot1*2.0f*PI)-PI; |
| efvanmarrewijk | 25:ac139331fe51 | 556 | return angle; |
| efvanmarrewijk | 25:ac139331fe51 | 557 | } |
| efvanmarrewijk | 25:ac139331fe51 | 558 | |
| efvanmarrewijk | 25:ac139331fe51 | 559 | float countsCalibrCalcR(int countsOffsetR) |
| efvanmarrewijk | 25:ac139331fe51 | 560 | { |
| efvanmarrewijk | 25:ac139331fe51 | 561 | countsCalibratedR = countsR - countsOffsetR + countsCalibration; |
| efvanmarrewijk | 25:ac139331fe51 | 562 | return countsCalibratedR; |
| efvanmarrewijk | 25:ac139331fe51 | 563 | } |
| efvanmarrewijk | 25:ac139331fe51 | 564 | |
| efvanmarrewijk | 25:ac139331fe51 | 565 | void calibrationR() // Partially the same as motorTurnR, only with potmeter input |
| efvanmarrewijk | 25:ac139331fe51 | 566 | // How it works: manually turn motor using potmeters until the robot arm touches the bookholder. |
| efvanmarrewijk | 25:ac139331fe51 | 567 | // This program sets the counts from the motor to the reference counts (an angle of PI/4.0) |
| efvanmarrewijk | 25:ac139331fe51 | 568 | // Do this for every motor and after calibrated all motors, press a button |
| efvanmarrewijk | 25:ac139331fe51 | 569 | { float angleReferenceR = angleDesiredR(); // insert kinematics output here instead of angleDesiredR() |
| efvanmarrewijk | 25:ac139331fe51 | 570 | angleReferenceR = -angleReferenceR; // different minus sign per motor |
| efvanmarrewijk | 25:ac139331fe51 | 571 | angleCurrentR = angleCurrent(countsR); // different minus sign per motor |
| efvanmarrewijk | 25:ac139331fe51 | 572 | errorR = errorCalc(angleReferenceR,angleCurrentR); // same for every motor |
| efvanmarrewijk | 25:ac139331fe51 | 573 | |
| efvanmarrewijk | 25:ac139331fe51 | 574 | if (fabs(errorR) >= 0.01f) |
| efvanmarrewijk | 25:ac139331fe51 | 575 | { float PIDControlR = PIDControllerR(angleReferenceR,angleCurrentR); // same for every motor |
| efvanmarrewijk | 25:ac139331fe51 | 576 | pin6 = fabs(PIDControlR); // different pins for every motor |
| efvanmarrewijk | 25:ac139331fe51 | 577 | pin7 = PIDControlR > 0.0f; // different pins for every motor |
| efvanmarrewijk | 25:ac139331fe51 | 578 | } |
| efvanmarrewijk | 25:ac139331fe51 | 579 | else if (fabs(errorR) < 0.01f) |
| efvanmarrewijk | 25:ac139331fe51 | 580 | { int countsOffsetR = countsR; |
| efvanmarrewijk | 25:ac139331fe51 | 581 | countsCalibrCalcR(countsOffsetR); |
| efvanmarrewijk | 25:ac139331fe51 | 582 | pin6 = 0.0f; |
| efvanmarrewijk | 25:ac139331fe51 | 583 | // BUTTON PRESS: NAAR VOLGENDE STATE |
| efvanmarrewijk | 25:ac139331fe51 | 584 | } |
| efvanmarrewijk | 25:ac139331fe51 | 585 | } |
| efvanmarrewijk | 25:ac139331fe51 | 586 | |
| efvanmarrewijk | 25:ac139331fe51 | 587 | void motorTurnR() // main function for movement of motor 1, all above functions with an extra tab are called |
| efvanmarrewijk | 25:ac139331fe51 | 588 | { |
| efvanmarrewijk | 25:ac139331fe51 | 589 | float angleReferenceR = angleDesiredR(); // insert kinematics output here instead of angleDesiredR() |
| efvanmarrewijk | 25:ac139331fe51 | 590 | angleReferenceR = -angleReferenceR; // different minus sign per motor |
| efvanmarrewijk | 25:ac139331fe51 | 591 | int countsR = countsInputR(); // different encoder pins per motor |
| efvanmarrewijk | 25:ac139331fe51 | 592 | angleCurrentR = angleCurrent(countsCalibratedR); // different minus sign per motor |
| efvanmarrewijk | 25:ac139331fe51 | 593 | errorCalibratedR = errorCalc(angleReferenceR,angleCurrentR); // same for every motor |
| efvanmarrewijk | 25:ac139331fe51 | 594 | |
| efvanmarrewijk | 25:ac139331fe51 | 595 | float PIDControlR = PIDControllerR(angleReferenceR,angleCurrentR); // same for every motor |
| efvanmarrewijk | 25:ac139331fe51 | 596 | pin6 = fabs(PIDControlR); // different pins for every motor |
| efvanmarrewijk | 25:ac139331fe51 | 597 | pin7 = PIDControlR > 0.0f; // different pins for every motor |
| efvanmarrewijk | 25:ac139331fe51 | 598 | } |
| efvanmarrewijk | 25:ac139331fe51 | 599 | |
| efvanmarrewijk | 25:ac139331fe51 | 600 | // ------------------------- MOTOR FUNCTIONS FOR MOTOR FLIP -------------------- |
| efvanmarrewijk | 35:3c937770aa41 | 601 | float PIDControllerF(float angleReference,float angleCurrent) // PID controller for the motors, based on the reference value and the current angle of the motor |
| efvanmarrewijk | 35:3c937770aa41 | 602 | { float Kp = 19.24f; |
| efvanmarrewijk | 35:3c937770aa41 | 603 | float Ki = 1.02f; |
| efvanmarrewijk | 35:3c937770aa41 | 604 | float Kd = 0.827f; |
| efvanmarrewijk | 35:3c937770aa41 | 605 | float error = errorCalc(angleReference,angleCurrent); |
| efvanmarrewijk | 35:3c937770aa41 | 606 | static float errorIntegralF = 0.0; |
| efvanmarrewijk | 35:3c937770aa41 | 607 | static float errorPreviousF = error; // initialization with this value only done once! |
| efvanmarrewijk | 35:3c937770aa41 | 608 | static BiQuad PIDFilterF(0.0640, 0.1279, 0.0640, -1.1683, 0.4241); |
| efvanmarrewijk | 35:3c937770aa41 | 609 | // Proportional part: |
| efvanmarrewijk | 35:3c937770aa41 | 610 | float u_k = Kp * error; |
| efvanmarrewijk | 35:3c937770aa41 | 611 | // Integral part |
| efvanmarrewijk | 35:3c937770aa41 | 612 | errorIntegralF = errorIntegralF + error * dt; |
| efvanmarrewijk | 35:3c937770aa41 | 613 | float u_i = Ki * errorIntegralF; |
| efvanmarrewijk | 35:3c937770aa41 | 614 | // Derivative part |
| efvanmarrewijk | 35:3c937770aa41 | 615 | float errorDerivative = (error - errorPreviousF)/dt; |
| efvanmarrewijk | 35:3c937770aa41 | 616 | float errorDerivativeFiltered = PIDFilterF.step(errorDerivative); |
| efvanmarrewijk | 35:3c937770aa41 | 617 | float u_d = Kd * errorDerivativeFiltered; |
| efvanmarrewijk | 35:3c937770aa41 | 618 | errorPreviousF = error; |
| efvanmarrewijk | 35:3c937770aa41 | 619 | // Sum all parts and return it |
| efvanmarrewijk | 35:3c937770aa41 | 620 | return u_k + u_i + u_d; |
| efvanmarrewijk | 35:3c937770aa41 | 621 | } |
| efvanmarrewijk | 35:3c937770aa41 | 622 | |
| efvanmarrewijk | 35:3c937770aa41 | 623 | float angleDesiredF() // Sets the desired angle for the controller dependent on the scaled angle of potmeter 1 |
| efvanmarrewijk | 35:3c937770aa41 | 624 | { float angle = (pot1*2.0f*PI)-PI; |
| efvanmarrewijk | 35:3c937770aa41 | 625 | return angle; |
| efvanmarrewijk | 35:3c937770aa41 | 626 | } |
| efvanmarrewijk | 35:3c937770aa41 | 627 | |
| efvanmarrewijk | 35:3c937770aa41 | 628 | float countsCalibrCalcF(int countsOffsetF) |
| efvanmarrewijk | 35:3c937770aa41 | 629 | { |
| efvanmarrewijk | 35:3c937770aa41 | 630 | countsCalibratedF = countsF - countsOffsetF + countsCalibration; |
| efvanmarrewijk | 35:3c937770aa41 | 631 | return countsCalibratedF; |
| efvanmarrewijk | 35:3c937770aa41 | 632 | } |
| efvanmarrewijk | 35:3c937770aa41 | 633 | |
| efvanmarrewijk | 35:3c937770aa41 | 634 | void calibrationF() // Partially the same as motorTurnF, only with potmeter input |
| efvanmarrewijk | 35:3c937770aa41 | 635 | // How it works: manually turn motor using potmeters until the robot arm touches the bookholder. |
| efvanmarrewijk | 35:3c937770aa41 | 636 | // This program sets the counts from the motor to the reference counts (an angle of PI/4.0) |
| efvanmarrewijk | 35:3c937770aa41 | 637 | // Do this for every motor and after calibrated all motors, press a button |
| efvanmarrewijk | 35:3c937770aa41 | 638 | { float angleReferenceF = angleDesiredF(); // insert kinematics output here instead of angleDesiredF() |
| efvanmarrewijk | 35:3c937770aa41 | 639 | angleReferenceF = -angleReferenceF; // different minus sign per motor |
| efvanmarrewijk | 35:3c937770aa41 | 640 | angleCurrentF = angleCurrent(countsF); // different minus sign per motor |
| efvanmarrewijk | 35:3c937770aa41 | 641 | errorF = errorCalc(angleReferenceF,angleCurrentF); // same for every motor |
| efvanmarrewijk | 35:3c937770aa41 | 642 | |
| efvanmarrewijk | 35:3c937770aa41 | 643 | if (fabs(errorF) >= 0.01f) |
| efvanmarrewijk | 35:3c937770aa41 | 644 | { float PIDControlF = PIDControllerF(angleReferenceF,angleCurrentF); // same for every motor |
| efvanmarrewijk | 35:3c937770aa41 | 645 | pin6 = fabs(PIDControlF); // different pins for every motor |
| efvanmarrewijk | 35:3c937770aa41 | 646 | pin7 = PIDControlF > 0.0f; // different pins for every motor |
| efvanmarrewijk | 35:3c937770aa41 | 647 | } |
| efvanmarrewijk | 35:3c937770aa41 | 648 | else if (fabs(errorF) < 0.01f) |
| efvanmarrewijk | 35:3c937770aa41 | 649 | { int countsOffsetF = countsF; |
| efvanmarrewijk | 35:3c937770aa41 | 650 | countsCalibrCalcF(countsOffsetF); |
| efvanmarrewijk | 35:3c937770aa41 | 651 | pin6 = 0.0f; |
| efvanmarrewijk | 35:3c937770aa41 | 652 | // BUTTON PRESS: TO NEXT STATE |
| efvanmarrewijk | 35:3c937770aa41 | 653 | } |
| efvanmarrewijk | 35:3c937770aa41 | 654 | } |
| efvanmarrewijk | 35:3c937770aa41 | 655 | |
| efvanmarrewijk | 35:3c937770aa41 | 656 | void motorTurnF() // main function for movement of motor 1, all above functions with an extra tab are called |
| efvanmarrewijk | 35:3c937770aa41 | 657 | { |
| efvanmarrewijk | 35:3c937770aa41 | 658 | float angleReferenceF = angleDesiredF(); // insert kinematics output here instead of angleDesiredF() |
| efvanmarrewijk | 35:3c937770aa41 | 659 | angleReferenceF = -angleReferenceF; // different minus sign per motor |
| efvanmarrewijk | 35:3c937770aa41 | 660 | int countsF = countsInputF(); // different encoder pins per motor |
| efvanmarrewijk | 35:3c937770aa41 | 661 | angleCurrentF = angleCurrent(countsCalibratedF); // different minus sign per motor |
| efvanmarrewijk | 35:3c937770aa41 | 662 | errorCalibratedF = errorCalc(angleReferenceF,angleCurrentF); // same for every motor |
| efvanmarrewijk | 35:3c937770aa41 | 663 | |
| efvanmarrewijk | 35:3c937770aa41 | 664 | float PIDControlF = PIDControllerF(angleReferenceF,angleCurrentF); // same for every motor |
| efvanmarrewijk | 35:3c937770aa41 | 665 | pin6 = fabs(PIDControlF); // different pins for every motor |
| efvanmarrewijk | 35:3c937770aa41 | 666 | pin7 = PIDControlF > 0.0f; // different pins for every motor |
| efvanmarrewijk | 35:3c937770aa41 | 667 | } |
| EvaKrolis | 13:4ba8f63e6ff4 | 668 | |
| tverouden | 2:d70795e4e0bf | 669 | // ≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡ STATE MACHINE ≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡ |
| tverouden | 15:6566c5dedeeb | 670 | void stateMachine(void) |
| tverouden | 3:9c63fc5f157e | 671 | { |
| tverouden | 24:0abc564349e1 | 672 | switch (currentState) { // determine which state Odin is in |
| tverouden | 3:9c63fc5f157e | 673 | |
| tverouden | 4:5ce2c8864908 | 674 | // ========================= MOTOR CALIBRATION MODE ========================== |
| tverouden | 4:5ce2c8864908 | 675 | case calibratingMotors: |
| tverouden | 4:5ce2c8864908 | 676 | // ------------------------- initialisation -------------------------- |
| tverouden | 4:5ce2c8864908 | 677 | if (changeState) { // when entering the state |
| tverouden | 15:6566c5dedeeb | 678 | pc.printf("[MODE] calibrating motors...\r\n"); |
| tverouden | 5:04b26b2f536a | 679 | // print current state |
| tverouden | 4:5ce2c8864908 | 680 | changeState = false; // stay in this state |
| tverouden | 4:5ce2c8864908 | 681 | |
| tverouden | 4:5ce2c8864908 | 682 | // Actions when entering state |
| tverouden | 15:6566c5dedeeb | 683 | ledRed = 1; // cyan-green blinking LED |
| tverouden | 15:6566c5dedeeb | 684 | ledGreen = 0; |
| tverouden | 15:6566c5dedeeb | 685 | ledBlue = 0; |
| tverouden | 15:6566c5dedeeb | 686 | blinkTimer.attach(&blinkLedBlue,0.5); |
| tverouden | 4:5ce2c8864908 | 687 | |
| tverouden | 4:5ce2c8864908 | 688 | } |
| tverouden | 4:5ce2c8864908 | 689 | // ----------------------------- action ------------------------------ |
| tverouden | 5:04b26b2f536a | 690 | // Actions for each loop iteration |
| tverouden | 5:04b26b2f536a | 691 | /* */ |
| tverouden | 4:5ce2c8864908 | 692 | |
| tverouden | 4:5ce2c8864908 | 693 | // --------------------------- transition ---------------------------- |
| tverouden | 24:0abc564349e1 | 694 | // Transition condition: when all motor errors smaller than 0.01, |
| tverouden | 24:0abc564349e1 | 695 | // start calibrating EMG |
| tverouden | 23:e282bdb9e9b7 | 696 | if (errorMotorL < 0.01 && errorMotorR < 0.01 |
| tverouden | 24:0abc564349e1 | 697 | && errorMotorF < 0.01 && buttonHome == false) { |
| tverouden | 24:0abc564349e1 | 698 | |
| tverouden | 23:e282bdb9e9b7 | 699 | // Actions when leaving state |
| tverouden | 23:e282bdb9e9b7 | 700 | blinkTimer.detach(); |
| tverouden | 23:e282bdb9e9b7 | 701 | |
| tverouden | 23:e282bdb9e9b7 | 702 | currentState = calibratingEMG; // change to state |
| tverouden | 23:e282bdb9e9b7 | 703 | changeState = true; // next loop, switch states |
| tverouden | 23:e282bdb9e9b7 | 704 | } |
| tverouden | 5:04b26b2f536a | 705 | |
| tverouden | 4:5ce2c8864908 | 706 | break; // end case |
| tverouden | 4:5ce2c8864908 | 707 | |
| tverouden | 7:ef5966469621 | 708 | // =========================== EMG CALIBRATION MODE =========================== |
| tverouden | 7:ef5966469621 | 709 | case calibratingEMG: |
| tverouden | 4:5ce2c8864908 | 710 | // ------------------------- initialisation -------------------------- |
| tverouden | 3:9c63fc5f157e | 711 | if (changeState) { // when entering the state |
| tverouden | 21:fbd900a55877 | 712 | pc.printf("[MODE] calibrating EMG...\r\n"); |
| tverouden | 5:04b26b2f536a | 713 | // print current state |
| tverouden | 4:5ce2c8864908 | 714 | changeState = false; // stay in this state |
| tverouden | 4:5ce2c8864908 | 715 | |
| tverouden | 4:5ce2c8864908 | 716 | // Actions when entering state |
| tverouden | 15:6566c5dedeeb | 717 | ledRed = 1; // cyan-blue blinking LED |
| tverouden | 15:6566c5dedeeb | 718 | ledGreen = 0; |
| tverouden | 15:6566c5dedeeb | 719 | ledBlue = 0; |
| tverouden | 15:6566c5dedeeb | 720 | blinkTimer.attach(&blinkLedGreen,0.5); |
| tverouden | 15:6566c5dedeeb | 721 | |
| tverouden | 4:5ce2c8864908 | 722 | |
| tverouden | 4:5ce2c8864908 | 723 | } |
| tverouden | 4:5ce2c8864908 | 724 | // ----------------------------- action ------------------------------ |
| tverouden | 5:04b26b2f536a | 725 | // Actions for each loop iteration |
| tverouden | 5:04b26b2f536a | 726 | /* */ |
| tverouden | 4:5ce2c8864908 | 727 | |
| tverouden | 4:5ce2c8864908 | 728 | // --------------------------- transition ---------------------------- |
| tverouden | 24:0abc564349e1 | 729 | // Transition condition: after 20 sec in state |
| tverouden | 24:0abc564349e1 | 730 | if (1) { // CONDITION -> Eva, hoe moet ik de 20 seconden regelen? |
| tverouden | 4:5ce2c8864908 | 731 | // Actions when leaving state |
| tverouden | 15:6566c5dedeeb | 732 | blinkTimer.detach(); |
| tverouden | 5:04b26b2f536a | 733 | |
| tverouden | 4:5ce2c8864908 | 734 | currentState = homing; // change to state |
| tverouden | 4:5ce2c8864908 | 735 | changeState = true; // next loop, switch states |
| tverouden | 5:04b26b2f536a | 736 | } |
| tverouden | 5:04b26b2f536a | 737 | break; // end case |
| tverouden | 4:5ce2c8864908 | 738 | |
| tverouden | 4:5ce2c8864908 | 739 | // ============================== HOMING MODE ================================ |
| tverouden | 4:5ce2c8864908 | 740 | case homing: |
| tverouden | 24:0abc564349e1 | 741 | // ------------------------- initialisation -------------------------- |
| tverouden | 4:5ce2c8864908 | 742 | if (changeState) { // when entering the state |
| tverouden | 4:5ce2c8864908 | 743 | pc.printf("[MODE] homing...\r\n"); |
| tverouden | 5:04b26b2f536a | 744 | // print current state |
| tverouden | 4:5ce2c8864908 | 745 | changeState = false; // stay in this state |
| tverouden | 4:5ce2c8864908 | 746 | |
| tverouden | 4:5ce2c8864908 | 747 | |
| tverouden | 4:5ce2c8864908 | 748 | // Actions when entering state |
| tverouden | 15:6566c5dedeeb | 749 | ledRed = 1; // cyan LED on |
| tverouden | 15:6566c5dedeeb | 750 | ledGreen = 0; |
| tverouden | 15:6566c5dedeeb | 751 | ledBlue = 0; |
| tverouden | 4:5ce2c8864908 | 752 | |
| tverouden | 4:5ce2c8864908 | 753 | } |
| tverouden | 4:5ce2c8864908 | 754 | // ----------------------------- action ------------------------------ |
| tverouden | 5:04b26b2f536a | 755 | // Actions for each loop iteration |
| tverouden | 5:04b26b2f536a | 756 | /* */ |
| tverouden | 4:5ce2c8864908 | 757 | |
| tverouden | 24:0abc564349e1 | 758 | // --------------------------- transition ---------------------------- |
| tverouden | 24:0abc564349e1 | 759 | // Transition condition #1: with button press, enter demo mode, |
| tverouden | 24:0abc564349e1 | 760 | // but only when velocity == 0 |
| tverouden | 24:0abc564349e1 | 761 | if (errorMotorL < 0.01 && errorMotorR < 0.01 |
| tverouden | 24:0abc564349e1 | 762 | && errorMotorF < 0.01 && buttonBio1 == true) { |
| tverouden | 24:0abc564349e1 | 763 | // Actions when leaving state |
| tverouden | 24:0abc564349e1 | 764 | /* */ |
| tverouden | 24:0abc564349e1 | 765 | |
| tverouden | 24:0abc564349e1 | 766 | currentState = reading; // change to state |
| tverouden | 24:0abc564349e1 | 767 | changeState = true; // next loop, switch states |
| tverouden | 24:0abc564349e1 | 768 | } |
| tverouden | 24:0abc564349e1 | 769 | // Transition condition #2: with button press, enter operation mode |
| tverouden | 24:0abc564349e1 | 770 | // but only when velocity == 0 |
| tverouden | 24:0abc564349e1 | 771 | if (errorMotorL < 0.01 && errorMotorR < 0.01 |
| tverouden | 24:0abc564349e1 | 772 | && errorMotorF < 0.01 && buttonBio2 == true) { |
| tverouden | 4:5ce2c8864908 | 773 | // Actions when leaving state |
| tverouden | 4:5ce2c8864908 | 774 | /* */ |
| tverouden | 5:04b26b2f536a | 775 | |
| tverouden | 4:5ce2c8864908 | 776 | currentState = demoing; // change to state |
| tverouden | 4:5ce2c8864908 | 777 | changeState = true; // next loop, switch states |
| tverouden | 4:5ce2c8864908 | 778 | } |
| tverouden | 4:5ce2c8864908 | 779 | break; // end case |
| tverouden | 4:5ce2c8864908 | 780 | |
| tverouden | 24:0abc564349e1 | 781 | // ============================== READING MODE =============================== |
| tverouden | 17:b04e1938491a | 782 | case reading: |
| tverouden | 17:b04e1938491a | 783 | // ------------------------- initialisation -------------------------- |
| tverouden | 17:b04e1938491a | 784 | if (changeState) { // when entering the state |
| tverouden | 17:b04e1938491a | 785 | pc.printf("[MODE] reading...\r\n"); |
| tverouden | 17:b04e1938491a | 786 | // print current state |
| tverouden | 17:b04e1938491a | 787 | changeState = false; // stay in this state |
| tverouden | 17:b04e1938491a | 788 | |
| tverouden | 17:b04e1938491a | 789 | // Actions when entering state |
| tverouden | 17:b04e1938491a | 790 | ledRed = 1; // blue LED on |
| tverouden | 17:b04e1938491a | 791 | ledGreen = 1; |
| tverouden | 17:b04e1938491a | 792 | ledBlue = 0; |
| tverouden | 24:0abc564349e1 | 793 | |
| tverouden | 24:0abc564349e1 | 794 | // TERUGKLAPPEN |
| tverouden | 17:b04e1938491a | 795 | |
| tverouden | 17:b04e1938491a | 796 | } |
| tverouden | 17:b04e1938491a | 797 | // ----------------------------- action ------------------------------ |
| tverouden | 17:b04e1938491a | 798 | // Actions for each loop iteration |
| tverouden | 17:b04e1938491a | 799 | /* */ |
| tverouden | 17:b04e1938491a | 800 | |
| tverouden | 17:b04e1938491a | 801 | // --------------------------- transition ---------------------------- |
| tverouden | 24:0abc564349e1 | 802 | // Transition condition #1: when EMG signal detected, enter reading |
| tverouden | 24:0abc564349e1 | 803 | // mode |
| tverouden | 24:0abc564349e1 | 804 | if (moving_average(EMG1 > threshold_value || // Namen variabelen? |
| tverouden | 24:0abc564349e1 | 805 | moving_average(EMG2 > threshold_value) { |
| tverouden | 24:0abc564349e1 | 806 | // Actions when leaving state |
| tverouden | 24:0abc564349e1 | 807 | /* */ |
| tverouden | 24:0abc564349e1 | 808 | |
| tverouden | 24:0abc564349e1 | 809 | currentState = reading; // change to state |
| tverouden | 24:0abc564349e1 | 810 | changeState = true; // next loop, switch states |
| tverouden | 24:0abc564349e1 | 811 | } |
| tverouden | 24:0abc564349e1 | 812 | // Transition condition #2: with button press, back to homing mode |
| tverouden | 24:0abc564349e1 | 813 | if (buttonHome == false) { |
| tverouden | 24:0abc564349e1 | 814 | // Actions when leaving state |
| tverouden | 17:b04e1938491a | 815 | /* */ |
| tverouden | 17:b04e1938491a | 816 | |
| tverouden | 17:b04e1938491a | 817 | currentState = homing; // change to state |
| tverouden | 17:b04e1938491a | 818 | changeState = true; // next loop, switch states |
| tverouden | 17:b04e1938491a | 819 | } |
| tverouden | 17:b04e1938491a | 820 | break; // end case |
| tverouden | 17:b04e1938491a | 821 | |
| tverouden | 4:5ce2c8864908 | 822 | // ============================= OPERATING MODE ============================== |
| tverouden | 4:5ce2c8864908 | 823 | case operating: |
| tverouden | 4:5ce2c8864908 | 824 | // ------------------------- initialisation -------------------------- |
| tverouden | 4:5ce2c8864908 | 825 | if (changeState) { // when entering the state |
| tverouden | 4:5ce2c8864908 | 826 | pc.printf("[MODE] operating...\r\n"); |
| tverouden | 5:04b26b2f536a | 827 | // print current state |
| tverouden | 5:04b26b2f536a | 828 | changeState = false; // stay in this state |
| tverouden | 5:04b26b2f536a | 829 | |
| tverouden | 5:04b26b2f536a | 830 | // Actions when entering state |
| tverouden | 15:6566c5dedeeb | 831 | ledRed = 1; // blue fast blinking LED |
| tverouden | 15:6566c5dedeeb | 832 | ledGreen = 1; |
| tverouden | 15:6566c5dedeeb | 833 | ledBlue = 1; |
| tverouden | 15:6566c5dedeeb | 834 | blinkTimer.attach(&blinkLedBlue,0.25); |
| tverouden | 5:04b26b2f536a | 835 | |
| tverouden | 5:04b26b2f536a | 836 | } |
| tverouden | 5:04b26b2f536a | 837 | // ----------------------------- action ------------------------------ |
| tverouden | 5:04b26b2f536a | 838 | // Actions for each loop iteration |
| tverouden | 5:04b26b2f536a | 839 | /* */ |
| tverouden | 5:04b26b2f536a | 840 | |
| tverouden | 5:04b26b2f536a | 841 | // --------------------------- transition ---------------------------- |
| tverouden | 24:0abc564349e1 | 842 | // Transition condition: when path is over, back to reading mode |
| tverouden | 24:0abc564349e1 | 843 | if (errorMotorL < 0.01 && errorMotorR < 0.01) { |
| tverouden | 5:04b26b2f536a | 844 | // Actions when leaving state |
| tverouden | 15:6566c5dedeeb | 845 | blinkTimer.detach(); |
| tverouden | 5:04b26b2f536a | 846 | |
| tverouden | 24:0abc564349e1 | 847 | currentState = reading; // change to state |
| tverouden | 5:04b26b2f536a | 848 | changeState = true; // next loop, switch states |
| tverouden | 5:04b26b2f536a | 849 | } |
| tverouden | 5:04b26b2f536a | 850 | break; // end case |
| tverouden | 5:04b26b2f536a | 851 | |
| tverouden | 5:04b26b2f536a | 852 | // ============================== DEMOING MODE =============================== |
| tverouden | 5:04b26b2f536a | 853 | case demoing: |
| tverouden | 5:04b26b2f536a | 854 | // ------------------------- initialisation -------------------------- |
| tverouden | 5:04b26b2f536a | 855 | if (changeState) { // when entering the state |
| tverouden | 5:04b26b2f536a | 856 | pc.printf("[MODE] demoing...\r\n"); |
| tverouden | 5:04b26b2f536a | 857 | // print current state |
| tverouden | 5:04b26b2f536a | 858 | changeState = false; // stay in this state |
| tverouden | 5:04b26b2f536a | 859 | |
| tverouden | 5:04b26b2f536a | 860 | // Actions when entering state |
| tverouden | 15:6566c5dedeeb | 861 | ledRed = 0; // yellow LED on |
| tverouden | 15:6566c5dedeeb | 862 | ledGreen = 0; |
| tverouden | 15:6566c5dedeeb | 863 | ledBlue = 1; |
| tverouden | 5:04b26b2f536a | 864 | |
| tverouden | 5:04b26b2f536a | 865 | } |
| tverouden | 5:04b26b2f536a | 866 | // ----------------------------- action ------------------------------ |
| tverouden | 5:04b26b2f536a | 867 | // Actions for each loop iteration |
| tverouden | 5:04b26b2f536a | 868 | /* */ |
| tverouden | 5:04b26b2f536a | 869 | |
| tverouden | 5:04b26b2f536a | 870 | // --------------------------- transition ---------------------------- |
| tverouden | 24:0abc564349e1 | 871 | // Transition condition: with button press, back to homing mode |
| tverouden | 24:0abc564349e1 | 872 | if (buttonHome == false) { |
| tverouden | 5:04b26b2f536a | 873 | // Actions when leaving state |
| tverouden | 5:04b26b2f536a | 874 | /* */ |
| tverouden | 5:04b26b2f536a | 875 | |
| tverouden | 5:04b26b2f536a | 876 | currentState = homing; // change to state |
| tverouden | 5:04b26b2f536a | 877 | changeState = true; // next loop, switch states |
| tverouden | 5:04b26b2f536a | 878 | } |
| tverouden | 5:04b26b2f536a | 879 | break; // end case |
| tverouden | 5:04b26b2f536a | 880 | |
| tverouden | 5:04b26b2f536a | 881 | // =============================== FAILING MODE ================================ |
| tverouden | 5:04b26b2f536a | 882 | case failing: |
| tverouden | 24:0abc564349e1 | 883 | changeState = false; // stay in this state |
| tverouden | 3:9c63fc5f157e | 884 | |
| tverouden | 3:9c63fc5f157e | 885 | // Actions when entering state |
| tverouden | 20:cf673a2cbc60 | 886 | ledRed = 0; // red LED on |
| tverouden | 20:cf673a2cbc60 | 887 | ledGreen = 1; |
| tverouden | 6:f32352bc5078 | 888 | ledBlue = 1; |
| tverouden | 4:5ce2c8864908 | 889 | |
| tverouden | 34:fb6889c5ca22 | 890 | pin3 = 0; // all motor forces to zero |
| tverouden | 34:fb6889c5ca22 | 891 | pin5 = 0; |
| tverouden | 34:fb6889c5ca22 | 892 | pin6 = 0; |
| tverouden | 20:cf673a2cbc60 | 893 | exit (0); // stop all current functions |
| tverouden | 4:5ce2c8864908 | 894 | break; // end case |
| tverouden | 4:5ce2c8864908 | 895 | |
| tverouden | 4:5ce2c8864908 | 896 | // ============================== DEFAULT MODE ================================= |
| tverouden | 3:9c63fc5f157e | 897 | default: |
| tverouden | 4:5ce2c8864908 | 898 | // ---------------------------- enter failing mode ----------------------------- |
| tverouden | 4:5ce2c8864908 | 899 | currentState = failing; // change to state |
| tverouden | 4:5ce2c8864908 | 900 | changeState = true; // next loop, switch states |
| tverouden | 4:5ce2c8864908 | 901 | // print current state |
| tverouden | 4:5ce2c8864908 | 902 | pc.printf("[ERROR] unknown or unimplemented state reached\r\n"); |
| tverouden | 3:9c63fc5f157e | 903 | |
| tverouden | 4:5ce2c8864908 | 904 | } // end switch |
| tverouden | 4:5ce2c8864908 | 905 | } // end stateMachine |
| tverouden | 3:9c63fc5f157e | 906 | |
| tverouden | 3:9c63fc5f157e | 907 | |
| tverouden | 2:d70795e4e0bf | 908 | |
| tverouden | 2:d70795e4e0bf | 909 | // ≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡ MAIN LOOP ≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡≡ |
| tverouden | 2:d70795e4e0bf | 910 | |
| tverouden | 3:9c63fc5f157e | 911 | int main() |
| tverouden | 3:9c63fc5f157e | 912 | { |
| tverouden | 8:8cef1050ebd9 | 913 | // ================================ EMERGENCY ================================ |
| tverouden | 15:6566c5dedeeb | 914 | //If the emergency button is pressed, stop program via failing state |
| tverouden | 24:0abc564349e1 | 915 | buttonEmergency.rise(stopProgram); // Automatische triggers voor failure mode? -> ook error message in andere functies plaatsen! |
| tverouden | 15:6566c5dedeeb | 916 | |
| tverouden | 19:2797bb471f9f | 917 | // ============================= PC-COMMUNICATION ============================= |
| tverouden | 19:2797bb471f9f | 918 | pc.baud(115200); // communication with terminal |
| tverouden | 19:2797bb471f9f | 919 | pc.printf("\n\n[START] starting O.D.I.N\r\n"); |
| tverouden | 6:f32352bc5078 | 920 | |
| efvanmarrewijk | 25:ac139331fe51 | 921 | // ============================= PIN DEFINE PERIOD ============================ |
| efvanmarrewijk | 25:ac139331fe51 | 922 | // If you give a period on one pin, c++ gives all pins this period |
| efvanmarrewijk | 25:ac139331fe51 | 923 | pin3.period_us(15); |
| efvanmarrewijk | 25:ac139331fe51 | 924 | |
| tverouden | 2:d70795e4e0bf | 925 | // ==================================== LOOP =================================== |
| tverouden | 24:0abc564349e1 | 926 | // run state machine at 500 Hz |
| efvanmarrewijk | 25:ac139331fe51 | 927 | stateTimer.attach(&stateMachine,dt); |
| tverouden | 2:d70795e4e0bf | 928 | } |
