Example project for the Line Follower robot.

Dependencies:   PM2_Libary Eigen

Revision:
24:86f1a63e35a0
Parent:
23:26b3a25fc637
Child:
25:ea1d6e27c895
--- a/main.cpp	Mon Mar 14 08:31:15 2022 +0000
+++ b/main.cpp	Mon Mar 14 15:26:35 2022 +0100
@@ -1,192 +1,191 @@
 #include "mbed.h"
 #include "PM2_Libary.h"
 
-InterruptIn user_button(PC_13);
-DigitalOut  led(LED1);
-
+// logical variable main task
+bool do_execute_main_task = false;  // this variable will be toggled via the user button (blue button) to or not to execute the main task
 
-bool  do_execute_main = false;
-Timer user_button_timer, loop_timer;
-int   loop_period_ms = 50;
-
+// user button on nucleo board
+Timer user_button_timer;            // create Timer object which we use to check if user button was pressed for a certain time (robust against signal bouncing)
+InterruptIn user_button(PC_13);     // create InterruptIn interface object to evaluate user button falling and rising edge (no blocking code in ISR)
+void user_button_pressed_fcn();     // custom functions which gets executed when user button gets pressed and released, definition below
+void user_button_released_fcn();
 
-/* declaration of custom button functions */
-void button_fall();
-void button_rise();
+// while loop gets executed every main_task_period_ms milliseconds
+int main_task_period_ms = 50;   // define main task period time in ms e.g. 50 ms -> main task runns 20 times per second
+Timer main_task_timer;          // create Timer object which we use to run the main task every main task period time in ms
 
+// led on nucleo board
+DigitalOut user_led(LED1);      // create DigitalOut object to command user led
 
-// SHARP GP2Y0A21Y IR Sensor
-/* create analog input object */
-AnalogIn analog_in(PC_2);
-float    dist_ir_sensor = 0.0f;
+// additional Led
+DigitalOut extra_led(PB_9);     // create DigitalOut object to command extra led (do add an aditional resistor, e.g. 220...500 Ohm)
 
+// mechanical button
+DigitalIn mechanical_button(PC_5);  // create DigitalIn object to evaluate extra mechanical button, you need to specify the mode for proper usage, see below
+
+// Sharp GP2Y0A41SK0F, 4-40 cm IR Sensor
+float ir_distance_mV = 0.0f;    // define variable to store measurement
+AnalogIn ir_analog_in(PC_2);    // create AnalogIn object to read in infrared distance sensor, 0...3.3V are mapped to 0...1
 
-// 78:1 Metal Gearmotor 20Dx43L mm 12V CB
-/* create enable dc motor digital out object */
-DigitalOut enable_motors(PB_15);
+// 78:1, 100:1, ... Metal Gearmotor 20Dx44L mm 12V CB
+DigitalOut enable_motors(PB_15);    // create DigitalOut object to enable dc motors
 
-/* create pwm objects */
-FastPWM pwm_M1(PB_13);
-FastPWM pwm_M2(PA_9);
-FastPWM pwm_M3(PA_10);
-float   pwm_period_s = 0.00005f;
+float   pwm_period_s = 0.00005f;    // define pwm period time in seconds and create FastPWM objects to command dc motors
+FastPWM pwm_M1(PB_13);              // motor M1 is used open loop
+FastPWM pwm_M2(PA_9);               // motor M2 is speed controlled
+FastPWM pwm_M3(PA_10);              // motor M3 is position controlled (angle controlled)
 
-/* create encoder read objects */
-EncoderCounter  encoder_M1(PA_6, PC_7);
+EncoderCounter  encoder_M1(PA_6, PC_7); // create encoder read objects
 EncoderCounter  encoder_M2(PB_6, PB_7);
 EncoderCounter  encoder_M3(PA_0, PA_1);
 
-/* create speed and position controller objects, default parametrization is for 78.125:1 gear */
-float max_voltage = 12.0f;               // adjust this to 6.0f if only one batterypack is used
-float counts_per_turn = 20.0f * 78.125f; // counts/turn * gearratio
-float kn = 180.0f / 12.0f;               // motor constant (RPM/V)
+// create SpeedController and PositionController controller objects, default parametrization is for 78.125:1 gear box
+float max_voltage = 12.0f;                  // define maximum voltage of battery packs, adjust this to 6.0f V if you only use one batterypack
+float counts_per_turn = 20.0f * 78.125f;    // define counts per turn at gearbox end: counts/turn * gearratio
+float kn = 180.0f / 12.0f;                  // define motor constant in rpm per V 
+// float k_gear = 25.0f / 78.125f;             // define additional ratio in case you are using a dc motor with a different gear box, e.g. 25:1
+// float kp = 0.1f;                            // define custom kp, this is the default speed controller gain for gear box 78.125:1
 
