Minor BioRobotics BMT Hierbij publish ik mijn code public ter inspiratie voor komende jaarlagen. Het gaat om een serial robot met twee links en een haak als end-effector. Veel plezier ermee!

Dependencies:   mbed QEI HIDScope biquadFilter MODSERIAL FastPWM

Committer:
fb07
Date:
Tue Oct 29 16:13:50 2019 +0000
Revision:
13:db1a8b51706b
Parent:
12:f5dc65f1c27b
Child:
14:236ae2d7ec41
Motor_calibration() in state machine zetten niet gelukt. Revisie voor het toevoegen van de motorcontroller

Who changed what in which revision?

UserRevisionLine numberNew contents of line
fb07 2:45a85caaebfb 1 // Project BioRobotics - Opening a Door - Group 13 2019/2020
fb07 2:45a85caaebfb 2 // Dion ten Berge - s1864734
fb07 2:45a85caaebfb 3 // Bas Rutteman - s1854305
fb07 2:45a85caaebfb 4 // Nick in het Veld - s1915584
fb07 2:45a85caaebfb 5 // Marleen van der Weij - s1800078
fb07 2:45a85caaebfb 6 // Mevlid Yildirim - s2005735
fb07 2:45a85caaebfb 7
fb07 5:7e2c6d2235fe 8 /* To-Do
fb07 5:7e2c6d2235fe 9 1. Kd, Ki, Kp waardes bepalen
fb07 5:7e2c6d2235fe 10 2. Filter cutoff frequentie bepalen, zie https://github.com/tomlankhorst/biquad
fb07 5:7e2c6d2235fe 11 3. Grenswaarde EMG signaal na het filteren
fb07 5:7e2c6d2235fe 12 */
fb07 2:45a85caaebfb 13
fb07 2:45a85caaebfb 14 //*****************************************************************************
fb07 2:45a85caaebfb 15 // 1. Libraries ******************************************************************
fb07 2:45a85caaebfb 16 //*****************************************************************************
RobertoO 0:67c50348f842 17 #include "mbed.h"
fb07 2:45a85caaebfb 18 #include "HIDScope.h"
fb07 2:45a85caaebfb 19 #include "QEI.h"
RobertoO 1:b862262a9d14 20 #include "MODSERIAL.h"
fb07 2:45a85caaebfb 21 #include "BiQuad.h"
fb07 2:45a85caaebfb 22 #include "FastPWM.h"
fb07 2:45a85caaebfb 23
fb07 2:45a85caaebfb 24 //*****************************************************************************
fb07 2:45a85caaebfb 25 // 2. States ******************************************************************
fb07 2:45a85caaebfb 26 //*****************************************************************************
fb07 12:f5dc65f1c27b 27 enum States {StartWait, MotorCalibration, EMGCalibration, Homing, Demo, Operating, EmergencyMode, Idle}; //All robot states
fb07 12:f5dc65f1c27b 28 States State;
RobertoO 0:67c50348f842 29
fb07 2:45a85caaebfb 30 //*****************************************************************************
fb07 5:7e2c6d2235fe 31 // 3. (Global) Variables ***********************************************************
fb07 2:45a85caaebfb 32 //*****************************************************************************
fb07 5:7e2c6d2235fe 33 // 3.1 Tickers *****************************************************************
fb07 5:7e2c6d2235fe 34 Ticker ticker_mainloop; // The ticker which runs the mainloop
fb07 5:7e2c6d2235fe 35 Ticker ticker_hidscope; // The ticker which sends data to the HIDScope server
fb07 5:7e2c6d2235fe 36
fb07 5:7e2c6d2235fe 37 // 3.2 General variables *******************************************************
fb07 5:7e2c6d2235fe 38
fb07 5:7e2c6d2235fe 39 MODSERIAL pc(USBTX, USBRX); // Serial communication with the board
fb07 5:7e2c6d2235fe 40 QEI encoder_motor1(D12,D13,NC,64); // Defines encoder for motor 1
fb07 5:7e2c6d2235fe 41 QEI encoder_motor2(D10,D11,NC,64); // Defines encoder for motor 1
fb07 5:7e2c6d2235fe 42 double f=1/100; // Frequency
fb07 5:7e2c6d2235fe 43 const double Ts = f/10; // Sampletime
fb07 5:7e2c6d2235fe 44 HIDScope scope(2); // Amount of HIDScope servers
fb07 10:a60b369c1711 45
fb07 5:7e2c6d2235fe 46
fb07 5:7e2c6d2235fe 47 // 3.3 BiQuad Filters **********************************************************
fb07 5:7e2c6d2235fe 48 static BiQuad notchfilter(9.97761e-01, -1.97095e+00, 9.97761e-01, -1.97095e+00, 9.95522e-01);
fb07 5:7e2c6d2235fe 49 static BiQuad highfilter(9.56543e-01, -1.91309e+00, 9.56543e-01, -1.91120e+00, 9.14976e-01);
fb07 5:7e2c6d2235fe 50 static BiQuad LowPassFilter( 4.12535e-02, 8.25071e-02, 4.12535e-02, -1.34897e+00, 5.13982e-01 );
RobertoO 0:67c50348f842 51
fb07 5:7e2c6d2235fe 52 // 3.4 Hardware ***************************************************************
fb07 5:7e2c6d2235fe 53 //3.4a Leds
fb07 5:7e2c6d2235fe 54 DigitalOut led_red(LED_RED); // Defines the red led on the K64 board (0=on, 1 = off)
fb07 5:7e2c6d2235fe 55 DigitalOut led_green(LED_GREEN); // Defines the green led on the K64 board (0=on, 1 = off)
fb07 5:7e2c6d2235fe 56 DigitalOut led_blue(LED_BLUE); // Defines the blue led on the K64 board (0=on, 1 = off)
fb07 5:7e2c6d2235fe 57 // FastPWM led1(D8); //CODE DOES NOT WORK WITH D8 PIN DEFINED //Defines Led1 on the BioRobotics Shield
fb07 5:7e2c6d2235fe 58 FastPWM led2(D9); //Defines Led2 on the BioRobotics Shield
fb07 5:7e2c6d2235fe 59
fb07 5:7e2c6d2235fe 60 //3.4b Potmeters and buttons
fb07 5:7e2c6d2235fe 61 AnalogIn pot1_links(A5); //Defines potmeter1 on the BioRobotics Shield
fb07 5:7e2c6d2235fe 62 AnalogIn pot2_rechts(A4); //Defines potmeter2 on the BioRobotics Shield
fb07 5:7e2c6d2235fe 63 DigitalIn button1(D2); //Defines button1 on the BioRobotics Shield
fb07 5:7e2c6d2235fe 64 DigitalIn button2(D3); //Defines button2 on the BioRobotics Shield
fb07 5:7e2c6d2235fe 65 DigitalIn sw2(SW2); //Defines button SW2 on the K64 board
fb07 5:7e2c6d2235fe 66 DigitalIn sw3(SW3); //Defines button SW3 on the K64 board
fb07 5:7e2c6d2235fe 67
fb07 5:7e2c6d2235fe 68 //3.4c Motors
fb07 5:7e2c6d2235fe 69 DigitalOut motor1DirectionPin(D7); // motor 1 direction control (1=cw, 0=ccw)
fb07 5:7e2c6d2235fe 70 FastPWM motor1(D6); // motor 1 velocity control (between 0-1)
fb07 5:7e2c6d2235fe 71 FastPWM motor2(D5); // motor 2 velocity control (between 0-1)
fb07 5:7e2c6d2235fe 72 DigitalOut motor2DirectionPin(D4); // motor 2 direction control (1=cw, 0=ccw)
fb07 11:a3fd9d5144bb 73 bool motor1_calibrated=false;
fb07 11:a3fd9d5144bb 74 bool motor2_calibrated=false;
fb07 5:7e2c6d2235fe 75
fb07 10:a60b369c1711 76 // 3.5 Motor 1 variables ***************************************************************
fb07 5:7e2c6d2235fe 77 //3.5a PID-controller motor 1
fb07 5:7e2c6d2235fe 78 double counts_per_rad_motor1 = (131.25*32)/(2*3.14159265359); // (gear ratio * counts per revolution) / (2* pi) = ~668.45 counts per rad
fb07 5:7e2c6d2235fe 79 static double error_integral_motor1 = 0;
fb07 5:7e2c6d2235fe 80 double Yref_motor1;
fb07 5:7e2c6d2235fe 81 double kp_motor1;
fb07 5:7e2c6d2235fe 82 double Ki_motor1;
fb07 5:7e2c6d2235fe 83 double Kd_motor1;
fb07 2:45a85caaebfb 84
fb07 5:7e2c6d2235fe 85 double positie_motor1; //counts encoder
fb07 5:7e2c6d2235fe 86 double error1_motor1;
fb07 5:7e2c6d2235fe 87 double error1_prev_motor1;
fb07 5:7e2c6d2235fe 88 double error1_derivative_motor1;
fb07 5:7e2c6d2235fe 89 double error1_derivative_filtered_motor1;
fb07 5:7e2c6d2235fe 90 double P_motor1;
fb07 5:7e2c6d2235fe 91
fb07 10:a60b369c1711 92 double positie_verschil_motor1;
fb07 10:a60b369c1711 93 double positie_prev_motor1;
fb07 10:a60b369c1711 94
fb07 10:a60b369c1711 95 // 3.5 Motor 2 variables ***************************************************************
fb07 5:7e2c6d2235fe 96 //3.5b PID-controller motor 2
fb07 5:7e2c6d2235fe 97 double counts_per_rad_motor2 = (131.25*32)/(2*3.14159265359); // (gear ratio * counts per revolution) / (2* pi) = ~668.45 counts per rad
fb07 5:7e2c6d2235fe 98 static double error_integral_motor2 = 0;
fb07 5:7e2c6d2235fe 99 double Yref_motor2;
fb07 5:7e2c6d2235fe 100 double kp_motor2;
fb07 5:7e2c6d2235fe 101 double Ki_motor2;
fb07 5:7e2c6d2235fe 102 double Kd_motor2;
fb07 2:45a85caaebfb 103
fb07 5:7e2c6d2235fe 104 double positie_motor2; //counts encoder
fb07 5:7e2c6d2235fe 105 double error1_motor2;
fb07 5:7e2c6d2235fe 106 double error1_prev_motor2;
fb07 5:7e2c6d2235fe 107 double error1_derivative_motor2;
fb07 5:7e2c6d2235fe 108 double error1_derivative_filtered_motor2;
fb07 5:7e2c6d2235fe 109 double P_motor2;
fb07 10:a60b369c1711 110
fb07 10:a60b369c1711 111 double positie_verschil_motor2;
fb07 10:a60b369c1711 112 double positie_prev_motor2;
RobertoO 0:67c50348f842 113
fb07 2:45a85caaebfb 114 //******************************************************************************
fb07 5:7e2c6d2235fe 115 // 4. Functions ****************************************************************
fb07 5:7e2c6d2235fe 116 //******************************************************************************
fb07 5:7e2c6d2235fe 117
fb07 5:7e2c6d2235fe 118 // 4.1 Hidscope ****************************************************************
fb07 5:7e2c6d2235fe 119 void HIDScope() //voor HIDscope
fb07 5:7e2c6d2235fe 120 {
fb07 9:c4fa72ffa1c2 121 scope.set(0, positie_motor1);
fb07 9:c4fa72ffa1c2 122 scope.set(1, positie_prev_motor1); //nog te definieren wat we willen weergeven
fb07 9:c4fa72ffa1c2 123 scope.set(2, positie_verschil_motor1); //nog te definieren wat we willen weergeven
fb07 9:c4fa72ffa1c2 124
fb07 5:7e2c6d2235fe 125 scope.send();
fb07 5:7e2c6d2235fe 126 }
fb07 10:a60b369c1711 127 // 4.x Encoder motor1 ****************************************************************
fb07 9:c4fa72ffa1c2 128 double fencoder_motor1() // bepaalt de positie van de motor
fb07 9:c4fa72ffa1c2 129 {
fb07 9:c4fa72ffa1c2 130 positie_motor1 = encoder_motor1.getPulses(); // haalt encoder waardes op
fb07 9:c4fa72ffa1c2 131 positie_verschil_motor1 = (positie_motor1-positie_prev_motor1)/Ts;
fb07 9:c4fa72ffa1c2 132 positie_prev_motor1 = positie_motor1;
fb07 9:c4fa72ffa1c2 133
fb07 9:c4fa72ffa1c2 134 return positie_motor1; //geeft positie van motor
fb07 9:c4fa72ffa1c2 135 }
fb07 10:a60b369c1711 136 // 4.x Encoder motor2 ****************************************************************
fb07 10:a60b369c1711 137 double fencoder_motor2() // bepaalt de positie van de motor
fb07 10:a60b369c1711 138 {
fb07 10:a60b369c1711 139 positie_motor2 = encoder_motor2.getPulses(); // haalt encoder waardes op
fb07 10:a60b369c1711 140 positie_verschil_motor2 = (positie_motor2-positie_prev_motor2)/Ts;
fb07 10:a60b369c1711 141 positie_prev_motor2 = positie_motor2;
fb07 10:a60b369c1711 142
fb07 10:a60b369c1711 143 return positie_motor2; //geeft positie van motor
fb07 10:a60b369c1711 144 }
fb07 10:a60b369c1711 145
fb07 11:a3fd9d5144bb 146 // 4.xa Calibration motors
fb07 11:a3fd9d5144bb 147
fb07 11:a3fd9d5144bb 148 void motor_calibration()
fb07 10:a60b369c1711 149 {
fb07 11:a3fd9d5144bb 150 // Calibration motor 2
fb07 10:a60b369c1711 151 motor1DirectionPin=0; //direction of the motor
fb07 10:a60b369c1711 152 motor1=1.0;
fb07 13:db1a8b51706b 153 wait(0.1);
fb07 10:a60b369c1711 154 while (abs(positie_verschil_motor1)>5)
fb07 10:a60b369c1711 155 {
fb07 10:a60b369c1711 156 motor1=0.2 ;
fb07 11:a3fd9d5144bb 157 pc.printf("\r\n Motor1 kalibratie = %s", motor1_calibrated ? "true" : "false");
fb07 10:a60b369c1711 158 }
fb07 10:a60b369c1711 159 motor1=0.0;
fb07 11:a3fd9d5144bb 160 motor1_calibrated=true;
fb07 11:a3fd9d5144bb 161 pc.printf("\r\n Motor1 kalibratie = %s", motor1_calibrated ? "true" : "false");
fb07 10:a60b369c1711 162
fb07 11:a3fd9d5144bb 163
fb07 10:a60b369c1711 164
fb07 11:a3fd9d5144bb 165 // Calibration motor 2
fb07 10:a60b369c1711 166 motor2DirectionPin=0; //direction of the motor
fb07 10:a60b369c1711 167 motor2=1.0;
fb07 13:db1a8b51706b 168 wait(0.1);
fb07 10:a60b369c1711 169 while (abs(positie_verschil_motor2)>5)
fb07 10:a60b369c1711 170 {
fb07 10:a60b369c1711 171 motor2=0.2 ;
fb07 11:a3fd9d5144bb 172 pc.printf("\r\n Motor2 kalibratie = %s", motor2_calibrated ? "true" : "false");
fb07 13:db1a8b51706b 173 led2=1;
fb07 10:a60b369c1711 174 }
fb07 10:a60b369c1711 175 motor2=0.0;
fb07 13:db1a8b51706b 176 led2=0;
fb07 11:a3fd9d5144bb 177 motor2_calibrated=true;
fb07 11:a3fd9d5144bb 178 pc.printf("\r\n Motor2 kalibratie = %s", motor2_calibrated ? "true" : "false");
fb07 13:db1a8b51706b 179
fb07 12:f5dc65f1c27b 180
fb07 10:a60b369c1711 181 }
fb07 10:a60b369c1711 182
fb07 5:7e2c6d2235fe 183 // 4.2a PID-Controller motor 1**************************************************
fb07 5:7e2c6d2235fe 184 double PID_controller_motor1()
fb07 5:7e2c6d2235fe 185 {
fb07 5:7e2c6d2235fe 186 //Proportional part
fb07 5:7e2c6d2235fe 187 kp_motor1 = 0.01 ; // moet nog getweaked worden
fb07 5:7e2c6d2235fe 188 double Up_motor1 = kp_motor1 * error1_motor1;
fb07 5:7e2c6d2235fe 189
fb07 5:7e2c6d2235fe 190 //Integral part
fb07 5:7e2c6d2235fe 191 Ki_motor1 = 0.0001; // moet nog getweaked worden
fb07 5:7e2c6d2235fe 192 error_integral_motor1 = error_integral_motor1 + (Ts*error1_motor1); // integrale fout + (de sample tijd * fout)
fb07 5:7e2c6d2235fe 193 double Ui_motor1 = Ki_motor1 * error_integral_motor1; // (fout * integrale fout)
fb07 5:7e2c6d2235fe 194
fb07 5:7e2c6d2235fe 195 //Derivative part
fb07 5:7e2c6d2235fe 196 Kd_motor1 = 0.01 ;// moet nog getweaked worden
fb07 5:7e2c6d2235fe 197 error1_derivative_motor1 = (error1_motor1 - error1_prev_motor1)/Ts; // (Fout - de vorige fout) / tijdstap = afgeleide
fb07 5:7e2c6d2235fe 198 error1_derivative_filtered_motor1 = LowPassFilter.step(error1_derivative_motor1); //derivative wordt gefiltered
fb07 5:7e2c6d2235fe 199 double Ud_motor1 = Kd_motor1 * error1_derivative_filtered_motor1; // (afgeleide gain) * (afgeleide gefilterde fout)
fb07 5:7e2c6d2235fe 200 error1_prev_motor1 = error1_motor1;
fb07 5:7e2c6d2235fe 201
fb07 5:7e2c6d2235fe 202 double P_motor1 = Up_motor1 + Ui_motor1 + Ud_motor1; //sommatie van de u's
fb07 5:7e2c6d2235fe 203
fb07 5:7e2c6d2235fe 204 return P_motor1;
fb07 5:7e2c6d2235fe 205 }
fb07 5:7e2c6d2235fe 206
fb07 5:7e2c6d2235fe 207 // 4.2b PID-Controller motor 2**************************************************
fb07 5:7e2c6d2235fe 208 double PID_controller_motor2()
fb07 5:7e2c6d2235fe 209 {
fb07 5:7e2c6d2235fe 210 //Proportional part
fb07 5:7e2c6d2235fe 211 kp_motor2 = 0.01 ; // moet nog getweaked worden
fb07 5:7e2c6d2235fe 212 double Up_motor2 = kp_motor2 * error1_motor2;
fb07 5:7e2c6d2235fe 213
fb07 5:7e2c6d2235fe 214 //Integral part
fb07 5:7e2c6d2235fe 215 Ki_motor2 = 0.0001; // moet nog getweaked worden
fb07 5:7e2c6d2235fe 216 error_integral_motor2 = error_integral_motor2 + (Ts*error1_motor2); // integrale fout + (de sample tijd * fout)
fb07 5:7e2c6d2235fe 217 double Ui_motor2 = Ki_motor2 * error_integral_motor2; //de fout keer de integrale fout
fb07 5:7e2c6d2235fe 218
fb07 5:7e2c6d2235fe 219 //Derivative part
fb07 5:7e2c6d2235fe 220 Kd_motor2 = 0.01 ;// moet nog getweaked worden
fb07 5:7e2c6d2235fe 221 error1_derivative_motor2 = (error1_motor2 - error1_prev_motor2)/Ts;
fb07 5:7e2c6d2235fe 222 error1_derivative_filtered_motor2 = LowPassFilter.step(error1_derivative_motor2); //derivative wordt gefiltered, dit later aanpassen
fb07 5:7e2c6d2235fe 223 double Ud_motor2 = Kd_motor2 * error1_derivative_filtered_motor2;
fb07 5:7e2c6d2235fe 224 error1_prev_motor2 = error1_motor2;
fb07 5:7e2c6d2235fe 225
fb07 5:7e2c6d2235fe 226 double P_motor2 = Up_motor2 + Ui_motor2 + Ud_motor2; //sommatie van de u's
fb07 5:7e2c6d2235fe 227
fb07 5:7e2c6d2235fe 228 return P_motor2;
fb07 5:7e2c6d2235fe 229 }
fb07 10:a60b369c1711 230
fb07 13:db1a8b51706b 231
fb07 13:db1a8b51706b 232
fb07 5:7e2c6d2235fe 233 // 4.3 State-Machine *******************************************************
fb07 10:a60b369c1711 234
fb07 12:f5dc65f1c27b 235 void state_machine()
fb07 12:f5dc65f1c27b 236 {
fb07 12:f5dc65f1c27b 237 if (sw2==0) {State = EmergencyMode;}
fb07 12:f5dc65f1c27b 238 switch(State)
fb07 12:f5dc65f1c27b 239 {
fb07 12:f5dc65f1c27b 240 case MotorCalibration:
fb07 12:f5dc65f1c27b 241 // pc.printf("\r\n State: MotorCalibration");
fb07 12:f5dc65f1c27b 242 led_blue.write(1);
fb07 12:f5dc65f1c27b 243 led_red.write(1);
fb07 12:f5dc65f1c27b 244 led_green.write(0); //Green Led on when in this state
fb07 12:f5dc65f1c27b 245
fb07 12:f5dc65f1c27b 246 if (motor1_calibrated==true&&motor2_calibrated==true)
fb07 12:f5dc65f1c27b 247 {
fb07 12:f5dc65f1c27b 248 pc.printf("\r\n Motor Calibration is done!");
fb07 12:f5dc65f1c27b 249 State=StartWait;
fb07 12:f5dc65f1c27b 250 }
fb07 12:f5dc65f1c27b 251 else {;} //pc.printf("\r\n Motor Calibration is not done!");}
fb07 12:f5dc65f1c27b 252
fb07 12:f5dc65f1c27b 253
fb07 12:f5dc65f1c27b 254 break;
fb07 12:f5dc65f1c27b 255
fb07 12:f5dc65f1c27b 256 case StartWait:
fb07 12:f5dc65f1c27b 257 // pc.printf("\r\n State: StartWait Button 1 = operation, Button 2 = Demo");
fb07 12:f5dc65f1c27b 258 led_blue.write(0);
fb07 12:f5dc65f1c27b 259 led_red.write(1);
fb07 12:f5dc65f1c27b 260 led_green.write(1);
fb07 12:f5dc65f1c27b 261
fb07 12:f5dc65f1c27b 262 if(button1==0) {State=EMGCalibration;}
fb07 12:f5dc65f1c27b 263 if(button2==0) {State=Demo;}
fb07 12:f5dc65f1c27b 264 break;
fb07 12:f5dc65f1c27b 265 case EMGCalibration:
fb07 12:f5dc65f1c27b 266 // pc.printf("\r\n State: EMGCalibration");
fb07 12:f5dc65f1c27b 267 led_blue.write(1);
fb07 12:f5dc65f1c27b 268 led_red.write(1);
fb07 12:f5dc65f1c27b 269 led_green.write(0);
fb07 12:f5dc65f1c27b 270
fb07 12:f5dc65f1c27b 271 State=Homing;
fb07 12:f5dc65f1c27b 272 break;
fb07 12:f5dc65f1c27b 273 case Homing:
fb07 12:f5dc65f1c27b 274 /* pc.printf("\r\n State: Homing");
fb07 12:f5dc65f1c27b 275 State=Operating; */
fb07 12:f5dc65f1c27b 276 break;
fb07 12:f5dc65f1c27b 277 case Demo:
fb07 12:f5dc65f1c27b 278 pc.printf("\r\n State: Demo");
fb07 12:f5dc65f1c27b 279 led_blue.write(1);
fb07 12:f5dc65f1c27b 280 led_red.write(1);
fb07 13:db1a8b51706b 281 led_green.write(0);
fb07 12:f5dc65f1c27b 282
fb07 12:f5dc65f1c27b 283
fb07 12:f5dc65f1c27b 284 break;
fb07 12:f5dc65f1c27b 285 case Operating:
fb07 12:f5dc65f1c27b 286 /* pc.printf("\r\n State: Operating");
fb07 12:f5dc65f1c27b 287 led_blue.write(1);
fb07 12:f5dc65f1c27b 288 led_red.write(1);
fb07 12:f5dc65f1c27b 289 led_green.write(0);
fb07 12:f5dc65f1c27b 290 wait(0.5);
fb07 12:f5dc65f1c27b 291 led_green.write(1);
fb07 12:f5dc65f1c27b 292 wait(0.5); */
fb07 12:f5dc65f1c27b 293 break;
fb07 12:f5dc65f1c27b 294 case EmergencyMode:
fb07 12:f5dc65f1c27b 295 pc.printf("\r\n State: EMERGENCY MODE! Press RESET to restart");
fb07 12:f5dc65f1c27b 296
fb07 12:f5dc65f1c27b 297 motor1=0;
fb07 12:f5dc65f1c27b 298 motor2=0;
fb07 12:f5dc65f1c27b 299
fb07 12:f5dc65f1c27b 300 led_blue.write(1);
fb07 12:f5dc65f1c27b 301 led_green.write(1);
fb07 12:f5dc65f1c27b 302 //SOS start
fb07 12:f5dc65f1c27b 303 led_red.write(0); // S
fb07 12:f5dc65f1c27b 304 wait(0.5);
fb07 12:f5dc65f1c27b 305 led_red.write(1); //pause
fb07 12:f5dc65f1c27b 306 wait(0.25);
fb07 12:f5dc65f1c27b 307 led_red.write(0); // O
fb07 12:f5dc65f1c27b 308 wait(1.5);
fb07 12:f5dc65f1c27b 309 led_red.write(1); // pause
fb07 12:f5dc65f1c27b 310 wait(0.25);
fb07 12:f5dc65f1c27b 311 led_red.write(0); // S
fb07 12:f5dc65f1c27b 312 wait(0.5);
fb07 12:f5dc65f1c27b 313 //SOS end
fb07 12:f5dc65f1c27b 314 break;
fb07 12:f5dc65f1c27b 315 case Idle:
fb07 12:f5dc65f1c27b 316 /* pc.printf("\r\n Idling..."); */
fb07 12:f5dc65f1c27b 317 break;
fb07 12:f5dc65f1c27b 318
fb07 12:f5dc65f1c27b 319 }
fb07 12:f5dc65f1c27b 320 }
fb07 9:c4fa72ffa1c2 321
fb07 5:7e2c6d2235fe 322 //******************************************************************************
fb07 5:7e2c6d2235fe 323 // 5. Main Loop ****************************************************************
fb07 2:45a85caaebfb 324 //******************************************************************************
fb07 2:45a85caaebfb 325
fb07 2:45a85caaebfb 326 void main_loop() { //Beginning of main_loop()
fb07 5:7e2c6d2235fe 327 // pc.printf("main_loop is running succesfully \r\n"); //confirmation that main_loop is running (als je dit erin zet krijg je elke duizendste dit bericht. Dit is niet gewenst)
fb07 9:c4fa72ffa1c2 328 fencoder_motor1() ;
fb07 10:a60b369c1711 329 fencoder_motor2() ;
fb07 12:f5dc65f1c27b 330 state_machine() ;
fb07 9:c4fa72ffa1c2 331
fb07 5:7e2c6d2235fe 332 // 5.1 Measure Analog and Digital input signals ********************************
fb07 5:7e2c6d2235fe 333 // 5.2 Run state-machine(s) ****************************************************
fb07 5:7e2c6d2235fe 334 // 5.3 Run controller(s) *******************************************************
fb07 5:7e2c6d2235fe 335 // 5.4 Send output signals to digital and PWM output pins **********************
fb07 2:45a85caaebfb 336
fb07 2:45a85caaebfb 337
fb07 2:45a85caaebfb 338 } //Ending of main_loop()
fb07 2:45a85caaebfb 339
fb07 2:45a85caaebfb 340 //******************************************************************************
fb07 5:7e2c6d2235fe 341 // 6. Main function ************************************************************
fb07 2:45a85caaebfb 342 //******************************************************************************
fb07 2:45a85caaebfb 343 int main()
fb07 5:7e2c6d2235fe 344 { //Beginning of Main() Function //All the things we do only once, some relevant things are now missing here: set pwmperiod to 60 microsec. Set Serial comm. Etc. Etc.
fb07 5:7e2c6d2235fe 345 // 6.1 Initialization **********************************************************
RobertoO 0:67c50348f842 346 pc.baud(115200);
fb07 2:45a85caaebfb 347 pc.printf("\r\nStarting Project BioRobotics - Opening a Door " //print Project information
fb07 2:45a85caaebfb 348 "- Group 13 2019/2020 \r\n"
fb07 2:45a85caaebfb 349 "Dion ten Berge - s1864734 \r\n"
fb07 2:45a85caaebfb 350 "Bas Rutteman - s1854305 \r\n"
fb07 2:45a85caaebfb 351 "Nick in het Veld - s1915584 \r\n"
fb07 2:45a85caaebfb 352 "Marleen van der Weij - s1800078 \r\n"
fb07 2:45a85caaebfb 353 "Mevlid Yildirim - s2005735 \r\n");
fb07 5:7e2c6d2235fe 354 led_green.write(1);
fb07 5:7e2c6d2235fe 355 led_red.write(1);
fb07 5:7e2c6d2235fe 356 led_blue.write(0);
fb07 12:f5dc65f1c27b 357 State = MotorCalibration;
fb07 9:c4fa72ffa1c2 358 ticker_mainloop.attach(&main_loop,0.001); // change back to 0.001f //Run the function main_loop 1000 times per second
fb07 9:c4fa72ffa1c2 359 ticker_hidscope.attach(&HIDScope, 0.001); //Ticker for Hidscope, different frequency compared to motors
fb07 11:a3fd9d5144bb 360 motor_calibration();
fb07 10:a60b369c1711 361
fb07 10:a60b369c1711 362
fb07 5:7e2c6d2235fe 363 // 6.2 While loop in main function**********************************************
fb07 2:45a85caaebfb 364 while (true) { } //Is not used but has to remain in the code!!
fb07 2:45a85caaebfb 365
fb07 2:45a85caaebfb 366 } //Ending of Main() Function