The code without functions and variables filled in

Dependencies:   HIDScope Servo mbed QEI biquadFilter

Committer:
s1725696
Date:
Fri Nov 02 08:34:45 2018 +0000
Revision:
23:cc8b95d7eb57
Parent:
22:be961d1830bb
Child:
24:ebcb41126f21
With wait mode filled in;

Who changed what in which revision?

UserRevisionLine numberNew contents of line
s1725696 5:3581013d4505 1 #include "mbed.h" // Use revision 119!!
s1725696 5:3581013d4505 2 #include "HIDScope.h" // For displaying data, select MBED - HID device, restart for every new code
s1725696 5:3581013d4505 3 #include "QEI.h" // For reading the encoder of the motors
s1725696 9:d7a6a3619576 4 #include <ctime> // for the timer during the process (if needed)
s1725696 11:79311abb2bc2 5 #include "Servo.h" // For controlling the servo
s1725696 13:c087c0f64769 6 #include "BiQuad.h"
s1725696 0:cb8857cf3ea4 7
s1725696 5:3581013d4505 8 #define SERIAL_BAUD 115200
s1725696 5:3581013d4505 9
s1725696 5:3581013d4505 10 // In- en outputs
s1725696 4:8183e7b228f0 11 // -----------------------------------------------------------------------------
s1725696 4:8183e7b228f0 12
s1725696 18:db53ac017f50 13 // EMG
s1725696 18:db53ac017f50 14 AnalogIn emg0_in( A0 ); // x_direction
s1725696 18:db53ac017f50 15 AnalogIn emg1_in( A1 ); // y_direction
s1725696 18:db53ac017f50 16 AnalogIn emg2_in( A2 ); // changing directions
s1725696 18:db53ac017f50 17
s1725696 18:db53ac017f50 18 // Motor related
s1725696 18:db53ac017f50 19 DigitalOut dirpin_1(D4); // direction of motor 1 (translation)
s1725696 18:db53ac017f50 20 PwmOut pwmpin_1(D5); // PWM pin of motor 1
s1725696 18:db53ac017f50 21 DigitalOut dirpin_2(D7); // direction of motor 2 (rotation)
s1725696 18:db53ac017f50 22 PwmOut pwmpin_2(D6); // PWM pin of motor 2
s1725696 18:db53ac017f50 23
s1725696 18:db53ac017f50 24 // Extra stuff
s1725696 18:db53ac017f50 25 DigitalIn button_motorcal(SW2); // button for motor calibration, on mbed
s1725696 18:db53ac017f50 26 DigitalIn button_emergency(D8); // button for emergency mode, on bioshield
s1725696 18:db53ac017f50 27 DigitalIn button_wait(SW3); // button for wait mode, on mbed
s1725696 18:db53ac017f50 28 DigitalIn button_demo(D9); // button for demo mode, on bioshield
s1725696 18:db53ac017f50 29
s1725696 18:db53ac017f50 30 DigitalIn led_red(LED_RED); // red led
s1725696 18:db53ac017f50 31 DigitalIn led_green(LED_GREEN); // green led
s1725696 18:db53ac017f50 32 DigitalIn led_blue(LED_BLUE); // blue led
s1725696 18:db53ac017f50 33
s1725696 18:db53ac017f50 34 Servo myservo(D3); // Define the servo to control (in penholder), up to start with
s1725696 18:db53ac017f50 35
s1725696 18:db53ac017f50 36 // Other stuff
s1725696 18:db53ac017f50 37 // -----------------------------------------------------------------------------
s1725696 18:db53ac017f50 38 // Define stuff like tickers etc
s1725696 18:db53ac017f50 39
s1725696 18:db53ac017f50 40 Ticker process_tick;
s1725696 18:db53ac017f50 41 Ticker emergency;
s1725696 18:db53ac017f50 42 HIDScope scope(6); // Number of channels in HIDScope
s1725696 18:db53ac017f50 43 QEI Encoder1(D13,D12,NC,64,QEI::X4_ENCODING); // Define the type of encoding: X4 encoding(default is X2)
s1725696 18:db53ac017f50 44 QEI Encoder2(D11,D10,NC,64,QEI::X4_ENCODING);
s1725696 18:db53ac017f50 45 Serial pc(USBTX,USBRX);
s1725696 18:db53ac017f50 46 Timer t; // For timing the time in each state (https://os.mbed.com/handbook/Timer)
s1725696 18:db53ac017f50 47
s1725696 18:db53ac017f50 48 // Variables
s1725696 18:db53ac017f50 49 // -----------------------------------------------------------------------------
s1725696 18:db53ac017f50 50 // Define here all variables needed throughout the whole code
s1725696 18:db53ac017f50 51 volatile double time_overall;
s1725696 18:db53ac017f50 52 volatile double time_in_state;
s1725696 18:db53ac017f50 53 volatile int counts1_prev = 0;
s1725696 18:db53ac017f50 54 volatile int counts2_prev = 0;
s1725696 18:db53ac017f50 55 volatile int counts1;
s1725696 18:db53ac017f50 56 volatile int counts2;
s1725696 18:db53ac017f50 57
s1725696 0:cb8857cf3ea4 58 // EMG related
s1725696 13:c087c0f64769 59 // Constants EMG filter
s1725696 13:c087c0f64769 60 const double m1 = 0.5000;
s1725696 13:c087c0f64769 61 const double m2 = -0.8090;
s1725696 13:c087c0f64769 62 const double n0 = 0.5000;
s1725696 13:c087c0f64769 63 const double n1 = -0.8090;
s1725696 13:c087c0f64769 64 const double n2 = 0.0;
s1725696 13:c087c0f64769 65 const double a1 = 0.9565;
s1725696 13:c087c0f64769 66 const double a2 = -1.9131;
s1725696 13:c087c0f64769 67 const double b0 = 0.9565;
s1725696 13:c087c0f64769 68 const double b1 = -1.9112;
s1725696 13:c087c0f64769 69 const double b2 = 0.9150;
s1725696 13:c087c0f64769 70 const double c1 = 0.0675;
s1725696 13:c087c0f64769 71 const double c2 = 0.1349;
s1725696 13:c087c0f64769 72 const double d0 = 0.0675;
s1725696 13:c087c0f64769 73 const double d1 = -1.1430;
s1725696 13:c087c0f64769 74 const double d2 = 0.4128;
s1725696 13:c087c0f64769 75
s1725696 13:c087c0f64769 76 // Variables EMG
s1725696 13:c087c0f64769 77 double emg0;
s1725696 13:c087c0f64769 78 double emg1;
s1725696 13:c087c0f64769 79 double emg2;
s1725696 13:c087c0f64769 80 double notch0;
s1725696 13:c087c0f64769 81 double notch1;
s1725696 13:c087c0f64769 82 double notch2;
s1725696 13:c087c0f64769 83 double high0;
s1725696 13:c087c0f64769 84 double high1;
s1725696 13:c087c0f64769 85 double high2;
s1725696 13:c087c0f64769 86 double absolute0;
s1725696 13:c087c0f64769 87 double absolute1;
s1725696 13:c087c0f64769 88 double absolute2;
s1725696 13:c087c0f64769 89 double low0;
s1725696 13:c087c0f64769 90 double low1;
s1725696 13:c087c0f64769 91 double low2;
s1725696 13:c087c0f64769 92
s1725696 13:c087c0f64769 93 // BiQuad values
s1725696 13:c087c0f64769 94 BiQuadChain notch;
s1725696 13:c087c0f64769 95 BiQuad N1( m1, m2, n0, n1, n2);
s1725696 13:c087c0f64769 96 BiQuad N2( m1, m2, n0, n1, n2);
s1725696 13:c087c0f64769 97 BiQuad N3( m1, m2, n0, n1, n2);
s1725696 13:c087c0f64769 98 BiQuadChain highpass;
s1725696 13:c087c0f64769 99 BiQuad H1( a1, a2, b0, b1, b2);
s1725696 13:c087c0f64769 100 BiQuad H2( a1, a2, b0, b1, b2);
s1725696 13:c087c0f64769 101 BiQuad H3( a1, a2, b0, b1, b2);
s1725696 13:c087c0f64769 102 BiQuadChain lowpass;
s1725696 13:c087c0f64769 103 BiQuad L1( c1, c2, d0, d1, d2);
s1725696 13:c087c0f64769 104 BiQuad L2( c1, c2, d0, d1, d2);
s1725696 13:c087c0f64769 105 BiQuad L3( c1, c2, d0, d1, d2);
s1725696 13:c087c0f64769 106
s1725696 16:37b491eac34b 107 const float T = 0.001f;
s1725696 13:c087c0f64769 108
s1725696 13:c087c0f64769 109 // EMG
s1725696 13:c087c0f64769 110 const int sizeMovAg = 100; //Size of array over which the moving average (MovAg) is calculated
s1725696 13:c087c0f64769 111 double sum, sum1, sum2, sum3; //Variables used in calibration and MovAg to sum the elements in the array
s1725696 13:c087c0f64769 112 double StoreArray0[sizeMovAg] = {}, StoreArray1[sizeMovAg] = {}, StoreArray2[sizeMovAg] = {};
s1725696 13:c087c0f64769 113
s1725696 13:c087c0f64769 114 //Empty arrays to calculate MovAgs
s1725696 13:c087c0f64769 115 double Average0, Average1, Average2; //Outcome of MovAg
s1725696 13:c087c0f64769 116 const int sizeCali = 500; //Size of array over which the Threshold will be calculated
s1725696 13:c087c0f64769 117 double StoreCali0[sizeCali] = {}, StoreCali1[sizeCali] = {}, StoreCali2[sizeCali] = {};
s1725696 13:c087c0f64769 118
s1725696 13:c087c0f64769 119 //Empty arrays to calculate means in calibration
s1725696 13:c087c0f64769 120 double Mean0, Mean1, Mean2; //Mean of maximum contraction, calculated in the calibration
s1725696 13:c087c0f64769 121 double Threshold0 = 1, Threshold1 = 1, Threshold2 = 1; //Thresholds for muscles 0 to 2
s1725696 13:c087c0f64769 122 int g = 0; //Part of the switch void, where the current state can be changed
s1725696 13:c087c0f64769 123 int emg_calib=0; //After calibration this value will be 1, enabling the
s1725696 13:c087c0f64769 124
s1725696 12:b2b082e73ef1 125 // MOTOR_CAL
s1725696 12:b2b082e73ef1 126 volatile double tower_1_position = 0.1; // the tower which he reaches first
s1725696 12:b2b082e73ef1 127 volatile double tower_end_position = 0.1; // the tower which he reaches second
s1725696 12:b2b082e73ef1 128 volatile double rotation_start_position = 0.1; // the position where the rotation will remain
s1725696 12:b2b082e73ef1 129 volatile double position;
s1725696 20:645483d7470c 130 volatile float speed = 1.0;
s1725696 17:65943f6e11dc 131 volatile int dir = 0;
s1725696 17:65943f6e11dc 132
s1725696 17:65943f6e11dc 133 // RKI related
s1725696 17:65943f6e11dc 134 const double Ts = 0.001;// sample frequency
s1725696 17:65943f6e11dc 135
s1725696 17:65943f6e11dc 136 // Constants motor
s1725696 17:65943f6e11dc 137 const double delta_t = 0.01;
s1725696 17:65943f6e11dc 138 const double el_1 = 370.0 / 2.0;
s1725696 17:65943f6e11dc 139 const double el_2 = 65.0 / 2.0;
s1725696 17:65943f6e11dc 140 const double pi = 3.14159265359;
s1725696 17:65943f6e11dc 141 const double alpha = (2.0 * pi) /(25.0*8400.0);
s1725696 17:65943f6e11dc 142 const double beta = (((2.0 * el_1) - (2.0 * el_2)) * 20.0 * pi) / (305.0 * 8400.0);
s1725696 17:65943f6e11dc 143 const double q1start = rotation_start_position * alpha;
s1725696 17:65943f6e11dc 144 const double q2start = tower_1_position * beta;
s1725696 17:65943f6e11dc 145 const double q2end = tower_end_position * beta;
s1725696 17:65943f6e11dc 146
s1725696 17:65943f6e11dc 147 // Variables motors
s1725696 17:65943f6e11dc 148 volatile double desired_x;
s1725696 17:65943f6e11dc 149 volatile double desired_y;
s1725696 17:65943f6e11dc 150 volatile double out1;
s1725696 17:65943f6e11dc 151 volatile double out2;
s1725696 17:65943f6e11dc 152 volatile double vdesx;
s1725696 17:65943f6e11dc 153 volatile double vdesy;
s1725696 17:65943f6e11dc 154 volatile double q1;
s1725696 17:65943f6e11dc 155 volatile double q2;
s1725696 17:65943f6e11dc 156 volatile double MPe;
s1725696 17:65943f6e11dc 157 volatile double xe;
s1725696 17:65943f6e11dc 158 volatile double ye;
s1725696 17:65943f6e11dc 159 volatile double gamma;
s1725696 17:65943f6e11dc 160 volatile double dq1;
s1725696 17:65943f6e11dc 161 volatile double dq2;
s1725696 17:65943f6e11dc 162 volatile double dC1;
s1725696 17:65943f6e11dc 163 volatile double dC2;
s1725696 17:65943f6e11dc 164 volatile double pwm1;
s1725696 17:65943f6e11dc 165 volatile double pwm2;
s1725696 17:65943f6e11dc 166
s1725696 17:65943f6e11dc 167 // PID rotation constants
s1725696 17:65943f6e11dc 168 volatile double Rot_Kp = 1.5;
s1725696 17:65943f6e11dc 169 volatile double Rot_Ki = 0.1;
s1725696 17:65943f6e11dc 170 volatile double Rot_Kd = 0.48;
s1725696 17:65943f6e11dc 171 volatile double Rot_error = 0.0;
s1725696 17:65943f6e11dc 172 volatile double Rot_prev_error = 0.0;
s1725696 17:65943f6e11dc 173
s1725696 17:65943f6e11dc 174 // PID translation constants
s1725696 17:65943f6e11dc 175 const double Trans_Kp = 0.5;
s1725696 17:65943f6e11dc 176 const double Trans_Ki = 0.5;
s1725696 17:65943f6e11dc 177 const double Trans_Kd = 0.1;
s1725696 17:65943f6e11dc 178 volatile double Trans_error = 0.0;
s1725696 17:65943f6e11dc 179 volatile double Trans_prev_error = 0.0;
s1725696 6:f495a77c2c95 180
s1725696 23:cc8b95d7eb57 181 // States
s1725696 20:645483d7470c 182 enum states {WAIT, MOTOR_CAL, EMG_CAL, START, OPERATING}; // states the robot can be in
s1725696 7:ec5add330cb3 183 states CurrentState = WAIT; // the CurrentState to start with is the WAIT state
s1725696 6:f495a77c2c95 184 bool StateChanged = true; // the state must be changed to go into the next state
s1725696 0:cb8857cf3ea4 185
s1725696 20:645483d7470c 186 enum direction {Pos_RB, Pos_LB, Pos_RO, Pos_LO};
s1725696 20:645483d7470c 187 direction currentdirection = Pos_RB;
s1725696 20:645483d7470c 188 bool directionchanged = true;
s1725696 20:645483d7470c 189
s1725696 0:cb8857cf3ea4 190 // Functions
s1725696 4:8183e7b228f0 191 // -----------------------------------------------------------------------------
s1725696 0:cb8857cf3ea4 192
s1725696 4:8183e7b228f0 193 // Encoder
s1725696 4:8183e7b228f0 194 // Getting encoder information from motors
s1725696 12:b2b082e73ef1 195 int Counts1(volatile int& a) // a = counts1
s1725696 4:8183e7b228f0 196 {
s1725696 12:b2b082e73ef1 197 counts1_prev = a;
s1725696 18:db53ac017f50 198 a = Encoder1.getPulses();
s1725696 12:b2b082e73ef1 199 return a;
s1725696 12:b2b082e73ef1 200 }
s1725696 12:b2b082e73ef1 201
s1725696 12:b2b082e73ef1 202 int Counts2(volatile int& a) // a = counts2
s1725696 12:b2b082e73ef1 203 {
s1725696 12:b2b082e73ef1 204 counts2_prev = a;
s1725696 18:db53ac017f50 205 a = Encoder2.getPulses();
s1725696 12:b2b082e73ef1 206 return a;
s1725696 12:b2b082e73ef1 207 }
s1725696 5:3581013d4505 208
s1725696 11:79311abb2bc2 209 // Servo control
s1725696 12:b2b082e73ef1 210 // To lift the pen up, with a push of button
s1725696 11:79311abb2bc2 211 void servocontrol()
s1725696 11:79311abb2bc2 212 {
s1725696 18:db53ac017f50 213 if(button_motorcal == false) // If button is pushed, pen should go up
s1725696 11:79311abb2bc2 214 {
s1725696 11:79311abb2bc2 215 myservo = 0.1;
s1725696 11:79311abb2bc2 216 }
s1725696 14:abc125dcc246 217 myservo = 0.0;
s1725696 6:f495a77c2c95 218 }
s1725696 9:d7a6a3619576 219
s1725696 10:56136a0da8c1 220 // EMG filter
s1725696 10:56136a0da8c1 221 // To process the EMG signal before information can be caught from it
s1725696 14:abc125dcc246 222
s1725696 14:abc125dcc246 223 // Filter of the first EMG signal
s1725696 13:c087c0f64769 224 void filtering()
s1725696 13:c087c0f64769 225 {
s1725696 13:c087c0f64769 226 // Reading the EMG signal
s1725696 13:c087c0f64769 227 emg0 = emg0_in.read();
s1725696 13:c087c0f64769 228 emg1 = emg1_in.read();
s1725696 13:c087c0f64769 229 emg2 = emg2_in.read();
s1725696 13:c087c0f64769 230
s1725696 13:c087c0f64769 231 // Applying a notch filter over the EMG data
s1725696 13:c087c0f64769 232 notch0 = N1.step(emg0);
s1725696 13:c087c0f64769 233 notch1 = N2.step(emg1);
s1725696 13:c087c0f64769 234 notch2 = N3.step(emg2);
s1725696 13:c087c0f64769 235
s1725696 13:c087c0f64769 236 // Applying a high pass filter
s1725696 13:c087c0f64769 237 high0 = H1.step(notch0);
s1725696 13:c087c0f64769 238 high1 = H2.step(notch1);
s1725696 13:c087c0f64769 239 high2 = H3.step(notch2);
s1725696 13:c087c0f64769 240
s1725696 13:c087c0f64769 241 // Rectifying the signal
s1725696 13:c087c0f64769 242 absolute0 = fabs(high0);
s1725696 13:c087c0f64769 243 absolute1 = fabs(high1);
s1725696 13:c087c0f64769 244 absolute2 = fabs(high2);
s1725696 13:c087c0f64769 245
s1725696 13:c087c0f64769 246 // Applying low pass filter
s1725696 13:c087c0f64769 247 low0 = L1.step(absolute0);
s1725696 13:c087c0f64769 248 low1 = L2.step(absolute1);
s1725696 13:c087c0f64769 249 low2 = L3.step(absolute2);
s1725696 13:c087c0f64769 250 }
s1725696 13:c087c0f64769 251
s1725696 13:c087c0f64769 252 // Moving average filter
s1725696 13:c087c0f64769 253 // To determine the moving average, apply after filtering
s1725696 13:c087c0f64769 254 void MovAg()
s1725696 13:c087c0f64769 255 {
s1725696 13:c087c0f64769 256 // For statement to make an array of the last datapoints of the filtered signal
s1725696 13:c087c0f64769 257 for (int i = sizeMovAg - 1; i >= 0; i--)
s1725696 13:c087c0f64769 258 {
s1725696 13:c087c0f64769 259 // Shifts the i'th element one place to the right
s1725696 13:c087c0f64769 260 StoreArray0[i] = StoreArray0[i-1];
s1725696 13:c087c0f64769 261 StoreArray1[i] = StoreArray1[i-1];
s1725696 13:c087c0f64769 262 StoreArray2[i] = StoreArray2[i-1];
s1725696 13:c087c0f64769 263 }
s1725696 13:c087c0f64769 264
s1725696 13:c087c0f64769 265 // Stores the latest datapoint in the first element of the array
s1725696 13:c087c0f64769 266 StoreArray0[0] = low0;
s1725696 13:c087c0f64769 267 StoreArray1[0] = low1;
s1725696 13:c087c0f64769 268 StoreArray2[0] = low2;
s1725696 13:c087c0f64769 269 sum1 = 0.0;
s1725696 13:c087c0f64769 270 sum2 = 0.0;
s1725696 13:c087c0f64769 271 sum3 = 0.0;
s1725696 13:c087c0f64769 272
s1725696 13:c087c0f64769 273 // For statement to sum the elements in the array
s1725696 13:c087c0f64769 274 for (int a = 0; a<=sizeMovAg-1; a++)
s1725696 13:c087c0f64769 275 {
s1725696 13:c087c0f64769 276 sum1+=StoreArray0[a];
s1725696 13:c087c0f64769 277 sum2+=StoreArray1[a];
s1725696 13:c087c0f64769 278 sum3+=StoreArray2[a];
s1725696 13:c087c0f64769 279 }
s1725696 13:c087c0f64769 280
s1725696 13:c087c0f64769 281 // Calculates an average over the datapoints in the array
s1725696 13:c087c0f64769 282 Average0 = sum1/sizeMovAg;
s1725696 13:c087c0f64769 283 Average1 = sum2/sizeMovAg;
s1725696 13:c087c0f64769 284 Average2 = sum3/sizeMovAg;
s1725696 13:c087c0f64769 285
s1725696 14:abc125dcc246 286 // Sending the signal to the HIDScope
s1725696 14:abc125dcc246 287 // Change the number of channels in the beginning of the script when necessary
s1725696 14:abc125dcc246 288 scope.set( 0, emg0);
s1725696 14:abc125dcc246 289 scope.set( 1, low0);
s1725696 13:c087c0f64769 290 scope.set( 2, Average0);
s1725696 13:c087c0f64769 291 scope.set( 3, low1);
s1725696 13:c087c0f64769 292 scope.set( 4, emg2);
s1725696 13:c087c0f64769 293 scope.set( 5, low2);
s1725696 13:c087c0f64769 294 scope.send();
s1725696 14:abc125dcc246 295 }
s1725696 10:56136a0da8c1 296
s1725696 17:65943f6e11dc 297 // This must be applied to all emg signals coming in
s1725696 17:65943f6e11dc 298 void processing_emg()
s1725696 17:65943f6e11dc 299 {
s1725696 17:65943f6e11dc 300 filtering();
s1725696 17:65943f6e11dc 301 MovAg();
s1725696 17:65943f6e11dc 302 }
s1725696 10:56136a0da8c1 303
s1725696 10:56136a0da8c1 304 // MOTOR_CAL
s1725696 10:56136a0da8c1 305 // To calibrate the motor angle to some mechanical boundaries
s1725696 10:56136a0da8c1 306 // Kenneth mee bezig
s1725696 12:b2b082e73ef1 307 void pos_store(int a){ //store position in counts to know count location of the ends of bridge
s1725696 12:b2b082e73ef1 308
s1725696 13:c087c0f64769 309 if (tower_1_position == 0.1)
s1725696 13:c087c0f64769 310 {
s1725696 12:b2b082e73ef1 311 tower_1_position = a;
s1725696 12:b2b082e73ef1 312 }
s1725696 13:c087c0f64769 313 else if (tower_end_position == 0.1)
s1725696 13:c087c0f64769 314 {
s1725696 12:b2b082e73ef1 315 tower_end_position = a;
s1725696 12:b2b082e73ef1 316 }
s1725696 13:c087c0f64769 317 else if (rotation_start_position == 0.1)
s1725696 13:c087c0f64769 318 {
s1725696 12:b2b082e73ef1 319 rotation_start_position = a;
s1725696 12:b2b082e73ef1 320 }
s1725696 12:b2b082e73ef1 321 }
s1725696 12:b2b082e73ef1 322
s1725696 12:b2b082e73ef1 323 // Start translation
s1725696 12:b2b082e73ef1 324 void translation_start(int a, float b) // a = dir , b = speed
s1725696 12:b2b082e73ef1 325 {
s1725696 12:b2b082e73ef1 326 dirpin_1.write(a);
s1725696 12:b2b082e73ef1 327 pwmpin_1 = b;
s1725696 12:b2b082e73ef1 328 }
s1725696 12:b2b082e73ef1 329
s1725696 12:b2b082e73ef1 330 // Stop translation
s1725696 12:b2b082e73ef1 331 void translation_stop()
s1725696 12:b2b082e73ef1 332 {
s1725696 12:b2b082e73ef1 333 pwmpin_1 = 0.0;
s1725696 12:b2b082e73ef1 334 }
s1725696 12:b2b082e73ef1 335
s1725696 12:b2b082e73ef1 336 // Start rotation
s1725696 12:b2b082e73ef1 337 void rotation_start(int a, float b)
s1725696 12:b2b082e73ef1 338 {
s1725696 12:b2b082e73ef1 339 dirpin_2.write(a);
s1725696 12:b2b082e73ef1 340 pwmpin_2 = b;
s1725696 12:b2b082e73ef1 341 }
s1725696 12:b2b082e73ef1 342
s1725696 12:b2b082e73ef1 343 // Stop rotation
s1725696 12:b2b082e73ef1 344 void rotation_stop()
s1725696 12:b2b082e73ef1 345 {
s1725696 12:b2b082e73ef1 346 pwmpin_2 = 0.0;
s1725696 12:b2b082e73ef1 347 }
s1725696 12:b2b082e73ef1 348
s1725696 12:b2b082e73ef1 349 // Calibration of translation
s1725696 12:b2b082e73ef1 350 void calibration_translation()
s1725696 12:b2b082e73ef1 351 {
s1725696 12:b2b082e73ef1 352 for(int m = 1; m <= 2; m++) // to do each direction one time
s1725696 12:b2b082e73ef1 353 {
s1725696 14:abc125dcc246 354 // dir = 0, means that the pen moves to the translation motor, dir = 1 means it moves to the rotation motor
s1725696 12:b2b082e73ef1 355 pc.printf("\r\nTranslatie loop\r\n");
s1725696 12:b2b082e73ef1 356 translation_start(dir,speed);
s1725696 12:b2b082e73ef1 357 pc.printf("Direction = %i\r\n", dir);
s1725696 12:b2b082e73ef1 358
s1725696 12:b2b082e73ef1 359 bool g = true; // to make a condition for the while loop
s1725696 12:b2b082e73ef1 360 while (g == true)
s1725696 12:b2b082e73ef1 361 {
s1725696 12:b2b082e73ef1 362 if (button_demo == false) // if button_demo is pushed, the translation should stop and change direction
s1725696 12:b2b082e73ef1 363 {
s1725696 12:b2b082e73ef1 364 translation_stop();
s1725696 12:b2b082e73ef1 365 pos_store(Counts1(counts1));
s1725696 12:b2b082e73ef1 366 pc.printf("position of first tower = %.1f, position of second tower = %.1f, position of rotation motor = %.1f \r\n",tower_1_position,tower_end_position,rotation_start_position);
s1725696 12:b2b082e73ef1 367 dir = dir + 1;
s1725696 12:b2b082e73ef1 368
s1725696 12:b2b082e73ef1 369 g = false; // to end the while loop
s1725696 12:b2b082e73ef1 370 }
s1725696 12:b2b082e73ef1 371
s1725696 12:b2b082e73ef1 372 wait(0.01);
s1725696 12:b2b082e73ef1 373 }
s1725696 12:b2b082e73ef1 374
s1725696 15:2772f8cbf382 375 wait(1.0); // wait 3 seconds before next round of translation/rotation
s1725696 12:b2b082e73ef1 376 }
s1725696 12:b2b082e73ef1 377 }
s1725696 12:b2b082e73ef1 378
s1725696 12:b2b082e73ef1 379 void calibration_rotation()
s1725696 12:b2b082e73ef1 380 {
s1725696 12:b2b082e73ef1 381 rotation_start(dir, speed);
s1725696 12:b2b082e73ef1 382 pc.printf("\r\nRotatie start\r\n");
s1725696 12:b2b082e73ef1 383
s1725696 12:b2b082e73ef1 384 bool f = true; // condition for while loop
s1725696 12:b2b082e73ef1 385 while(f == true)
s1725696 12:b2b082e73ef1 386 {
s1725696 12:b2b082e73ef1 387 if (button_motorcal == false) // If button_motorcal is pushed, then the motor should stop and remain in that position until homing
s1725696 12:b2b082e73ef1 388 {
s1725696 12:b2b082e73ef1 389 rotation_stop();
s1725696 12:b2b082e73ef1 390
s1725696 12:b2b082e73ef1 391 f = false; // to end the while loop
s1725696 12:b2b082e73ef1 392 }
s1725696 12:b2b082e73ef1 393
s1725696 12:b2b082e73ef1 394 wait(0.01);
s1725696 12:b2b082e73ef1 395 }
s1725696 14:abc125dcc246 396 int start_counts = 0;
s1725696 14:abc125dcc246 397 pos_store(Counts2(start_counts));
s1725696 12:b2b082e73ef1 398 pc.printf("position of first tower = %.1f, position of second tower = %.1f, position of rotation motor = %.1f \r\n",tower_1_position,tower_end_position,rotation_start_position);
s1725696 12:b2b082e73ef1 399 }
s1725696 12:b2b082e73ef1 400
s1725696 10:56136a0da8c1 401 void motor_calibration()
s1725696 10:56136a0da8c1 402 {
s1725696 12:b2b082e73ef1 403 // translation
s1725696 12:b2b082e73ef1 404 calibration_translation();
s1725696 12:b2b082e73ef1 405
s1725696 12:b2b082e73ef1 406 pc.printf("before wait\r\n");
s1725696 12:b2b082e73ef1 407 wait(1.5);
s1725696 12:b2b082e73ef1 408
s1725696 12:b2b082e73ef1 409 // rotation
s1725696 12:b2b082e73ef1 410 calibration_rotation();
s1725696 12:b2b082e73ef1 411
s1725696 12:b2b082e73ef1 412 pc.printf("Motor calibration done");
s1725696 10:56136a0da8c1 413 }
s1725696 10:56136a0da8c1 414
s1725696 23:cc8b95d7eb57 415 // WAIT
s1725696 23:cc8b95d7eb57 416 // To do nothing
s1725696 23:cc8b95d7eb57 417 void wait_mode()
s1725696 23:cc8b95d7eb57 418 {
s1725696 23:cc8b95d7eb57 419 // Go back to the initial values
s1725696 23:cc8b95d7eb57 420
s1725696 23:cc8b95d7eb57 421 // All pwm's to zero
s1725696 23:cc8b95d7eb57 422 translation_stop();
s1725696 23:cc8b95d7eb57 423 rotation_stop();
s1725696 23:cc8b95d7eb57 424 // All counts to zero
s1725696 23:cc8b95d7eb57 425 counts1 = 0;
s1725696 23:cc8b95d7eb57 426 counts2 = 0;
s1725696 23:cc8b95d7eb57 427 }
s1725696 23:cc8b95d7eb57 428
s1725696 10:56136a0da8c1 429 // EMG_CAL
s1725696 10:56136a0da8c1 430 // To calibrate the EMG signal to some boundary values
s1725696 13:c087c0f64769 431 // Void to switch between signals to calibrate
s1725696 13:c087c0f64769 432 void switch_to_calibrate()
s1725696 13:c087c0f64769 433 {
s1725696 13:c087c0f64769 434 g++;
s1725696 13:c087c0f64769 435 //If g = 0, led is blue
s1725696 13:c087c0f64769 436 if (g == 0)
s1725696 13:c087c0f64769 437 {
s1725696 13:c087c0f64769 438 led_blue==0;
s1725696 13:c087c0f64769 439 led_red==1;
s1725696 13:c087c0f64769 440 led_green==1;
s1725696 13:c087c0f64769 441 }
s1725696 13:c087c0f64769 442 //If g = 1, led is red
s1725696 13:c087c0f64769 443 else if(g == 1)
s1725696 13:c087c0f64769 444 {
s1725696 13:c087c0f64769 445 led_blue==1;
s1725696 13:c087c0f64769 446 led_red==0;
s1725696 13:c087c0f64769 447 led_green==1;
s1725696 13:c087c0f64769 448 }
s1725696 13:c087c0f64769 449 //If g = 2, led is green
s1725696 13:c087c0f64769 450 else if(g == 2)
s1725696 13:c087c0f64769 451 {
s1725696 13:c087c0f64769 452 led_blue==1;
s1725696 13:c087c0f64769 453 led_red==1;
s1725696 13:c087c0f64769 454 led_green==0;
s1725696 13:c087c0f64769 455 }
s1725696 13:c087c0f64769 456 //If g > 3, led is white
s1725696 13:c087c0f64769 457 else
s1725696 13:c087c0f64769 458 {
s1725696 13:c087c0f64769 459 led_blue==0;
s1725696 13:c087c0f64769 460 led_red==0;
s1725696 13:c087c0f64769 461 led_green==0;
s1725696 13:c087c0f64769 462 emg_calib = 0;
s1725696 13:c087c0f64769 463 g = 0;
s1725696 13:c087c0f64769 464 }
s1725696 14:abc125dcc246 465 }
s1725696 13:c087c0f64769 466
s1725696 13:c087c0f64769 467 // Void to calibrate the signals, depends on value g. While calibrating, maximal contraction is required
s1725696 14:abc125dcc246 468 void calibrate()
s1725696 13:c087c0f64769 469 {
s1725696 13:c087c0f64769 470 switch (g)
s1725696 13:c087c0f64769 471 {
s1725696 13:c087c0f64769 472 case 0:
s1725696 13:c087c0f64769 473 { // Case zero, calibrate EMG signal of right biceps
s1725696 13:c087c0f64769 474 sum = 0.0;
s1725696 13:c087c0f64769 475
s1725696 13:c087c0f64769 476 //For statement to make an array of the latest datapoints of the filtered signal
s1725696 13:c087c0f64769 477 for (int j = 0; j<=sizeCali-1; j++)
s1725696 13:c087c0f64769 478 {
s1725696 13:c087c0f64769 479
s1725696 13:c087c0f64769 480 StoreCali0[j] = low0; // Stores the latest datapoint in the first element of the array
s1725696 13:c087c0f64769 481 sum+=StoreCali0[j]; // Sums the elements in the array
s1725696 13:c087c0f64769 482 wait(0.001f);
s1725696 13:c087c0f64769 483 }
s1725696 13:c087c0f64769 484 Mean0 = sum/sizeCali; // Calculates the mean of the signal
s1725696 20:645483d7470c 485 Threshold0 = 1.5*Mean0; // Factor *2 is for resting and *1 is for max contraction
s1725696 13:c087c0f64769 486 break;
s1725696 13:c087c0f64769 487 }
s1725696 13:c087c0f64769 488 case 1:
s1725696 13:c087c0f64769 489 { // Case one, calibrate EMG signal of left biceps
s1725696 13:c087c0f64769 490 sum = 0.0;
s1725696 13:c087c0f64769 491 for(int j=0; j<=sizeCali-1; j++)
s1725696 13:c087c0f64769 492 {
s1725696 13:c087c0f64769 493 StoreCali1[j] = low1;
s1725696 13:c087c0f64769 494 sum+=StoreCali1[j];
s1725696 13:c087c0f64769 495 wait(0.001f);
s1725696 13:c087c0f64769 496 }
s1725696 13:c087c0f64769 497 Mean1 = sum/sizeCali;
s1725696 19:a3a7baab9dbc 498 Threshold1 = 2.0*Mean1; // Factor *2 is for resting and *1 is for max contraction
s1725696 13:c087c0f64769 499 break;
s1725696 13:c087c0f64769 500 }
s1725696 13:c087c0f64769 501 case 2:
s1725696 13:c087c0f64769 502 { // Case two, calibrate EMG signal of calf
s1725696 13:c087c0f64769 503 sum = 0.0;
s1725696 13:c087c0f64769 504 for(int j=0; j<=sizeCali-1; j++)
s1725696 13:c087c0f64769 505 {
s1725696 13:c087c0f64769 506 StoreCali2[j] = low2;
s1725696 13:c087c0f64769 507 sum+=StoreCali2[j];
s1725696 13:c087c0f64769 508 wait(0.001f);
s1725696 13:c087c0f64769 509 }
s1725696 13:c087c0f64769 510 Mean2 = sum/sizeCali;
s1725696 19:a3a7baab9dbc 511 Threshold2 = 2.0*Mean2; //Factor *2 is for resting and *1 is for max contraction
s1725696 13:c087c0f64769 512 break;
s1725696 13:c087c0f64769 513 }
s1725696 13:c087c0f64769 514 case 3:
s1725696 13:c087c0f64769 515 { // Sets calibration value to 1; robot can be set to Home position
s1725696 13:c087c0f64769 516 emg_calib=1;
s1725696 13:c087c0f64769 517 wait(0.001f);
s1725696 13:c087c0f64769 518 break;
s1725696 13:c087c0f64769 519 }
s1725696 13:c087c0f64769 520 default:
s1725696 13:c087c0f64769 521 { // Ensures nothing happens if g is not equal to 0, 1 or 2.
s1725696 13:c087c0f64769 522 break;
s1725696 13:c087c0f64769 523 }
s1725696 13:c087c0f64769 524 }
s1725696 13:c087c0f64769 525 }
s1725696 13:c087c0f64769 526
s1725696 13:c087c0f64769 527 // Void to calibrate the EMG signal
s1725696 10:56136a0da8c1 528 void emg_calibration()
s1725696 10:56136a0da8c1 529 {
s1725696 13:c087c0f64769 530 for(int m = 1; m <= 4; m++)
s1725696 13:c087c0f64769 531 {
s1725696 13:c087c0f64769 532 led_blue == 0;
s1725696 13:c087c0f64769 533 led_red == 1;
s1725696 17:65943f6e11dc 534 led_green == 1;
s1725696 13:c087c0f64769 535
s1725696 13:c087c0f64769 536 pc.printf("g is %i\n\r",g);
s1725696 13:c087c0f64769 537 pc.printf("Average0 = %f , Average1 = %f, Average2 = %f \n\r",Average0, Average1, Average2);
s1725696 13:c087c0f64769 538 pc.printf("Thresh0 = %f , Thresh1 = %f, Thresh2 = %f \n\r",Threshold0, Threshold1, Threshold2);
s1725696 13:c087c0f64769 539
s1725696 13:c087c0f64769 540 bool k = true;
s1725696 13:c087c0f64769 541 while(k == true)
s1725696 13:c087c0f64769 542 {
s1725696 13:c087c0f64769 543 if(button_motorcal == false)
s1725696 13:c087c0f64769 544 {
s1725696 13:c087c0f64769 545 calibrate(); // Calibrate threshold for 3 muscles
s1725696 13:c087c0f64769 546 k = false;
s1725696 13:c087c0f64769 547 }
s1725696 13:c087c0f64769 548 wait(0.2f); // Wait to avoid bouncing of button
s1725696 13:c087c0f64769 549 }
s1725696 13:c087c0f64769 550
s1725696 13:c087c0f64769 551 bool h = true;
s1725696 13:c087c0f64769 552 while(h == true)
s1725696 13:c087c0f64769 553 {
s1725696 13:c087c0f64769 554 if (button_demo == false)
s1725696 13:c087c0f64769 555 {
s1725696 13:c087c0f64769 556 switch_to_calibrate(); // Switch state of calibration (which muscle)
s1725696 13:c087c0f64769 557 h = false;
s1725696 13:c087c0f64769 558 }
s1725696 13:c087c0f64769 559
s1725696 13:c087c0f64769 560 wait(0.2f); // Wait to avoid bouncing of button
s1725696 13:c087c0f64769 561 }
s1725696 13:c087c0f64769 562 }
s1725696 14:abc125dcc246 563
s1725696 14:abc125dcc246 564 // Turning all leds off
s1725696 14:abc125dcc246 565 led_red == 1;
s1725696 14:abc125dcc246 566 led_blue == 1;
s1725696 14:abc125dcc246 567 led_green == 1;
s1725696 10:56136a0da8c1 568 }
s1725696 0:cb8857cf3ea4 569
s1725696 10:56136a0da8c1 570 // START
s1725696 0:cb8857cf3ea4 571 // To move the robot to the starting position: middle
s1725696 10:56136a0da8c1 572 void start_mode()
s1725696 4:8183e7b228f0 573 {
s1725696 12:b2b082e73ef1 574 // move to middle, only motor1 has to do something, the other one you can move yourself during the calibration
s1725696 18:db53ac017f50 575 int a = tower_end_position - ((tower_end_position - tower_1_position)/2);
s1725696 18:db53ac017f50 576 pc.printf("position middle = %i, position pen = %i \r\n", a, Counts1(counts1));
s1725696 18:db53ac017f50 577
s1725696 14:abc125dcc246 578 //translation home
s1725696 18:db53ac017f50 579 if (Counts1(counts1) > a)
s1725696 14:abc125dcc246 580 {
s1725696 18:db53ac017f50 581 translation_start(1,1.0);
s1725696 18:db53ac017f50 582 pc.printf("start to 1 \r\n");
s1725696 14:abc125dcc246 583 }
s1725696 14:abc125dcc246 584 else {
s1725696 18:db53ac017f50 585 translation_start(0,1.0);
s1725696 18:db53ac017f50 586 pc.printf("start to 0 \r\n");
s1725696 14:abc125dcc246 587 }
s1725696 18:db53ac017f50 588 while(true){
s1725696 18:db53ac017f50 589 if ((Counts1(counts1) > (a - 500)) && (Counts1(counts1) < (a + 500)))
s1725696 14:abc125dcc246 590 {
s1725696 14:abc125dcc246 591 translation_stop();
s1725696 18:db53ac017f50 592 pc.printf("stop \r\n");
s1725696 18:db53ac017f50 593 break;
s1725696 14:abc125dcc246 594 }
s1725696 4:8183e7b228f0 595 }
s1725696 18:db53ac017f50 596 }
s1574396 22:be961d1830bb 597
s1725696 10:56136a0da8c1 598 // OPERATING
s1725696 0:cb8857cf3ea4 599 // To control the robot with EMG signals
s1725696 17:65943f6e11dc 600 // Function for using muscle for direction control
s1725696 17:65943f6e11dc 601 void Directioncontrol()
s1725696 20:645483d7470c 602 {
s1725696 17:65943f6e11dc 603 switch (currentdirection)
s1725696 17:65943f6e11dc 604 {
s1725696 17:65943f6e11dc 605 case Pos_RB:
s1725696 17:65943f6e11dc 606
s1574396 22:be961d1830bb 607 out1 = out1;
s1574396 22:be961d1830bb 608 out2 = out2;
s1725696 17:65943f6e11dc 609 directionchanged = false;
s1725696 21:bf09f236c9fa 610 led_red == 0;
s1574396 22:be961d1830bb 611
s1725696 17:65943f6e11dc 612
s1725696 17:65943f6e11dc 613 if (Average2 > Threshold2)
s1725696 17:65943f6e11dc 614 {
s1725696 17:65943f6e11dc 615 currentdirection = Pos_LB;
s1725696 17:65943f6e11dc 616 pc.printf("\r\n direction = Pos_LB\r\n");
s1725696 17:65943f6e11dc 617 directionchanged = true;
s1725696 17:65943f6e11dc 618 }
s1574396 22:be961d1830bb 619 wait(0.5); // wait 0.5 seconds, otherwise it goes directly to the next case
s1725696 17:65943f6e11dc 620 break;
s1725696 17:65943f6e11dc 621
s1725696 17:65943f6e11dc 622 case Pos_LB:
s1574396 22:be961d1830bb 623
s1574396 22:be961d1830bb 624 out1 = out1 * -1.0;
s1574396 22:be961d1830bb 625 out2 = out2;
s1725696 17:65943f6e11dc 626 directionchanged = false;
s1725696 21:bf09f236c9fa 627 led_blue == 0;
s1574396 22:be961d1830bb 628
s1725696 17:65943f6e11dc 629 if (Average2 > Threshold2)
s1725696 17:65943f6e11dc 630 {
s1725696 17:65943f6e11dc 631 currentdirection = Pos_RO;
s1725696 17:65943f6e11dc 632 pc.printf("\r\n direction = Pos_RO\r\n");
s1725696 17:65943f6e11dc 633 directionchanged = true;
s1725696 17:65943f6e11dc 634 }
s1725696 20:645483d7470c 635 wait(0.5);
s1725696 17:65943f6e11dc 636 break;
s1725696 17:65943f6e11dc 637
s1725696 17:65943f6e11dc 638 case Pos_RO:
s1725696 17:65943f6e11dc 639
s1574396 22:be961d1830bb 640 out1 = out1;
s1574396 22:be961d1830bb 641 out2 = out2 * -1.0;
s1725696 17:65943f6e11dc 642 directionchanged = false;
s1725696 21:bf09f236c9fa 643 led_green == 0;
s1574396 22:be961d1830bb 644
s1725696 17:65943f6e11dc 645 if (Average2 > Threshold2)
s1725696 17:65943f6e11dc 646 {
s1725696 17:65943f6e11dc 647 currentdirection = Pos_LO;
s1725696 17:65943f6e11dc 648 pc.printf("\r\n direction = Pos_LO\r\n");
s1725696 17:65943f6e11dc 649 directionchanged = true;
s1725696 17:65943f6e11dc 650 }
s1725696 20:645483d7470c 651 wait(0.5);
s1725696 17:65943f6e11dc 652 break;
s1725696 17:65943f6e11dc 653
s1725696 17:65943f6e11dc 654 case Pos_LO:
s1574396 22:be961d1830bb 655 out1 = out1 * -1.0;
s1574396 22:be961d1830bb 656 out2 = out2 * -1.0;
s1725696 17:65943f6e11dc 657 directionchanged = false;
s1725696 21:bf09f236c9fa 658 led_red == 0;
s1725696 21:bf09f236c9fa 659 led_blue == 0;
s1725696 21:bf09f236c9fa 660 led_green == 0;
s1574396 22:be961d1830bb 661
s1725696 17:65943f6e11dc 662
s1725696 17:65943f6e11dc 663 if (Average2 > Threshold2)
s1725696 17:65943f6e11dc 664 {
s1725696 17:65943f6e11dc 665 currentdirection = Pos_RB;
s1725696 17:65943f6e11dc 666 pc.printf("\r\n direction = Pos_RB\r\n");
s1725696 17:65943f6e11dc 667 directionchanged = true;
s1725696 17:65943f6e11dc 668 }
s1725696 20:645483d7470c 669 wait(0.5);
s1725696 17:65943f6e11dc 670 break;
s1725696 17:65943f6e11dc 671 }
s1725696 19:a3a7baab9dbc 672 }
s1725696 17:65943f6e11dc 673
s1725696 17:65943f6e11dc 674 // PID controller
s1725696 17:65943f6e11dc 675 // To control the input signal before it goes into the motor control
s1725696 17:65943f6e11dc 676 // PID execution
s1725696 17:65943f6e11dc 677 double PID_control(volatile double error, const double kp, const double ki, const double kd, volatile double &error_int, volatile double &error_prev)
s1725696 17:65943f6e11dc 678 {
s1725696 17:65943f6e11dc 679 // P control
s1725696 17:65943f6e11dc 680 double u_k = kp * error;
s1725696 17:65943f6e11dc 681
s1725696 17:65943f6e11dc 682 // I control
s1725696 17:65943f6e11dc 683 error_int = error_int + (Ts * error);
s1725696 17:65943f6e11dc 684 double u_i = ki * error_int;
s1725696 17:65943f6e11dc 685
s1725696 17:65943f6e11dc 686 // D control
s1725696 17:65943f6e11dc 687 double error_deriv = (error - error_prev);
s1725696 17:65943f6e11dc 688 double u_d = kd * error_deriv;
s1725696 17:65943f6e11dc 689 error_prev = error;
s1725696 17:65943f6e11dc 690
s1725696 17:65943f6e11dc 691 return u_k + u_i + u_d;
s1725696 17:65943f6e11dc 692 }
s1725696 17:65943f6e11dc 693
s1725696 16:37b491eac34b 694 void boundaries()
s1725696 16:37b491eac34b 695 {
s1725696 16:37b491eac34b 696 double q2tot = q2 + dq2;
s1725696 16:37b491eac34b 697 if (q2tot > q2end)
s1725696 16:37b491eac34b 698 {
s1725696 16:37b491eac34b 699 dq2 = 0;
s1725696 16:37b491eac34b 700 } //kan ook zeggen q2end-q2 is dat dan juiste waarde of moet q2-q2end?
s1725696 16:37b491eac34b 701 else if (q2tot < q2start)
s1725696 16:37b491eac34b 702 {
s1725696 16:37b491eac34b 703 dq2 = 0;
s1725696 16:37b491eac34b 704 }
s1725696 16:37b491eac34b 705 }
s1725696 16:37b491eac34b 706
s1725696 16:37b491eac34b 707 void motor_control()
s1725696 12:b2b082e73ef1 708 {
s1725696 16:37b491eac34b 709 // servocontrol(); // make sure the servo is used in this mode, maybe attach to a ticker?
s1725696 17:65943f6e11dc 710
s1725696 17:65943f6e11dc 711 // filtering emg
s1725696 17:65943f6e11dc 712
s1725696 17:65943f6e11dc 713 if (Average0 > Threshold0)
s1725696 17:65943f6e11dc 714 {
s1725696 17:65943f6e11dc 715 desired_x = 1.0;
s1725696 17:65943f6e11dc 716 }
s1725696 20:645483d7470c 717 else
s1725696 20:645483d7470c 718 {
s1725696 20:645483d7470c 719 desired_x = 0.0;
s1725696 20:645483d7470c 720 }
s1725696 17:65943f6e11dc 721
s1725696 17:65943f6e11dc 722 if (Average1 > Threshold1)
s1725696 17:65943f6e11dc 723 {
s1725696 17:65943f6e11dc 724 desired_y = 1.0;
s1725696 17:65943f6e11dc 725 }
s1725696 20:645483d7470c 726 else
s1725696 20:645483d7470c 727 {
s1725696 20:645483d7470c 728 desired_y = 0.0;
s1725696 20:645483d7470c 729 }
s1725696 17:65943f6e11dc 730
s1574396 22:be961d1830bb 731 // calling functions
s1725696 17:65943f6e11dc 732
s1725696 17:65943f6e11dc 733
s1725696 17:65943f6e11dc 734 // motor control
s1725696 20:645483d7470c 735 out1 = desired_x; //control x-direction
s1725696 20:645483d7470c 736 out2 = desired_y; //control y-direction
s1574396 22:be961d1830bb 737 Directioncontrol();
s1725696 16:37b491eac34b 738 vdesx = out1 * 20.0; //speed x-direction
s1725696 16:37b491eac34b 739 vdesy = out2 * 20.0; //speed y-direction
s1725696 16:37b491eac34b 740
s1725696 18:db53ac017f50 741 q1 = Counts2(counts2) * alpha + q1start; //counts to rotation (rad)
s1725696 18:db53ac017f50 742 q2 = Counts1(counts1)* beta + q2start; //counts to translation (mm)
s1725696 17:65943f6e11dc 743 MPe = el_1 - el_2 + q2; //x location end effector, x-axis along the translation
s1725696 16:37b491eac34b 744 xe = cos(q1) * MPe; //x location in frame 0
s1725696 16:37b491eac34b 745 ye = sin(q1) * MPe; //y location in frame 0
s1725696 16:37b491eac34b 746 gamma = 1.0 /((-1.0 * ye * sin(q1)) - (xe * cos(q1))); //(1 / det(J'')inverse)
s1725696 16:37b491eac34b 747 dq1 = gamma * delta_t * (sin(q1) * vdesx - cos(q1) * vdesy); //target rotation
s1725696 20:645483d7470c 748 dq2 = gamma * delta_t * (xe * vdesx + ye * vdesy) * -1.0; //target translation
s1574396 22:be961d1830bb 749 //boundaries();
s1725696 16:37b491eac34b 750 dC1 = PID_control( dq1, Rot_Kp, Rot_Ki, Rot_Kd, Rot_error, Rot_prev_error) / alpha; //target rotation to counts
s1725696 16:37b491eac34b 751 dC2 = PID_control( dq2, Trans_Kp, Trans_Ki, Trans_Kd, Trans_error, Trans_prev_error) / beta; //target translation to counts
s1725696 16:37b491eac34b 752 pwm1 = 3.0 * (dC1 / delta_t) / 8400.0; //
s1574396 22:be961d1830bb 753 pwm2 = 7.0 * (dC2 / delta_t) / 8400.0; //
s1725696 18:db53ac017f50 754 dirpin_1.write(pwm2 < 0); // translatie
s1725696 18:db53ac017f50 755 pwmpin_1 = fabs (pwm2);
s1725696 18:db53ac017f50 756 dirpin_2.write(pwm1 < 0); // rotatie
s1725696 18:db53ac017f50 757 pwmpin_2 = fabs (pwm1);
s1725696 16:37b491eac34b 758 }
s1725696 0:cb8857cf3ea4 759
s1725696 10:56136a0da8c1 760 // DEMO
s1725696 0:cb8857cf3ea4 761 // To control the robot with a written code and write 'HELLO'
s1725696 4:8183e7b228f0 762 // Voor het laatst bewaren
s1725696 10:56136a0da8c1 763 void demo_mode()
s1725696 10:56136a0da8c1 764 {
s1725696 10:56136a0da8c1 765 // code here
s1725696 10:56136a0da8c1 766 }
s1725696 0:cb8857cf3ea4 767
s1725696 10:56136a0da8c1 768 // FAILURE
s1725696 0:cb8857cf3ea4 769 // To shut down the robot after an error etc
s1725696 13:c087c0f64769 770 void failure_mode()
s1725696 10:56136a0da8c1 771 {
s1725696 18:db53ac017f50 772 if (button_emergency == false) // condition for MOTOR_CAL --> FAILURE; button_emergency press
s1725696 18:db53ac017f50 773 {
s1725696 18:db53ac017f50 774 led_red == 0; // turning red led on to show emergency mode
s1725696 14:abc125dcc246 775
s1725696 18:db53ac017f50 776 // all pwmpins zero
s1725696 18:db53ac017f50 777 pwmpin_1 = 0.0;
s1725696 18:db53ac017f50 778 pwmpin_2 = 0.0;
s1725696 14:abc125dcc246 779
s1725696 18:db53ac017f50 780 // Servo up?
s1725696 18:db53ac017f50 781 // myservo = 0.1;
s1725696 14:abc125dcc246 782
s1725696 18:db53ac017f50 783 pc.printf("\r\nEmergency mode, reset system to continue\r\n");
s1725696 18:db53ac017f50 784 }
s1725696 10:56136a0da8c1 785 }
s1725696 0:cb8857cf3ea4 786
s1725696 0:cb8857cf3ea4 787 // Main function
s1725696 4:8183e7b228f0 788 // -----------------------------------------------------------------------------
s1725696 0:cb8857cf3ea4 789 int main()
s1725696 0:cb8857cf3ea4 790 {
s1725696 0:cb8857cf3ea4 791 pc.baud(115200); // For TeraTerm, the baudrate, set also in TeraTerm itself!
s1725696 0:cb8857cf3ea4 792 pc.printf("Start code\r\n"); // To check if the program starts
s1725696 9:d7a6a3619576 793 pwmpin_1.period_us(60); // Setting period for PWM
s1725696 17:65943f6e11dc 794 process_tick.attach(&processing_emg,T); // EMG signals must be filtered all the time! EMG signals filtered every T sec.
s1725696 18:db53ac017f50 795 emergency.attach(&failure_mode,0.01); // To make sure you can go to emergency mode all the time
s1725696 1:1a8211e1f3f3 796
s1725696 1:1a8211e1f3f3 797 while(true){
s1725696 6:f495a77c2c95 798 // timer
s1725696 6:f495a77c2c95 799 clock_t start; // start the timer
s1725696 6:f495a77c2c95 800 start = clock();
s1725696 9:d7a6a3619576 801 time_overall = (clock() - start) / (double) CLOCKS_PER_SEC;
s1725696 14:abc125dcc246 802 myservo = 0.1; // Keep the pen lifted until servo function is called (operation mode)
s1725696 5:3581013d4505 803
s1725696 6:f495a77c2c95 804 //pc.printf("potmeter value = %f ", potmeter_value);
s1725696 6:f495a77c2c95 805 //pc.printf("counts = %i\r\n", counts);
s1725696 5:3581013d4505 806
s1725696 6:f495a77c2c95 807 // With the help of a switch loop and states we can switch between states and the robot knows what to do
s1725696 9:d7a6a3619576 808 switch(CurrentState)
s1725696 6:f495a77c2c95 809 {
s1725696 6:f495a77c2c95 810 case WAIT:
s1725696 6:f495a77c2c95 811
s1725696 6:f495a77c2c95 812 if(StateChanged) // so if StateChanged is true
s1725696 6:f495a77c2c95 813 {
s1725696 18:db53ac017f50 814 pc.printf("\r\nState is WAIT\r\n");
s1725696 10:56136a0da8c1 815
s1725696 6:f495a77c2c95 816 // Execute WAIT mode
s1725696 10:56136a0da8c1 817 wait_mode();
s1725696 10:56136a0da8c1 818
s1725696 6:f495a77c2c95 819 StateChanged = false; // the state is still WAIT
s1725696 6:f495a77c2c95 820 }
s1725696 6:f495a77c2c95 821
s1725696 12:b2b082e73ef1 822 if(button_motorcal == false) // condition for WAIT --> MOTOR_CAl; button_motorcal press
s1725696 6:f495a77c2c95 823 {
s1725696 6:f495a77c2c95 824 CurrentState = MOTOR_CAL;
s1725696 18:db53ac017f50 825 pc.printf("\r\nState is MOTOR_CAL\r\n");
s1725696 7:ec5add330cb3 826 StateChanged = true;
s1725696 7:ec5add330cb3 827 }
s1725696 6:f495a77c2c95 828
s1725696 6:f495a77c2c95 829 break;
s1725696 6:f495a77c2c95 830
s1725696 6:f495a77c2c95 831 case MOTOR_CAL:
s1725696 6:f495a77c2c95 832
s1725696 6:f495a77c2c95 833 if(StateChanged) // so if StateChanged is true
s1725696 6:f495a77c2c95 834 {
s1725696 6:f495a77c2c95 835 // Execute MOTOR_CAL mode
s1725696 10:56136a0da8c1 836 motor_calibration();
s1725696 10:56136a0da8c1 837
s1725696 6:f495a77c2c95 838 StateChanged = false; // the state is still MOTOR_CAL
s1725696 6:f495a77c2c95 839 }
s1725696 6:f495a77c2c95 840
s1725696 18:db53ac017f50 841 if((pwmpin_1 < 0.01) && (pwmpin_2 < 0.01)) // condition for MOTOR_CAL --> EMG_CAL; 3s and motors stopped moving
s1725696 6:f495a77c2c95 842 {
s1725696 6:f495a77c2c95 843 CurrentState = EMG_CAL;
s1725696 18:db53ac017f50 844 pc.printf("\r\nState is EMG_CAL\r\n");
s1725696 6:f495a77c2c95 845 StateChanged = true;
s1725696 6:f495a77c2c95 846 }
s1725696 18:db53ac017f50 847
s1725696 6:f495a77c2c95 848 break;
s1725696 6:f495a77c2c95 849
s1725696 6:f495a77c2c95 850 case EMG_CAL:
s1725696 6:f495a77c2c95 851
s1725696 6:f495a77c2c95 852 if(StateChanged) // so if StateChanged is true
s1725696 6:f495a77c2c95 853 {
s1725696 6:f495a77c2c95 854 // Execute EMG_CAL mode
s1725696 10:56136a0da8c1 855 emg_calibration();
s1725696 10:56136a0da8c1 856
s1725696 6:f495a77c2c95 857 StateChanged = false; // state is still EMG_CAL
s1725696 6:f495a77c2c95 858 }
s1725696 6:f495a77c2c95 859
s1725696 18:db53ac017f50 860 if((Average0 < 0.04) && (Average1 < 0.04) && (Average2 < 0.04)) // condition for EMG_CAL --> START; 5s and EMG is low
s1725696 6:f495a77c2c95 861 {
s1725696 6:f495a77c2c95 862 CurrentState = START;
s1725696 18:db53ac017f50 863 pc.printf("\r\nState is START\r\n");
s1725696 7:ec5add330cb3 864 StateChanged = true;
s1725696 7:ec5add330cb3 865 }
s1725696 7:ec5add330cb3 866
s1725696 6:f495a77c2c95 867 break;
s1725696 6:f495a77c2c95 868
s1725696 6:f495a77c2c95 869 case START:
s1725696 6:f495a77c2c95 870
s1725696 6:f495a77c2c95 871 if(StateChanged) // so if StateChanged is true
s1725696 6:f495a77c2c95 872 {
s1725696 6:f495a77c2c95 873 // Execute START mode
s1725696 10:56136a0da8c1 874 start_mode();
s1725696 10:56136a0da8c1 875
s1725696 18:db53ac017f50 876 pc.printf("pwmpin_1 = %f pwmpin_2 = %f \r\n", pwmpin_1, pwmpin_2);
s1725696 10:56136a0da8c1 877
s1725696 6:f495a77c2c95 878 StateChanged = false; // state is still START
s1725696 6:f495a77c2c95 879 }
s1725696 6:f495a77c2c95 880
s1725696 18:db53ac017f50 881 if((pwmpin_1 < 0.01) && (pwmpin_2 < 0.01)) // condition for START --> OPERATING; 5s and motors stopped moving
s1725696 6:f495a77c2c95 882 {
s1725696 6:f495a77c2c95 883 CurrentState = OPERATING;
s1725696 18:db53ac017f50 884 pc.printf("\r\nState is OPERATING\r\n");
s1725696 6:f495a77c2c95 885 StateChanged = true;
s1725696 6:f495a77c2c95 886 }
s1725696 18:db53ac017f50 887
s1725696 6:f495a77c2c95 888 break;
s1725696 6:f495a77c2c95 889
s1725696 6:f495a77c2c95 890 case OPERATING:
s1725696 6:f495a77c2c95 891
s1725696 6:f495a77c2c95 892 if(StateChanged) // so if StateChanged is true
s1725696 6:f495a77c2c95 893 {
s1725696 6:f495a77c2c95 894 // Execute OPERATING mode
s1725696 17:65943f6e11dc 895 while(true)
s1725696 16:37b491eac34b 896 {
s1725696 16:37b491eac34b 897 motor_control();
s1725696 16:37b491eac34b 898 pc.printf("PWM_rot = %f PWM_trans = %f VdesX = %f VdesY = %f \n\r",pwm1,pwm2,vdesx,vdesy);
s1574396 22:be961d1830bb 899 pc.printf("out1 = %f out2 = %f \n\r", out1, out2);
s1574396 22:be961d1830bb 900 //pc.printf("Average0 = %f Average1 = %f Average2 = %f\r\n", Average0,Average1,Average2);
s1725696 17:65943f6e11dc 901
s1725696 17:65943f6e11dc 902 if(button_wait == false) // condition OPERATING --> WAIT; button_wait press
s1725696 17:65943f6e11dc 903 {
s1725696 17:65943f6e11dc 904 CurrentState = WAIT;
s1725696 18:db53ac017f50 905 pc.printf("\r\nState is WAIT\r\n");
s1725696 17:65943f6e11dc 906 StateChanged = true;
s1725696 17:65943f6e11dc 907 break;
s1725696 17:65943f6e11dc 908 }
s1725696 17:65943f6e11dc 909
s1725696 16:37b491eac34b 910 wait(delta_t);
s1725696 16:37b491eac34b 911 }
s1725696 10:56136a0da8c1 912
s1725696 6:f495a77c2c95 913 StateChanged = false; // state is still OPERATING
s1725696 6:f495a77c2c95 914 }
s1725696 6:f495a77c2c95 915
s1725696 6:f495a77c2c95 916 break;
s1725696 20:645483d7470c 917
s1725696 6:f495a77c2c95 918 // no default
s1725696 4:8183e7b228f0 919 }
s1725696 6:f495a77c2c95 920
s1725696 6:f495a77c2c95 921 // while loop does not have to loop every time
s1725696 5:3581013d4505 922 }
s1725696 5:3581013d4505 923
s1725696 0:cb8857cf3ea4 924 }