The code without functions and variables filled in

Dependencies:   HIDScope Servo mbed QEI biquadFilter

Committer:
s1574396
Date:
Fri Nov 02 08:11:09 2018 +0000
Revision:
22:be961d1830bb
Parent:
21:bf09f236c9fa
Child:
23:cc8b95d7eb57
mooie tekeningen maken

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