
first commit
steering_methods.h@28:1c2eb25d624e, 2021-11-17 (annotated)
- Committer:
- aalawfi
- Date:
- Wed Nov 17 21:37:29 2021 +0000
- Revision:
- 28:1c2eb25d624e
- Parent:
- 27:0fa9d61c5fc6
- Child:
- 31:d570f957e083
0.17 speed => ~~ 17.35 s
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
aalawfi | 2:c857935f928e | 1 | //#include "steering_header.h" |
aalawfi | 2:c857935f928e | 2 | /* |
aalawfi | 2:c857935f928e | 3 | Include methods and functions |
aalawfi | 2:c857935f928e | 4 | */ |
aalawfi | 2:c857935f928e | 5 | |
aalawfi | 2:c857935f928e | 6 | // --------- LANDMARK COUNTER -------- |
aalawfi | 2:c857935f928e | 7 | static int decimal_to_bin[16][BITS] = { |
aalawfi | 2:c857935f928e | 8 | {0,0,0,0}, // zero |
aalawfi | 2:c857935f928e | 9 | {0,0,0,1}, // one |
aalawfi | 2:c857935f928e | 10 | {0,0,1,0}, //two |
aalawfi | 2:c857935f928e | 11 | {0,0,1,1}, //three |
aalawfi | 2:c857935f928e | 12 | {0,1,0,0}, // four |
aalawfi | 2:c857935f928e | 13 | {0,1,0,1}, //five |
aalawfi | 2:c857935f928e | 14 | {0,1,1,0}, // six |
aalawfi | 2:c857935f928e | 15 | {0,1,1,1}, //seven |
aalawfi | 2:c857935f928e | 16 | {1,0,0,0}, //eight |
aalawfi | 2:c857935f928e | 17 | {1,0,0,1}, //nine |
aalawfi | 2:c857935f928e | 18 | {1,0,1,0}, //ten |
aalawfi | 2:c857935f928e | 19 | {1,0,1,1}, //11 |
aalawfi | 2:c857935f928e | 20 | {1,1,0,0}, //12 |
aalawfi | 2:c857935f928e | 21 | {1,1,0,1}, //13 |
aalawfi | 2:c857935f928e | 22 | {1,1,1,0}, //14 |
aalawfi | 2:c857935f928e | 23 | {1,1,1,1}, //15 |
aalawfi | 2:c857935f928e | 24 | } ; |
aalawfi | 2:c857935f928e | 25 | void turn_seg_off(DigitalOut segment[]){ |
aalawfi | 2:c857935f928e | 26 | for(int i =0; i<BITS; i++){ |
aalawfi | 2:c857935f928e | 27 | segment[i] = 0; |
aalawfi | 2:c857935f928e | 28 | } |
aalawfi | 2:c857935f928e | 29 | } |
aalawfi | 2:c857935f928e | 30 | void show_decimal(int number, DigitalOut segment[]) { |
aalawfi | 2:c857935f928e | 31 | turn_seg_off(segment); |
aalawfi | 2:c857935f928e | 32 | for(int i =0; i < BITS; i++){ |
aalawfi | 2:c857935f928e | 33 | segment[i] = decimal_to_bin[number][i]; |
aalawfi | 2:c857935f928e | 34 | }; |
aalawfi | 2:c857935f928e | 35 | } |
aalawfi | 2:c857935f928e | 36 | // ------------ LANDMARK DETECTION ------------ |
aalawfi | 23:4c743746533c | 37 | Timer land; |
aalawfi | 25:8bd029d58251 | 38 | |
quarren42 | 19:65fecaa2a387 | 39 | volatile bool landmark_triggered=false; // Debugging purposes only |
quarren42 | 19:65fecaa2a387 | 40 | volatile bool restarted = false; // Debugging purposes only |
aalawfi | 23:4c743746533c | 41 | |
aalawfi | 2:c857935f928e | 42 | void landmark_counter(void){ |
aalawfi | 23:4c743746533c | 43 | land.start(); |
quarren42 | 19:65fecaa2a387 | 44 | landmark_triggered=false; // Debugging purposes only |
quarren42 | 19:65fecaa2a387 | 45 | restarted = false; // Debugging purposes only |
aalawfi | 2:c857935f928e | 46 | if(counter >= 15) |
aalawfi | 2:c857935f928e | 47 | counter =0; |
aalawfi | 2:c857935f928e | 48 | turn_seg_off(seg1); |
aalawfi | 25:8bd029d58251 | 49 | if((right_landmark_sensor.read() == 1 || left_landmark_sensor.read() == 1) && land.read_us() > 10 ) |
aalawfi | 25:8bd029d58251 | 50 | { |
aalawfi | 23:4c743746533c | 51 | landmark_triggered =true; // Debugging purpose only |
aalawfi | 25:8bd029d58251 | 52 | (counter > 6 ? counter = 7 : counter++); |
aalawfi | 23:4c743746533c | 53 | land.stop(); |
aalawfi | 23:4c743746533c | 54 | } |
aalawfi | 23:4c743746533c | 55 | |
aalawfi | 23:4c743746533c | 56 | // } |
aalawfi | 25:8bd029d58251 | 57 | if(right_landmark_sensor.read() == 1 && left_landmark_sensor.read() == 1&& land.read_us() > 4) |
quarren42 | 19:65fecaa2a387 | 58 | { |
aalawfi | 25:8bd029d58251 | 59 | lap++; |
aalawfi | 23:4c743746533c | 60 | counter = 0; |
aalawfi | 23:4c743746533c | 61 | restarted=true; |
aalawfi | 25:8bd029d58251 | 62 | // Debugging purposes only |
quarren42 | 19:65fecaa2a387 | 63 | } |
aalawfi | 23:4c743746533c | 64 | land.stop(); |
aalawfi | 2:c857935f928e | 65 | show_decimal(counter, seg1); |
aalawfi | 2:c857935f928e | 66 | } |
aalawfi | 2:c857935f928e | 67 | |
aalawfi | 2:c857935f928e | 68 | |
aalawfi | 2:c857935f928e | 69 | float rad2dc (float angle){ |
aalawfi | 2:c857935f928e | 70 | angle = std::max(MIN_TURN_ANGLE, std::min(angle, MAX_TURN_ANGLE)); |
aalawfi | 2:c857935f928e | 71 | float x = (angle - MIN_TURN_ANGLE)/(MAX_TURN_ANGLE - MIN_TURN_ANGLE); |
aalawfi | 2:c857935f928e | 72 | float dutyCycle = 0.05*x+0.05; |
aalawfi | 2:c857935f928e | 73 | return dutyCycle; |
aalawfi | 2:c857935f928e | 74 | } |
aalawfi | 2:c857935f928e | 75 | |
aalawfi | 2:c857935f928e | 76 | float current_duty_cycle=0.075; |
aalawfi | 2:c857935f928e | 77 | // -------------- PD CONTROLLER -------------- |
aalawfi | 2:c857935f928e | 78 | // Global declearation |
aalawfi | 2:c857935f928e | 79 | float err_prev = 0; |
quarren42 | 6:d2bd68ba99c9 | 80 | float prev_duty = 0; |
aalawfi | 22:08d30ea47111 | 81 | float errorArea; |
aalawfi | 22:08d30ea47111 | 82 | float errorAreaPrev =0.0; |
aalawfi | 25:8bd029d58251 | 83 | float feedback; |
aalawfi | 25:8bd029d58251 | 84 | float err; |
aalawfi | 25:8bd029d58251 | 85 | float left_sens; float right_sens; |
aalawfi | 25:8bd029d58251 | 86 | volatile bool clamp; |
aalawfi | 28:1c2eb25d624e | 87 | float OFFSET_ANGLE=0.0; float KICK_ERR; float PREV_KICK_ERR; float KICK_CHNG_ERR; |
aalawfi | 2:c857935f928e | 88 | void steering_control(void) |
aalawfi | 2:c857935f928e | 89 | { |
aalawfi | 2:c857935f928e | 90 | |
aalawfi | 25:8bd029d58251 | 91 | |
aalawfi | 2:c857935f928e | 92 | if(steering_enabled == true ){ |
aalawfi | 2:c857935f928e | 93 | //Read each sensor and calculate the sensor difference |
aalawfi | 26:54ce9f642477 | 94 | |
aalawfi | 26:54ce9f642477 | 95 | |
aalawfi | 26:54ce9f642477 | 96 | float sensor_difference = left_distance_sensor.read() - |
aalawfi | 22:08d30ea47111 | 97 | right_distance_sensor.read(); |
aalawfi | 28:1c2eb25d624e | 98 | |
aalawfi | 28:1c2eb25d624e | 99 | /*if (counter == 1 && lap == 3){ |
aalawfi | 28:1c2eb25d624e | 100 | KP = 6; |
aalawfi | 28:1c2eb25d624e | 101 | KD = 1; |
aalawfi | 28:1c2eb25d624e | 102 | KI_STEERINg = 0.8; |
aalawfi | 28:1c2eb25d624e | 103 | |
aalawfi | 28:1c2eb25d624e | 104 | }*/ |
aalawfi | 2:c857935f928e | 105 | //calculate the feedback term for the controller. distance (meters) from |
aalawfi | 2:c857935f928e | 106 | //track to sensor |
aalawfi | 25:8bd029d58251 | 107 | feedback = (sensor_difference/SEN_DIFF_TO_DIST); // |
aalawfi | 25:8bd029d58251 | 108 | |
aalawfi | 2:c857935f928e | 109 | //calculate the error term for the controller. distance (meters) from |
aalawfi | 2:c857935f928e | 110 | //desired position to sensor |
aalawfi | 2:c857935f928e | 111 | err = REF - feedback; // |
aalawfi | 28:1c2eb25d624e | 112 | KICK_ERR = -1 * feedback; |
aalawfi | 22:08d30ea47111 | 113 | //Area of the error: TimeStep*err (width*length of a rectangle) |
aalawfi | 26:54ce9f642477 | 114 | |
aalawfi | 27:0fa9d61c5fc6 | 115 | // if(clamp == false) |
aalawfi | 22:08d30ea47111 | 116 | errorArea= TI_STEERING*err + errorAreaPrev; |
aalawfi | 25:8bd029d58251 | 117 | |
aalawfi | 2:c857935f928e | 118 | //Calculate the derivative of the error term for the controller. |
aalawfi | 2:c857935f928e | 119 | // e'(t) = (error(t) - error(t-1))/dt |
aalawfi | 22:08d30ea47111 | 120 | float errChange = (err - err_prev)/(TI_STEERING); |
aalawfi | 28:1c2eb25d624e | 121 | KICK_CHNG_ERR = (KICK_ERR - PREV_KICK_ERR)/(TI_STEERING); |
aalawfi | 2:c857935f928e | 122 | //Calculate the controller output |
aalawfi | 2:c857935f928e | 123 | //Angle in radians |
aalawfi | 28:1c2eb25d624e | 124 | float servo_angle = (OFFSET_ANGLE+KP*err + KD*errChange*TIME_DERIVATIVE + KI_STEERING*errorArea*TIME_INTEGRAL); |
aalawfi | 2:c857935f928e | 125 | //Calculate the duty cycle for the servo motor |
aalawfi | 2:c857935f928e | 126 | current_duty_cycle = rad2dc(servo_angle); |
aalawfi | 24:7bf492bf50f4 | 127 | |
aalawfi | 26:54ce9f642477 | 128 | //--- integral anti-windup --- |
aalawfi | 25:8bd029d58251 | 129 | if (servo_angle > 0.1 || servo_angle < 0.05){ |
aalawfi | 25:8bd029d58251 | 130 | if (errorArea > 0.0){ |
aalawfi | 25:8bd029d58251 | 131 | clamp = true; |
aalawfi | 25:8bd029d58251 | 132 | } |
aalawfi | 25:8bd029d58251 | 133 | } else { |
aalawfi | 25:8bd029d58251 | 134 | clamp = false; |
aalawfi | 25:8bd029d58251 | 135 | } |
aalawfi | 26:54ce9f642477 | 136 | |
aalawfi | 28:1c2eb25d624e | 137 | float strCheck = rad2dc(0); |
aalawfi | 28:1c2eb25d624e | 138 | servo_motor_pwm.write(current_duty_cycle); |
aalawfi | 26:54ce9f642477 | 139 | |
aalawfi | 28:1c2eb25d624e | 140 | err_prev = err; |
aalawfi | 28:1c2eb25d624e | 141 | PREV_KICK_ERR = KICK_ERR; |
aalawfi | 28:1c2eb25d624e | 142 | errorAreaPrev = errorArea; |
aalawfi | 22:08d30ea47111 | 143 | |
aalawfi | 2:c857935f928e | 144 | } |
aalawfi | 9:5320c2dfb913 | 145 | else { |
aalawfi | 2:c857935f928e | 146 | current_duty_cycle = rad2dc(M_PI/4); |
aalawfi | 25:8bd029d58251 | 147 | |
aalawfi | 2:c857935f928e | 148 | servo_motor_pwm.write(current_duty_cycle); |
aalawfi | 9:5320c2dfb913 | 149 | }; |
aalawfi | 28:1c2eb25d624e | 150 | |
aalawfi | 2:c857935f928e | 151 | } |
aalawfi | 2:c857935f928e | 152 | |
aalawfi | 2:c857935f928e | 153 | |
aalawfi | 2:c857935f928e | 154 |