-float k_gear = 25.0f / 78.125f; // in case you are using a dc motor with a different gear box
-float kp = 0.1f;                // this is the default speed controller gain for gear box 78.125:1
-
-SpeedController speedController_M2(counts_per_turn, kn, max_voltage, pwm_M2, encoder_M2); // default 78.125:1 gear with default contoller parameters
+SpeedController speedController_M2(counts_per_turn, kn, max_voltage, pwm_M2, encoder_M2); // default 78.125:1 gear box  with default contoller parameters
 // SpeedController speedController_M2(counts_per_turn * k_gear, kn / k_gear, max_voltage, pwm_M2, encoder_M2); // parameters adjusted to 25:1 gear
 
+float max_speed_rps = 0.5f;                 // define maximum speed that the position controller is changig the speed, has to be smaller or equal to kn * max_voltage
 PositionController positionController_M3(counts_per_turn, kn, max_voltage, pwm_M3, encoder_M3); // default 78.125:1 gear with default contoller parameters
 // PositionController positionController_M3(counts_per_turn * k_gear, kn / k_gear, kp * k_gear, max_voltage, pwm_M3, encoder_M3); // parameters adjusted to 25:1 gear, we need a different speed controller gain here
-float max_speed_rps = 0.5f;              // has to be smaller or equal to kn * max_voltage
-
 
 // Futaba Servo S3001 20mm 3kg Analog
-/* create servo objects */
-Servo servo_S1(PB_2);
+Servo servo_S1(PB_2);           // create servo objects
 Servo servo_S2(PC_8);
-int servo_position_S1_mus = 0;
-int servo_position_S2_mus = 0;
-int servo_period_mus = 20000;
-int servo_counter = 0;
-int loops_per_second = static_cast<int>(ceilf(1.0f/(0.001f*(float)loop_period_ms)));
+int servo_pos_S1_mus = 0;       // servo S1 position, the desired position gets commanded as a time
+int servo_pos_S2_mus = 0;       // servo S2 position
+int servo_period_mus = 20000;   // define servo period time in mus
 
+int servo_counter = 0;          // define servo counter, this is an additional variable to make the servos move
+int loops_per_second = static_cast<int>(ceilf(1.0f/(0.001f*(float)main_task_period_ms))); // define loops per second
 
 // Groove Ultrasonic Ranger V2.0
-// https://ch.rs-online.com/web/p/entwicklungstools-sensorik/1743238/?cm_mmc=CH-PLA-DS3A-_-google-_-CSS_CH_DE_Raspberry_Pi_%26_Arduino_und_Entwicklungstools_Whoop-_-(CH:Whoop!)+Entwicklungstools+Sensorik-_-1743238&matchtype=&pla-306637898829&gclid=Cj0KCQjwpdqDBhCSARIsAEUJ0hOLQOOaw_2-Ob03u4YGwXthQPeSyjaazFqNuMkTIT8Ie18B1pD7P9AaAn18EALw_wcB&gclsrc=aw.ds
-/* create range finder object (ultra sonic distance sensor) */
-// RangeFinder range_finder(PB_12, 5782.0f, 0.02f, 17500); // 1/loop_period_ms = 20 Hz parametrization
-RangeFinder range_finder(PB_12, 5782.0f, 0.02f,  7000); // 1/loop_period_ms = 50 Hz parametrization
-float       dist_us_sensor = 0.0f;
+float us_distance_cm = 0.0f;    // define variable to store measurement
+RangeFinder us_range_finder(PB_12, 5782.0f, 0.02f, 17500); 
+// RangeFinder us_range_finder(PB_12, 5782.0f, 0.02f,  7000); // create range finder object (ultra sonic distance sensor), 1/main_task_period_ms = 20 Hz parametrization
 
