Library for the PsiSwarm Robot - Version 0.4
demo.cpp@3:7c0d1f581757, 2016-03-15 (annotated)
- Committer:
- jah128
- Date:
- Tue Mar 15 00:58:09 2016 +0000
- Revision:
- 3:7c0d1f581757
- Parent:
- 2:c6986ee3c7c5
Added to serial code; reverted back to old version of message handling [temporary fix?]
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
jah128 | 0:d6269d17c8cf | 1 | /* University of York Robotics Laboratory PsiSwarm Library: Demo Mode Source File |
jah128 | 0:d6269d17c8cf | 2 | * |
jah128 | 0:d6269d17c8cf | 3 | * File: demo.cpp |
jah128 | 0:d6269d17c8cf | 4 | * |
jah128 | 0:d6269d17c8cf | 5 | * (C) Dept. Electronics & Computer Science, University of York |
jah128 | 0:d6269d17c8cf | 6 | * James Hilder, Alan Millard, Alexander Horsfield, Homero Elizondo, Jon Timmis |
jah128 | 0:d6269d17c8cf | 7 | * |
jah128 | 2:c6986ee3c7c5 | 8 | * PsiSwarm Library Version: 0.41 |
jah128 | 0:d6269d17c8cf | 9 | * |
jah128 | 0:d6269d17c8cf | 10 | * Version 0.4 : Added PsiSwarmBasic menu |
jah128 | 0:d6269d17c8cf | 11 | * Version 0.2 : Remove most the functionality from center-button push to allow all operations to be accessable from |
jah128 | 0:d6269d17c8cf | 12 | * four directions alone. |
jah128 | 0:d6269d17c8cf | 13 | * Added extra sensor information, added various testing demos |
jah128 | 0:d6269d17c8cf | 14 | * |
jah128 | 2:c6986ee3c7c5 | 15 | * |
jah128 | 2:c6986ee3c7c5 | 16 | * March 2016 |
jah128 | 0:d6269d17c8cf | 17 | * |
jah128 | 0:d6269d17c8cf | 18 | */ |
jah128 | 0:d6269d17c8cf | 19 | |
jah128 | 0:d6269d17c8cf | 20 | |
jah128 | 0:d6269d17c8cf | 21 | #include "psiswarm.h" |
jah128 | 0:d6269d17c8cf | 22 | |
jah128 | 0:d6269d17c8cf | 23 | // PID terms |
jah128 | 0:d6269d17c8cf | 24 | #define LF_P_TERM 0.2 |
jah128 | 0:d6269d17c8cf | 25 | #define LF_I_TERM 0 |
jah128 | 0:d6269d17c8cf | 26 | #define LF_D_TERM 4 |
jah128 | 0:d6269d17c8cf | 27 | |
jah128 | 0:d6269d17c8cf | 28 | char top_menu = 0; |
jah128 | 0:d6269d17c8cf | 29 | char sub_menu = 0; |
jah128 | 0:d6269d17c8cf | 30 | char level = 0; |
jah128 | 0:d6269d17c8cf | 31 | char started = 0; |
jah128 | 0:d6269d17c8cf | 32 | char topline[17]; |
jah128 | 0:d6269d17c8cf | 33 | char bottomline[17]; |
jah128 | 0:d6269d17c8cf | 34 | char led_state[9]; |
jah128 | 0:d6269d17c8cf | 35 | char all_led_state = 0; |
jah128 | 0:d6269d17c8cf | 36 | char base_led_state = 0; |
jah128 | 0:d6269d17c8cf | 37 | char brightness = 20; |
jah128 | 0:d6269d17c8cf | 38 | char bl_brightness = 100; |
jah128 | 0:d6269d17c8cf | 39 | char base_ir_index = 0; |
jah128 | 0:d6269d17c8cf | 40 | char side_ir_index = 0; |
jah128 | 0:d6269d17c8cf | 41 | signed short left_speed = 0; |
jah128 | 0:d6269d17c8cf | 42 | signed short right_speed = 0; |
jah128 | 0:d6269d17c8cf | 43 | char both_motor_mode = 0; |
jah128 | 0:d6269d17c8cf | 44 | char last_switch_pressed; |
jah128 | 0:d6269d17c8cf | 45 | Timeout demo_event; |
jah128 | 0:d6269d17c8cf | 46 | char handling_event = 0; |
jah128 | 0:d6269d17c8cf | 47 | |
jah128 | 0:d6269d17c8cf | 48 | Timeout demo_timeout; |
jah128 | 0:d6269d17c8cf | 49 | char demo_running = 0; |
jah128 | 0:d6269d17c8cf | 50 | Timer demo_timer; |
jah128 | 0:d6269d17c8cf | 51 | float time_out; |
jah128 | 0:d6269d17c8cf | 52 | float speed; |
jah128 | 0:d6269d17c8cf | 53 | char state; |
jah128 | 0:d6269d17c8cf | 54 | char led_step = 0; |
jah128 | 0:d6269d17c8cf | 55 | char spin_step = 0; |
jah128 | 0:d6269d17c8cf | 56 | char stress_step = 0; |
jah128 | 0:d6269d17c8cf | 57 | |
jah128 | 0:d6269d17c8cf | 58 | |
jah128 | 0:d6269d17c8cf | 59 | float lf_right; |
jah128 | 0:d6269d17c8cf | 60 | float lf_left; |
jah128 | 0:d6269d17c8cf | 61 | float lf_current_pos_of_line = 0.0; |
jah128 | 0:d6269d17c8cf | 62 | float lf_previous_pos_of_line = 0.0; |
jah128 | 0:d6269d17c8cf | 63 | float lf_derivative,lf_proportional,lf_integral = 0; |
jah128 | 0:d6269d17c8cf | 64 | float lf_power; |
jah128 | 0:d6269d17c8cf | 65 | float lf_speed = 0.4; |
jah128 | 0:d6269d17c8cf | 66 | |
jah128 | 0:d6269d17c8cf | 67 | |
jah128 | 0:d6269d17c8cf | 68 | |
jah128 | 0:d6269d17c8cf | 69 | void demo_mode() |
jah128 | 0:d6269d17c8cf | 70 | { |
jah128 | 0:d6269d17c8cf | 71 | debug("- Starting Demo Mode\n"); |
jah128 | 0:d6269d17c8cf | 72 | if(use_flash_basic == 1) top_menu = 7; |
jah128 | 0:d6269d17c8cf | 73 | demo_on = 1; |
jah128 | 0:d6269d17c8cf | 74 | display.set_backlight_brightness(bl_brightness * 0.01f); |
jah128 | 0:d6269d17c8cf | 75 | display.clear_display(); |
jah128 | 0:d6269d17c8cf | 76 | display.write_string("PSI SWARM SYSTEM"); |
jah128 | 0:d6269d17c8cf | 77 | display.set_position(1,0); |
jah128 | 0:d6269d17c8cf | 78 | display.write_string(" DEMO MODE"); |
jah128 | 0:d6269d17c8cf | 79 | wait(0.5); |
jah128 | 0:d6269d17c8cf | 80 | display.clear_display(); |
jah128 | 0:d6269d17c8cf | 81 | display.write_string("Use cursor to"); |
jah128 | 0:d6269d17c8cf | 82 | display.set_position(1,0); |
jah128 | 0:d6269d17c8cf | 83 | display.write_string("navigate menus"); |
jah128 | 0:d6269d17c8cf | 84 | char step = 0; |
jah128 | 0:d6269d17c8cf | 85 | while(demo_on) { |
jah128 | 0:d6269d17c8cf | 86 | if(demo_running == 0) { |
jah128 | 0:d6269d17c8cf | 87 | switch(step) { |
jah128 | 0:d6269d17c8cf | 88 | case 0: |
jah128 | 0:d6269d17c8cf | 89 | mbed_led1 = 1; |
jah128 | 0:d6269d17c8cf | 90 | mbed_led2 = 0; |
jah128 | 0:d6269d17c8cf | 91 | break; |
jah128 | 0:d6269d17c8cf | 92 | case 1: |
jah128 | 0:d6269d17c8cf | 93 | mbed_led2 = 1; |
jah128 | 0:d6269d17c8cf | 94 | mbed_led1 = 0; |
jah128 | 0:d6269d17c8cf | 95 | break; |
jah128 | 0:d6269d17c8cf | 96 | } |
jah128 | 0:d6269d17c8cf | 97 | step++; |
jah128 | 0:d6269d17c8cf | 98 | if(step==2)step=0; |
jah128 | 0:d6269d17c8cf | 99 | } else { |
jah128 | 0:d6269d17c8cf | 100 | mbed_led1 = 0; |
jah128 | 0:d6269d17c8cf | 101 | mbed_led2 = 0; |
jah128 | 0:d6269d17c8cf | 102 | mbed_led3 = 0; |
jah128 | 0:d6269d17c8cf | 103 | mbed_led4 = 0; |
jah128 | 0:d6269d17c8cf | 104 | } |
jah128 | 0:d6269d17c8cf | 105 | wait(0.5); |
jah128 | 0:d6269d17c8cf | 106 | } |
jah128 | 0:d6269d17c8cf | 107 | debug("- Demo mode ended\n"); |
jah128 | 0:d6269d17c8cf | 108 | } |
jah128 | 0:d6269d17c8cf | 109 | |
jah128 | 0:d6269d17c8cf | 110 | void demo_handle_switch_event(char switch_pressed) |
jah128 | 0:d6269d17c8cf | 111 | { |
jah128 | 0:d6269d17c8cf | 112 | if(!handling_event) { |
jah128 | 0:d6269d17c8cf | 113 | handling_event = 1; |
jah128 | 0:d6269d17c8cf | 114 | last_switch_pressed = switch_pressed; |
jah128 | 0:d6269d17c8cf | 115 | demo_event.attach_us(&demo_event_thread, 1000); |
jah128 | 0:d6269d17c8cf | 116 | } |
jah128 | 0:d6269d17c8cf | 117 | } |
jah128 | 0:d6269d17c8cf | 118 | |
jah128 | 0:d6269d17c8cf | 119 | void demo_event_thread() |
jah128 | 0:d6269d17c8cf | 120 | { |
jah128 | 0:d6269d17c8cf | 121 | handling_event = 0; |
jah128 | 0:d6269d17c8cf | 122 | if(started == 1) { |
jah128 | 0:d6269d17c8cf | 123 | switch(last_switch_pressed) { |
jah128 | 0:d6269d17c8cf | 124 | case 1: //Up pressed |
jah128 | 0:d6269d17c8cf | 125 | switch(level) { |
jah128 | 0:d6269d17c8cf | 126 | case 0: |
jah128 | 0:d6269d17c8cf | 127 | if(top_menu != 6) { |
jah128 | 0:d6269d17c8cf | 128 | level++; |
jah128 | 0:d6269d17c8cf | 129 | sub_menu = 0; |
jah128 | 0:d6269d17c8cf | 130 | } else { |
jah128 | 0:d6269d17c8cf | 131 | demo_on = 0; |
jah128 | 0:d6269d17c8cf | 132 | user_code_running = user_code_restore_mode; |
jah128 | 0:d6269d17c8cf | 133 | } |
jah128 | 0:d6269d17c8cf | 134 | break; |
jah128 | 0:d6269d17c8cf | 135 | case 1: |
jah128 | 0:d6269d17c8cf | 136 | switch(top_menu) { |
jah128 | 0:d6269d17c8cf | 137 | case 7: // PsiBasic Menu |
jah128 | 0:d6269d17c8cf | 138 | if(sub_menu == psi_basic_file_count) level = 0; |
jah128 | 0:d6269d17c8cf | 139 | break; |
jah128 | 0:d6269d17c8cf | 140 | case 0: //LED Menu |
jah128 | 0:d6269d17c8cf | 141 | if(sub_menu < 9) { |
jah128 | 0:d6269d17c8cf | 142 | if(led_state[sub_menu] == 0) led_state[sub_menu] = 3; |
jah128 | 0:d6269d17c8cf | 143 | else led_state[sub_menu]--; |
jah128 | 0:d6269d17c8cf | 144 | demo_update_leds(); |
jah128 | 0:d6269d17c8cf | 145 | } |
jah128 | 0:d6269d17c8cf | 146 | if(sub_menu == 9) { |
jah128 | 0:d6269d17c8cf | 147 | if(all_led_state == 0) all_led_state = 3; |
jah128 | 0:d6269d17c8cf | 148 | else all_led_state--; |
jah128 | 0:d6269d17c8cf | 149 | for(int i=0; i<9; i++) { |
jah128 | 0:d6269d17c8cf | 150 | led_state[i]=all_led_state; |
jah128 | 0:d6269d17c8cf | 151 | } |
jah128 | 0:d6269d17c8cf | 152 | demo_update_leds(); |
jah128 | 0:d6269d17c8cf | 153 | } |
jah128 | 0:d6269d17c8cf | 154 | if(sub_menu == 10) { |
jah128 | 0:d6269d17c8cf | 155 | base_led_state = 1 - base_led_state; |
jah128 | 0:d6269d17c8cf | 156 | demo_update_leds(); |
jah128 | 0:d6269d17c8cf | 157 | } |
jah128 | 0:d6269d17c8cf | 158 | if(sub_menu == 11) { |
jah128 | 0:d6269d17c8cf | 159 | switch(brightness) { |
jah128 | 0:d6269d17c8cf | 160 | case 100: |
jah128 | 0:d6269d17c8cf | 161 | brightness = 50; |
jah128 | 0:d6269d17c8cf | 162 | break; |
jah128 | 0:d6269d17c8cf | 163 | case 2: |
jah128 | 0:d6269d17c8cf | 164 | brightness = 1; |
jah128 | 0:d6269d17c8cf | 165 | break; |
jah128 | 0:d6269d17c8cf | 166 | case 5: |
jah128 | 0:d6269d17c8cf | 167 | brightness = 2; |
jah128 | 0:d6269d17c8cf | 168 | break; |
jah128 | 0:d6269d17c8cf | 169 | case 10: |
jah128 | 0:d6269d17c8cf | 170 | brightness = 5; |
jah128 | 0:d6269d17c8cf | 171 | break; |
jah128 | 0:d6269d17c8cf | 172 | case 20: |
jah128 | 0:d6269d17c8cf | 173 | brightness = 10; |
jah128 | 0:d6269d17c8cf | 174 | break; |
jah128 | 0:d6269d17c8cf | 175 | case 50: |
jah128 | 0:d6269d17c8cf | 176 | brightness = 20; |
jah128 | 0:d6269d17c8cf | 177 | break; |
jah128 | 0:d6269d17c8cf | 178 | } |
jah128 | 0:d6269d17c8cf | 179 | demo_update_leds(); |
jah128 | 0:d6269d17c8cf | 180 | } |
jah128 | 0:d6269d17c8cf | 181 | if(sub_menu == 12) { |
jah128 | 0:d6269d17c8cf | 182 | if(bl_brightness > 0) bl_brightness-=10; |
jah128 | 0:d6269d17c8cf | 183 | display.set_backlight_brightness(bl_brightness * 0.01f); |
jah128 | 0:d6269d17c8cf | 184 | } |
jah128 | 0:d6269d17c8cf | 185 | if(sub_menu == 13) level = 0; |
jah128 | 0:d6269d17c8cf | 186 | break; |
jah128 | 0:d6269d17c8cf | 187 | case 1: // Sensors Menu |
jah128 | 0:d6269d17c8cf | 188 | if(sub_menu == 4 || sub_menu == 5) { |
jah128 | 0:d6269d17c8cf | 189 | if(base_ir_index == 0) base_ir_index = 4; |
jah128 | 0:d6269d17c8cf | 190 | else base_ir_index --; |
jah128 | 0:d6269d17c8cf | 191 | } |
jah128 | 0:d6269d17c8cf | 192 | if(sub_menu > 5 && sub_menu < 9) { |
jah128 | 0:d6269d17c8cf | 193 | if(side_ir_index == 0) side_ir_index = 7; |
jah128 | 0:d6269d17c8cf | 194 | else side_ir_index --; |
jah128 | 0:d6269d17c8cf | 195 | } |
jah128 | 0:d6269d17c8cf | 196 | if(sub_menu == 11) level = 0; |
jah128 | 0:d6269d17c8cf | 197 | break; |
jah128 | 0:d6269d17c8cf | 198 | case 2: // Motor Menu |
jah128 | 0:d6269d17c8cf | 199 | if(sub_menu == 0) { |
jah128 | 0:d6269d17c8cf | 200 | left_speed += 5; |
jah128 | 0:d6269d17c8cf | 201 | if(left_speed > 100) left_speed = 100; |
jah128 | 0:d6269d17c8cf | 202 | set_left_motor_speed(left_speed / 100.0f); |
jah128 | 0:d6269d17c8cf | 203 | } |
jah128 | 0:d6269d17c8cf | 204 | if(sub_menu == 1) { |
jah128 | 0:d6269d17c8cf | 205 | right_speed += 5; |
jah128 | 0:d6269d17c8cf | 206 | if(right_speed > 100) right_speed = 100; |
jah128 | 0:d6269d17c8cf | 207 | set_right_motor_speed(right_speed / 100.0f); |
jah128 | 0:d6269d17c8cf | 208 | } |
jah128 | 0:d6269d17c8cf | 209 | if(sub_menu == 2) { |
jah128 | 0:d6269d17c8cf | 210 | if(both_motor_mode == 0) both_motor_mode=5; |
jah128 | 0:d6269d17c8cf | 211 | else both_motor_mode--; |
jah128 | 0:d6269d17c8cf | 212 | switch(both_motor_mode) { |
jah128 | 0:d6269d17c8cf | 213 | case 0: |
jah128 | 0:d6269d17c8cf | 214 | stop(); |
jah128 | 0:d6269d17c8cf | 215 | break; |
jah128 | 0:d6269d17c8cf | 216 | case 1: |
jah128 | 0:d6269d17c8cf | 217 | brake(); |
jah128 | 0:d6269d17c8cf | 218 | break; |
jah128 | 0:d6269d17c8cf | 219 | case 2: |
jah128 | 0:d6269d17c8cf | 220 | forward(0.5); |
jah128 | 0:d6269d17c8cf | 221 | break; |
jah128 | 0:d6269d17c8cf | 222 | case 3: |
jah128 | 0:d6269d17c8cf | 223 | forward(1); |
jah128 | 0:d6269d17c8cf | 224 | break; |
jah128 | 0:d6269d17c8cf | 225 | case 4: |
jah128 | 0:d6269d17c8cf | 226 | backward(0.5); |
jah128 | 0:d6269d17c8cf | 227 | break; |
jah128 | 0:d6269d17c8cf | 228 | case 5: |
jah128 | 0:d6269d17c8cf | 229 | backward(1.0); |
jah128 | 0:d6269d17c8cf | 230 | break; |
jah128 | 0:d6269d17c8cf | 231 | } |
jah128 | 0:d6269d17c8cf | 232 | } |
jah128 | 0:d6269d17c8cf | 233 | if(sub_menu == 3) { |
jah128 | 0:d6269d17c8cf | 234 | level = 0; |
jah128 | 0:d6269d17c8cf | 235 | } |
jah128 | 0:d6269d17c8cf | 236 | break; |
jah128 | 0:d6269d17c8cf | 237 | case 3: // Radio Menu |
jah128 | 0:d6269d17c8cf | 238 | if(sub_menu == 0) level = 0; |
jah128 | 0:d6269d17c8cf | 239 | break; |
jah128 | 0:d6269d17c8cf | 240 | case 4: // Info Menu |
jah128 | 0:d6269d17c8cf | 241 | if(sub_menu == 6) level = 0; |
jah128 | 0:d6269d17c8cf | 242 | break; |
jah128 | 0:d6269d17c8cf | 243 | case 5: // Demo Menu |
jah128 | 0:d6269d17c8cf | 244 | if(sub_menu == 0) { |
jah128 | 0:d6269d17c8cf | 245 | if(demo_running == 0) { |
jah128 | 0:d6269d17c8cf | 246 | start_line_demo(); |
jah128 | 0:d6269d17c8cf | 247 | } else { |
jah128 | 0:d6269d17c8cf | 248 | demo_running = 0; |
jah128 | 0:d6269d17c8cf | 249 | display.set_backlight_brightness(bl_brightness * 0.01f); |
jah128 | 0:d6269d17c8cf | 250 | stop(); |
jah128 | 0:d6269d17c8cf | 251 | } |
jah128 | 0:d6269d17c8cf | 252 | } |
jah128 | 0:d6269d17c8cf | 253 | if(sub_menu == 1) { |
jah128 | 0:d6269d17c8cf | 254 | if(demo_running == 0) { |
jah128 | 0:d6269d17c8cf | 255 | start_obstacle_demo(); |
jah128 | 0:d6269d17c8cf | 256 | } else { |
jah128 | 0:d6269d17c8cf | 257 | demo_running = 0; |
jah128 | 0:d6269d17c8cf | 258 | display.set_backlight_brightness(bl_brightness * 0.01f); |
jah128 | 0:d6269d17c8cf | 259 | stop(); |
jah128 | 0:d6269d17c8cf | 260 | } |
jah128 | 0:d6269d17c8cf | 261 | } |
jah128 | 0:d6269d17c8cf | 262 | if(sub_menu == 2) { |
jah128 | 0:d6269d17c8cf | 263 | if(demo_running == 0) { |
jah128 | 0:d6269d17c8cf | 264 | start_spinning_demo(); |
jah128 | 0:d6269d17c8cf | 265 | } else { |
jah128 | 0:d6269d17c8cf | 266 | demo_running = 0; |
jah128 | 0:d6269d17c8cf | 267 | display.set_backlight_brightness(bl_brightness * 0.01f); |
jah128 | 0:d6269d17c8cf | 268 | stop(); |
jah128 | 0:d6269d17c8cf | 269 | } |
jah128 | 0:d6269d17c8cf | 270 | } |
jah128 | 0:d6269d17c8cf | 271 | if(sub_menu == 3) { |
jah128 | 0:d6269d17c8cf | 272 | if(demo_running == 0) { |
jah128 | 0:d6269d17c8cf | 273 | start_stress_demo(); |
jah128 | 0:d6269d17c8cf | 274 | } else { |
jah128 | 0:d6269d17c8cf | 275 | demo_running = 0; |
jah128 | 0:d6269d17c8cf | 276 | display.set_backlight_brightness(bl_brightness * 0.01f); |
jah128 | 0:d6269d17c8cf | 277 | stop(); |
jah128 | 0:d6269d17c8cf | 278 | } |
jah128 | 0:d6269d17c8cf | 279 | } |
jah128 | 0:d6269d17c8cf | 280 | if(sub_menu == 4) level = 0; |
jah128 | 0:d6269d17c8cf | 281 | break; |
jah128 | 0:d6269d17c8cf | 282 | } |
jah128 | 0:d6269d17c8cf | 283 | break; |
jah128 | 0:d6269d17c8cf | 284 | } |
jah128 | 0:d6269d17c8cf | 285 | break; |
jah128 | 0:d6269d17c8cf | 286 | case 2: //Down pressed |
jah128 | 0:d6269d17c8cf | 287 | switch(level) { |
jah128 | 0:d6269d17c8cf | 288 | case 0: |
jah128 | 0:d6269d17c8cf | 289 | if(top_menu != 6) { |
jah128 | 0:d6269d17c8cf | 290 | level++; |
jah128 | 0:d6269d17c8cf | 291 | sub_menu = 0; |
jah128 | 0:d6269d17c8cf | 292 | } else { |
jah128 | 0:d6269d17c8cf | 293 | demo_on = 0; |
jah128 | 0:d6269d17c8cf | 294 | user_code_running = user_code_restore_mode; |
jah128 | 0:d6269d17c8cf | 295 | } |
jah128 | 0:d6269d17c8cf | 296 | break; |
jah128 | 0:d6269d17c8cf | 297 | case 1: |
jah128 | 0:d6269d17c8cf | 298 | switch(top_menu) { |
jah128 | 0:d6269d17c8cf | 299 | case 7: // PsiBasic Menu |
jah128 | 0:d6269d17c8cf | 300 | if(sub_menu == psi_basic_file_count) level = 0; |
jah128 | 0:d6269d17c8cf | 301 | break; |
jah128 | 0:d6269d17c8cf | 302 | case 0: //LED Menu |
jah128 | 0:d6269d17c8cf | 303 | if(sub_menu < 9) { |
jah128 | 0:d6269d17c8cf | 304 | led_state[sub_menu]++; |
jah128 | 0:d6269d17c8cf | 305 | if(led_state[sub_menu] == 4) led_state[sub_menu] = 0; |
jah128 | 0:d6269d17c8cf | 306 | demo_update_leds(); |
jah128 | 0:d6269d17c8cf | 307 | } |
jah128 | 0:d6269d17c8cf | 308 | if(sub_menu == 9) { |
jah128 | 0:d6269d17c8cf | 309 | all_led_state++; |
jah128 | 0:d6269d17c8cf | 310 | if(all_led_state == 4) all_led_state = 0; |
jah128 | 0:d6269d17c8cf | 311 | for(int i=0; i<9; i++) { |
jah128 | 0:d6269d17c8cf | 312 | led_state[i]=all_led_state; |
jah128 | 0:d6269d17c8cf | 313 | } |
jah128 | 0:d6269d17c8cf | 314 | demo_update_leds(); |
jah128 | 0:d6269d17c8cf | 315 | } |
jah128 | 0:d6269d17c8cf | 316 | if(sub_menu == 10) { |
jah128 | 0:d6269d17c8cf | 317 | base_led_state = 1 - base_led_state; |
jah128 | 0:d6269d17c8cf | 318 | demo_update_leds(); |
jah128 | 0:d6269d17c8cf | 319 | } |
jah128 | 0:d6269d17c8cf | 320 | if(sub_menu == 11) { |
jah128 | 0:d6269d17c8cf | 321 | switch(brightness) { |
jah128 | 0:d6269d17c8cf | 322 | case 1: |
jah128 | 0:d6269d17c8cf | 323 | brightness = 2; |
jah128 | 0:d6269d17c8cf | 324 | break; |
jah128 | 0:d6269d17c8cf | 325 | case 2: |
jah128 | 0:d6269d17c8cf | 326 | brightness = 5; |
jah128 | 0:d6269d17c8cf | 327 | break; |
jah128 | 0:d6269d17c8cf | 328 | case 5: |
jah128 | 0:d6269d17c8cf | 329 | brightness = 10; |
jah128 | 0:d6269d17c8cf | 330 | break; |
jah128 | 0:d6269d17c8cf | 331 | case 10: |
jah128 | 0:d6269d17c8cf | 332 | brightness = 20; |
jah128 | 0:d6269d17c8cf | 333 | break; |
jah128 | 0:d6269d17c8cf | 334 | case 20: |
jah128 | 0:d6269d17c8cf | 335 | brightness = 50; |
jah128 | 0:d6269d17c8cf | 336 | break; |
jah128 | 0:d6269d17c8cf | 337 | case 50: |
jah128 | 0:d6269d17c8cf | 338 | brightness = 100; |
jah128 | 0:d6269d17c8cf | 339 | break; |
jah128 | 0:d6269d17c8cf | 340 | } |
jah128 | 0:d6269d17c8cf | 341 | demo_update_leds(); |
jah128 | 0:d6269d17c8cf | 342 | } |
jah128 | 0:d6269d17c8cf | 343 | |
jah128 | 0:d6269d17c8cf | 344 | if(sub_menu == 12) { |
jah128 | 0:d6269d17c8cf | 345 | if(bl_brightness < 100) bl_brightness+=10; |
jah128 | 0:d6269d17c8cf | 346 | display.set_backlight_brightness(bl_brightness * 0.01f); |
jah128 | 0:d6269d17c8cf | 347 | } |
jah128 | 0:d6269d17c8cf | 348 | if(sub_menu == 13) level = 0; |
jah128 | 0:d6269d17c8cf | 349 | |
jah128 | 0:d6269d17c8cf | 350 | break; |
jah128 | 0:d6269d17c8cf | 351 | case 1: // Sensors Menu |
jah128 | 0:d6269d17c8cf | 352 | if(sub_menu == 4 || sub_menu == 5) { |
jah128 | 0:d6269d17c8cf | 353 | if(base_ir_index == 4) base_ir_index = 0; |
jah128 | 0:d6269d17c8cf | 354 | else base_ir_index ++; |
jah128 | 0:d6269d17c8cf | 355 | } |
jah128 | 0:d6269d17c8cf | 356 | if(sub_menu > 5 && sub_menu < 9) { |
jah128 | 0:d6269d17c8cf | 357 | if(side_ir_index == 7) side_ir_index = 0; |
jah128 | 0:d6269d17c8cf | 358 | else side_ir_index ++; |
jah128 | 0:d6269d17c8cf | 359 | } |
jah128 | 0:d6269d17c8cf | 360 | if(sub_menu == 11) level = 0; |
jah128 | 0:d6269d17c8cf | 361 | break; |
jah128 | 0:d6269d17c8cf | 362 | case 2: // Motor Menu |
jah128 | 0:d6269d17c8cf | 363 | if(sub_menu == 0) { |
jah128 | 0:d6269d17c8cf | 364 | left_speed -= 5; |
jah128 | 0:d6269d17c8cf | 365 | if(left_speed < -100) left_speed = -100; |
jah128 | 0:d6269d17c8cf | 366 | set_left_motor_speed(left_speed / 100.0f); |
jah128 | 0:d6269d17c8cf | 367 | } |
jah128 | 0:d6269d17c8cf | 368 | if(sub_menu == 1) { |
jah128 | 0:d6269d17c8cf | 369 | right_speed -= 5; |
jah128 | 0:d6269d17c8cf | 370 | if(right_speed < -100) right_speed = -100; |
jah128 | 0:d6269d17c8cf | 371 | set_right_motor_speed(right_speed / 100.0f); |
jah128 | 0:d6269d17c8cf | 372 | } |
jah128 | 0:d6269d17c8cf | 373 | if(sub_menu == 2) { |
jah128 | 0:d6269d17c8cf | 374 | both_motor_mode++; |
jah128 | 0:d6269d17c8cf | 375 | if(both_motor_mode == 6) both_motor_mode=0; |
jah128 | 0:d6269d17c8cf | 376 | switch(both_motor_mode) { |
jah128 | 0:d6269d17c8cf | 377 | case 0: |
jah128 | 0:d6269d17c8cf | 378 | stop(); |
jah128 | 0:d6269d17c8cf | 379 | break; |
jah128 | 0:d6269d17c8cf | 380 | case 1: |
jah128 | 0:d6269d17c8cf | 381 | brake(); |
jah128 | 0:d6269d17c8cf | 382 | break; |
jah128 | 0:d6269d17c8cf | 383 | case 2: |
jah128 | 0:d6269d17c8cf | 384 | forward(0.5); |
jah128 | 0:d6269d17c8cf | 385 | break; |
jah128 | 0:d6269d17c8cf | 386 | case 3: |
jah128 | 0:d6269d17c8cf | 387 | forward(1); |
jah128 | 0:d6269d17c8cf | 388 | break; |
jah128 | 0:d6269d17c8cf | 389 | case 4: |
jah128 | 0:d6269d17c8cf | 390 | backward(0.5); |
jah128 | 0:d6269d17c8cf | 391 | break; |
jah128 | 0:d6269d17c8cf | 392 | case 5: |
jah128 | 0:d6269d17c8cf | 393 | backward(1.0); |
jah128 | 0:d6269d17c8cf | 394 | break; |
jah128 | 0:d6269d17c8cf | 395 | } |
jah128 | 0:d6269d17c8cf | 396 | } |
jah128 | 0:d6269d17c8cf | 397 | if(sub_menu == 3) { |
jah128 | 0:d6269d17c8cf | 398 | level = 0; |
jah128 | 0:d6269d17c8cf | 399 | } |
jah128 | 0:d6269d17c8cf | 400 | break; |
jah128 | 0:d6269d17c8cf | 401 | case 3: // Radio Menu |
jah128 | 0:d6269d17c8cf | 402 | if(sub_menu == 0) level = 0; |
jah128 | 0:d6269d17c8cf | 403 | break; |
jah128 | 0:d6269d17c8cf | 404 | case 4: // Info Menu |
jah128 | 0:d6269d17c8cf | 405 | if(sub_menu == 6) level = 0; |
jah128 | 0:d6269d17c8cf | 406 | break; |
jah128 | 0:d6269d17c8cf | 407 | case 5: // Demo Menu |
jah128 | 0:d6269d17c8cf | 408 | if(sub_menu == 0) { |
jah128 | 0:d6269d17c8cf | 409 | if(demo_running == 0) { |
jah128 | 0:d6269d17c8cf | 410 | start_line_demo(); |
jah128 | 0:d6269d17c8cf | 411 | } else { |
jah128 | 0:d6269d17c8cf | 412 | demo_running = 0; |
jah128 | 0:d6269d17c8cf | 413 | display.set_backlight_brightness(bl_brightness * 0.01f); |
jah128 | 0:d6269d17c8cf | 414 | stop(); |
jah128 | 0:d6269d17c8cf | 415 | } |
jah128 | 0:d6269d17c8cf | 416 | } |
jah128 | 0:d6269d17c8cf | 417 | if(sub_menu == 1) { |
jah128 | 0:d6269d17c8cf | 418 | if(demo_running == 0) { |
jah128 | 0:d6269d17c8cf | 419 | start_obstacle_demo(); |
jah128 | 0:d6269d17c8cf | 420 | } else { |
jah128 | 0:d6269d17c8cf | 421 | demo_running = 0; |
jah128 | 0:d6269d17c8cf | 422 | display.set_backlight_brightness(bl_brightness * 0.01f); |
jah128 | 0:d6269d17c8cf | 423 | stop(); |
jah128 | 0:d6269d17c8cf | 424 | |
jah128 | 0:d6269d17c8cf | 425 | } |
jah128 | 0:d6269d17c8cf | 426 | } |
jah128 | 0:d6269d17c8cf | 427 | if(sub_menu == 2) { |
jah128 | 0:d6269d17c8cf | 428 | if(demo_running == 0) { |
jah128 | 0:d6269d17c8cf | 429 | start_spinning_demo(); |
jah128 | 0:d6269d17c8cf | 430 | } else { |
jah128 | 0:d6269d17c8cf | 431 | demo_running = 0; |
jah128 | 0:d6269d17c8cf | 432 | display.set_backlight_brightness(bl_brightness * 0.01f); |
jah128 | 0:d6269d17c8cf | 433 | stop(); |
jah128 | 0:d6269d17c8cf | 434 | } |
jah128 | 0:d6269d17c8cf | 435 | } |
jah128 | 0:d6269d17c8cf | 436 | if(sub_menu == 3) { |
jah128 | 0:d6269d17c8cf | 437 | if(demo_running == 0) { |
jah128 | 0:d6269d17c8cf | 438 | start_stress_demo(); |
jah128 | 0:d6269d17c8cf | 439 | } else { |
jah128 | 0:d6269d17c8cf | 440 | demo_running = 0; |
jah128 | 0:d6269d17c8cf | 441 | display.set_backlight_brightness(bl_brightness * 0.01f); |
jah128 | 0:d6269d17c8cf | 442 | stop(); |
jah128 | 0:d6269d17c8cf | 443 | } |
jah128 | 0:d6269d17c8cf | 444 | } |
jah128 | 0:d6269d17c8cf | 445 | if(sub_menu == 4) level = 0; |
jah128 | 0:d6269d17c8cf | 446 | break; |
jah128 | 0:d6269d17c8cf | 447 | } |
jah128 | 0:d6269d17c8cf | 448 | break; |
jah128 | 0:d6269d17c8cf | 449 | } |
jah128 | 0:d6269d17c8cf | 450 | break; |
jah128 | 0:d6269d17c8cf | 451 | case 4: //Left pressed |
jah128 | 0:d6269d17c8cf | 452 | switch(level) { |
jah128 | 0:d6269d17c8cf | 453 | case 0: |
jah128 | 0:d6269d17c8cf | 454 | if(top_menu == 0) { |
jah128 | 0:d6269d17c8cf | 455 | top_menu = 6; |
jah128 | 0:d6269d17c8cf | 456 | if(use_flash_basic == 1) top_menu = 7; |
jah128 | 0:d6269d17c8cf | 457 | } |
jah128 | 0:d6269d17c8cf | 458 | else top_menu --; |
jah128 | 0:d6269d17c8cf | 459 | break; |
jah128 | 0:d6269d17c8cf | 460 | case 1: |
jah128 | 0:d6269d17c8cf | 461 | switch(top_menu) { |
jah128 | 0:d6269d17c8cf | 462 | case 0: //LED Menu |
jah128 | 0:d6269d17c8cf | 463 | if(sub_menu == 0) sub_menu = 13; |
jah128 | 0:d6269d17c8cf | 464 | else sub_menu --; |
jah128 | 0:d6269d17c8cf | 465 | break; |
jah128 | 0:d6269d17c8cf | 466 | case 1: //Sensors Menu |
jah128 | 0:d6269d17c8cf | 467 | if(sub_menu == 0) sub_menu = 11; |
jah128 | 0:d6269d17c8cf | 468 | else sub_menu --; |
jah128 | 0:d6269d17c8cf | 469 | break; |
jah128 | 0:d6269d17c8cf | 470 | |
jah128 | 0:d6269d17c8cf | 471 | case 2: //Motor Menu |
jah128 | 0:d6269d17c8cf | 472 | if(sub_menu == 0) sub_menu = 3; |
jah128 | 0:d6269d17c8cf | 473 | else sub_menu --; |
jah128 | 0:d6269d17c8cf | 474 | break; |
jah128 | 0:d6269d17c8cf | 475 | case 4: //Info Menu |
jah128 | 0:d6269d17c8cf | 476 | if(sub_menu == 0) sub_menu = 6; |
jah128 | 0:d6269d17c8cf | 477 | else sub_menu --; |
jah128 | 0:d6269d17c8cf | 478 | break; |
jah128 | 0:d6269d17c8cf | 479 | case 5: //Demo Menu |
jah128 | 0:d6269d17c8cf | 480 | if(sub_menu == 0) sub_menu = 4; |
jah128 | 0:d6269d17c8cf | 481 | else sub_menu --; |
jah128 | 0:d6269d17c8cf | 482 | break; |
jah128 | 0:d6269d17c8cf | 483 | case 7: //PsiBasic Menu |
jah128 | 0:d6269d17c8cf | 484 | if(sub_menu == 0) sub_menu = psi_basic_file_count; |
jah128 | 0:d6269d17c8cf | 485 | else sub_menu --; |
jah128 | 0:d6269d17c8cf | 486 | } |
jah128 | 0:d6269d17c8cf | 487 | break; |
jah128 | 0:d6269d17c8cf | 488 | |
jah128 | 0:d6269d17c8cf | 489 | } |
jah128 | 0:d6269d17c8cf | 490 | break; |
jah128 | 0:d6269d17c8cf | 491 | case 8: //Right pressed |
jah128 | 0:d6269d17c8cf | 492 | switch(level) { |
jah128 | 0:d6269d17c8cf | 493 | case 0: |
jah128 | 0:d6269d17c8cf | 494 | top_menu ++; |
jah128 | 0:d6269d17c8cf | 495 | if((top_menu - use_flash_basic) > 6) top_menu = 0; |
jah128 | 0:d6269d17c8cf | 496 | break; |
jah128 | 0:d6269d17c8cf | 497 | case 1: |
jah128 | 0:d6269d17c8cf | 498 | switch(top_menu) { |
jah128 | 0:d6269d17c8cf | 499 | case 0: //LED Menu |
jah128 | 0:d6269d17c8cf | 500 | if(sub_menu == 13) sub_menu = 0; |
jah128 | 0:d6269d17c8cf | 501 | else sub_menu ++; |
jah128 | 0:d6269d17c8cf | 502 | break; |
jah128 | 0:d6269d17c8cf | 503 | case 1: //Sensors Menu |
jah128 | 0:d6269d17c8cf | 504 | if(sub_menu == 11) sub_menu = 0; |
jah128 | 0:d6269d17c8cf | 505 | else sub_menu ++; |
jah128 | 0:d6269d17c8cf | 506 | break; |
jah128 | 0:d6269d17c8cf | 507 | case 2: //Motor Menu |
jah128 | 0:d6269d17c8cf | 508 | if(sub_menu == 3) sub_menu = 0; |
jah128 | 0:d6269d17c8cf | 509 | else sub_menu ++; |
jah128 | 0:d6269d17c8cf | 510 | break; |
jah128 | 0:d6269d17c8cf | 511 | case 4: //Info Menu |
jah128 | 0:d6269d17c8cf | 512 | if(sub_menu == 6) sub_menu = 0; |
jah128 | 0:d6269d17c8cf | 513 | else sub_menu ++; |
jah128 | 0:d6269d17c8cf | 514 | break; |
jah128 | 0:d6269d17c8cf | 515 | case 5: //Demo Menu |
jah128 | 0:d6269d17c8cf | 516 | if(sub_menu == 4) sub_menu = 0; |
jah128 | 0:d6269d17c8cf | 517 | else sub_menu ++; |
jah128 | 0:d6269d17c8cf | 518 | break; |
jah128 | 0:d6269d17c8cf | 519 | case 7: //PsiBasic Menu |
jah128 | 0:d6269d17c8cf | 520 | if(sub_menu == psi_basic_file_count) sub_menu = 0; |
jah128 | 0:d6269d17c8cf | 521 | else sub_menu ++; |
jah128 | 0:d6269d17c8cf | 522 | } |
jah128 | 0:d6269d17c8cf | 523 | break; |
jah128 | 0:d6269d17c8cf | 524 | } |
jah128 | 0:d6269d17c8cf | 525 | break; |
jah128 | 0:d6269d17c8cf | 526 | case 16: //Select pressed |
jah128 | 0:d6269d17c8cf | 527 | switch(level) { |
jah128 | 0:d6269d17c8cf | 528 | case 0: |
jah128 | 0:d6269d17c8cf | 529 | if(top_menu != 6) { |
jah128 | 0:d6269d17c8cf | 530 | level++; |
jah128 | 0:d6269d17c8cf | 531 | sub_menu = 0; |
jah128 | 0:d6269d17c8cf | 532 | } else { |
jah128 | 0:d6269d17c8cf | 533 | demo_on = 0; |
jah128 | 0:d6269d17c8cf | 534 | user_code_running = user_code_restore_mode; |
jah128 | 0:d6269d17c8cf | 535 | } |
jah128 | 0:d6269d17c8cf | 536 | break; |
jah128 | 0:d6269d17c8cf | 537 | case 1: |
jah128 | 0:d6269d17c8cf | 538 | switch(top_menu) { |
jah128 | 0:d6269d17c8cf | 539 | case 0: //LED Menu |
jah128 | 0:d6269d17c8cf | 540 | if(sub_menu == 9) { |
jah128 | 0:d6269d17c8cf | 541 | for(int i=0; i<9; i++) { |
jah128 | 0:d6269d17c8cf | 542 | led_state[i]=all_led_state; |
jah128 | 0:d6269d17c8cf | 543 | } |
jah128 | 0:d6269d17c8cf | 544 | demo_update_leds(); |
jah128 | 0:d6269d17c8cf | 545 | } |
jah128 | 0:d6269d17c8cf | 546 | if(sub_menu == 13) level = 0; |
jah128 | 0:d6269d17c8cf | 547 | break; |
jah128 | 0:d6269d17c8cf | 548 | case 1: // Sensors Menu |
jah128 | 0:d6269d17c8cf | 549 | if(sub_menu == 11) level = 0; |
jah128 | 0:d6269d17c8cf | 550 | break; |
jah128 | 0:d6269d17c8cf | 551 | case 2: //Motor Menu |
jah128 | 0:d6269d17c8cf | 552 | if(sub_menu == 2) { |
jah128 | 0:d6269d17c8cf | 553 | switch(both_motor_mode) { |
jah128 | 0:d6269d17c8cf | 554 | case 0: |
jah128 | 0:d6269d17c8cf | 555 | stop(); |
jah128 | 0:d6269d17c8cf | 556 | break; |
jah128 | 0:d6269d17c8cf | 557 | case 1: |
jah128 | 0:d6269d17c8cf | 558 | brake(); |
jah128 | 0:d6269d17c8cf | 559 | break; |
jah128 | 0:d6269d17c8cf | 560 | case 2: |
jah128 | 0:d6269d17c8cf | 561 | forward(0.5); |
jah128 | 0:d6269d17c8cf | 562 | break; |
jah128 | 0:d6269d17c8cf | 563 | case 3: |
jah128 | 0:d6269d17c8cf | 564 | forward(1); |
jah128 | 0:d6269d17c8cf | 565 | break; |
jah128 | 0:d6269d17c8cf | 566 | case 4: |
jah128 | 0:d6269d17c8cf | 567 | backward(0.5); |
jah128 | 0:d6269d17c8cf | 568 | break; |
jah128 | 0:d6269d17c8cf | 569 | case 5: |
jah128 | 0:d6269d17c8cf | 570 | backward(1.0); |
jah128 | 0:d6269d17c8cf | 571 | break; |
jah128 | 0:d6269d17c8cf | 572 | } |
jah128 | 0:d6269d17c8cf | 573 | } |
jah128 | 0:d6269d17c8cf | 574 | if(sub_menu == 3) { |
jah128 | 0:d6269d17c8cf | 575 | level = 0; |
jah128 | 0:d6269d17c8cf | 576 | } |
jah128 | 0:d6269d17c8cf | 577 | break; |
jah128 | 0:d6269d17c8cf | 578 | case 3: // Radio Menu |
jah128 | 0:d6269d17c8cf | 579 | if(sub_menu == 0) level = 0; |
jah128 | 0:d6269d17c8cf | 580 | break; |
jah128 | 0:d6269d17c8cf | 581 | case 4: // Info Menu |
jah128 | 0:d6269d17c8cf | 582 | if(sub_menu == 6) level = 0; |
jah128 | 0:d6269d17c8cf | 583 | break; |
jah128 | 0:d6269d17c8cf | 584 | case 5: // Demo Menu |
jah128 | 0:d6269d17c8cf | 585 | if(sub_menu == 4) level = 0; |
jah128 | 0:d6269d17c8cf | 586 | break; |
jah128 | 0:d6269d17c8cf | 587 | case 7: // PsiBasic Menu |
jah128 | 0:d6269d17c8cf | 588 | if(sub_menu == psi_basic_file_count) level = 0; |
jah128 | 0:d6269d17c8cf | 589 | break; |
jah128 | 0:d6269d17c8cf | 590 | } |
jah128 | 0:d6269d17c8cf | 591 | break; |
jah128 | 0:d6269d17c8cf | 592 | } |
jah128 | 0:d6269d17c8cf | 593 | break; |
jah128 | 0:d6269d17c8cf | 594 | } |
jah128 | 0:d6269d17c8cf | 595 | } else started = 1; |
jah128 | 0:d6269d17c8cf | 596 | display.clear_display(); |
jah128 | 0:d6269d17c8cf | 597 | switch(level) { |
jah128 | 0:d6269d17c8cf | 598 | case 0: |
jah128 | 0:d6269d17c8cf | 599 | //Top level menu |
jah128 | 0:d6269d17c8cf | 600 | switch(top_menu) { |
jah128 | 0:d6269d17c8cf | 601 | case 0: |
jah128 | 0:d6269d17c8cf | 602 | strcpy(topline,"---TEST LEDS----"); |
jah128 | 0:d6269d17c8cf | 603 | break; |
jah128 | 0:d6269d17c8cf | 604 | case 1: |
jah128 | 0:d6269d17c8cf | 605 | strcpy(topline,"--TEST SENSORS--"); |
jah128 | 0:d6269d17c8cf | 606 | break; |
jah128 | 0:d6269d17c8cf | 607 | case 2: |
jah128 | 0:d6269d17c8cf | 608 | strcpy(topline,"--TEST MOTORS---"); |
jah128 | 0:d6269d17c8cf | 609 | break; |
jah128 | 0:d6269d17c8cf | 610 | case 3: |
jah128 | 0:d6269d17c8cf | 611 | strcpy(topline,"---TEST RADIO---"); |
jah128 | 0:d6269d17c8cf | 612 | break; |
jah128 | 0:d6269d17c8cf | 613 | case 4: |
jah128 | 0:d6269d17c8cf | 614 | strcpy(topline,"------INFO------"); |
jah128 | 0:d6269d17c8cf | 615 | break; |
jah128 | 0:d6269d17c8cf | 616 | case 5: |
jah128 | 0:d6269d17c8cf | 617 | strcpy(topline,"---CODE DEMOS---"); |
jah128 | 0:d6269d17c8cf | 618 | break; |
jah128 | 0:d6269d17c8cf | 619 | case 6: |
jah128 | 0:d6269d17c8cf | 620 | strcpy(topline,"------EXIT------"); |
jah128 | 0:d6269d17c8cf | 621 | break; |
jah128 | 0:d6269d17c8cf | 622 | case 7: |
jah128 | 0:d6269d17c8cf | 623 | strcpy(topline,"---PSI BASIC----"); |
jah128 | 0:d6269d17c8cf | 624 | break; |
jah128 | 0:d6269d17c8cf | 625 | } |
jah128 | 0:d6269d17c8cf | 626 | strcpy(bottomline,""); |
jah128 | 0:d6269d17c8cf | 627 | break; |
jah128 | 0:d6269d17c8cf | 628 | case 1: |
jah128 | 0:d6269d17c8cf | 629 | //Sub level menu |
jah128 | 0:d6269d17c8cf | 630 | switch(top_menu) { |
jah128 | 0:d6269d17c8cf | 631 | case 7: |
jah128 | 0:d6269d17c8cf | 632 | strcpy(topline,"-PSI BASIC MENU-"); |
jah128 | 0:d6269d17c8cf | 633 | if(sub_menu == psi_basic_file_count) strcpy(bottomline,"EXIT"); |
jah128 | 0:d6269d17c8cf | 634 | else strcpy(bottomline,basic_filenames.at(sub_menu).c_str()); |
jah128 | 0:d6269d17c8cf | 635 | break; |
jah128 | 0:d6269d17c8cf | 636 | case 0: |
jah128 | 0:d6269d17c8cf | 637 | strcpy(topline,"----LED MENU----"); |
jah128 | 0:d6269d17c8cf | 638 | char led_status[7]; |
jah128 | 0:d6269d17c8cf | 639 | if(sub_menu<9) { |
jah128 | 0:d6269d17c8cf | 640 | switch(led_state[sub_menu]) { |
jah128 | 0:d6269d17c8cf | 641 | case 0: |
jah128 | 0:d6269d17c8cf | 642 | strcpy(led_status,"OFF"); |
jah128 | 0:d6269d17c8cf | 643 | break; |
jah128 | 0:d6269d17c8cf | 644 | case 1: |
jah128 | 0:d6269d17c8cf | 645 | strcpy(led_status,"RED"); |
jah128 | 0:d6269d17c8cf | 646 | break; |
jah128 | 0:d6269d17c8cf | 647 | case 2: |
jah128 | 0:d6269d17c8cf | 648 | strcpy(led_status,"GREEN"); |
jah128 | 0:d6269d17c8cf | 649 | break; |
jah128 | 0:d6269d17c8cf | 650 | case 3: |
jah128 | 0:d6269d17c8cf | 651 | strcpy(led_status,"YELLOW"); |
jah128 | 0:d6269d17c8cf | 652 | break; |
jah128 | 0:d6269d17c8cf | 653 | } |
jah128 | 0:d6269d17c8cf | 654 | } |
jah128 | 0:d6269d17c8cf | 655 | if(sub_menu < 8) sprintf(bottomline,"OUTER %d: %s",(sub_menu + 1),led_status); |
jah128 | 0:d6269d17c8cf | 656 | if(sub_menu == 8) sprintf(bottomline,"CENTER: %s",led_status); |
jah128 | 0:d6269d17c8cf | 657 | if(sub_menu == 9) { |
jah128 | 0:d6269d17c8cf | 658 | switch(all_led_state) { |
jah128 | 0:d6269d17c8cf | 659 | case 0: |
jah128 | 0:d6269d17c8cf | 660 | strcpy(led_status,"OFF"); |
jah128 | 0:d6269d17c8cf | 661 | break; |
jah128 | 0:d6269d17c8cf | 662 | case 1: |
jah128 | 0:d6269d17c8cf | 663 | strcpy(led_status,"RED"); |
jah128 | 0:d6269d17c8cf | 664 | break; |
jah128 | 0:d6269d17c8cf | 665 | case 2: |
jah128 | 0:d6269d17c8cf | 666 | strcpy(led_status,"GREEN"); |
jah128 | 0:d6269d17c8cf | 667 | break; |
jah128 | 0:d6269d17c8cf | 668 | case 3: |
jah128 | 0:d6269d17c8cf | 669 | strcpy(led_status,"YELLOW"); |
jah128 | 0:d6269d17c8cf | 670 | break; |
jah128 | 0:d6269d17c8cf | 671 | } |
jah128 | 0:d6269d17c8cf | 672 | sprintf(bottomline,"SET ALL %s", led_status); |
jah128 | 0:d6269d17c8cf | 673 | } |
jah128 | 0:d6269d17c8cf | 674 | if(sub_menu == 10) { |
jah128 | 0:d6269d17c8cf | 675 | if(base_led_state == 0) strcpy(led_status,"OFF"); |
jah128 | 0:d6269d17c8cf | 676 | else strcpy(led_status,"ON"); |
jah128 | 0:d6269d17c8cf | 677 | sprintf(bottomline,"BASE: %s",led_status); |
jah128 | 0:d6269d17c8cf | 678 | } |
jah128 | 0:d6269d17c8cf | 679 | if(sub_menu == 11) sprintf(bottomline,"CLED BNESS %d%%", brightness); |
jah128 | 0:d6269d17c8cf | 680 | if(sub_menu == 12) sprintf(bottomline,"DISP BNESS %d%%", bl_brightness); |
jah128 | 0:d6269d17c8cf | 681 | if(sub_menu == 13) strcpy(bottomline,"EXIT"); |
jah128 | 0:d6269d17c8cf | 682 | break; |
jah128 | 0:d6269d17c8cf | 683 | |
jah128 | 0:d6269d17c8cf | 684 | case 1: |
jah128 | 0:d6269d17c8cf | 685 | strcpy(topline,"--SENSORS MENU--"); |
jah128 | 0:d6269d17c8cf | 686 | switch(sub_menu) { |
jah128 | 0:d6269d17c8cf | 687 | case 0: { |
jah128 | 0:d6269d17c8cf | 688 | float battery = get_battery_voltage (); |
jah128 | 0:d6269d17c8cf | 689 | sprintf(bottomline,"BATTERY: %1.3fV",battery); |
jah128 | 0:d6269d17c8cf | 690 | break; |
jah128 | 0:d6269d17c8cf | 691 | } |
jah128 | 0:d6269d17c8cf | 692 | case 1: { |
jah128 | 0:d6269d17c8cf | 693 | float dc = get_dc_voltage (); |
jah128 | 0:d6269d17c8cf | 694 | sprintf(bottomline,"DC: %1.3fV",dc); |
jah128 | 0:d6269d17c8cf | 695 | break; |
jah128 | 0:d6269d17c8cf | 696 | } |
jah128 | 0:d6269d17c8cf | 697 | case 2: { |
jah128 | 0:d6269d17c8cf | 698 | float current = get_current (); |
jah128 | 0:d6269d17c8cf | 699 | sprintf(bottomline,"CURRENT: %1.3fA",current); |
jah128 | 0:d6269d17c8cf | 700 | break; |
jah128 | 0:d6269d17c8cf | 701 | } |
jah128 | 0:d6269d17c8cf | 702 | case 3: { |
jah128 | 0:d6269d17c8cf | 703 | float temperature = get_temperature(); |
jah128 | 0:d6269d17c8cf | 704 | sprintf(bottomline,"TEMP: %3.2fC", temperature); |
jah128 | 0:d6269d17c8cf | 705 | break; |
jah128 | 0:d6269d17c8cf | 706 | } |
jah128 | 0:d6269d17c8cf | 707 | case 4: |
jah128 | 0:d6269d17c8cf | 708 | store_background_base_ir_values(); |
jah128 | 0:d6269d17c8cf | 709 | sprintf(bottomline,"BIR%dB:%d",base_ir_index+1,get_background_base_ir_value(base_ir_index)); |
jah128 | 0:d6269d17c8cf | 710 | break; |
jah128 | 0:d6269d17c8cf | 711 | case 5: |
jah128 | 0:d6269d17c8cf | 712 | store_illuminated_base_ir_values(); |
jah128 | 0:d6269d17c8cf | 713 | sprintf(bottomline,"BIR%dR:%d",base_ir_index+1,get_illuminated_base_ir_value(base_ir_index)); |
jah128 | 0:d6269d17c8cf | 714 | break; |
jah128 | 0:d6269d17c8cf | 715 | case 6: |
jah128 | 0:d6269d17c8cf | 716 | store_background_raw_ir_values(); |
jah128 | 0:d6269d17c8cf | 717 | sprintf(bottomline,"SIR%dB:%d",side_ir_index+1,get_background_raw_ir_value(side_ir_index)); |
jah128 | 0:d6269d17c8cf | 718 | break; |
jah128 | 0:d6269d17c8cf | 719 | case 7: |
jah128 | 0:d6269d17c8cf | 720 | store_illuminated_raw_ir_values(); |
jah128 | 0:d6269d17c8cf | 721 | sprintf(bottomline,"SIR%dR:%d",side_ir_index+1,get_illuminated_raw_ir_value(side_ir_index)); |
jah128 | 0:d6269d17c8cf | 722 | break; |
jah128 | 0:d6269d17c8cf | 723 | case 8: |
jah128 | 0:d6269d17c8cf | 724 | sprintf(bottomline,"SIR%dD:%3.1f",side_ir_index+1,0.0); |
jah128 | 0:d6269d17c8cf | 725 | break; |
jah128 | 0:d6269d17c8cf | 726 | case 9: |
jah128 | 0:d6269d17c8cf | 727 | if(ultrasonic_distance_updated == 1) { |
jah128 | 0:d6269d17c8cf | 728 | sprintf(bottomline,"USONIC:%3dcm",ultrasonic_distance); |
jah128 | 0:d6269d17c8cf | 729 | } else sprintf(bottomline,"USONIC:---------"); |
jah128 | 0:d6269d17c8cf | 730 | update_ultrasonic_measure(); |
jah128 | 0:d6269d17c8cf | 731 | break; |
jah128 | 0:d6269d17c8cf | 732 | case 10: |
jah128 | 0:d6269d17c8cf | 733 | store_line_position(); |
jah128 | 0:d6269d17c8cf | 734 | if(line_found == 1)sprintf(bottomline,"LINE:%1.3f",line_position); |
jah128 | 0:d6269d17c8cf | 735 | else sprintf(bottomline,"LINE:---------"); |
jah128 | 0:d6269d17c8cf | 736 | break; |
jah128 | 0:d6269d17c8cf | 737 | case 11: |
jah128 | 0:d6269d17c8cf | 738 | sprintf(bottomline,"EXIT"); |
jah128 | 0:d6269d17c8cf | 739 | break; |
jah128 | 0:d6269d17c8cf | 740 | } |
jah128 | 0:d6269d17c8cf | 741 | break; |
jah128 | 0:d6269d17c8cf | 742 | case 2: |
jah128 | 0:d6269d17c8cf | 743 | strcpy(topline,"--MOTORS MENU---"); |
jah128 | 0:d6269d17c8cf | 744 | switch(sub_menu) { |
jah128 | 0:d6269d17c8cf | 745 | case 0: |
jah128 | 0:d6269d17c8cf | 746 | sprintf(bottomline,"LEFT: %d%%", left_speed); |
jah128 | 0:d6269d17c8cf | 747 | break; |
jah128 | 0:d6269d17c8cf | 748 | case 1: |
jah128 | 0:d6269d17c8cf | 749 | sprintf(bottomline,"RIGHT: %d%%", right_speed); |
jah128 | 0:d6269d17c8cf | 750 | break; |
jah128 | 0:d6269d17c8cf | 751 | case 2: |
jah128 | 0:d6269d17c8cf | 752 | char both_mode_string[16]; |
jah128 | 0:d6269d17c8cf | 753 | switch(both_motor_mode) { |
jah128 | 0:d6269d17c8cf | 754 | case 0: |
jah128 | 0:d6269d17c8cf | 755 | strcpy(both_mode_string,"OFF"); |
jah128 | 0:d6269d17c8cf | 756 | break; |
jah128 | 0:d6269d17c8cf | 757 | case 1: |
jah128 | 0:d6269d17c8cf | 758 | strcpy(both_mode_string,"BRAKE"); |
jah128 | 0:d6269d17c8cf | 759 | break; |
jah128 | 0:d6269d17c8cf | 760 | case 2: |
jah128 | 0:d6269d17c8cf | 761 | strcpy(both_mode_string,"+50%"); |
jah128 | 0:d6269d17c8cf | 762 | break; |
jah128 | 0:d6269d17c8cf | 763 | case 3: |
jah128 | 0:d6269d17c8cf | 764 | strcpy(both_mode_string,"+100%"); |
jah128 | 0:d6269d17c8cf | 765 | break; |
jah128 | 0:d6269d17c8cf | 766 | case 4: |
jah128 | 0:d6269d17c8cf | 767 | strcpy(both_mode_string,"-50%"); |
jah128 | 0:d6269d17c8cf | 768 | break; |
jah128 | 0:d6269d17c8cf | 769 | case 5: |
jah128 | 0:d6269d17c8cf | 770 | strcpy(both_mode_string,"-100%"); |
jah128 | 0:d6269d17c8cf | 771 | break; |
jah128 | 0:d6269d17c8cf | 772 | } |
jah128 | 0:d6269d17c8cf | 773 | sprintf(bottomline,"BOTH TO %s",both_mode_string); |
jah128 | 0:d6269d17c8cf | 774 | break; |
jah128 | 0:d6269d17c8cf | 775 | case 3: |
jah128 | 0:d6269d17c8cf | 776 | sprintf(bottomline,"EXIT"); |
jah128 | 0:d6269d17c8cf | 777 | break; |
jah128 | 0:d6269d17c8cf | 778 | } |
jah128 | 0:d6269d17c8cf | 779 | break; |
jah128 | 0:d6269d17c8cf | 780 | case 3: |
jah128 | 0:d6269d17c8cf | 781 | strcpy(topline,"---RADIO MENU---"); |
jah128 | 0:d6269d17c8cf | 782 | switch(sub_menu) { |
jah128 | 0:d6269d17c8cf | 783 | |
jah128 | 0:d6269d17c8cf | 784 | case 0: |
jah128 | 0:d6269d17c8cf | 785 | sprintf(bottomline,"EXIT"); |
jah128 | 0:d6269d17c8cf | 786 | break; |
jah128 | 0:d6269d17c8cf | 787 | } |
jah128 | 0:d6269d17c8cf | 788 | break; |
jah128 | 0:d6269d17c8cf | 789 | case 4: |
jah128 | 0:d6269d17c8cf | 790 | strcpy(topline,"---INFO MENU----"); |
jah128 | 0:d6269d17c8cf | 791 | switch(sub_menu) { |
jah128 | 0:d6269d17c8cf | 792 | case 0: |
jah128 | 0:d6269d17c8cf | 793 | sprintf(bottomline,"ROBOT ID: %d",robot_id); |
jah128 | 0:d6269d17c8cf | 794 | break; |
jah128 | 0:d6269d17c8cf | 795 | case 1: |
jah128 | 0:d6269d17c8cf | 796 | sprintf(bottomline,"SOFTWARE: %1.2f",SOFTWARE_VERSION_CODE); |
jah128 | 0:d6269d17c8cf | 797 | break; |
jah128 | 0:d6269d17c8cf | 798 | case 2: |
jah128 | 0:d6269d17c8cf | 799 | if(firmware_version > 0) sprintf(bottomline,"FIRMWARE: %1.2f",firmware_version); |
jah128 | 0:d6269d17c8cf | 800 | else sprintf(bottomline,"FIRMWARE: ?????"); |
jah128 | 0:d6269d17c8cf | 801 | break; |
jah128 | 0:d6269d17c8cf | 802 | case 3: |
jah128 | 0:d6269d17c8cf | 803 | sprintf(bottomline,"PROG:%s",program_name); |
jah128 | 0:d6269d17c8cf | 804 | break; |
jah128 | 0:d6269d17c8cf | 805 | case 4: |
jah128 | 0:d6269d17c8cf | 806 | sprintf(bottomline,"AUTH:%s",author_name); |
jah128 | 0:d6269d17c8cf | 807 | break; |
jah128 | 0:d6269d17c8cf | 808 | case 5: |
jah128 | 0:d6269d17c8cf | 809 | sprintf(bottomline,"VER:%s",version_name); |
jah128 | 0:d6269d17c8cf | 810 | break; |
jah128 | 0:d6269d17c8cf | 811 | case 6: |
jah128 | 0:d6269d17c8cf | 812 | sprintf(bottomline,"EXIT"); |
jah128 | 0:d6269d17c8cf | 813 | break; |
jah128 | 0:d6269d17c8cf | 814 | } |
jah128 | 0:d6269d17c8cf | 815 | break; |
jah128 | 0:d6269d17c8cf | 816 | case 5: |
jah128 | 0:d6269d17c8cf | 817 | strcpy(topline,"---CODE DEMOS---"); |
jah128 | 0:d6269d17c8cf | 818 | switch(sub_menu) { |
jah128 | 0:d6269d17c8cf | 819 | case 0: |
jah128 | 0:d6269d17c8cf | 820 | sprintf(bottomline,"LINE FOLLOW"); |
jah128 | 0:d6269d17c8cf | 821 | break; |
jah128 | 0:d6269d17c8cf | 822 | case 1: |
jah128 | 0:d6269d17c8cf | 823 | sprintf(bottomline,"OBST. AVOID"); |
jah128 | 0:d6269d17c8cf | 824 | break; |
jah128 | 0:d6269d17c8cf | 825 | case 2: |
jah128 | 0:d6269d17c8cf | 826 | sprintf(bottomline,"COLOUR SPIN"); |
jah128 | 0:d6269d17c8cf | 827 | break; |
jah128 | 0:d6269d17c8cf | 828 | case 3: |
jah128 | 0:d6269d17c8cf | 829 | sprintf(bottomline,"STRESS TEST"); |
jah128 | 0:d6269d17c8cf | 830 | break; |
jah128 | 0:d6269d17c8cf | 831 | case 4: |
jah128 | 0:d6269d17c8cf | 832 | sprintf(bottomline,"EXIT"); |
jah128 | 0:d6269d17c8cf | 833 | break; |
jah128 | 0:d6269d17c8cf | 834 | } |
jah128 | 0:d6269d17c8cf | 835 | break; |
jah128 | 0:d6269d17c8cf | 836 | case 6: |
jah128 | 0:d6269d17c8cf | 837 | strcpy(topline,""); |
jah128 | 0:d6269d17c8cf | 838 | break; |
jah128 | 0:d6269d17c8cf | 839 | } |
jah128 | 0:d6269d17c8cf | 840 | break; |
jah128 | 0:d6269d17c8cf | 841 | } |
jah128 | 0:d6269d17c8cf | 842 | display.write_string(topline); |
jah128 | 0:d6269d17c8cf | 843 | display.set_position(1,0); |
jah128 | 0:d6269d17c8cf | 844 | display.write_string(bottomline); |
jah128 | 0:d6269d17c8cf | 845 | if(top_menu == 1 && level == 1) { |
jah128 | 0:d6269d17c8cf | 846 | demo_event.attach(&demo_event_thread, 0.25); |
jah128 | 0:d6269d17c8cf | 847 | } |
jah128 | 0:d6269d17c8cf | 848 | } |
jah128 | 0:d6269d17c8cf | 849 | |
jah128 | 0:d6269d17c8cf | 850 | void start_line_demo() |
jah128 | 0:d6269d17c8cf | 851 | { |
jah128 | 0:d6269d17c8cf | 852 | display.set_backlight_brightness(0); |
jah128 | 0:d6269d17c8cf | 853 | time_out = 0.25f; |
jah128 | 0:d6269d17c8cf | 854 | demo_timer.start(); |
jah128 | 0:d6269d17c8cf | 855 | state = 0; |
jah128 | 0:d6269d17c8cf | 856 | speed = 0; |
jah128 | 0:d6269d17c8cf | 857 | led_step = 0; |
jah128 | 0:d6269d17c8cf | 858 | demo_running = 1; |
jah128 | 0:d6269d17c8cf | 859 | demo_timeout.attach_us(&line_demo_cycle,1000); |
jah128 | 0:d6269d17c8cf | 860 | } |
jah128 | 0:d6269d17c8cf | 861 | |
jah128 | 0:d6269d17c8cf | 862 | void start_obstacle_demo() |
jah128 | 0:d6269d17c8cf | 863 | { |
jah128 | 0:d6269d17c8cf | 864 | display.set_backlight_brightness(0); |
jah128 | 0:d6269d17c8cf | 865 | time_out = 0.25f; |
jah128 | 0:d6269d17c8cf | 866 | demo_timer.start(); |
jah128 | 0:d6269d17c8cf | 867 | state = 0; |
jah128 | 0:d6269d17c8cf | 868 | speed = 0; |
jah128 | 0:d6269d17c8cf | 869 | led_step = 0; |
jah128 | 0:d6269d17c8cf | 870 | demo_running = 1; |
jah128 | 0:d6269d17c8cf | 871 | demo_timeout.attach_us(&obstacle_demo_cycle,1000); |
jah128 | 0:d6269d17c8cf | 872 | } |
jah128 | 0:d6269d17c8cf | 873 | |
jah128 | 0:d6269d17c8cf | 874 | void start_stress_demo() |
jah128 | 0:d6269d17c8cf | 875 | { |
jah128 | 0:d6269d17c8cf | 876 | display.set_backlight_brightness(0.25); |
jah128 | 0:d6269d17c8cf | 877 | display.write_string("STRESS TEST"); |
jah128 | 0:d6269d17c8cf | 878 | display.set_position(1,0); |
jah128 | 0:d6269d17c8cf | 879 | display.write_string("----25%----"); |
jah128 | 0:d6269d17c8cf | 880 | time_out = 0.04f; |
jah128 | 0:d6269d17c8cf | 881 | demo_timer.start(); |
jah128 | 0:d6269d17c8cf | 882 | state = 0; |
jah128 | 0:d6269d17c8cf | 883 | speed = 0; |
jah128 | 0:d6269d17c8cf | 884 | stress_step = 0; |
jah128 | 0:d6269d17c8cf | 885 | spin_step = 0; |
jah128 | 0:d6269d17c8cf | 886 | demo_running = 1; |
jah128 | 0:d6269d17c8cf | 887 | demo_timeout.attach_us(&stress_demo_cycle,1000); |
jah128 | 0:d6269d17c8cf | 888 | } |
jah128 | 0:d6269d17c8cf | 889 | |
jah128 | 0:d6269d17c8cf | 890 | void start_spinning_demo() |
jah128 | 0:d6269d17c8cf | 891 | { |
jah128 | 0:d6269d17c8cf | 892 | display.set_backlight_brightness(0); |
jah128 | 0:d6269d17c8cf | 893 | time_out = 0.0f; |
jah128 | 0:d6269d17c8cf | 894 | demo_timer.start(); |
jah128 | 0:d6269d17c8cf | 895 | state = 0; |
jah128 | 0:d6269d17c8cf | 896 | speed = 0; |
jah128 | 0:d6269d17c8cf | 897 | led_step = 0; |
jah128 | 0:d6269d17c8cf | 898 | spin_step = 0; |
jah128 | 0:d6269d17c8cf | 899 | demo_running = 1; |
jah128 | 0:d6269d17c8cf | 900 | demo_timeout.attach_us(&spinning_demo_cycle,1000); |
jah128 | 0:d6269d17c8cf | 901 | } |
jah128 | 0:d6269d17c8cf | 902 | |
jah128 | 0:d6269d17c8cf | 903 | void line_demo_cycle() |
jah128 | 0:d6269d17c8cf | 904 | { |
jah128 | 0:d6269d17c8cf | 905 | if(demo_timer.read() > time_out) { |
jah128 | 0:d6269d17c8cf | 906 | store_line_position(); |
jah128 | 0:d6269d17c8cf | 907 | if(line_found) { |
jah128 | 0:d6269d17c8cf | 908 | time_out = 0.01f; |
jah128 | 0:d6269d17c8cf | 909 | state = 0; |
jah128 | 0:d6269d17c8cf | 910 | // Get the position of the line. |
jah128 | 0:d6269d17c8cf | 911 | lf_current_pos_of_line = line_position; |
jah128 | 0:d6269d17c8cf | 912 | lf_proportional = lf_current_pos_of_line; |
jah128 | 0:d6269d17c8cf | 913 | |
jah128 | 0:d6269d17c8cf | 914 | // Compute the derivative |
jah128 | 0:d6269d17c8cf | 915 | lf_derivative = lf_current_pos_of_line - lf_previous_pos_of_line; |
jah128 | 0:d6269d17c8cf | 916 | |
jah128 | 0:d6269d17c8cf | 917 | // Compute the integral |
jah128 | 0:d6269d17c8cf | 918 | lf_integral += lf_proportional; |
jah128 | 0:d6269d17c8cf | 919 | |
jah128 | 0:d6269d17c8cf | 920 | // Remember the last position. |
jah128 | 0:d6269d17c8cf | 921 | lf_previous_pos_of_line = lf_current_pos_of_line; |
jah128 | 0:d6269d17c8cf | 922 | |
jah128 | 0:d6269d17c8cf | 923 | // Compute the power |
jah128 | 0:d6269d17c8cf | 924 | lf_power = (lf_proportional * (LF_P_TERM) ) + (lf_integral*(LF_I_TERM)) + (lf_derivative*(LF_D_TERM)) ; |
jah128 | 0:d6269d17c8cf | 925 | |
jah128 | 0:d6269d17c8cf | 926 | // Compute new speeds |
jah128 | 0:d6269d17c8cf | 927 | lf_right = lf_speed-lf_power; |
jah128 | 0:d6269d17c8cf | 928 | lf_left = lf_speed+lf_power; |
jah128 | 0:d6269d17c8cf | 929 | |
jah128 | 0:d6269d17c8cf | 930 | // limit checks |
jah128 | 0:d6269d17c8cf | 931 | if (lf_right < 0) |
jah128 | 0:d6269d17c8cf | 932 | lf_right = 0; |
jah128 | 0:d6269d17c8cf | 933 | else if (lf_right > 1.0f) |
jah128 | 0:d6269d17c8cf | 934 | lf_right = 1.0f; |
jah128 | 0:d6269d17c8cf | 935 | |
jah128 | 0:d6269d17c8cf | 936 | if (lf_left < 0) |
jah128 | 0:d6269d17c8cf | 937 | lf_left = 0; |
jah128 | 0:d6269d17c8cf | 938 | else if (lf_left > 1.0f) |
jah128 | 0:d6269d17c8cf | 939 | lf_left = 1.0f; |
jah128 | 0:d6269d17c8cf | 940 | }else{ |
jah128 | 0:d6269d17c8cf | 941 | //Cannot see line: hunt for it |
jah128 | 0:d6269d17c8cf | 942 | if(lf_left > lf_right){ |
jah128 | 0:d6269d17c8cf | 943 | //Currently turning left, keep turning left |
jah128 | 0:d6269d17c8cf | 944 | state ++; |
jah128 | 0:d6269d17c8cf | 945 | float d_step = state * 0.04; |
jah128 | 0:d6269d17c8cf | 946 | lf_left = 0.2 + d_step; |
jah128 | 0:d6269d17c8cf | 947 | lf_right = -0.2 - d_step; |
jah128 | 0:d6269d17c8cf | 948 | if(state > 20){ |
jah128 | 0:d6269d17c8cf | 949 | state = 0; |
jah128 | 0:d6269d17c8cf | 950 | lf_right = 0.2; |
jah128 | 0:d6269d17c8cf | 951 | lf_left = -0.2; |
jah128 | 0:d6269d17c8cf | 952 | time_out += 0.01f; |
jah128 | 0:d6269d17c8cf | 953 | if(time_out > 0.1f) demo_running = 0; |
jah128 | 0:d6269d17c8cf | 954 | } |
jah128 | 0:d6269d17c8cf | 955 | }else{ |
jah128 | 0:d6269d17c8cf | 956 | //Currently turning right, keep turning right |
jah128 | 0:d6269d17c8cf | 957 | state ++; |
jah128 | 0:d6269d17c8cf | 958 | float d_step = state * 0.04; |
jah128 | 0:d6269d17c8cf | 959 | lf_left = -0.2 - d_step; |
jah128 | 0:d6269d17c8cf | 960 | lf_right = 0.2 + d_step; |
jah128 | 0:d6269d17c8cf | 961 | if(state > 20){ |
jah128 | 0:d6269d17c8cf | 962 | state = 0; |
jah128 | 0:d6269d17c8cf | 963 | lf_right = -0.2; |
jah128 | 0:d6269d17c8cf | 964 | lf_left = 0.2; |
jah128 | 0:d6269d17c8cf | 965 | time_out += 0.01f; |
jah128 | 0:d6269d17c8cf | 966 | if(time_out > 0.1f) demo_running = 0; |
jah128 | 0:d6269d17c8cf | 967 | } |
jah128 | 0:d6269d17c8cf | 968 | } |
jah128 | 0:d6269d17c8cf | 969 | } |
jah128 | 0:d6269d17c8cf | 970 | // set speed |
jah128 | 0:d6269d17c8cf | 971 | set_left_motor_speed(lf_left); |
jah128 | 0:d6269d17c8cf | 972 | set_right_motor_speed(lf_right); |
jah128 | 0:d6269d17c8cf | 973 | |
jah128 | 0:d6269d17c8cf | 974 | |
jah128 | 0:d6269d17c8cf | 975 | demo_timer.reset(); |
jah128 | 0:d6269d17c8cf | 976 | } |
jah128 | 0:d6269d17c8cf | 977 | if(demo_running == 1)demo_timeout.attach_us(&line_demo_cycle,500); |
jah128 | 0:d6269d17c8cf | 978 | else { |
jah128 | 0:d6269d17c8cf | 979 | stop(); |
jah128 | 0:d6269d17c8cf | 980 | display.set_backlight_brightness(bl_brightness * 0.01f); |
jah128 | 0:d6269d17c8cf | 981 | } |
jah128 | 0:d6269d17c8cf | 982 | } |
jah128 | 0:d6269d17c8cf | 983 | |
jah128 | 0:d6269d17c8cf | 984 | void stress_demo_cycle() |
jah128 | 0:d6269d17c8cf | 985 | { |
jah128 | 0:d6269d17c8cf | 986 | if(demo_timer.read() > time_out) { |
jah128 | 0:d6269d17c8cf | 987 | float pct = 0.25 + (0.25 * stress_step); |
jah128 | 0:d6269d17c8cf | 988 | switch(state) { |
jah128 | 0:d6269d17c8cf | 989 | case 0: |
jah128 | 0:d6269d17c8cf | 990 | if(spin_step % 2 == 0) { |
jah128 | 0:d6269d17c8cf | 991 | forward(pct); |
jah128 | 0:d6269d17c8cf | 992 | set_leds(0xFF,0xFF); |
jah128 | 0:d6269d17c8cf | 993 | } else { |
jah128 | 0:d6269d17c8cf | 994 | backward(pct); |
jah128 | 0:d6269d17c8cf | 995 | set_leds(0,0xFF); |
jah128 | 0:d6269d17c8cf | 996 | } |
jah128 | 0:d6269d17c8cf | 997 | spin_step ++; |
jah128 | 0:d6269d17c8cf | 998 | if(spin_step > 199) { |
jah128 | 0:d6269d17c8cf | 999 | state ++; |
jah128 | 0:d6269d17c8cf | 1000 | spin_step = 0; |
jah128 | 0:d6269d17c8cf | 1001 | } |
jah128 | 0:d6269d17c8cf | 1002 | break; |
jah128 | 0:d6269d17c8cf | 1003 | case 1: |
jah128 | 0:d6269d17c8cf | 1004 | if(stress_step < 3) stress_step ++; |
jah128 | 0:d6269d17c8cf | 1005 | float pct = 0.25 + (0.25 * stress_step); |
jah128 | 0:d6269d17c8cf | 1006 | display.set_backlight_brightness(pct); |
jah128 | 0:d6269d17c8cf | 1007 | display.set_position(1,0); |
jah128 | 0:d6269d17c8cf | 1008 | switch(stress_step) { |
jah128 | 0:d6269d17c8cf | 1009 | case 1: |
jah128 | 0:d6269d17c8cf | 1010 | display.write_string("----50%----"); |
jah128 | 0:d6269d17c8cf | 1011 | break; |
jah128 | 0:d6269d17c8cf | 1012 | case 2: |
jah128 | 0:d6269d17c8cf | 1013 | display.write_string("----75%----"); |
jah128 | 0:d6269d17c8cf | 1014 | break; |
jah128 | 0:d6269d17c8cf | 1015 | case 3: |
jah128 | 0:d6269d17c8cf | 1016 | display.write_string("---100%----"); |
jah128 | 0:d6269d17c8cf | 1017 | break; |
jah128 | 0:d6269d17c8cf | 1018 | } |
jah128 | 0:d6269d17c8cf | 1019 | state = 0; |
jah128 | 0:d6269d17c8cf | 1020 | break; |
jah128 | 0:d6269d17c8cf | 1021 | } |
jah128 | 0:d6269d17c8cf | 1022 | demo_timer.reset(); |
jah128 | 0:d6269d17c8cf | 1023 | } |
jah128 | 0:d6269d17c8cf | 1024 | if(demo_running == 1)demo_timeout.attach_us(&stress_demo_cycle,500); |
jah128 | 0:d6269d17c8cf | 1025 | else { |
jah128 | 0:d6269d17c8cf | 1026 | stop(); |
jah128 | 0:d6269d17c8cf | 1027 | display.set_backlight_brightness(bl_brightness * 0.01f); |
jah128 | 0:d6269d17c8cf | 1028 | } |
jah128 | 0:d6269d17c8cf | 1029 | } |
jah128 | 0:d6269d17c8cf | 1030 | |
jah128 | 0:d6269d17c8cf | 1031 | void spinning_demo_cycle() |
jah128 | 0:d6269d17c8cf | 1032 | { |
jah128 | 0:d6269d17c8cf | 1033 | if(demo_timer.read() > time_out) { |
jah128 | 0:d6269d17c8cf | 1034 | switch(state) { |
jah128 | 0:d6269d17c8cf | 1035 | case 0: //Robot is stopped |
jah128 | 0:d6269d17c8cf | 1036 | set_leds(0,0xFF); |
jah128 | 0:d6269d17c8cf | 1037 | set_center_led(1,1); |
jah128 | 0:d6269d17c8cf | 1038 | speed = 0.1f; |
jah128 | 0:d6269d17c8cf | 1039 | brake(); |
jah128 | 0:d6269d17c8cf | 1040 | time_out = 0.5; |
jah128 | 0:d6269d17c8cf | 1041 | state = 1; |
jah128 | 0:d6269d17c8cf | 1042 | led_step = 0; |
jah128 | 0:d6269d17c8cf | 1043 | break; |
jah128 | 0:d6269d17c8cf | 1044 | case 1: //Motor is turning right, accelerating |
jah128 | 0:d6269d17c8cf | 1045 | time_out = 0.1; |
jah128 | 0:d6269d17c8cf | 1046 | set_center_led(2,1); |
jah128 | 0:d6269d17c8cf | 1047 | switch(led_step) { |
jah128 | 0:d6269d17c8cf | 1048 | case 0: |
jah128 | 0:d6269d17c8cf | 1049 | set_leds(0x01,0); |
jah128 | 0:d6269d17c8cf | 1050 | break; |
jah128 | 0:d6269d17c8cf | 1051 | case 1: |
jah128 | 0:d6269d17c8cf | 1052 | set_leds(0x02,0); |
jah128 | 0:d6269d17c8cf | 1053 | break; |
jah128 | 0:d6269d17c8cf | 1054 | case 2: |
jah128 | 0:d6269d17c8cf | 1055 | set_leds(0x04,0); |
jah128 | 0:d6269d17c8cf | 1056 | break; |
jah128 | 0:d6269d17c8cf | 1057 | case 3: |
jah128 | 0:d6269d17c8cf | 1058 | set_leds(0x08,0); |
jah128 | 0:d6269d17c8cf | 1059 | break; |
jah128 | 0:d6269d17c8cf | 1060 | case 4: |
jah128 | 0:d6269d17c8cf | 1061 | set_leds(0x10,0); |
jah128 | 0:d6269d17c8cf | 1062 | break; |
jah128 | 0:d6269d17c8cf | 1063 | case 5: |
jah128 | 0:d6269d17c8cf | 1064 | set_leds(0x20,0); |
jah128 | 0:d6269d17c8cf | 1065 | break; |
jah128 | 0:d6269d17c8cf | 1066 | case 6: |
jah128 | 0:d6269d17c8cf | 1067 | set_leds(0x40,0); |
jah128 | 0:d6269d17c8cf | 1068 | break; |
jah128 | 0:d6269d17c8cf | 1069 | case 7: |
jah128 | 0:d6269d17c8cf | 1070 | set_leds(0x80,0); |
jah128 | 0:d6269d17c8cf | 1071 | break; |
jah128 | 0:d6269d17c8cf | 1072 | } |
jah128 | 0:d6269d17c8cf | 1073 | led_step ++; |
jah128 | 0:d6269d17c8cf | 1074 | if(led_step == 8) led_step =0; |
jah128 | 0:d6269d17c8cf | 1075 | if(speed < 1) { |
jah128 | 0:d6269d17c8cf | 1076 | speed += 0.0125; |
jah128 | 0:d6269d17c8cf | 1077 | turn(speed); |
jah128 | 0:d6269d17c8cf | 1078 | } else { |
jah128 | 0:d6269d17c8cf | 1079 | state = 2; |
jah128 | 0:d6269d17c8cf | 1080 | spin_step = 0; |
jah128 | 0:d6269d17c8cf | 1081 | led_step =0; |
jah128 | 0:d6269d17c8cf | 1082 | } |
jah128 | 0:d6269d17c8cf | 1083 | break; |
jah128 | 0:d6269d17c8cf | 1084 | case 2: //Motor is turning right, full speed |
jah128 | 0:d6269d17c8cf | 1085 | set_center_led(3,1); |
jah128 | 0:d6269d17c8cf | 1086 | switch(led_step) { |
jah128 | 0:d6269d17c8cf | 1087 | case 0: |
jah128 | 0:d6269d17c8cf | 1088 | set_leds(0x33,0x33); |
jah128 | 0:d6269d17c8cf | 1089 | break; |
jah128 | 0:d6269d17c8cf | 1090 | case 1: |
jah128 | 0:d6269d17c8cf | 1091 | set_leds(0x66,0x66); |
jah128 | 0:d6269d17c8cf | 1092 | break; |
jah128 | 0:d6269d17c8cf | 1093 | case 2: |
jah128 | 0:d6269d17c8cf | 1094 | set_leds(0xCC,0xCC); |
jah128 | 0:d6269d17c8cf | 1095 | break; |
jah128 | 0:d6269d17c8cf | 1096 | case 3: |
jah128 | 0:d6269d17c8cf | 1097 | set_leds(0x99,0x99); |
jah128 | 0:d6269d17c8cf | 1098 | break; |
jah128 | 0:d6269d17c8cf | 1099 | } |
jah128 | 0:d6269d17c8cf | 1100 | led_step ++; |
jah128 | 0:d6269d17c8cf | 1101 | if(led_step == 4) led_step = 0; |
jah128 | 0:d6269d17c8cf | 1102 | spin_step ++; |
jah128 | 0:d6269d17c8cf | 1103 | if(spin_step == 40) { |
jah128 | 0:d6269d17c8cf | 1104 | state = 3; |
jah128 | 0:d6269d17c8cf | 1105 | led_step = 0; |
jah128 | 0:d6269d17c8cf | 1106 | } |
jah128 | 0:d6269d17c8cf | 1107 | break; |
jah128 | 0:d6269d17c8cf | 1108 | case 3: //Motor is turning right, decelerating |
jah128 | 0:d6269d17c8cf | 1109 | set_center_led(2,1); |
jah128 | 0:d6269d17c8cf | 1110 | switch(led_step) { |
jah128 | 0:d6269d17c8cf | 1111 | case 0: |
jah128 | 0:d6269d17c8cf | 1112 | set_leds(0x01,0); |
jah128 | 0:d6269d17c8cf | 1113 | break; |
jah128 | 0:d6269d17c8cf | 1114 | case 1: |
jah128 | 0:d6269d17c8cf | 1115 | set_leds(0x02,0); |
jah128 | 0:d6269d17c8cf | 1116 | break; |
jah128 | 0:d6269d17c8cf | 1117 | case 2: |
jah128 | 0:d6269d17c8cf | 1118 | set_leds(0x04,0); |
jah128 | 0:d6269d17c8cf | 1119 | break; |
jah128 | 0:d6269d17c8cf | 1120 | case 3: |
jah128 | 0:d6269d17c8cf | 1121 | set_leds(0x08,0); |
jah128 | 0:d6269d17c8cf | 1122 | break; |
jah128 | 0:d6269d17c8cf | 1123 | case 4: |
jah128 | 0:d6269d17c8cf | 1124 | set_leds(0x10,0); |
jah128 | 0:d6269d17c8cf | 1125 | break; |
jah128 | 0:d6269d17c8cf | 1126 | case 5: |
jah128 | 0:d6269d17c8cf | 1127 | set_leds(0x20,0); |
jah128 | 0:d6269d17c8cf | 1128 | break; |
jah128 | 0:d6269d17c8cf | 1129 | case 6: |
jah128 | 0:d6269d17c8cf | 1130 | set_leds(0x40,0); |
jah128 | 0:d6269d17c8cf | 1131 | break; |
jah128 | 0:d6269d17c8cf | 1132 | case 7: |
jah128 | 0:d6269d17c8cf | 1133 | set_leds(0x80,0); |
jah128 | 0:d6269d17c8cf | 1134 | break; |
jah128 | 0:d6269d17c8cf | 1135 | } |
jah128 | 0:d6269d17c8cf | 1136 | if(led_step == 0) led_step =8; |
jah128 | 0:d6269d17c8cf | 1137 | led_step --; |
jah128 | 0:d6269d17c8cf | 1138 | if(speed > 0.1) { |
jah128 | 0:d6269d17c8cf | 1139 | speed -= 0.025; |
jah128 | 0:d6269d17c8cf | 1140 | turn(speed); |
jah128 | 0:d6269d17c8cf | 1141 | } else { |
jah128 | 0:d6269d17c8cf | 1142 | state = 4; |
jah128 | 0:d6269d17c8cf | 1143 | spin_step = 0; |
jah128 | 0:d6269d17c8cf | 1144 | led_step =0; |
jah128 | 0:d6269d17c8cf | 1145 | } |
jah128 | 0:d6269d17c8cf | 1146 | break; |
jah128 | 0:d6269d17c8cf | 1147 | case 4: //Robot is stopped |
jah128 | 0:d6269d17c8cf | 1148 | set_leds(0,0xFF); |
jah128 | 0:d6269d17c8cf | 1149 | set_center_led(1,1); |
jah128 | 0:d6269d17c8cf | 1150 | speed = 0.1f; |
jah128 | 0:d6269d17c8cf | 1151 | brake(); |
jah128 | 0:d6269d17c8cf | 1152 | time_out = 0.5; |
jah128 | 0:d6269d17c8cf | 1153 | led_step =0; |
jah128 | 0:d6269d17c8cf | 1154 | state = 5; |
jah128 | 0:d6269d17c8cf | 1155 | break; |
jah128 | 0:d6269d17c8cf | 1156 | case 5: //Motor is turning left, accelerating |
jah128 | 0:d6269d17c8cf | 1157 | time_out = 0.1; |
jah128 | 0:d6269d17c8cf | 1158 | set_center_led(2,1); |
jah128 | 0:d6269d17c8cf | 1159 | switch(led_step) { |
jah128 | 0:d6269d17c8cf | 1160 | case 0: |
jah128 | 0:d6269d17c8cf | 1161 | set_leds(0x01,0); |
jah128 | 0:d6269d17c8cf | 1162 | break; |
jah128 | 0:d6269d17c8cf | 1163 | case 1: |
jah128 | 0:d6269d17c8cf | 1164 | set_leds(0x02,0); |
jah128 | 0:d6269d17c8cf | 1165 | break; |
jah128 | 0:d6269d17c8cf | 1166 | case 2: |
jah128 | 0:d6269d17c8cf | 1167 | set_leds(0x04,0); |
jah128 | 0:d6269d17c8cf | 1168 | break; |
jah128 | 0:d6269d17c8cf | 1169 | case 3: |
jah128 | 0:d6269d17c8cf | 1170 | set_leds(0x08,0); |
jah128 | 0:d6269d17c8cf | 1171 | break; |
jah128 | 0:d6269d17c8cf | 1172 | case 4: |
jah128 | 0:d6269d17c8cf | 1173 | set_leds(0x10,0); |
jah128 | 0:d6269d17c8cf | 1174 | break; |
jah128 | 0:d6269d17c8cf | 1175 | case 5: |
jah128 | 0:d6269d17c8cf | 1176 | set_leds(0x20,0); |
jah128 | 0:d6269d17c8cf | 1177 | break; |
jah128 | 0:d6269d17c8cf | 1178 | case 6: |
jah128 | 0:d6269d17c8cf | 1179 | set_leds(0x40,0); |
jah128 | 0:d6269d17c8cf | 1180 | break; |
jah128 | 0:d6269d17c8cf | 1181 | case 7: |
jah128 | 0:d6269d17c8cf | 1182 | set_leds(0x80,0); |
jah128 | 0:d6269d17c8cf | 1183 | break; |
jah128 | 0:d6269d17c8cf | 1184 | } |
jah128 | 0:d6269d17c8cf | 1185 | if(led_step == 0) led_step =8; |
jah128 | 0:d6269d17c8cf | 1186 | led_step --; |
jah128 | 0:d6269d17c8cf | 1187 | if(speed < 1) { |
jah128 | 0:d6269d17c8cf | 1188 | speed += 0.0125; |
jah128 | 0:d6269d17c8cf | 1189 | turn(-speed); |
jah128 | 0:d6269d17c8cf | 1190 | } else { |
jah128 | 0:d6269d17c8cf | 1191 | state = 6; |
jah128 | 0:d6269d17c8cf | 1192 | spin_step = 0; |
jah128 | 0:d6269d17c8cf | 1193 | led_step = 0; |
jah128 | 0:d6269d17c8cf | 1194 | } |
jah128 | 0:d6269d17c8cf | 1195 | break; |
jah128 | 0:d6269d17c8cf | 1196 | case 6: //Motor is turning left, full speed |
jah128 | 0:d6269d17c8cf | 1197 | set_center_led(3,1); |
jah128 | 0:d6269d17c8cf | 1198 | switch(led_step) { |
jah128 | 0:d6269d17c8cf | 1199 | case 0: |
jah128 | 0:d6269d17c8cf | 1200 | set_leds(0x33,0x33); |
jah128 | 0:d6269d17c8cf | 1201 | break; |
jah128 | 0:d6269d17c8cf | 1202 | case 1: |
jah128 | 0:d6269d17c8cf | 1203 | set_leds(0x66,0x66); |
jah128 | 0:d6269d17c8cf | 1204 | break; |
jah128 | 0:d6269d17c8cf | 1205 | case 2: |
jah128 | 0:d6269d17c8cf | 1206 | set_leds(0xCC,0xCC); |
jah128 | 0:d6269d17c8cf | 1207 | break; |
jah128 | 0:d6269d17c8cf | 1208 | case 3: |
jah128 | 0:d6269d17c8cf | 1209 | set_leds(0x99,0x99); |
jah128 | 0:d6269d17c8cf | 1210 | break; |
jah128 | 0:d6269d17c8cf | 1211 | } |
jah128 | 0:d6269d17c8cf | 1212 | if(led_step == 0) led_step = 4; |
jah128 | 0:d6269d17c8cf | 1213 | led_step --; |
jah128 | 0:d6269d17c8cf | 1214 | spin_step ++; |
jah128 | 0:d6269d17c8cf | 1215 | if(spin_step == 40) { |
jah128 | 0:d6269d17c8cf | 1216 | state = 7; |
jah128 | 0:d6269d17c8cf | 1217 | led_step = 0; |
jah128 | 0:d6269d17c8cf | 1218 | } |
jah128 | 0:d6269d17c8cf | 1219 | break; |
jah128 | 0:d6269d17c8cf | 1220 | case 7: //Motor is turning left, decelerating |
jah128 | 0:d6269d17c8cf | 1221 | set_center_led(2,1); |
jah128 | 0:d6269d17c8cf | 1222 | switch(led_step) { |
jah128 | 0:d6269d17c8cf | 1223 | case 0: |
jah128 | 0:d6269d17c8cf | 1224 | set_leds(0x01,0); |
jah128 | 0:d6269d17c8cf | 1225 | break; |
jah128 | 0:d6269d17c8cf | 1226 | case 1: |
jah128 | 0:d6269d17c8cf | 1227 | set_leds(0x02,0); |
jah128 | 0:d6269d17c8cf | 1228 | break; |
jah128 | 0:d6269d17c8cf | 1229 | case 2: |
jah128 | 0:d6269d17c8cf | 1230 | set_leds(0x04,0); |
jah128 | 0:d6269d17c8cf | 1231 | break; |
jah128 | 0:d6269d17c8cf | 1232 | case 3: |
jah128 | 0:d6269d17c8cf | 1233 | set_leds(0x08,0); |
jah128 | 0:d6269d17c8cf | 1234 | break; |
jah128 | 0:d6269d17c8cf | 1235 | case 4: |
jah128 | 0:d6269d17c8cf | 1236 | set_leds(0x10,0); |
jah128 | 0:d6269d17c8cf | 1237 | break; |
jah128 | 0:d6269d17c8cf | 1238 | case 5: |
jah128 | 0:d6269d17c8cf | 1239 | set_leds(0x20,0); |
jah128 | 0:d6269d17c8cf | 1240 | break; |
jah128 | 0:d6269d17c8cf | 1241 | case 6: |
jah128 | 0:d6269d17c8cf | 1242 | set_leds(0x40,0); |
jah128 | 0:d6269d17c8cf | 1243 | break; |
jah128 | 0:d6269d17c8cf | 1244 | case 7: |
jah128 | 0:d6269d17c8cf | 1245 | set_leds(0x80,0); |
jah128 | 0:d6269d17c8cf | 1246 | break; |
jah128 | 0:d6269d17c8cf | 1247 | } |
jah128 | 0:d6269d17c8cf | 1248 | led_step ++; |
jah128 | 0:d6269d17c8cf | 1249 | if(led_step == 8) led_step =0; |
jah128 | 0:d6269d17c8cf | 1250 | if(speed > 0.1) { |
jah128 | 0:d6269d17c8cf | 1251 | speed -= 0.025; |
jah128 | 0:d6269d17c8cf | 1252 | turn(-speed); |
jah128 | 0:d6269d17c8cf | 1253 | } else { |
jah128 | 0:d6269d17c8cf | 1254 | state = 0; |
jah128 | 0:d6269d17c8cf | 1255 | spin_step = 0; |
jah128 | 0:d6269d17c8cf | 1256 | led_step = 0; |
jah128 | 0:d6269d17c8cf | 1257 | } |
jah128 | 0:d6269d17c8cf | 1258 | break; |
jah128 | 0:d6269d17c8cf | 1259 | } |
jah128 | 0:d6269d17c8cf | 1260 | demo_timer.reset(); |
jah128 | 0:d6269d17c8cf | 1261 | } |
jah128 | 0:d6269d17c8cf | 1262 | if(demo_running == 1)demo_timeout.attach_us(&spinning_demo_cycle,500); |
jah128 | 0:d6269d17c8cf | 1263 | else { |
jah128 | 0:d6269d17c8cf | 1264 | stop(); |
jah128 | 0:d6269d17c8cf | 1265 | display.set_backlight_brightness(bl_brightness * 0.01f); |
jah128 | 0:d6269d17c8cf | 1266 | } |
jah128 | 0:d6269d17c8cf | 1267 | } |
jah128 | 0:d6269d17c8cf | 1268 | |
jah128 | 0:d6269d17c8cf | 1269 | void obstacle_demo_cycle() |
jah128 | 0:d6269d17c8cf | 1270 | { |
jah128 | 0:d6269d17c8cf | 1271 | if(demo_timer.read() > time_out) { |
jah128 | 0:d6269d17c8cf | 1272 | switch(state) { |
jah128 | 0:d6269d17c8cf | 1273 | case 0: //Robot is stopped |
jah128 | 0:d6269d17c8cf | 1274 | set_leds(0,0xFF); |
jah128 | 0:d6269d17c8cf | 1275 | set_center_led(1,0.4); |
jah128 | 0:d6269d17c8cf | 1276 | speed = 0.3f; |
jah128 | 0:d6269d17c8cf | 1277 | forward(speed); |
jah128 | 0:d6269d17c8cf | 1278 | time_out = 0.05; |
jah128 | 0:d6269d17c8cf | 1279 | state = 1; |
jah128 | 0:d6269d17c8cf | 1280 | break; |
jah128 | 0:d6269d17c8cf | 1281 | case 1: { //Motor is moving forward |
jah128 | 0:d6269d17c8cf | 1282 | store_ir_values(); |
jah128 | 0:d6269d17c8cf | 1283 | int front_right = read_illuminated_raw_ir_value(0); |
jah128 | 0:d6269d17c8cf | 1284 | int front_left = read_illuminated_raw_ir_value(7); |
jah128 | 0:d6269d17c8cf | 1285 | if(front_left > 400 || front_right > 400) { |
jah128 | 0:d6269d17c8cf | 1286 | brake(); |
jah128 | 0:d6269d17c8cf | 1287 | time_out = 0.04; |
jah128 | 0:d6269d17c8cf | 1288 | if(front_left > front_right)state=2; |
jah128 | 0:d6269d17c8cf | 1289 | else state=3; |
jah128 | 0:d6269d17c8cf | 1290 | } else { |
jah128 | 0:d6269d17c8cf | 1291 | if(speed < 0.5) { |
jah128 | 0:d6269d17c8cf | 1292 | speed += 0.03; |
jah128 | 0:d6269d17c8cf | 1293 | forward(speed); |
jah128 | 0:d6269d17c8cf | 1294 | } |
jah128 | 0:d6269d17c8cf | 1295 | switch(led_step) { |
jah128 | 0:d6269d17c8cf | 1296 | case 0: |
jah128 | 0:d6269d17c8cf | 1297 | set_leds(0x01,0); |
jah128 | 0:d6269d17c8cf | 1298 | break; |
jah128 | 0:d6269d17c8cf | 1299 | case 1: |
jah128 | 0:d6269d17c8cf | 1300 | set_leds(0x38,0); |
jah128 | 0:d6269d17c8cf | 1301 | break; |
jah128 | 0:d6269d17c8cf | 1302 | case 2: |
jah128 | 0:d6269d17c8cf | 1303 | set_leds(0x6C,0); |
jah128 | 0:d6269d17c8cf | 1304 | break; |
jah128 | 0:d6269d17c8cf | 1305 | case 3: |
jah128 | 0:d6269d17c8cf | 1306 | set_leds(0xC6,0); |
jah128 | 0:d6269d17c8cf | 1307 | break; |
jah128 | 0:d6269d17c8cf | 1308 | case 4: |
jah128 | 0:d6269d17c8cf | 1309 | set_leds(0x83,0); |
jah128 | 0:d6269d17c8cf | 1310 | break; |
jah128 | 0:d6269d17c8cf | 1311 | } |
jah128 | 0:d6269d17c8cf | 1312 | set_center_led(2, 0.6); |
jah128 | 0:d6269d17c8cf | 1313 | led_step ++; |
jah128 | 0:d6269d17c8cf | 1314 | if(led_step == 5) led_step = 0; |
jah128 | 0:d6269d17c8cf | 1315 | } |
jah128 | 0:d6269d17c8cf | 1316 | break; |
jah128 | 0:d6269d17c8cf | 1317 | } |
jah128 | 0:d6269d17c8cf | 1318 | case 2: //Turn right |
jah128 | 0:d6269d17c8cf | 1319 | set_left_motor_speed(0.85); |
jah128 | 0:d6269d17c8cf | 1320 | set_right_motor_speed(-0.85); |
jah128 | 0:d6269d17c8cf | 1321 | time_out = 0.4; |
jah128 | 0:d6269d17c8cf | 1322 | state = 0; |
jah128 | 0:d6269d17c8cf | 1323 | set_leds(0x0E,0x0E); |
jah128 | 0:d6269d17c8cf | 1324 | set_center_led(3,0.5); |
jah128 | 0:d6269d17c8cf | 1325 | break; |
jah128 | 0:d6269d17c8cf | 1326 | case 3: //Turn left |
jah128 | 0:d6269d17c8cf | 1327 | set_left_motor_speed(-0.85); |
jah128 | 0:d6269d17c8cf | 1328 | set_right_motor_speed(0.85); |
jah128 | 0:d6269d17c8cf | 1329 | time_out = 0.4; |
jah128 | 0:d6269d17c8cf | 1330 | state = 0; |
jah128 | 0:d6269d17c8cf | 1331 | set_leds(0xE0,0xE0); |
jah128 | 0:d6269d17c8cf | 1332 | set_center_led(3,0.5); |
jah128 | 0:d6269d17c8cf | 1333 | break; |
jah128 | 0:d6269d17c8cf | 1334 | } |
jah128 | 0:d6269d17c8cf | 1335 | demo_timer.reset(); |
jah128 | 0:d6269d17c8cf | 1336 | } |
jah128 | 0:d6269d17c8cf | 1337 | if(demo_running == 1)demo_timeout.attach_us(&obstacle_demo_cycle,200); |
jah128 | 0:d6269d17c8cf | 1338 | else { |
jah128 | 0:d6269d17c8cf | 1339 | stop(); |
jah128 | 0:d6269d17c8cf | 1340 | display.set_backlight_brightness(bl_brightness * 0.01f); |
jah128 | 0:d6269d17c8cf | 1341 | } |
jah128 | 0:d6269d17c8cf | 1342 | } |
jah128 | 0:d6269d17c8cf | 1343 | |
jah128 | 0:d6269d17c8cf | 1344 | void demo_update_leds() |
jah128 | 0:d6269d17c8cf | 1345 | { |
jah128 | 0:d6269d17c8cf | 1346 | char red = 0; |
jah128 | 0:d6269d17c8cf | 1347 | char green = 0; |
jah128 | 0:d6269d17c8cf | 1348 | for(int i=0; i<8; i++) { |
jah128 | 0:d6269d17c8cf | 1349 | if(led_state[i]==1 || led_state[i]==3) red+=(1<<i); |
jah128 | 0:d6269d17c8cf | 1350 | if(led_state[i]==2 || led_state[i]==3) green+=(1<<i); |
jah128 | 0:d6269d17c8cf | 1351 | } |
jah128 | 0:d6269d17c8cf | 1352 | set_leds(green,red); |
jah128 | 0:d6269d17c8cf | 1353 | float brightness_f = brightness / 100.0f; |
jah128 | 0:d6269d17c8cf | 1354 | set_center_led(led_state[8], brightness_f); |
jah128 | 0:d6269d17c8cf | 1355 | set_base_led(base_led_state); |
jah128 | 0:d6269d17c8cf | 1356 | } |