Example project for the Line Follower robot.

Dependencies:   PM2_Libary Eigen

Committer:
pmic
Date:
Sat May 07 12:50:49 2022 +0200
Revision:
43:5648b7083fe5
Parent:
42:b54a4f294aa9
Child:
44:340cdc4b6e47
Both nonlinear controller aproaches working great

Who changed what in which revision?

UserRevisionLine numberNew contents of line
pmic 33:cff70742569d 1 #include <mbed.h>
pmic 33:cff70742569d 2 #include <math.h>
pmic 33:cff70742569d 3
pmic 17:c19b471f05cb 4 #include "PM2_Libary.h"
pmic 40:eb7f8dce5787 5 #include "Eigen/Dense.h"
pmic 6:e1fa1a2d7483 6
pmic 34:702246639f02 7 # define M_PI 3.14159265358979323846 // number pi
pmic 33:cff70742569d 8
pmic 24:86f1a63e35a0 9 // logical variable main task
pmic 24:86f1a63e35a0 10 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
pmic 17:c19b471f05cb 11
pmic 24:86f1a63e35a0 12 // user button on nucleo board
pmic 24:86f1a63e35a0 13 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)
pmic 24:86f1a63e35a0 14 InterruptIn user_button(PC_13); // create InterruptIn interface object to evaluate user button falling and rising edge (no blocking code in ISR)
pmic 24:86f1a63e35a0 15 void user_button_pressed_fcn(); // custom functions which gets executed when user button gets pressed and released, definition below
pmic 24:86f1a63e35a0 16 void user_button_released_fcn();
pmic 6:e1fa1a2d7483 17
pmic 24:86f1a63e35a0 18 // while loop gets executed every main_task_period_ms milliseconds
pmic 34:702246639f02 19 int main_task_period_ms = 10; // define main task period time in ms e.g. 50 ms -> main task runns 20 times per second
pmic 24:86f1a63e35a0 20 Timer main_task_timer; // create Timer object which we use to run the main task every main task period time in ms
pmic 6:e1fa1a2d7483 21
pmic 24:86f1a63e35a0 22 // led on nucleo board
pmic 24:86f1a63e35a0 23 DigitalOut user_led(LED1); // create DigitalOut object to command user led
pmic 17:c19b471f05cb 24
pmic 38:6d11788e14c0 25 // Sharp GP2Y0A41SK0F, 4-40 cm IR Sensor
pmic 38:6d11788e14c0 26 float ir_distance_mV = 0.0f; // define variable to store measurement
pmic 38:6d11788e14c0 27 AnalogIn ir_analog_in(PC_2); // create AnalogIn object to read in infrared distance sensor, 0...3.3V are mapped to 0...1
pmic 38:6d11788e14c0 28
pmic 38:6d11788e14c0 29 // 78:1, 100:1, ... Metal Gearmotor 20Dx44L mm 12V CB
pmic 38:6d11788e14c0 30 DigitalOut enable_motors(PB_15); // create DigitalOut object to enable dc motors
pmic 38:6d11788e14c0 31
pmic 38:6d11788e14c0 32 float pwm_period_s = 0.00005f; // define pwm period time in seconds and create FastPWM objects to command dc motors
pmic 38:6d11788e14c0 33 FastPWM pwm_M1(PB_13); // motor M1 is closed-loop speed controlled (angle velocity)
pmic 38:6d11788e14c0 34 FastPWM pwm_M2(PA_9); // motor M2 is closed-loop speed controlled (angle velocity)
pmic 38:6d11788e14c0 35
pmic 38:6d11788e14c0 36 EncoderCounter encoder_M1(PA_6, PC_7); // create encoder objects to read in the encoder counter values
pmic 38:6d11788e14c0 37 EncoderCounter encoder_M2(PB_6, PB_7);
pmic 38:6d11788e14c0 38
pmic 38:6d11788e14c0 39 // create SpeedController and PositionController objects, default parametrization is for 78.125:1 gear box
pmic 38:6d11788e14c0 40 float max_voltage = 12.0f; // define maximum voltage of battery packs, adjust this to 6.0f V if you only use one batterypack
pmic 38:6d11788e14c0 41 float counts_per_turn = 20.0f * 78.125f; // define counts per turn at gearbox end: counts/turn * gearratio
pmic 38:6d11788e14c0 42 float kn = 180.0f / 12.0f; // define motor constant in rpm per V
pmic 38:6d11788e14c0 43 float k_gear = 100.0f / 78.125f; // define additional ratio in case you are using a dc motor with a different gear box, e.g. 100:1
pmic 38:6d11788e14c0 44 float kp = 0.1f; // define custom kp, this is the default speed controller gain for gear box 78.125:1
pmic 38:6d11788e14c0 45
pmic 38:6d11788e14c0 46 SpeedController speedController_M1(counts_per_turn, kn, max_voltage, pwm_M1, encoder_M1); // default 78.125:1 gear box with default contoller parameters
pmic 38:6d11788e14c0 47 SpeedController speedController_M2(counts_per_turn, kn, max_voltage, pwm_M2, encoder_M2); // default 78.125:1 gear box with default contoller parameters
pmic 43:5648b7083fe5 48 //SpeedController speedController_M2(counts_per_turn * k_gear, kn / k_gear, max_voltage, pwm_M2, encoder_M2); // parameters adjusted to 100:1 gear
pmic 38:6d11788e14c0 49
pmic 38:6d11788e14c0 50 // sparkfun line follower array
pmic 33:cff70742569d 51 I2C i2c(PB_9, PB_8); // I2C (PinName sda, PinName scl)
pmic 33:cff70742569d 52 SensorBar sensor_bar(i2c, 0.1175f);
pmic 20:7e7325edcf5c 53
pmic 42:b54a4f294aa9 54 // transformations and stuff
pmic 38:6d11788e14c0 55 float r_wheel = 0.0358f / 2.0f;
pmic 38:6d11788e14c0 56 float L_wheel = 0.143f;
pmic 42:b54a4f294aa9 57 Eigen::Matrix<float, 2, 2> Cwheel2robot; // transform wheel to robot
pmic 42:b54a4f294aa9 58 Eigen::Matrix<float, 2, 2> Crobot2wheel; // transform robot to wheel
pmic 42:b54a4f294aa9 59 Eigen::Matrix<float, 2, 1> robot_coord; // contains v and w
pmic 42:b54a4f294aa9 60 Eigen::Matrix<float, 2, 1> wheel_speed; // w1 w2
pmic 41:d8067ab9def5 61
pmic 43:5648b7083fe5 62 float fcn_ang_cntrl(const float& Kp, const float& Kp_nl, const float& angle);
pmic 43:5648b7083fe5 63 float fcn_vel_cntrl_v1(const float& vel_max, const float& vel_min, const float& ang_max, const float& angle);
pmic 43:5648b7083fe5 64 float fcn_vel_cntrl_v2(float wheel_speed_max, float b, float robot_omega);
pmic 38:6d11788e14c0 65
pmic 1:93d997d6b232 66 int main()
pmic 41:d8067ab9def5 67 {
pmic 24:86f1a63e35a0 68 // attach button fall and rise functions to user button object
pmic 24:86f1a63e35a0 69 user_button.fall(&user_button_pressed_fcn);
pmic 24:86f1a63e35a0 70 user_button.rise(&user_button_released_fcn);
pmic 17:c19b471f05cb 71
pmic 29:d6f1ccf42a31 72 // start timer
pmic 24:86f1a63e35a0 73 main_task_timer.start();
pmic 6:e1fa1a2d7483 74
pmic 38:6d11788e14c0 75 // enable hardwaredriver dc motors: 0 -> disabled, 1 -> enabled
pmic 38:6d11788e14c0 76 enable_motors = 1;
pmic 6:e1fa1a2d7483 77
pmic 42:b54a4f294aa9 78 // initialise matrizes and vectros
pmic 42:b54a4f294aa9 79 Cwheel2robot << r_wheel / 2.0f , r_wheel / 2.0f ,
pmic 42:b54a4f294aa9 80 r_wheel / L_wheel, -r_wheel / L_wheel;
pmic 42:b54a4f294aa9 81 Crobot2wheel << 1.0f / r_wheel, L_wheel / (2.0f * r_wheel),
pmic 42:b54a4f294aa9 82 1.0f / r_wheel, -L_wheel / (2.0f * r_wheel);
pmic 42:b54a4f294aa9 83 robot_coord << 0.06f, 0.0f;
pmic 42:b54a4f294aa9 84 wheel_speed << 0.0f, 0.0f;
pmic 42:b54a4f294aa9 85
pmic 24:86f1a63e35a0 86 while (true) { // this loop will run forever
pmic 6:e1fa1a2d7483 87
pmic 24:86f1a63e35a0 88 main_task_timer.reset();
pmic 6:e1fa1a2d7483 89
pmic 24:86f1a63e35a0 90 if (do_execute_main_task) {
pmic 34:702246639f02 91
pmic 42:b54a4f294aa9 92 // read SensorBar
pmic 43:5648b7083fe5 93 static float sensor_bar_avgAngleRad = 0.0f; // by making this static it will not be overwritten (only fist time set to zero)
pmic 42:b54a4f294aa9 94 if (sensor_bar.isAnyLedActive()) {
pmic 42:b54a4f294aa9 95 sensor_bar_avgAngleRad = sensor_bar.getAvgAngleRad();
pmic 42:b54a4f294aa9 96 }
pmic 42:b54a4f294aa9 97
pmic 42:b54a4f294aa9 98 const static float Kp = 2.0f; //2.0f;
pmic 42:b54a4f294aa9 99 const static float Kp_nl = 17.0f; //10.0f; //5.0f;
pmic 42:b54a4f294aa9 100 robot_coord(1) = fcn_ang_cntrl(Kp, Kp_nl, sensor_bar_avgAngleRad);
pmic 42:b54a4f294aa9 101
pmic 43:5648b7083fe5 102 // nonlinear controllers version 1 (whatever came to my mind)
pmic 43:5648b7083fe5 103 /*
pmic 43:5648b7083fe5 104 const static float vel_max = 0.3374f; //0.10f;
pmic 43:5648b7083fe5 105 const static float vel_min = 0.00f; //0.02f;
pmic 43:5648b7083fe5 106 const static float ang_max = 27.0f * M_PI / 180.0f;
pmic 43:5648b7083fe5 107 robot_coord(0) = fcn_vel_cntrl_v1(vel_max, vel_min, ang_max, sensor_bar_avgAngleRad);
pmic 43:5648b7083fe5 108 */
pmic 43:5648b7083fe5 109
pmic 43:5648b7083fe5 110 // nonlinear controllers version 2 (one wheel always at full speed controller)
pmic 43:5648b7083fe5 111 ///*
pmic 43:5648b7083fe5 112 static float wheel_speed_max = max_voltage * kn / 60.0f * 2.0f * M_PI;
pmic 43:5648b7083fe5 113 static float b = L_wheel / (2.0f * r_wheel);
pmic 43:5648b7083fe5 114 robot_coord(0) = fcn_vel_cntrl_v2(wheel_speed_max, b, robot_coord(1));
pmic 43:5648b7083fe5 115 //*/
pmic 43:5648b7083fe5 116
pmic 42:b54a4f294aa9 117 // transform to robot coordinates
pmic 42:b54a4f294aa9 118 wheel_speed = Crobot2wheel * robot_coord;
pmic 42:b54a4f294aa9 119
pmic 38:6d11788e14c0 120 // read analog input
pmic 38:6d11788e14c0 121 ir_distance_mV = 1.0e3f * ir_analog_in.read() * 3.3f;
pmic 38:6d11788e14c0 122
pmic 42:b54a4f294aa9 123 speedController_M1.setDesiredSpeedRPS(wheel_speed(0) / (2.0f * M_PI)); // set a desired speed for speed controlled dc motors M1
pmic 42:b54a4f294aa9 124 speedController_M2.setDesiredSpeedRPS(wheel_speed(1) / (2.0f * M_PI)); // set a desired speed for speed controlled dc motors M2
pmic 38:6d11788e14c0 125
pmic 34:702246639f02 126 /*
pmic 34:702246639f02 127 uint8_t sensor_bar_raw_value = sensor_bar.getRaw();
pmic 34:702246639f02 128 for( int i = 7; i >= 0; i-- ) {
pmic 34:702246639f02 129 printf("%d", (sensor_bar_raw_value >> i) & 0x01);
pmic 34:702246639f02 130 }
pmic 34:702246639f02 131 printf(", ");
pmic 34:702246639f02 132 */
pmic 42:b54a4f294aa9 133
pmic 42:b54a4f294aa9 134 /*
pmic 34:702246639f02 135 int8_t sensor_bar_binaryPosition = sensor_bar.getBinaryPosition();
pmic 34:702246639f02 136 printf("%d, ", sensor_bar_binaryPosition);
pmic 34:702246639f02 137
pmic 34:702246639f02 138 uint8_t sensor_bar_nrOfLedsActive = sensor_bar.getNrOfLedsActive();
pmic 34:702246639f02 139 printf("%d, ", sensor_bar_nrOfLedsActive);
pmic 34:702246639f02 140
pmic 34:702246639f02 141 float sensor_bar_angleRad = 0.0f;
pmic 34:702246639f02 142 float sensor_bar_avgAngleRad = 0.0f;
pmic 34:702246639f02 143 if (sensor_bar.isAnyLedActive()) {
pmic 34:702246639f02 144 sensor_bar_angleRad = sensor_bar.getAngleRad();
pmic 34:702246639f02 145 sensor_bar_avgAngleRad = sensor_bar.getAvgAngleRad();
pmic 34:702246639f02 146 }
pmic 34:702246639f02 147 printf("%f, ", sensor_bar_angleRad * 180.0f / M_PI);
pmic 42:b54a4f294aa9 148 printf("%f, ", sensor_bar_avgAngleRad * 180.0f / M_PI);
pmic 42:b54a4f294aa9 149 */
pmic 42:b54a4f294aa9 150
pmic 42:b54a4f294aa9 151 printf("%f, %f\r\n", wheel_speed(0) / (2.0f * M_PI), wheel_speed(1) / (2.0f * M_PI));
pmic 34:702246639f02 152
pmic 1:93d997d6b232 153 } else {
pmic 6:e1fa1a2d7483 154
pmic 38:6d11788e14c0 155 ir_distance_mV = 0.0f;
pmic 38:6d11788e14c0 156
pmic 38:6d11788e14c0 157 speedController_M1.setDesiredSpeedRPS(0.0f);
pmic 38:6d11788e14c0 158 speedController_M2.setDesiredSpeedRPS(0.0f);
pmic 33:cff70742569d 159 }
pmic 6:e1fa1a2d7483 160
pmic 24:86f1a63e35a0 161 user_led = !user_led;
pmic 24:86f1a63e35a0 162
pmic 24:86f1a63e35a0 163 // do only output via serial what's really necessary (this makes your code slow)
pmic 33:cff70742569d 164 // printf("%d, %d\r\n", sensor_bar_raw_value_time_ms, sensor_bar_position_time_ms);
pmic 17:c19b471f05cb 165
pmic 24:86f1a63e35a0 166 // read timer and make the main thread sleep for the remaining time span (non blocking)
pmic 24:86f1a63e35a0 167 int main_task_elapsed_time_ms = std::chrono::duration_cast<std::chrono::milliseconds>(main_task_timer.elapsed_time()).count();
pmic 24:86f1a63e35a0 168 thread_sleep_for(main_task_period_ms - main_task_elapsed_time_ms);
pmic 1:93d997d6b232 169 }
pmic 1:93d997d6b232 170 }
pmic 6:e1fa1a2d7483 171
pmic 24:86f1a63e35a0 172 void user_button_pressed_fcn()
pmic 25:ea1d6e27c895 173 {
pmic 26:28693b369945 174 user_button_timer.start();
pmic 6:e1fa1a2d7483 175 user_button_timer.reset();
pmic 6:e1fa1a2d7483 176 }
pmic 6:e1fa1a2d7483 177
pmic 24:86f1a63e35a0 178 void user_button_released_fcn()
pmic 6:e1fa1a2d7483 179 {
pmic 24:86f1a63e35a0 180 // read timer and toggle do_execute_main_task if the button was pressed longer than the below specified time
pmic 24:86f1a63e35a0 181 int user_button_elapsed_time_ms = std::chrono::duration_cast<std::chrono::milliseconds>(user_button_timer.elapsed_time()).count();
pmic 6:e1fa1a2d7483 182 user_button_timer.stop();
pmic 24:86f1a63e35a0 183 if (user_button_elapsed_time_ms > 200) {
pmic 24:86f1a63e35a0 184 do_execute_main_task = !do_execute_main_task;
pmic 8:9bb806a7f585 185 }
pmic 42:b54a4f294aa9 186 }
pmic 42:b54a4f294aa9 187
pmic 43:5648b7083fe5 188 float fcn_ang_cntrl(const float& Kp, const float& Kp_nl, const float& angle)
pmic 43:5648b7083fe5 189 {
pmic 43:5648b7083fe5 190 float retval = 0.0f;
pmic 43:5648b7083fe5 191 if (angle > 0) {
pmic 43:5648b7083fe5 192 retval = Kp * angle + Kp_nl * angle * angle;
pmic 43:5648b7083fe5 193 } else if (angle < 0) {
pmic 43:5648b7083fe5 194 retval = Kp * angle - Kp_nl * angle * angle;
pmic 43:5648b7083fe5 195 }
pmic 43:5648b7083fe5 196 return retval;
pmic 43:5648b7083fe5 197 }
pmic 43:5648b7083fe5 198
pmic 43:5648b7083fe5 199 float fcn_vel_cntrl_v1(const float& vel_max, const float& vel_min, const float& ang_max, const float& angle)
pmic 42:b54a4f294aa9 200 {
pmic 42:b54a4f294aa9 201 const static float gain = (vel_min - vel_max) / ang_max;
pmic 42:b54a4f294aa9 202 const static float offset = vel_max;
pmic 43:5648b7083fe5 203 return gain * fabs(angle) + offset;
pmic 42:b54a4f294aa9 204 }
pmic 42:b54a4f294aa9 205
pmic 43:5648b7083fe5 206 float fcn_vel_cntrl_v2(float wheel_speed_max, float b, float robot_omega)
pmic 42:b54a4f294aa9 207 {
pmic 43:5648b7083fe5 208 static Eigen::Matrix<float, 2, 2> _wheel_speed;
pmic 43:5648b7083fe5 209 static Eigen::Matrix<float, 2, 2> _robot_coord;
pmic 43:5648b7083fe5 210 if (robot_omega > 0) {
pmic 43:5648b7083fe5 211 _wheel_speed(0) = wheel_speed_max;
pmic 43:5648b7083fe5 212 _wheel_speed(1) = wheel_speed_max - 2*b*robot_omega;
pmic 43:5648b7083fe5 213 } else {
pmic 43:5648b7083fe5 214 _wheel_speed(0) = wheel_speed_max + 2*b*robot_omega;
pmic 43:5648b7083fe5 215 _wheel_speed(1) = wheel_speed_max;
pmic 42:b54a4f294aa9 216 }
pmic 43:5648b7083fe5 217 _robot_coord = Cwheel2robot * _wheel_speed;
pmic 43:5648b7083fe5 218 return _robot_coord(0);
pmic 6:e1fa1a2d7483 219 }