-
-// LSM9DS1 IMU
-// create imu comunication objects, carefull: not all PES boards have an imu (chip shortage)
-// LSM9DS1 imu(PC_9, PA_8); // if you want to be able to use the imu you need to #include "LSM9DS1_i2c.h"
+// LSM9DS1 IMU, carefull: not all PES boards have an imu (chip shortage)
+// LSM9DS1 imu(PC_9, PA_8); // create LSM9DS1 comunication object, if you want to be able to use the imu you need to #include "LSM9DS1_i2c.h"   
 
 int main()
 {
-    /* attach button fall and rise functions */
-    user_button.fall(&button_fall);
-    user_button.rise(&button_rise);
+    // attach button fall and rise functions to user button object
+    user_button.fall(&user_button_pressed_fcn);
+    user_button.rise(&user_button_released_fcn);
 
-    /* start loop_timer */
-    loop_timer.start();
+    // start timers
+    user_button_timer.start();
+    main_task_timer.start();
 
-    /* enable hardwaredriver dc motors: 0 -> disabled, 1 -> enabled */
+    // set pullup mode: add resistor between pin and 3.3 V, so that there is a defined potential
+    mechanical_button.mode(PullUp);
+
+    // enable hardwaredriver dc motors: 0 -> disabled, 1 -> enabled
     enable_motors = 1;
 
-    /* initialize pwm for motor M1*/
-    pwm_M1.period(pwm_period_s);
-    /* set pwm output zero at the beginning, range: 0...1 -> u_min...u_max , 0.5 -> 0 V */
+    // motor M1 is used open-loop, we need to initialize the pwm and set pwm output to zero at the beginning, range: 0...1 -> u_min...u_max: 0.5 -> 0 V
+    pwm_M1.period(pwm_period_s);        
     pwm_M1.write(0.5);
 
-    /* enable servos, you can also disable them */
-    servo_S1.Enable(servo_position_S1_mus, servo_period_mus);
-    servo_S2.Enable(servo_position_S2_mus, servo_period_mus);
+    // enable servos, you can also disable them at any point in your program if you don't want your servos to become warm
+    servo_S1.Enable(servo_pos_S1_mus, servo_period_mus);
+    servo_S2.Enable(servo_pos_S2_mus, servo_period_mus);
 
-    while (true) {
-
-        loop_timer.reset();
+    while (true) { // this loop will run forever
 
-        if (do_execute_main) {
+        main_task_timer.reset();
 
-            /* read analog input */
-            dist_ir_sensor = analog_in.read() * 3.3f;
+        if (do_execute_main_task) {
 
-            /* write output voltage to motor M1 */
-            pwm_M1.write(0.75);
+            // read analog input
+            ir_distance_mV = 1.0e3f * ir_analog_in.read() * 3.3f;
 
-            /* set a desired speed for speed controlled dc motors M2 */
-            speedController_M2.setDesiredSpeedRPS(0.5f);
-
-            /* set a desired rotation for position controlled dc motors M3 */
-            positionController_M3.setDesiredRotation(1.5f, max_speed_rps);
-
+            // command dc motors if mechanical button is pressed
+            if (mechanical_button) {
+                pwm_M1.write(0.75); // write output voltage to motor M1
+                speedController_M2.setDesiredSpeedRPS(0.5f); // set a desired speed for speed controlled dc motors M2
+                positionController_M3.setDesiredRotation(1.5f, max_speed_rps); // set a desired rotation for position controlled dc motors M3
+            } else {
+                pwm_M1.write(0.5);
+                speedController_M2.setDesiredSpeedRPS(0.0f);
+                positionController_M3.setDesiredRotation(0.0f, max_speed_rps);
+            }
 
-            /* command servo position via output time, this needs to be calibrated */
-            servo_S1.SetPosition(servo_position_S1_mus);
-            servo_S2.SetPosition(servo_position_S2_mus);
-            if (servo_position_S1_mus <= servo_period_mus & servo_counter%loops_per_second == 0 & servo_counter != 0) {
-                servo_position_S1_mus += 100;
+            // command servo position, this needs to be calibrated
+            servo_S1.SetPosition(servo_pos_S1_mus);
+            servo_S2.SetPosition(servo_pos_S2_mus);
+            if (servo_pos_S1_mus <= servo_period_mus & servo_counter%loops_per_second == 0 & servo_counter != 0) {
+                servo_pos_S1_mus += 100;
             }
-            if (servo_position_S2_mus <= servo_period_mus & servo_counter%loops_per_second == 0 & servo_counter != 0) {
-                servo_position_S2_mus += 100;
+            if (servo_pos_S2_mus <= servo_period_mus & servo_counter%loops_per_second == 0 & servo_counter != 0) {
+                servo_pos_S2_mus += 100;
             }
             servo_counter++;
 
-            /* read ultra sonic distance sensor */
-            dist_us_sensor = range_finder.read_cm();
+            // read ultra sonic distance sensor
+            us_distance_cm = us_range_finder.read_cm();
 
-            /* visual feedback that the main task is executed */
-            led = !led;
+            // visual feedback that the main task is executed
+            extra_led = 1;
 
         } else {
 
-            dist_ir_sensor = 0.0f;
+            ir_distance_mV = 0.0f;
 
             pwm_M1.write(0.5);
             speedController_M2.setDesiredSpeedRPS(0.0f);
             positionController_M3.setDesiredRotation(0.0f, max_speed_rps);
 
-            servo_position_S1_mus = 0;
-            servo_position_S2_mus = 0;
-            servo_S1.SetPosition(servo_position_S1_mus);
-            servo_S2.SetPosition(servo_position_S2_mus);
+            servo_pos_S1_mus = 0;
+            servo_pos_S2_mus = 0;
+            servo_S1.SetPosition(servo_pos_S1_mus);
+            servo_S2.SetPosition(servo_pos_S2_mus);
 
-            dist_us_sensor = 0.0f;
+            us_distance_cm = 0.0f;
 
-            led = 0;
+            extra_led = 0;
         }
 
-        /* do only output via serial what's really necessary (this makes your code slow)*/
-        printf("%3.3f, %3d, %3.3f, %3.3f, %3d, %3d, %3.3f;\r\n",
-               dist_ir_sensor * 1e3,
+        user_led = !user_led;
+
+        // do only output via serial what's really necessary (this makes your code slow)
+        printf("IR sensor (mV): %3.3f, Encoder M1: %3d, Speed M2 (rps) %3.3f, Position M3 (rot): %3.3f, Servo S1 position (ms): %3d, Servo S2 position (ms): %3d, US sensor (cm): %3.3f\r\n",
+               ir_distance_mV,
                encoder_M1.read(),
                speedController_M2.getSpeedRPS(),
                positionController_M3.getRotation(),
-               servo_position_S1_mus,
-               servo_position_S2_mus,
-               dist_us_sensor);
+               servo_pos_S1_mus,
+               servo_pos_S2_mus,
+               us_distance_cm);
 
-        /* read out the imu, the actual frames of the sensor reading needs to be figured out */
-        /*
-        imu.updateGyro();
-        imu.updateAcc();
-        imu.updateMag();
-        printf("%.6f, %.6f, %.6f, %.6f, %.6f, %.6f, %.6f, %.6f, %.6f\r\n", imu.readGyroX(), imu.readGyroY(), imu.readGyroZ(),
-        imu.readAccX(), imu.readAccY(), imu.readAccZ(), imu.readMagX(), imu.readMagY(), imu.readMagZ());
-        */
+        // read out the imu, the actual frames of the sensor reading needs to be figured out
+        // imu.updateGyro();
+        // imu.updateAcc();
+        // imu.updateMag();
+        // printf("%.6f, %.6f, %.6f, %.6f, %.6f, %.6f, %.6f, %.6f, %.6f\r\n", imu.readGyroX(), imu.readGyroY(), imu.readGyroZ(),
+        // imu.readAccX(), imu.readAccY(), imu.readAccZ(), imu.readMagX(), imu.readMagY(), imu.readMagZ());
 
-        /* ------------- stop hacking ----------------------------------------*/
-
-        int loop_time_ms = std::chrono::duration_cast<std::chrono::milliseconds>(loop_timer.elapsed_time()).count();
-        thread_sleep_for(loop_period_ms - loop_time_ms);
+        // read timer and make the main thread sleep for the remaining time span (non blocking)
+        int main_task_elapsed_time_ms = std::chrono::duration_cast<std::chrono::milliseconds>(main_task_timer.elapsed_time()).count();
+        thread_sleep_for(main_task_period_ms - main_task_elapsed_time_ms);
     }
 }
 
-void button_fall()
-{
+void user_button_pressed_fcn()
+{   
     user_button_timer.reset();
-    user_button_timer.start();
 }
 
-void button_rise()
+void user_button_released_fcn()
 {
-    int user_button_time_ms = std::chrono::duration_cast<std::chrono::milliseconds>(user_button_timer.elapsed_time()).count();
+    // read timer and toggle do_execute_main_task if the button was pressed longer than the below specified time
+    int user_button_elapsed_time_ms = std::chrono::duration_cast<std::chrono::milliseconds>(user_button_timer.elapsed_time()).count();
     user_button_timer.stop();
-    if (user_button_time_ms > 200) {
-        do_execute_main = !do_execute_main;
+    if (user_button_elapsed_time_ms > 200) {
+        do_execute_main_task = !do_execute_main_task;
     }
 }
\ No newline at end of file