De hele robot in 1 keer bam

Dependencies:   mbed QEI Servo HIDScope biquadFilter MODSERIAL FastPWM

Files at this revision

API Documentation at this revision

Comitter:
Jellehierck
Date:
Tue Nov 05 16:49:03 2019 +0000
Parent:
69:bfefdfb04c29
Commit message:
FINAL VERSION: added many comments to code.

Changed in this revision

main.cpp Show annotated file Show diff for this revision Revisions of this file
--- a/main.cpp	Tue Nov 05 10:24:09 2019 +0000
+++ b/main.cpp	Tue Nov 05 16:49:03 2019 +0000
@@ -15,26 +15,26 @@
 */
 
 // PC connections
-HIDScope        scope( 6 );
-MODSERIAL pc(USBTX, USBRX);
+HIDScope        scope( 6 ); // Only to visualize data, not necessary for operation
+MODSERIAL pc(USBTX, USBRX); // Only to visualize data, not necessary for operation
 
 // Buttons
-InterruptIn button1(D11);
-InterruptIn button2(D10);
-InterruptIn switch2(SW2);
-InterruptIn switch3(SW3);
-DigitalIn extButton1(D2);   //Servo button
+InterruptIn button1(D11); // First dynamic button
+InterruptIn button2(D10); // Second dynamic button
+InterruptIn switch2(SW2); // Third dynamic button
+InterruptIn switch3(SW3); // Failure button
+DigitalIn extButton1(D2); // External servo button
 
 // LEDs
-DigitalOut      led_g(LED_GREEN);
-DigitalOut      led_r(LED_RED);
-DigitalOut      led_b(LED_BLUE);
+DigitalOut led_g(LED_GREEN);
+DigitalOut led_r(LED_RED);
+DigitalOut led_b(LED_BLUE);
 
 // Analog EMG inputs
-AnalogIn emg1_in (A0); // Right biceps  -> x axis
-AnalogIn emg2_in (A1); // Left biceps   -> y axis
-AnalogIn emg3_in (A2); // Right tibia   -> x direction
-AnalogIn emg4_in (A3); // Left tibia    -> y direction
+AnalogIn emg1_in (A0); // Right biceps              -> x velocity
+AnalogIn emg2_in (A1); // Left biceps               -> y velocity
+AnalogIn emg3_in (A2); // Right tibialis anterior   -> x direction
+AnalogIn emg4_in (A3); // Left tibialis anterior    -> y direction
 
 // Analog Potmeter inputs
 AnalogIn potmeter1 (A4);
@@ -90,19 +90,19 @@
 bool motor_encoder_cal_done = false; // Internal encoder calibration flag
 
 // Operation Substate variables
-enum Operation_States { operation_wait, operation_movement, operation_finish }; // Define operation substates
+enum Operation_States { operation_wait, operation_movement }; // Define operation substates
 Operation_States operation_curr_state = operation_wait; // Initialize operation substate variable
 bool operation_state_changed = true; // Enable entry functions
 bool operation_showcard = false; // Internal flag to toggle servo position
-bool exit_operation = false;
+bool exit_operation = false; // State transition flag for operation exit
 
 // Demo Substate variables
 enum Demo_States { demo_wait, demo_motor_cal, demo_positioning, demo_XY }; // Define demo substates
 Demo_States demo_curr_state; // Initialize demo substate variable
 bool demo_state_changed = true; // Enable entry functions
-bool exit_demo = false;
+bool exit_demo = false; // State transition flag for demo exit
 
-// Button press interrupts (to prevent bounce)
+// Button press flags (to prevent bounce)
 bool button1_pressed = false;
 bool button2_pressed = false;
 bool switch2_pressed = false;
@@ -114,13 +114,13 @@
 bool led_color_changed = true; // Enable LED entry functions
 
 // Global constants
-const double Fs = 500.0; //Sampling frequency
-const double Ts = 1/Fs;     
+const double Fs = 500.0; // Sampling frequency
+const double Ts = 1/Fs; // Sampling time
 
 /*
 ------------------------------ LED COLOR FUNCTIONS ------------------------------
 */
-// Only called once when color is changed
+// Function to set the color of the blinking LED
 void set_led_color(char color)
 {
     switch(color) {
@@ -153,16 +153,16 @@
     led_color_changed = true;
 }
 
-// Run constantly
+// Function which toggles the LED output
 void disp_led_color()
 {
-    if (led_color_changed == true) {
+    if (led_color_changed == true) { // Turns all LEDs off
         led_color_changed = false;
         led_g = 1;
         led_b = 1;
         led_r = 1;
     }
-    switch(curr_led_color) {
+    switch(curr_led_color) { // Toggles LEDs according to color requirement
         case off:
             break;
         case red:
@@ -245,29 +245,42 @@
 ------------------------------ BUTTON FUNCTIONS ------------------------------
 */
 
-// Handle button press
+// Prevent button bounce
 void button1Press()
 {
     button1_pressed = true;
 }
 
-// Handle button press
+// Prevent button bounce
 void button2Press()
 {
     button2_pressed = true;
 }
 
+// Prevent button bounce
 void switch2Press()
 {
     switch2_pressed = true;
 }
 
+// Set global state to failure mode
 void switch3Press()
 {
     global_curr_state = global_failure;
     global_state_changed = true;
 }
 
+// Toggle the servo (end effector orientation)
+void changeservo()
+{
+    servo_button1 = extButton1.read();
+    if (servo_button1 == 1) {
+        myservo.SetPosition(2000);
+    } else {
+        myservo.SetPosition(1000);
+    }
+}
+
 /*
 ------------------------------ EMG GLOBAL VARIABLES & CONSTANTS ------------------------------
 */
@@ -275,55 +288,52 @@
 // Set global constant values for EMG reading & analysis
 const double Tcal = 7.5f; // Calibration duration (s)
 
-// Initialize variables for EMG reading & analysis
-double emg1;
-double emg1_env;
-double emg1_MVC;
-double emg1_rest;
-double emg1_factor;//delete
-double emg1_th;
-double emg1_out;
-double emg1_norm; //delete
-vector<double> emg1_cal;
-int emg1_cal_size; //delete
-double emg1_dir = 1.0;
+// Initialize variables for EMG reading & analysis of biceps signals
+vector<double> emg1_cal; // Array of calibration data 
+double emg1; // Raw EMG input
+double emg1_env; // Filtered EMG input
+double emg1_MVC; // MVC value for signal scaling
+double emg1_factor; // Scale factor for MVC scaling
+double emg1_rest; // Rest value for signal threshold
+double emg1_th; // Signal threshold
+double emg1_dir = 1.0; // Direction of EMG output (1.0 = positive, -1.0 = negative)
+double emg1_out; // EMG output (normalized reference velocity with direction)
 
+// See emg1 for documentation
+vector<double> emg2_cal;
 double emg2;
 double emg2_env;
 double emg2_MVC;
+double emg2_factor;
 double emg2_rest;
-double emg2_factor;//delete
 double emg2_th;
+double emg2_dir = 1.0;
 double emg2_out;
-double emg2_norm;//delete
-vector<double> emg2_cal;
-int emg2_cal_size;//delete
-double emg2_dir = 1.0;
 
-double emg3;
-double emg3_env;
-double emg3_MVC;
-double emg3_rest;
-double emg3_factor;//delete
-double emg3_th;
-double emg3_out;
-double emg3_norm;//delete
-vector<double> emg3_cal;
+// Initialize variables for EMG reading & analysis of tibialis anterior signals
+vector<double> emg3_cal; // Array of calibration data 
+double emg3; // Raw EMG input
+double emg3_env; // Filtered EMG input
+double emg3_MVC; // MVC value for signal scaling
+double emg3_factor; // Scale factor for MVC scaling
+double emg3_rest; // Rest value for signal threshold
+double emg3_th; // Signal threshold
 
+// See emg3 for documentation
+vector<double> emg4_cal;
 double emg4;
 double emg4_env;
 double emg4_MVC;
+double emg4_factor;
 double emg4_rest;
-double emg4_factor;//delete
 double emg4_th;
-double emg4_out;
-double emg4_norm;//delete
-vector<double> emg4_cal;
 
 /*
 ------------------------------ EMG FILTERS ------------------------------
 */
 
+// NOTE: Every filter needs to be repeated for every EMG input signal, 4 times in total. All filters are equal for every EMG input signal.
+
 // Notch biquad filter coefficients (iirnotch Q factor 35 @50Hz) from MATLAB:
 BiQuad bq1_notch( 0.995636295063941,  -1.89829218816065,   0.995636295063941,  1, -1.89829218816065,   0.991272590127882); // b01 b11 b21 a01 a11 a21
 BiQuad bq2_notch = bq1_notch;
@@ -335,6 +345,7 @@
 BiQuadChain bqc4_notch;
 
 // Highpass biquad filter coefficients (butter 4th order @10Hz cutoff) from MATLAB
+// 4th order behaviour is obtained by chaining two BiQuad (2nd order) filters (H1 and H2)
 BiQuad bq1_H1(0.922946103200875, -1.84589220640175,  0.922946103200875,  1,  -1.88920703055163,  0.892769008131025); // b01 b11 b21 a01 a11 a21
 BiQuad bq1_H2(1,                 -2,                 1,                  1,  -1.95046575793011,  0.954143234875078); // b02 b12 b22 a02 a12 a22
 BiQuad bq2_H1 = bq1_H1;
@@ -349,6 +360,7 @@
 BiQuadChain bqc4_high;
 
 // Lowpass biquad filter coefficients (butter 4th order @5Hz cutoff) from MATLAB:
+// 4th order behaviour is obtained by chaining two BiQuad (2nd order) filters (L1 and L2)
 BiQuad bq1_L1(5.32116245737504e-08,  1.06423249147501e-07,   5.32116245737504e-08,   1,  -1.94396715039462,  0.944882378004138); // b01 b11 b21 a01 a11 a21
 BiQuad bq1_L2(1,                     2,                      1,                      1,  -1.97586467534468,  0.976794920438162); // b02 b12 b22 a02 a12 a22
 BiQuad bq2_L1 = bq1_L1;
@@ -362,7 +374,7 @@
 BiQuadChain bqc3_low;
 BiQuadChain bqc4_low;
 
-// Function to check filter stability
+// DEPRECATED Function to check filter stability
 bool checkBQChainStable()
 {
     bool n_stable = bqc1_notch.stable(); // Check stability of all BQ Chains
@@ -379,16 +391,16 @@
 /*
 ------------------------------ EMG GLOBAL FUNCTIONS ------------------------------
 */
-
+// Function to bundle camputations in operation mode for better overview in (sub)state functions
 void EMGOperationFunc()
 {
-    emg1_norm = emg1_env * emg1_factor; // Normalize current EMG signal with calibrated factor
-    emg2_norm = emg2_env * emg2_factor; // Idem
-    emg3_norm = emg3_env * emg3_factor; // Idem
-    emg4_norm = emg4_env * emg4_factor; // Idem
+    double emg1_norm = emg1_env * emg1_factor; // Normalize current EMG signal with calibrated factor
+    double emg2_norm = emg2_env * emg2_factor; // Idem
+    double emg3_norm = emg3_env * emg3_factor; // Idem
+    double emg4_norm = emg4_env * emg4_factor; // Idem
 
 
-    // Set normalized EMG output signal (CAN BE MOVED TO EXTERNAL FUNCTION BECAUSE IT IS REPEATED 3 TIMES)
+    // Set normalized EMG output signal
     if ( emg1_norm < emg1_th ) { // If below threshold, emg_out = 0 (ignored)
         emg1_out = 0.0;
     } else if ( emg1_norm > 1.0f ) { // If above MVC (e.g. due to filtering), emg_out = 1 (max value)
@@ -399,7 +411,7 @@
         emg1_out = rescale(emg1_norm, 0, 1, emg1_th, 1);
     }
 
-    // Idem for emg2
+    // See emg1 for documentation
     if ( emg2_norm < emg2_th ) {
         emg2_out = 0.0;
     } else if ( emg2_norm > 1.0f ) {
@@ -408,16 +420,17 @@
         emg2_out = rescale(emg2_norm, 0, 1, emg2_th, 1);
     }
 
-    // Idem for emg3
-    if ( emg3_norm < emg3_th ) {
+    // Sets direction of emg1
+    if ( emg3_norm < emg3_th ) { // Default: no tibialis activity = positive x direction
         emg1_dir = 1.0;
-    } else {
+    } else { // Tibialis activity = negative x direction
         emg1_dir = -1.0;
     }
 
+    // Sets direction of emg2
     if ( emg4_norm < emg4_th ) {
-        emg2_dir = 1.0;
-    } else {
+        emg2_dir = 1.0; // Default: no tibialis activity = positive y direction
+    } else { // Tibialis activity = negative y direction
         emg2_dir = -1.0;
     }
 }
@@ -481,6 +494,7 @@
     }
 
     // Do stuff until end condition is met
+    
     // Set HIDScope outputs
     scope.set(0, emg1 );
     scope.set(1, emg2 );
@@ -531,7 +545,7 @@
         emg_state_changed = false; // Disable entry functions
 
         // Compute scale factors for all EMG signals
-        double margin_percentage = 5; // Set up % margin for rest
+        double margin_percentage = 5; // Set up % margin for rest. This percentage was aqcuired after testing multiple thresholds, user found a 5% margin felt most 'natural'
         emg1_factor = 1 / emg1_MVC; // Factor to normalize MVC
         emg1_th = emg1_rest * emg1_factor + margin_percentage/100; // Set normalized rest threshold
         emg2_factor = 1 / emg2_MVC; // Factor to normalize MVC
@@ -582,23 +596,23 @@
 ------------------------------ MOTOR GLOBAL VARIABLES & CONSTANTS ------------------------------
 */
 // Initialize encoder
-int encoder_res = 64;
+int encoder_res = 64; // Encoder resolution
 
-QEI encoder1(D9, D8, NC, encoder_res, QEI::X4_ENCODING);     //Encoder of motor 1
-QEI encoder2(D12, D13, NC, encoder_res, QEI::X4_ENCODING);   //Encoder of motor 2
+QEI encoder1(D9, D8, NC, encoder_res, QEI::X4_ENCODING); //Encoder of motor 1
+QEI encoder2(D12, D13, NC, encoder_res, QEI::X4_ENCODING); //Encoder of motor 2
 
 // Initialize variables for encoder reading
 volatile int counts1; //Counts after compensation with offset
 volatile int counts1af; //Counts measured by encoder
 int counts1offset; //Offset due to calibration
-volatile int countsPrev1 = 0;
-volatile int deltaCounts1;
+volatile int countsPrev1 = 0; // Stores previous encoder counts for time delay
+volatile int deltaCounts1; // Difference in counts 
 
 volatile int counts2; // Counts after compensation with offset
 volatile int counts2af; //Counts measured by encoder
 int counts2offset; //Offset due to calibration
-volatile int countsPrev2 = 0;
-volatile int deltaCounts2;
+volatile int countsPrev2 = 0; // Stores previous encoder counts for time delay
+volatile int deltaCounts2; // Difference in counts
 
 // PWM period
 const float PWM_period = 1/(18*10e3); // 18000 Hz
@@ -683,37 +697,38 @@
     static float e_prev1 = motor1_error; // Saving the previous error, needed for derivative computation
 
     //Proportional part
-    u_p1 = Kp * motor1_error;
+    u_p1 = Kp * motor1_error; // Output of proportional part
 
     //Integral part
     if ( motor_curr_state == motor_finish || operation_curr_state == operation_movement || demo_curr_state == demo_XY || demo_curr_state == demo_positioning ) { // Only active during operational states to prevent windup
-        error_integral1 = error_integral1 + ei1 * Ts; 
-        u_i1 = Ki * error_integral1;
+        error_integral1 = error_integral1 + ei1 * Ts; // Previous integral error addition 
+        u_i1 = Ki * error_integral1; // Output of integral part
     }
 
     //Derivative part
-    float error_derivative1 = (motor1_error - e_prev1) / Ts;
-    float u_d1 = Kd * error_derivative1;
-    e_prev1 = motor1_error;
+    float error_derivative1 = (motor1_error - e_prev1) / Ts; // Derivative error
+    float u_d1 = Kd * error_derivative1; // Output of derivative part
+    e_prev1 = motor1_error; // Set up derivative error for next cycle
 
-    // Sum and limit
     up1 = u_p1 + u_i1 + u_d1;   // Sum the contributions of P, I and D
-    if ( up1 > 1.0f ) {         // Saturated limit of motor, contintue with value between -1 and 1
+    
+    // Saturation
+    if ( up1 > 1.0f ) {         // Saturated positive limit of motor, set output equal to 1
         controlsignal1 = 1.0f;  
-    } else if ( up1 < -1.0f ) {
+    } else if ( up1 < -1.0f ) { // Saturated negative limit of motor, set output equal to -1
         controlsignal1 = -1.0f;
     } else {
-        controlsignal1 = up1;
+        controlsignal1 = up1;   // No saturation, motor output is scaled normally
     }
 
-    // To prevent windup
+    // Windup control
     ux1 = up1 - controlsignal1; // Computation of the overflow
-    ek1 = Ka * ux1;
+    ek1 = Ka * ux1; // Output of windup action
     ei1 = motor1_error - ek1;   // Integral error with windup subtracted 
 
-    // Motor 2
+    // Motor 2 (see motor 1 for documentation)
     static float error_integral2 = 0.0;
-    static float e_prev2 = motor2_error; // Saving the previous error, needed for derivative computation
+    static float e_prev2 = motor2_error;
 
     //Proportional part:
     u_p2 = Kp * motor2_error;
@@ -729,9 +744,10 @@
     float u_d2 = Kd * error_derivative2;
     e_prev2 = motor2_error;
 
-    // Sum and limit
-    up2 = u_p2 + u_i2 + u_d2; // Sum the contributions of P, I and D
-    if ( up2 > 1.0f ) { // Saturated limit of motor, contintue with value between -1 and 1
+    up2 = u_p2 + u_i2 + u_d2; 
+    
+    // Saturation
+    if ( up2 > 1.0f ) {
         controlsignal2 = 1.0f;
     } else if ( up2 < -1.0f ) {
         controlsignal2 = -1.0f;
@@ -739,10 +755,10 @@
         controlsignal2 = up2;
     }
 
-    // To prevent windup
-    ux2 = up2 - controlsignal2; // Computation of the overflow
+    // Windup control
+    ux2 = up2 - controlsignal2;
     ek2 = Ka * ux2;
-    ei2 = motor2_error - ek2;   // Integral error with windup subtracted 
+    ei2 = motor2_error - ek2;
 }
 
 void RKI()
@@ -756,19 +772,19 @@
     xe = l1 * cos(q1) + l2 * cos(q1+q2); // Calculation of the current endpoint position
     ye = l1 * sin(q1) + l2 * sin(q1+q2); // Calculation of the current endpoint position
 
-    if ( q1 < -5.0f * deg2rad) {            // Setting limits to the joint angles
+    if ( q1 < -5.0f * deg2rad) {            // Prevent angles to exceed software limits
         q1 = -5.0f * deg2rad;
-    } else if ( q1 > 65.0f * deg2rad ) {    // Setting limits to the joint angles
+    } else if ( q1 > 65.0f * deg2rad ) {    // Prevent angles to exceed software limits
         q1 = 65.0f * deg2rad;
-    } else {
+    } else {                                // Regular angle output
         q1 = q1;
     }
 
-    if ( q2 > -50.0f * deg2rad ) {          // Setting limits to the joint angles
+    if ( q2 > -50.0f * deg2rad ) {          // Prevent angles to exceed software limits
         q2 = -50.0f * deg2rad;
-    } else if ( q2 < -138.0f * deg2rad ) {  // Setting limits to the joint angles
+    } else if ( q2 < -138.0f * deg2rad ) {  // Prevent angles to exceed software limits
         q2 = -138.0f * deg2rad;
-    } else {
+    } else {                                // Regular angle output
         q2 = q2;
     }
 
@@ -776,6 +792,7 @@
     motor2_ref = 2.75f * q1;                // Calculating the desired motor angle to attain the correct joint angles
 }
 
+// Function to provide power to motors
 void motorControl()
 {
     counts1 = counts1af - counts1offset;    // Counts measured by encoder compensated with the offset due to calibration
@@ -806,6 +823,7 @@
     motor2Direction = motordir2; // Assigning the desired direction to the motor
 }
 
+// Function to stop all motor movement
 void motorKillPower()
 {
     motor1Power.write(0.0f); // Setting motor power to 0 to stop motion
@@ -822,10 +840,9 @@
     // Entry function
     if ( motor_state_changed == true ) {
         motor_state_changed = false;
-        // More functions
     }
     motor1Power.write(0.0f); // Giving the motor no power to be able to adjust the robot configuration
-    motor2Power.write(0.0f);
+    motor2Power.write(0.0f); // Giving the motor no power to be able to adjust the robot configuration
     counts1offset = counts1af ; // Storing the offset of the encoder
     counts2offset = counts2af; // Storing the offset of the encoder
 
@@ -843,17 +860,19 @@
     // Entry function
     if ( motor_state_changed == true ) {
         motor_state_changed = false;
-        timerStateChange.reset();
-        timerStateChange.start();
+        timerStateChange.reset(); // Sets timer to 0
+        timerStateChange.start(); // Starts timer to proceed automatically to next state
     }
 
     // Do stuff until end condition is true
+    
+    // Perform all motor functions
     PID_controller();
-    motorControl(); //These three functions cause the robot to move within the link limits
+    motorControl();
     RKI();
 
     // State transition guard
-    if ( timerStateChange.read() >= 3.0f ) { // After 3 seconds move to next state
+    if ( timerStateChange.read() >= 3.0f ) { // After 3 seconds, the robot is in its home position. Move to next state
         button2_pressed = false;
         motor_cal_done = true;
         motor_curr_state = motor_encoder_set;
@@ -889,27 +908,29 @@
     }
 
     // Do stuff until end condition is met
-    EMGOperationFunc();
+    
+    EMGOperationFunc(); // Run EMG operation
 
-    Vx = emg1_out * (10.0f + 10.0f * potmeter1.read() ) * emg1_dir;
-    Vy = emg2_out * (10.0f + 10.0f * potmeter2.read() ) * emg2_dir;
+    Vx = emg1_out * (10.0f + 10.0f * potmeter1.read() ) * emg1_dir; // Scale Vx to have more responsive motor control. Potmeter is used to allow user to further finetune
+    Vy = emg2_out * (10.0f + 10.0f * potmeter2.read() ) * emg2_dir; // Scale Vy to have more responsive motor control. Potmeter is used to allow user to further finetune
 
+    // Perform all motor functions
     PID_controller();
     motorControl();
     RKI();
 
-    motorKillPower(); // Disables motor outputs
+    motorKillPower(); // Disables motor outputs to prevent any actual output, since this is the waiting state
 
     // State transition guard
-    if ( button1_pressed == true ) {
+    if ( button1_pressed == true ) { // operation_movement
         button1_pressed = false;
         operation_curr_state = operation_movement;
         operation_state_changed = true;
-    } else if ( button2_pressed == true ) {
+    } else if ( button2_pressed == true ) { // global_wait
         button2_pressed = false;
-        operation_curr_state = operation_wait;
-        operation_state_changed = true;
-        exit_operation = true;
+        operation_curr_state = operation_wait; // Prepares system to enter operation mode again
+        operation_state_changed = true; // Prepares system to enter operation mode again
+        exit_operation = true; // This flag actually makes the state proceed to global_wait
     }
 }
 
@@ -923,25 +944,22 @@
     }
 
     // Do stuff until end condition is met
-    EMGOperationFunc();
+    
+    EMGOperationFunc(); // Run EMG operation
 
-    Vx = emg1_out * (10.0f + 10.0f * potmeter1.read() ) * emg1_dir;
-    Vy = emg2_out * (10.0f + 10.0f * potmeter2.read() ) * emg2_dir;
+    Vx = emg1_out * (10.0f + 10.0f * potmeter1.read() ) * emg1_dir; // Scale Vx to have more responsive motor control. Potmeter is used to allow user to further finetune
+    Vy = emg2_out * (10.0f + 10.0f * potmeter2.read() ) * emg2_dir; // Scale Vy to have more responsive motor control. Potmeter is used to allow user to further finetune
 
+    // Perform all motor functions
     PID_controller();
     motorControl();
     RKI();
 
     // State transition guard
-    if ( button1_pressed == true ) {
+    if ( button1_pressed == true ) { // operation_wait
         button1_pressed = false;
         operation_curr_state = operation_wait;
         operation_state_changed = true;
-    } else if ( button2_pressed == true ) {
-        button2_pressed = false;
-        operation_curr_state = operation_wait;
-        operation_state_changed = true;
-        exit_operation = true;
     }
 }
 
@@ -971,25 +989,25 @@
         demo_state_changed = false;
     }
 
-    // Do nothing until end condition is met
+    // Perform all motor functions
     PID_controller();
     motorControl();
     RKI();
     
-    motorKillPower();
+    motorKillPower(); // Set output to zero to prevent any motor outputs, since this is a waiting state
 
     // State transition guard
-    if ( button1_pressed == true ) { // demo_XY
+    if ( button1_pressed == true ) { // demo_positioning
         button1_pressed = false;
         demo_curr_state = demo_positioning;
         demo_state_changed = true;
         // More functions
     } else if ( switch2_pressed == true ) { // Return to global wait
         switch2_pressed = false;
-        demo_curr_state = demo_wait;
-        demo_state_changed = true;
-        motor_cal_done = false; // Disables motor calibration again (robot is probably not in reference position)
-        exit_demo = true;
+        demo_curr_state = demo_wait; // Prepares system to enter demo mode again
+        demo_state_changed = true; // Prepares system to enter demo mode again
+        motor_cal_done = false; // Disables motor calibration again (since robot is probably not in reference position anymore)
+        exit_demo = true; // This flag actually makes the state proceed to global_wait
     }
 }
 
@@ -1005,8 +1023,7 @@
     motorControl();
     RKI();
 
-    // Do stuff until end condition is met
-    motor_state_machine();
+    motor_state_machine(); // Run regular motor calibration state machine
 
     // State transition guard
     if ( motor_cal_done == true ) { // demo_wait
@@ -1025,7 +1042,6 @@
         timerStateChange.start();
     }
 
-
     Vx = 5.0; // Move in the positive x direction
     Vy = 5.0; // Move in the positive y direction
 
@@ -1033,12 +1049,8 @@
     motorControl();
     RKI();
 
-    scope.set(0, motor2_ref * rad2deg );
-    scope.set(1, motor2_angle * rad2deg );
-    scope.send();
-
     // State transition guard
-    if ( timerStateChange.read() >= 5.0f ) { // demo_wait
+    if ( timerStateChange.read() >= 5.0f ) { // demo_XY
         button1_pressed = false;
         demo_curr_state = demo_XY;
         demo_state_changed = true;
@@ -1053,9 +1065,11 @@
     }
 
     // Do stuff until end condition is met
+    
     static float t = 0.0;
-
-    if ( t >= 0.0f && t < 3.0f ) {          // With this code the endpoint will make a square every 12 seconds
+    
+    // The endpoint will make a square every 12 seconds
+    if ( t >= 0.0f && t < 3.0f ) {          
         Vx = 5.0;
     } else if ( t >= 3.0f && t < 6.0f ) {
         Vx = 0.0;
@@ -1076,12 +1090,6 @@
     motorControl();
     RKI();
 
-    scope.set(0, motor2_ref * rad2deg );
-    scope.set(1, motor2_angle * rad2deg );
-    //scope.set(2, motor2_ref );
-    //scope.set(3, motor2_angle );
-    scope.send();
-
     // State transition guard
     if ( button1_pressed == true ) { // demo_wait
         t = 0.0;
@@ -1167,9 +1175,9 @@
         set_led_color('y'); // Set demo mode LED (YELLOW)
         emg_cal_done = false; // Disables EMG calibration to prevent going into operation mode after exiting demo state
 
-        if ( motor_cal_done == true ) {
+        if ( motor_cal_done == true ) { // Motor calibration is already finished, move to demo_wait
             demo_curr_state = demo_wait;
-        } else if (motor_cal_done == false ) {
+        } else if (motor_cal_done == false ) { // Motor calibration is not yet finished, perform motor calibration first
             demo_curr_state = demo_motor_cal;
         }
         demo_state_changed = true;
@@ -1179,13 +1187,13 @@
     demo_state_machine();
 
     // State transition guard
-    if ( exit_demo == true ) {
+    if ( exit_demo == true ) { // global_wait
         exit_demo = false;
         global_curr_state = global_wait;
         global_state_changed = true;
         set_led_color('o'); // Disable demo mode LED
         
-        motor1_ref = motor1_init;
+        motor1_ref = motor1_init; // Reset all motor values to prevent aggressive swing when entering another movement mode
         motor1_angle = motor1_init;
         motor2_ref = motor2_init;
         motor2_angle = motor2_init;
@@ -1206,25 +1214,25 @@
 
 
     // State transition guard
-    if ( switch2_pressed == true ) { // DEMO MODE
+    if ( switch2_pressed == true ) { // global_demo
         switch2_pressed = false;
         global_curr_state = global_demo;
         global_state_changed = true;
         set_led_color('o'); // Disable wait mode LED
 
-    } else if ( button1_pressed == true ) { // EMG CALIBRATION
+    } else if ( button1_pressed == true ) { // global_emg_cal
         button1_pressed = false;
         global_curr_state = global_emg_cal;
         global_state_changed = true;
         set_led_color('o'); // Disable wait mode LED
 
-    } else if ( button2_pressed == true ) { // MOTOR CALIBRATION
+    } else if ( button2_pressed == true ) { // global_motor_cal
         button2_pressed = false;
         global_curr_state = global_motor_cal;
         global_state_changed = true;
         set_led_color('o'); // Disable wait mode LED
 
-    } else if ( emg_cal_done && motor_cal_done ) { // OPERATION MODE
+    } else if ( emg_cal_done && motor_cal_done ) { // global_operation
         global_curr_state = global_operation;
         global_state_changed = true;
         set_led_color('o'); // Disable wait mode LED
@@ -1244,7 +1252,7 @@
     emg_state_machine();
 
     // State transition guard
-    if ( emg_cal_done == true ) { // WAIT MODE
+    if ( emg_cal_done == true ) { // global_wait
         global_curr_state = global_wait;
         global_state_changed = true;
         set_led_color('o'); // Disable EMG calibration LED
@@ -1264,7 +1272,7 @@
     motor_state_machine();
 
     // State transition guard
-    if ( motor_cal_done == true ) { // WAIT MODE
+    if ( motor_cal_done == true ) { // global_wait
         global_curr_state = global_wait;
         global_state_changed = true;
         set_led_color('o'); // Disable motor calibration LED
@@ -1278,8 +1286,8 @@
     if ( global_state_changed == true ) {
         global_state_changed = false;
         
-        button1.fall( &button1Press );
-        button2.fall( &button2Press );
+        button1.fall( &button1Press ); // Enables buttons again
+        button2.fall( &button2Press ); // Enables buttons again
 
         emg_sampleNow = true; // Enable signal sampling in sampleSignals()
         emg_calibrateNow = false; // Disable calibration functionality in sampleSignals()
@@ -1292,20 +1300,22 @@
     // Set HIDScope outputs
     scope.set(0, emg1 );
     scope.set(1, Vx );
-    scope.set(2, emg2 );
-    scope.set(3, Vy );
+    scope.set(2, motor1_angle );
+    scope.set(3, emg2 );
+    scope.set(4, Vy );
+    scope.set(5, motor1_angle );
     scope.send();
 
     // State transition guard
-    if ( exit_operation == true ) {
+    if ( exit_operation == true ) { // global_wait
         exit_operation = false;
         global_curr_state = global_wait;
         global_state_changed = true;
         set_led_color('o'); // Disable operation led
         emg_sampleNow = false; // Enable signal sampling in sampleSignals()
         emg_calibrateNow = false; // Disable calibration functionality in sampleSignals()
-        emg_cal_done = false;
-        motor_cal_done = false;
+        emg_cal_done = false; // Requires user to calibrate again
+        motor_cal_done = false; // Requires user to calibrate again
     }
 }
 /*
@@ -1340,7 +1350,7 @@
 */
 void sampleSignals()
 {
-    if (emg_sampleNow == true) { // This ticker only samples if the sample flag is true, to prevent unnecessary computations
+    if (emg_sampleNow == true) { // Only samples if the sample flag is true, to prevent unnecessary computations
         // Read EMG inputs
         emg1 = emg1_in.read();
         emg2 = emg2_in.read();
@@ -1375,6 +1385,7 @@
         }
     }
 
+    // Always reads encoder inputs
     counts1af = encoder1.getPulses();
     deltaCounts1 = counts1af - countsPrev1;
     countsPrev1 = counts1af;
@@ -1384,16 +1395,6 @@
     countsPrev2 = counts2af;
 }
 
-void changeservo()
-{
-    servo_button1 = extButton1.read();
-    if (servo_button1 == 1) {
-        myservo.SetPosition(2000);
-    } else {
-        myservo.SetPosition(1000);
-    }
-}
-
 /*
 ------------------------------ GLOBAL PROGRAM LOOP ------------------------------
 */
@@ -1451,9 +1452,7 @@
     set_led_color('o');
 
     while(true) {
-        pc.printf("Global state: %i EMG state: %i Motor state: %i Operation state: %i Demo state: %i\r\n", global_curr_state, emg_curr_state, motor_curr_state, operation_curr_state, demo_curr_state);
-        pc.printf("Potmeter 1: %f Potmeter 2: %f\r\n", potmeter1.read(), potmeter2.read());
-        //pc.printf("Xe: %f Ye: %f\r\n",xe,ye);
+        pc.printf("Global state: %i EMG state: %i Motor state: %i Operation state: %i Demo state: %i\r\n", global_curr_state, emg_curr_state, motor_curr_state, operation_curr_state, demo_curr_state); // Displays current (sub)states
         wait(0.5f);
     }
 }
\ No newline at end of file