Psi Swarm robot library version 0.9
Fork of PsiSwarmV9 by
demo.cpp@18:9204f74069b4, 2017-06-04 (annotated)
- Committer:
- jah128
- Date:
- Sun Jun 04 20:22:41 2017 +0000
- Revision:
- 18:9204f74069b4
- Parent:
- 17:bf614e28668f
- Child:
- 19:3e3b03d80ea3
Updated self-test
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 | 15:66be5ec52c3b | 2 | * |
jah128 | 14:2f1ad77d281e | 3 | * Copyright 2017 University of York |
jah128 | 6:b340a527add9 | 4 | * |
jah128 | 15:66be5ec52c3b | 5 | * Licensed under the Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. |
jah128 | 6:b340a527add9 | 6 | * You may obtain a copy of the License at http://www.apache.org/licenses/LICENSE-2.0 |
jah128 | 6:b340a527add9 | 7 | * Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS |
jah128 | 15:66be5ec52c3b | 8 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
jah128 | 6:b340a527add9 | 9 | * See the License for the specific language governing permissions and limitations under the License. |
jah128 | 0:d6269d17c8cf | 10 | * |
jah128 | 0:d6269d17c8cf | 11 | * File: demo.cpp |
jah128 | 0:d6269d17c8cf | 12 | * |
jah128 | 0:d6269d17c8cf | 13 | * (C) Dept. Electronics & Computer Science, University of York |
jah128 | 0:d6269d17c8cf | 14 | * James Hilder, Alan Millard, Alexander Horsfield, Homero Elizondo, Jon Timmis |
jah128 | 0:d6269d17c8cf | 15 | * |
jah128 | 14:2f1ad77d281e | 16 | * PsiSwarm Library Version: 0.9 |
jah128 | 0:d6269d17c8cf | 17 | * |
jah128 | 16:50686c07ad07 | 18 | * Version 0.9 : Added colour sensor functions, colour sensor demo and self-test mode |
jah128 | 8:6c92789d5f87 | 19 | * Version 0.8 : Rewritten as OO\C++ |
jah128 | 5:3cdd1a37cdd7 | 20 | * Version 0.7 : Updated for new MBED API |
jah128 | 4:1c621cb8cf0d | 21 | * Version 0.5 : Added motor calibration menu |
jah128 | 0:d6269d17c8cf | 22 | * Version 0.4 : Added PsiSwarmBasic menu |
jah128 | 0:d6269d17c8cf | 23 | * Version 0.2 : Remove most the functionality from center-button push to allow all operations to be accessable from |
jah128 | 0:d6269d17c8cf | 24 | * four directions alone. |
jah128 | 0:d6269d17c8cf | 25 | * Added extra sensor information, added various testing demos |
jah128 | 0:d6269d17c8cf | 26 | * |
jah128 | 2:c6986ee3c7c5 | 27 | * |
jah128 | 14:2f1ad77d281e | 28 | * June 2017 |
jah128 | 0:d6269d17c8cf | 29 | * |
jah128 | 0:d6269d17c8cf | 30 | */ |
jah128 | 0:d6269d17c8cf | 31 | |
jah128 | 0:d6269d17c8cf | 32 | |
jah128 | 0:d6269d17c8cf | 33 | #include "psiswarm.h" |
jah128 | 0:d6269d17c8cf | 34 | |
jah128 | 0:d6269d17c8cf | 35 | // PID terms |
jah128 | 0:d6269d17c8cf | 36 | #define LF_P_TERM 0.2 |
jah128 | 0:d6269d17c8cf | 37 | #define LF_I_TERM 0 |
jah128 | 0:d6269d17c8cf | 38 | #define LF_D_TERM 4 |
jah128 | 0:d6269d17c8cf | 39 | |
jah128 | 15:66be5ec52c3b | 40 | char quick_test = 0; |
jah128 | 0:d6269d17c8cf | 41 | char top_menu = 0; |
jah128 | 0:d6269d17c8cf | 42 | char sub_menu = 0; |
jah128 | 0:d6269d17c8cf | 43 | char level = 0; |
jah128 | 0:d6269d17c8cf | 44 | char started = 0; |
jah128 | 0:d6269d17c8cf | 45 | char topline[17]; |
jah128 | 0:d6269d17c8cf | 46 | char bottomline[17]; |
jah128 | 0:d6269d17c8cf | 47 | char led_state[9]; |
jah128 | 0:d6269d17c8cf | 48 | char all_led_state = 0; |
jah128 | 0:d6269d17c8cf | 49 | char base_led_state = 0; |
jah128 | 0:d6269d17c8cf | 50 | char brightness = 20; |
jah128 | 0:d6269d17c8cf | 51 | char bl_brightness = 100; |
jah128 | 0:d6269d17c8cf | 52 | char base_ir_index = 0; |
jah128 | 0:d6269d17c8cf | 53 | char side_ir_index = 0; |
jah128 | 0:d6269d17c8cf | 54 | signed short left_speed = 0; |
jah128 | 0:d6269d17c8cf | 55 | signed short right_speed = 0; |
jah128 | 0:d6269d17c8cf | 56 | char both_motor_mode = 0; |
jah128 | 0:d6269d17c8cf | 57 | char last_switch_pressed; |
jah128 | 0:d6269d17c8cf | 58 | Timeout demo_event; |
jah128 | 0:d6269d17c8cf | 59 | char handling_event = 0; |
jah128 | 0:d6269d17c8cf | 60 | |
jah128 | 0:d6269d17c8cf | 61 | Timeout demo_timeout; |
jah128 | 0:d6269d17c8cf | 62 | char demo_running = 0; |
jah128 | 0:d6269d17c8cf | 63 | Timer demo_timer; |
jah128 | 0:d6269d17c8cf | 64 | float time_out; |
jah128 | 0:d6269d17c8cf | 65 | float speed; |
jah128 | 0:d6269d17c8cf | 66 | char state; |
jah128 | 0:d6269d17c8cf | 67 | char led_step = 0; |
jah128 | 0:d6269d17c8cf | 68 | char spin_step = 0; |
jah128 | 0:d6269d17c8cf | 69 | char stress_step = 0; |
jah128 | 0:d6269d17c8cf | 70 | |
jah128 | 0:d6269d17c8cf | 71 | |
jah128 | 0:d6269d17c8cf | 72 | float lf_right; |
jah128 | 0:d6269d17c8cf | 73 | float lf_left; |
jah128 | 0:d6269d17c8cf | 74 | float lf_current_pos_of_line = 0.0; |
jah128 | 0:d6269d17c8cf | 75 | float lf_previous_pos_of_line = 0.0; |
jah128 | 0:d6269d17c8cf | 76 | float lf_derivative,lf_proportional,lf_integral = 0; |
jah128 | 0:d6269d17c8cf | 77 | float lf_power; |
jah128 | 0:d6269d17c8cf | 78 | float lf_speed = 0.4; |
jah128 | 0:d6269d17c8cf | 79 | |
jah128 | 0:d6269d17c8cf | 80 | |
jah128 | 0:d6269d17c8cf | 81 | |
jah128 | 11:312663037b8c | 82 | void Demo::start_demo_mode() |
jah128 | 0:d6269d17c8cf | 83 | { |
jah128 | 12:878c6e9d9e60 | 84 | psi.debug("- Starting Demo Mode\n"); |
jah128 | 17:bf614e28668f | 85 | if(use_flash_basic == 1) top_menu = 8; |
jah128 | 17:bf614e28668f | 86 | if((has_base_ir == 1 && base_ir_calibration_set != 1) || (has_base_colour_sensor == 1 && base_colour_calibration_set != 1)) top_menu = 7; |
jah128 | 0:d6269d17c8cf | 87 | demo_on = 1; |
jah128 | 0:d6269d17c8cf | 88 | display.set_backlight_brightness(bl_brightness * 0.01f); |
jah128 | 0:d6269d17c8cf | 89 | display.clear_display(); |
jah128 | 0:d6269d17c8cf | 90 | display.write_string("PSI SWARM SYSTEM"); |
jah128 | 0:d6269d17c8cf | 91 | display.set_position(1,0); |
jah128 | 0:d6269d17c8cf | 92 | display.write_string(" DEMO MODE"); |
jah128 | 0:d6269d17c8cf | 93 | wait(0.5); |
jah128 | 0:d6269d17c8cf | 94 | display.clear_display(); |
jah128 | 0:d6269d17c8cf | 95 | display.write_string("Use cursor to"); |
jah128 | 0:d6269d17c8cf | 96 | display.set_position(1,0); |
jah128 | 0:d6269d17c8cf | 97 | display.write_string("navigate menus"); |
jah128 | 0:d6269d17c8cf | 98 | char step = 0; |
jah128 | 0:d6269d17c8cf | 99 | while(demo_on) { |
jah128 | 0:d6269d17c8cf | 100 | if(demo_running == 0) { |
jah128 | 0:d6269d17c8cf | 101 | switch(step) { |
jah128 | 0:d6269d17c8cf | 102 | case 0: |
jah128 | 0:d6269d17c8cf | 103 | mbed_led1 = 1; |
jah128 | 0:d6269d17c8cf | 104 | mbed_led2 = 0; |
jah128 | 0:d6269d17c8cf | 105 | break; |
jah128 | 0:d6269d17c8cf | 106 | case 1: |
jah128 | 0:d6269d17c8cf | 107 | mbed_led2 = 1; |
jah128 | 0:d6269d17c8cf | 108 | mbed_led1 = 0; |
jah128 | 0:d6269d17c8cf | 109 | break; |
jah128 | 0:d6269d17c8cf | 110 | } |
jah128 | 0:d6269d17c8cf | 111 | step++; |
jah128 | 0:d6269d17c8cf | 112 | if(step==2)step=0; |
jah128 | 0:d6269d17c8cf | 113 | } else { |
jah128 | 0:d6269d17c8cf | 114 | mbed_led1 = 0; |
jah128 | 0:d6269d17c8cf | 115 | mbed_led2 = 0; |
jah128 | 0:d6269d17c8cf | 116 | mbed_led3 = 0; |
jah128 | 0:d6269d17c8cf | 117 | mbed_led4 = 0; |
jah128 | 0:d6269d17c8cf | 118 | } |
jah128 | 0:d6269d17c8cf | 119 | wait(0.5); |
jah128 | 0:d6269d17c8cf | 120 | } |
jah128 | 12:878c6e9d9e60 | 121 | psi.debug("- Demo mode ended\n"); |
jah128 | 0:d6269d17c8cf | 122 | } |
jah128 | 0:d6269d17c8cf | 123 | |
jah128 | 11:312663037b8c | 124 | void Demo::demo_handle_switch_event(char switch_pressed) |
jah128 | 0:d6269d17c8cf | 125 | { |
jah128 | 0:d6269d17c8cf | 126 | if(!handling_event) { |
jah128 | 0:d6269d17c8cf | 127 | handling_event = 1; |
jah128 | 0:d6269d17c8cf | 128 | last_switch_pressed = switch_pressed; |
jah128 | 11:312663037b8c | 129 | demo_event.attach_us(this,&Demo::demo_event_thread, 1000); |
jah128 | 0:d6269d17c8cf | 130 | } |
jah128 | 0:d6269d17c8cf | 131 | } |
jah128 | 0:d6269d17c8cf | 132 | |
jah128 | 11:312663037b8c | 133 | void Demo::demo_event_thread() |
jah128 | 0:d6269d17c8cf | 134 | { |
jah128 | 0:d6269d17c8cf | 135 | handling_event = 0; |
jah128 | 0:d6269d17c8cf | 136 | if(started == 1) { |
jah128 | 0:d6269d17c8cf | 137 | switch(last_switch_pressed) { |
jah128 | 0:d6269d17c8cf | 138 | case 1: //Up pressed |
jah128 | 0:d6269d17c8cf | 139 | switch(level) { |
jah128 | 0:d6269d17c8cf | 140 | case 0: |
jah128 | 15:66be5ec52c3b | 141 | if(top_menu != 9 && top_menu!= 0) { |
jah128 | 0:d6269d17c8cf | 142 | level++; |
jah128 | 0:d6269d17c8cf | 143 | sub_menu = 0; |
jah128 | 0:d6269d17c8cf | 144 | } else { |
jah128 | 15:66be5ec52c3b | 145 | if(top_menu == 0) { |
jah128 | 15:66be5ec52c3b | 146 | toggle_quick_test(); |
jah128 | 15:66be5ec52c3b | 147 | } else { |
jah128 | 15:66be5ec52c3b | 148 | demo_on = 0; |
jah128 | 15:66be5ec52c3b | 149 | user_code_running = user_code_restore_mode; |
jah128 | 15:66be5ec52c3b | 150 | } |
jah128 | 0:d6269d17c8cf | 151 | } |
jah128 | 0:d6269d17c8cf | 152 | break; |
jah128 | 0:d6269d17c8cf | 153 | case 1: |
jah128 | 0:d6269d17c8cf | 154 | switch(top_menu) { |
jah128 | 15:66be5ec52c3b | 155 | case 8: // PsiBasic Menu |
jah128 | 0:d6269d17c8cf | 156 | if(sub_menu == psi_basic_file_count) level = 0; |
jah128 | 0:d6269d17c8cf | 157 | break; |
jah128 | 17:bf614e28668f | 158 | case 1: //LED Menu |
jah128 | 0:d6269d17c8cf | 159 | if(sub_menu < 9) { |
jah128 | 0:d6269d17c8cf | 160 | if(led_state[sub_menu] == 0) led_state[sub_menu] = 3; |
jah128 | 0:d6269d17c8cf | 161 | else led_state[sub_menu]--; |
jah128 | 0:d6269d17c8cf | 162 | demo_update_leds(); |
jah128 | 0:d6269d17c8cf | 163 | } |
jah128 | 0:d6269d17c8cf | 164 | if(sub_menu == 9) { |
jah128 | 0:d6269d17c8cf | 165 | if(all_led_state == 0) all_led_state = 3; |
jah128 | 0:d6269d17c8cf | 166 | else all_led_state--; |
jah128 | 0:d6269d17c8cf | 167 | for(int i=0; i<9; i++) { |
jah128 | 0:d6269d17c8cf | 168 | led_state[i]=all_led_state; |
jah128 | 0:d6269d17c8cf | 169 | } |
jah128 | 0:d6269d17c8cf | 170 | demo_update_leds(); |
jah128 | 0:d6269d17c8cf | 171 | } |
jah128 | 0:d6269d17c8cf | 172 | if(sub_menu == 10) { |
jah128 | 0:d6269d17c8cf | 173 | base_led_state = 1 - base_led_state; |
jah128 | 0:d6269d17c8cf | 174 | demo_update_leds(); |
jah128 | 0:d6269d17c8cf | 175 | } |
jah128 | 0:d6269d17c8cf | 176 | if(sub_menu == 11) { |
jah128 | 0:d6269d17c8cf | 177 | switch(brightness) { |
jah128 | 0:d6269d17c8cf | 178 | case 100: |
jah128 | 0:d6269d17c8cf | 179 | brightness = 50; |
jah128 | 0:d6269d17c8cf | 180 | break; |
jah128 | 0:d6269d17c8cf | 181 | case 2: |
jah128 | 0:d6269d17c8cf | 182 | brightness = 1; |
jah128 | 0:d6269d17c8cf | 183 | break; |
jah128 | 0:d6269d17c8cf | 184 | case 5: |
jah128 | 0:d6269d17c8cf | 185 | brightness = 2; |
jah128 | 0:d6269d17c8cf | 186 | break; |
jah128 | 0:d6269d17c8cf | 187 | case 10: |
jah128 | 0:d6269d17c8cf | 188 | brightness = 5; |
jah128 | 0:d6269d17c8cf | 189 | break; |
jah128 | 0:d6269d17c8cf | 190 | case 20: |
jah128 | 0:d6269d17c8cf | 191 | brightness = 10; |
jah128 | 0:d6269d17c8cf | 192 | break; |
jah128 | 0:d6269d17c8cf | 193 | case 50: |
jah128 | 0:d6269d17c8cf | 194 | brightness = 20; |
jah128 | 0:d6269d17c8cf | 195 | break; |
jah128 | 0:d6269d17c8cf | 196 | } |
jah128 | 0:d6269d17c8cf | 197 | demo_update_leds(); |
jah128 | 0:d6269d17c8cf | 198 | } |
jah128 | 0:d6269d17c8cf | 199 | if(sub_menu == 12) { |
jah128 | 0:d6269d17c8cf | 200 | if(bl_brightness > 0) bl_brightness-=10; |
jah128 | 0:d6269d17c8cf | 201 | display.set_backlight_brightness(bl_brightness * 0.01f); |
jah128 | 0:d6269d17c8cf | 202 | } |
jah128 | 0:d6269d17c8cf | 203 | if(sub_menu == 13) level = 0; |
jah128 | 0:d6269d17c8cf | 204 | break; |
jah128 | 15:66be5ec52c3b | 205 | case 2: // Sensors Menu |
jah128 | 17:bf614e28668f | 206 | if(sub_menu == 4 || sub_menu == 5 || sub_menu==6) { |
jah128 | 0:d6269d17c8cf | 207 | if(base_ir_index == 0) base_ir_index = 4; |
jah128 | 0:d6269d17c8cf | 208 | else base_ir_index --; |
jah128 | 0:d6269d17c8cf | 209 | } |
jah128 | 17:bf614e28668f | 210 | if(sub_menu > 6 && sub_menu < 10) { |
jah128 | 0:d6269d17c8cf | 211 | if(side_ir_index == 0) side_ir_index = 7; |
jah128 | 0:d6269d17c8cf | 212 | else side_ir_index --; |
jah128 | 0:d6269d17c8cf | 213 | } |
jah128 | 17:bf614e28668f | 214 | if(sub_menu == 13) level = 0; |
jah128 | 0:d6269d17c8cf | 215 | break; |
jah128 | 15:66be5ec52c3b | 216 | case 3: // Motor Menu |
jah128 | 0:d6269d17c8cf | 217 | if(sub_menu == 0) { |
jah128 | 0:d6269d17c8cf | 218 | left_speed += 5; |
jah128 | 0:d6269d17c8cf | 219 | if(left_speed > 100) left_speed = 100; |
jah128 | 8:6c92789d5f87 | 220 | motors.set_left_motor_speed(left_speed / 100.0f); |
jah128 | 0:d6269d17c8cf | 221 | } |
jah128 | 0:d6269d17c8cf | 222 | if(sub_menu == 1) { |
jah128 | 0:d6269d17c8cf | 223 | right_speed += 5; |
jah128 | 0:d6269d17c8cf | 224 | if(right_speed > 100) right_speed = 100; |
jah128 | 8:6c92789d5f87 | 225 | motors.set_right_motor_speed(right_speed / 100.0f); |
jah128 | 0:d6269d17c8cf | 226 | } |
jah128 | 0:d6269d17c8cf | 227 | if(sub_menu == 2) { |
jah128 | 0:d6269d17c8cf | 228 | if(both_motor_mode == 0) both_motor_mode=5; |
jah128 | 0:d6269d17c8cf | 229 | else both_motor_mode--; |
jah128 | 0:d6269d17c8cf | 230 | switch(both_motor_mode) { |
jah128 | 0:d6269d17c8cf | 231 | case 0: |
jah128 | 8:6c92789d5f87 | 232 | motors.stop(); |
jah128 | 0:d6269d17c8cf | 233 | break; |
jah128 | 0:d6269d17c8cf | 234 | case 1: |
jah128 | 8:6c92789d5f87 | 235 | motors.brake(); |
jah128 | 0:d6269d17c8cf | 236 | break; |
jah128 | 0:d6269d17c8cf | 237 | case 2: |
jah128 | 8:6c92789d5f87 | 238 | motors.forward(0.5); |
jah128 | 0:d6269d17c8cf | 239 | break; |
jah128 | 0:d6269d17c8cf | 240 | case 3: |
jah128 | 8:6c92789d5f87 | 241 | motors.forward(1); |
jah128 | 0:d6269d17c8cf | 242 | break; |
jah128 | 0:d6269d17c8cf | 243 | case 4: |
jah128 | 8:6c92789d5f87 | 244 | motors.backward(0.5); |
jah128 | 0:d6269d17c8cf | 245 | break; |
jah128 | 0:d6269d17c8cf | 246 | case 5: |
jah128 | 8:6c92789d5f87 | 247 | motors.backward(1.0); |
jah128 | 0:d6269d17c8cf | 248 | break; |
jah128 | 0:d6269d17c8cf | 249 | } |
jah128 | 0:d6269d17c8cf | 250 | } |
jah128 | 0:d6269d17c8cf | 251 | if(sub_menu == 3) { |
jah128 | 0:d6269d17c8cf | 252 | level = 0; |
jah128 | 0:d6269d17c8cf | 253 | } |
jah128 | 0:d6269d17c8cf | 254 | break; |
jah128 | 15:66be5ec52c3b | 255 | case 4: // Radio Menu |
jah128 | 0:d6269d17c8cf | 256 | if(sub_menu == 0) level = 0; |
jah128 | 0:d6269d17c8cf | 257 | break; |
jah128 | 15:66be5ec52c3b | 258 | case 5: // Info Menu |
jah128 | 0:d6269d17c8cf | 259 | if(sub_menu == 6) level = 0; |
jah128 | 0:d6269d17c8cf | 260 | break; |
jah128 | 17:bf614e28668f | 261 | case 7: // Calibration Menu |
jah128 | 17:bf614e28668f | 262 | if(sub_menu == 0) sensors.calibrate_base_sensors(); |
jah128 | 18:9204f74069b4 | 263 | if(sub_menu == 1) motors.calibrate_motors(); |
jah128 | 17:bf614e28668f | 264 | if(sub_menu == 2) level = 0; |
jah128 | 17:bf614e28668f | 265 | break; |
jah128 | 15:66be5ec52c3b | 266 | case 6: // Demo Menu |
jah128 | 0:d6269d17c8cf | 267 | if(sub_menu == 0) { |
jah128 | 0:d6269d17c8cf | 268 | if(demo_running == 0) { |
jah128 | 0:d6269d17c8cf | 269 | start_line_demo(); |
jah128 | 0:d6269d17c8cf | 270 | } else { |
jah128 | 0:d6269d17c8cf | 271 | demo_running = 0; |
jah128 | 0:d6269d17c8cf | 272 | display.set_backlight_brightness(bl_brightness * 0.01f); |
jah128 | 8:6c92789d5f87 | 273 | motors.stop(); |
jah128 | 0:d6269d17c8cf | 274 | } |
jah128 | 0:d6269d17c8cf | 275 | } |
jah128 | 0:d6269d17c8cf | 276 | if(sub_menu == 1) { |
jah128 | 0:d6269d17c8cf | 277 | if(demo_running == 0) { |
jah128 | 0:d6269d17c8cf | 278 | start_obstacle_demo(); |
jah128 | 0:d6269d17c8cf | 279 | } else { |
jah128 | 0:d6269d17c8cf | 280 | demo_running = 0; |
jah128 | 0:d6269d17c8cf | 281 | display.set_backlight_brightness(bl_brightness * 0.01f); |
jah128 | 8:6c92789d5f87 | 282 | motors.stop(); |
jah128 | 0:d6269d17c8cf | 283 | } |
jah128 | 0:d6269d17c8cf | 284 | } |
jah128 | 0:d6269d17c8cf | 285 | if(sub_menu == 2) { |
jah128 | 0:d6269d17c8cf | 286 | if(demo_running == 0) { |
jah128 | 0:d6269d17c8cf | 287 | start_spinning_demo(); |
jah128 | 0:d6269d17c8cf | 288 | } else { |
jah128 | 0:d6269d17c8cf | 289 | demo_running = 0; |
jah128 | 0:d6269d17c8cf | 290 | display.set_backlight_brightness(bl_brightness * 0.01f); |
jah128 | 8:6c92789d5f87 | 291 | motors.stop(); |
jah128 | 0:d6269d17c8cf | 292 | } |
jah128 | 0:d6269d17c8cf | 293 | } |
jah128 | 0:d6269d17c8cf | 294 | if(sub_menu == 3) { |
jah128 | 0:d6269d17c8cf | 295 | if(demo_running == 0) { |
jah128 | 0:d6269d17c8cf | 296 | start_stress_demo(); |
jah128 | 0:d6269d17c8cf | 297 | } else { |
jah128 | 0:d6269d17c8cf | 298 | demo_running = 0; |
jah128 | 0:d6269d17c8cf | 299 | display.set_backlight_brightness(bl_brightness * 0.01f); |
jah128 | 8:6c92789d5f87 | 300 | motors.stop(); |
jah128 | 0:d6269d17c8cf | 301 | } |
jah128 | 0:d6269d17c8cf | 302 | } |
jah128 | 16:50686c07ad07 | 303 | if(sub_menu == 4) { |
jah128 | 16:50686c07ad07 | 304 | if(demo_running == 0) { |
jah128 | 16:50686c07ad07 | 305 | start_colour_demo(); |
jah128 | 16:50686c07ad07 | 306 | } else { |
jah128 | 16:50686c07ad07 | 307 | demo_running = 0; |
jah128 | 16:50686c07ad07 | 308 | display.set_backlight_brightness(bl_brightness * 0.01f); |
jah128 | 16:50686c07ad07 | 309 | motors.stop(); |
jah128 | 16:50686c07ad07 | 310 | } |
jah128 | 16:50686c07ad07 | 311 | } |
jah128 | 16:50686c07ad07 | 312 | if(sub_menu == 5) level = 0; |
jah128 | 0:d6269d17c8cf | 313 | break; |
jah128 | 0:d6269d17c8cf | 314 | } |
jah128 | 0:d6269d17c8cf | 315 | break; |
jah128 | 0:d6269d17c8cf | 316 | } |
jah128 | 0:d6269d17c8cf | 317 | break; |
jah128 | 0:d6269d17c8cf | 318 | case 2: //Down pressed |
jah128 | 0:d6269d17c8cf | 319 | switch(level) { |
jah128 | 0:d6269d17c8cf | 320 | case 0: |
jah128 | 15:66be5ec52c3b | 321 | if(top_menu != 9 && top_menu != 0) { |
jah128 | 0:d6269d17c8cf | 322 | level++; |
jah128 | 0:d6269d17c8cf | 323 | sub_menu = 0; |
jah128 | 0:d6269d17c8cf | 324 | } else { |
jah128 | 15:66be5ec52c3b | 325 | if(top_menu == 0) { |
jah128 | 15:66be5ec52c3b | 326 | toggle_quick_test(); |
jah128 | 15:66be5ec52c3b | 327 | } else { |
jah128 | 15:66be5ec52c3b | 328 | demo_on = 0; |
jah128 | 15:66be5ec52c3b | 329 | user_code_running = user_code_restore_mode; |
jah128 | 15:66be5ec52c3b | 330 | } |
jah128 | 0:d6269d17c8cf | 331 | } |
jah128 | 0:d6269d17c8cf | 332 | break; |
jah128 | 0:d6269d17c8cf | 333 | case 1: |
jah128 | 0:d6269d17c8cf | 334 | switch(top_menu) { |
jah128 | 15:66be5ec52c3b | 335 | case 8: // PsiBasic Menu |
jah128 | 0:d6269d17c8cf | 336 | if(sub_menu == psi_basic_file_count) level = 0; |
jah128 | 0:d6269d17c8cf | 337 | break; |
jah128 | 15:66be5ec52c3b | 338 | case 1: //LED Menu |
jah128 | 0:d6269d17c8cf | 339 | if(sub_menu < 9) { |
jah128 | 0:d6269d17c8cf | 340 | led_state[sub_menu]++; |
jah128 | 0:d6269d17c8cf | 341 | if(led_state[sub_menu] == 4) led_state[sub_menu] = 0; |
jah128 | 0:d6269d17c8cf | 342 | demo_update_leds(); |
jah128 | 0:d6269d17c8cf | 343 | } |
jah128 | 0:d6269d17c8cf | 344 | if(sub_menu == 9) { |
jah128 | 0:d6269d17c8cf | 345 | all_led_state++; |
jah128 | 0:d6269d17c8cf | 346 | if(all_led_state == 4) all_led_state = 0; |
jah128 | 0:d6269d17c8cf | 347 | for(int i=0; i<9; i++) { |
jah128 | 0:d6269d17c8cf | 348 | led_state[i]=all_led_state; |
jah128 | 0:d6269d17c8cf | 349 | } |
jah128 | 0:d6269d17c8cf | 350 | demo_update_leds(); |
jah128 | 0:d6269d17c8cf | 351 | } |
jah128 | 0:d6269d17c8cf | 352 | if(sub_menu == 10) { |
jah128 | 0:d6269d17c8cf | 353 | base_led_state = 1 - base_led_state; |
jah128 | 0:d6269d17c8cf | 354 | demo_update_leds(); |
jah128 | 0:d6269d17c8cf | 355 | } |
jah128 | 0:d6269d17c8cf | 356 | if(sub_menu == 11) { |
jah128 | 0:d6269d17c8cf | 357 | switch(brightness) { |
jah128 | 0:d6269d17c8cf | 358 | case 1: |
jah128 | 0:d6269d17c8cf | 359 | brightness = 2; |
jah128 | 0:d6269d17c8cf | 360 | break; |
jah128 | 0:d6269d17c8cf | 361 | case 2: |
jah128 | 0:d6269d17c8cf | 362 | brightness = 5; |
jah128 | 0:d6269d17c8cf | 363 | break; |
jah128 | 0:d6269d17c8cf | 364 | case 5: |
jah128 | 0:d6269d17c8cf | 365 | brightness = 10; |
jah128 | 0:d6269d17c8cf | 366 | break; |
jah128 | 0:d6269d17c8cf | 367 | case 10: |
jah128 | 0:d6269d17c8cf | 368 | brightness = 20; |
jah128 | 0:d6269d17c8cf | 369 | break; |
jah128 | 0:d6269d17c8cf | 370 | case 20: |
jah128 | 0:d6269d17c8cf | 371 | brightness = 50; |
jah128 | 0:d6269d17c8cf | 372 | break; |
jah128 | 0:d6269d17c8cf | 373 | case 50: |
jah128 | 0:d6269d17c8cf | 374 | brightness = 100; |
jah128 | 0:d6269d17c8cf | 375 | break; |
jah128 | 0:d6269d17c8cf | 376 | } |
jah128 | 0:d6269d17c8cf | 377 | demo_update_leds(); |
jah128 | 0:d6269d17c8cf | 378 | } |
jah128 | 0:d6269d17c8cf | 379 | |
jah128 | 0:d6269d17c8cf | 380 | if(sub_menu == 12) { |
jah128 | 0:d6269d17c8cf | 381 | if(bl_brightness < 100) bl_brightness+=10; |
jah128 | 0:d6269d17c8cf | 382 | display.set_backlight_brightness(bl_brightness * 0.01f); |
jah128 | 0:d6269d17c8cf | 383 | } |
jah128 | 0:d6269d17c8cf | 384 | if(sub_menu == 13) level = 0; |
jah128 | 0:d6269d17c8cf | 385 | |
jah128 | 0:d6269d17c8cf | 386 | break; |
jah128 | 15:66be5ec52c3b | 387 | case 2: // Sensors Menu |
jah128 | 17:bf614e28668f | 388 | if(sub_menu == 4 || sub_menu == 5 || sub_menu == 6) { |
jah128 | 0:d6269d17c8cf | 389 | if(base_ir_index == 4) base_ir_index = 0; |
jah128 | 0:d6269d17c8cf | 390 | else base_ir_index ++; |
jah128 | 0:d6269d17c8cf | 391 | } |
jah128 | 17:bf614e28668f | 392 | if(sub_menu > 6 && sub_menu < 10) { |
jah128 | 0:d6269d17c8cf | 393 | if(side_ir_index == 7) side_ir_index = 0; |
jah128 | 0:d6269d17c8cf | 394 | else side_ir_index ++; |
jah128 | 0:d6269d17c8cf | 395 | } |
jah128 | 17:bf614e28668f | 396 | if(sub_menu == 13) level = 0; |
jah128 | 0:d6269d17c8cf | 397 | break; |
jah128 | 15:66be5ec52c3b | 398 | case 3: // Motor Menu |
jah128 | 0:d6269d17c8cf | 399 | if(sub_menu == 0) { |
jah128 | 0:d6269d17c8cf | 400 | left_speed -= 5; |
jah128 | 0:d6269d17c8cf | 401 | if(left_speed < -100) left_speed = -100; |
jah128 | 8:6c92789d5f87 | 402 | motors.set_left_motor_speed(left_speed / 100.0f); |
jah128 | 0:d6269d17c8cf | 403 | } |
jah128 | 0:d6269d17c8cf | 404 | if(sub_menu == 1) { |
jah128 | 0:d6269d17c8cf | 405 | right_speed -= 5; |
jah128 | 0:d6269d17c8cf | 406 | if(right_speed < -100) right_speed = -100; |
jah128 | 8:6c92789d5f87 | 407 | motors.set_right_motor_speed(right_speed / 100.0f); |
jah128 | 0:d6269d17c8cf | 408 | } |
jah128 | 0:d6269d17c8cf | 409 | if(sub_menu == 2) { |
jah128 | 0:d6269d17c8cf | 410 | both_motor_mode++; |
jah128 | 0:d6269d17c8cf | 411 | if(both_motor_mode == 6) both_motor_mode=0; |
jah128 | 0:d6269d17c8cf | 412 | switch(both_motor_mode) { |
jah128 | 0:d6269d17c8cf | 413 | case 0: |
jah128 | 8:6c92789d5f87 | 414 | motors.stop(); |
jah128 | 0:d6269d17c8cf | 415 | break; |
jah128 | 0:d6269d17c8cf | 416 | case 1: |
jah128 | 8:6c92789d5f87 | 417 | motors.brake(); |
jah128 | 0:d6269d17c8cf | 418 | break; |
jah128 | 0:d6269d17c8cf | 419 | case 2: |
jah128 | 8:6c92789d5f87 | 420 | motors.forward(0.5); |
jah128 | 0:d6269d17c8cf | 421 | break; |
jah128 | 0:d6269d17c8cf | 422 | case 3: |
jah128 | 8:6c92789d5f87 | 423 | motors.forward(1); |
jah128 | 0:d6269d17c8cf | 424 | break; |
jah128 | 0:d6269d17c8cf | 425 | case 4: |
jah128 | 8:6c92789d5f87 | 426 | motors.backward(0.5); |
jah128 | 0:d6269d17c8cf | 427 | break; |
jah128 | 0:d6269d17c8cf | 428 | case 5: |
jah128 | 8:6c92789d5f87 | 429 | motors.backward(1.0); |
jah128 | 0:d6269d17c8cf | 430 | break; |
jah128 | 0:d6269d17c8cf | 431 | } |
jah128 | 0:d6269d17c8cf | 432 | } |
jah128 | 0:d6269d17c8cf | 433 | if(sub_menu == 3) { |
jah128 | 0:d6269d17c8cf | 434 | level = 0; |
jah128 | 0:d6269d17c8cf | 435 | } |
jah128 | 0:d6269d17c8cf | 436 | break; |
jah128 | 15:66be5ec52c3b | 437 | case 4: // Radio Menu |
jah128 | 0:d6269d17c8cf | 438 | if(sub_menu == 0) level = 0; |
jah128 | 0:d6269d17c8cf | 439 | break; |
jah128 | 15:66be5ec52c3b | 440 | case 5: // Info Menu |
jah128 | 0:d6269d17c8cf | 441 | if(sub_menu == 6) level = 0; |
jah128 | 0:d6269d17c8cf | 442 | break; |
jah128 | 17:bf614e28668f | 443 | case 7: // Calibration Menu |
jah128 | 17:bf614e28668f | 444 | if(sub_menu == 0) sensors.calibrate_base_sensors(); |
jah128 | 18:9204f74069b4 | 445 | if(sub_menu == 1) motors.calibrate_motors(); |
jah128 | 17:bf614e28668f | 446 | if(sub_menu == 2) level = 0; |
jah128 | 18:9204f74069b4 | 447 | break; |
jah128 | 15:66be5ec52c3b | 448 | case 6: // Demo Menu |
jah128 | 0:d6269d17c8cf | 449 | if(sub_menu == 0) { |
jah128 | 0:d6269d17c8cf | 450 | if(demo_running == 0) { |
jah128 | 0:d6269d17c8cf | 451 | start_line_demo(); |
jah128 | 0:d6269d17c8cf | 452 | } else { |
jah128 | 0:d6269d17c8cf | 453 | demo_running = 0; |
jah128 | 0:d6269d17c8cf | 454 | display.set_backlight_brightness(bl_brightness * 0.01f); |
jah128 | 8:6c92789d5f87 | 455 | motors.stop(); |
jah128 | 0:d6269d17c8cf | 456 | } |
jah128 | 0:d6269d17c8cf | 457 | } |
jah128 | 0:d6269d17c8cf | 458 | if(sub_menu == 1) { |
jah128 | 0:d6269d17c8cf | 459 | if(demo_running == 0) { |
jah128 | 0:d6269d17c8cf | 460 | start_obstacle_demo(); |
jah128 | 0:d6269d17c8cf | 461 | } else { |
jah128 | 0:d6269d17c8cf | 462 | demo_running = 0; |
jah128 | 0:d6269d17c8cf | 463 | display.set_backlight_brightness(bl_brightness * 0.01f); |
jah128 | 8:6c92789d5f87 | 464 | motors.stop(); |
jah128 | 0:d6269d17c8cf | 465 | |
jah128 | 0:d6269d17c8cf | 466 | } |
jah128 | 0:d6269d17c8cf | 467 | } |
jah128 | 0:d6269d17c8cf | 468 | if(sub_menu == 2) { |
jah128 | 0:d6269d17c8cf | 469 | if(demo_running == 0) { |
jah128 | 0:d6269d17c8cf | 470 | start_spinning_demo(); |
jah128 | 0:d6269d17c8cf | 471 | } else { |
jah128 | 0:d6269d17c8cf | 472 | demo_running = 0; |
jah128 | 0:d6269d17c8cf | 473 | display.set_backlight_brightness(bl_brightness * 0.01f); |
jah128 | 8:6c92789d5f87 | 474 | motors.stop(); |
jah128 | 0:d6269d17c8cf | 475 | } |
jah128 | 0:d6269d17c8cf | 476 | } |
jah128 | 0:d6269d17c8cf | 477 | if(sub_menu == 3) { |
jah128 | 0:d6269d17c8cf | 478 | if(demo_running == 0) { |
jah128 | 0:d6269d17c8cf | 479 | start_stress_demo(); |
jah128 | 0:d6269d17c8cf | 480 | } else { |
jah128 | 0:d6269d17c8cf | 481 | demo_running = 0; |
jah128 | 0:d6269d17c8cf | 482 | display.set_backlight_brightness(bl_brightness * 0.01f); |
jah128 | 8:6c92789d5f87 | 483 | motors.stop(); |
jah128 | 0:d6269d17c8cf | 484 | } |
jah128 | 0:d6269d17c8cf | 485 | } |
jah128 | 16:50686c07ad07 | 486 | if(sub_menu == 4) { |
jah128 | 16:50686c07ad07 | 487 | if(demo_running == 0) { |
jah128 | 16:50686c07ad07 | 488 | start_colour_demo(); |
jah128 | 16:50686c07ad07 | 489 | } else { |
jah128 | 16:50686c07ad07 | 490 | demo_running = 0; |
jah128 | 16:50686c07ad07 | 491 | display.set_backlight_brightness(bl_brightness * 0.01f); |
jah128 | 16:50686c07ad07 | 492 | motors.stop(); |
jah128 | 16:50686c07ad07 | 493 | } |
jah128 | 16:50686c07ad07 | 494 | } |
jah128 | 16:50686c07ad07 | 495 | if(sub_menu == 5) level = 0; |
jah128 | 0:d6269d17c8cf | 496 | break; |
jah128 | 0:d6269d17c8cf | 497 | } |
jah128 | 0:d6269d17c8cf | 498 | break; |
jah128 | 0:d6269d17c8cf | 499 | } |
jah128 | 0:d6269d17c8cf | 500 | break; |
jah128 | 0:d6269d17c8cf | 501 | case 4: //Left pressed |
jah128 | 0:d6269d17c8cf | 502 | switch(level) { |
jah128 | 0:d6269d17c8cf | 503 | case 0: |
jah128 | 0:d6269d17c8cf | 504 | if(top_menu == 0) { |
jah128 | 15:66be5ec52c3b | 505 | top_menu = 9; |
jah128 | 15:66be5ec52c3b | 506 | } else { |
jah128 | 17:bf614e28668f | 507 | top_menu --; |
jah128 | 15:66be5ec52c3b | 508 | if(use_flash_basic == 0 && top_menu == 8) top_menu = 7; |
jah128 | 4:1c621cb8cf0d | 509 | } |
jah128 | 0:d6269d17c8cf | 510 | break; |
jah128 | 0:d6269d17c8cf | 511 | case 1: |
jah128 | 0:d6269d17c8cf | 512 | switch(top_menu) { |
jah128 | 15:66be5ec52c3b | 513 | case 1: //LED Menu |
jah128 | 0:d6269d17c8cf | 514 | if(sub_menu == 0) sub_menu = 13; |
jah128 | 0:d6269d17c8cf | 515 | else sub_menu --; |
jah128 | 0:d6269d17c8cf | 516 | break; |
jah128 | 15:66be5ec52c3b | 517 | case 2: //Sensors Menu |
jah128 | 17:bf614e28668f | 518 | if(sub_menu == 0) sub_menu = 13; |
jah128 | 0:d6269d17c8cf | 519 | else sub_menu --; |
jah128 | 0:d6269d17c8cf | 520 | break; |
jah128 | 0:d6269d17c8cf | 521 | |
jah128 | 15:66be5ec52c3b | 522 | case 3: //Motor Menu |
jah128 | 0:d6269d17c8cf | 523 | if(sub_menu == 0) sub_menu = 3; |
jah128 | 0:d6269d17c8cf | 524 | else sub_menu --; |
jah128 | 0:d6269d17c8cf | 525 | break; |
jah128 | 15:66be5ec52c3b | 526 | case 5: //Info Menu |
jah128 | 0:d6269d17c8cf | 527 | if(sub_menu == 0) sub_menu = 6; |
jah128 | 0:d6269d17c8cf | 528 | else sub_menu --; |
jah128 | 0:d6269d17c8cf | 529 | break; |
jah128 | 15:66be5ec52c3b | 530 | case 6: //Demo Menu |
jah128 | 16:50686c07ad07 | 531 | if(sub_menu == 0) sub_menu = 5; |
jah128 | 0:d6269d17c8cf | 532 | else sub_menu --; |
jah128 | 0:d6269d17c8cf | 533 | break; |
jah128 | 15:66be5ec52c3b | 534 | case 7: //Calibrate Menu |
jah128 | 4:1c621cb8cf0d | 535 | if(sub_menu == 0) sub_menu = 2; |
jah128 | 4:1c621cb8cf0d | 536 | else sub_menu --; |
jah128 | 4:1c621cb8cf0d | 537 | break; |
jah128 | 15:66be5ec52c3b | 538 | case 8: //PsiBasic Menu |
jah128 | 0:d6269d17c8cf | 539 | if(sub_menu == 0) sub_menu = psi_basic_file_count; |
jah128 | 0:d6269d17c8cf | 540 | else sub_menu --; |
jah128 | 0:d6269d17c8cf | 541 | } |
jah128 | 0:d6269d17c8cf | 542 | break; |
jah128 | 0:d6269d17c8cf | 543 | |
jah128 | 0:d6269d17c8cf | 544 | } |
jah128 | 0:d6269d17c8cf | 545 | break; |
jah128 | 0:d6269d17c8cf | 546 | case 8: //Right pressed |
jah128 | 0:d6269d17c8cf | 547 | switch(level) { |
jah128 | 0:d6269d17c8cf | 548 | case 0: |
jah128 | 0:d6269d17c8cf | 549 | top_menu ++; |
jah128 | 17:bf614e28668f | 550 | if(top_menu == 8 && use_flash_basic == 0) top_menu = 9; |
jah128 | 17:bf614e28668f | 551 | if((top_menu) > 9) top_menu = 0; |
jah128 | 0:d6269d17c8cf | 552 | break; |
jah128 | 0:d6269d17c8cf | 553 | case 1: |
jah128 | 0:d6269d17c8cf | 554 | switch(top_menu) { |
jah128 | 15:66be5ec52c3b | 555 | case 1: //LED Menu |
jah128 | 0:d6269d17c8cf | 556 | if(sub_menu == 13) sub_menu = 0; |
jah128 | 0:d6269d17c8cf | 557 | else sub_menu ++; |
jah128 | 0:d6269d17c8cf | 558 | break; |
jah128 | 15:66be5ec52c3b | 559 | case 2: //Sensors Menu |
jah128 | 17:bf614e28668f | 560 | if(sub_menu == 13) sub_menu = 0; |
jah128 | 0:d6269d17c8cf | 561 | else sub_menu ++; |
jah128 | 0:d6269d17c8cf | 562 | break; |
jah128 | 15:66be5ec52c3b | 563 | case 3: //Motor Menu |
jah128 | 0:d6269d17c8cf | 564 | if(sub_menu == 3) sub_menu = 0; |
jah128 | 0:d6269d17c8cf | 565 | else sub_menu ++; |
jah128 | 0:d6269d17c8cf | 566 | break; |
jah128 | 15:66be5ec52c3b | 567 | case 5: //Info Menu |
jah128 | 0:d6269d17c8cf | 568 | if(sub_menu == 6) sub_menu = 0; |
jah128 | 0:d6269d17c8cf | 569 | else sub_menu ++; |
jah128 | 0:d6269d17c8cf | 570 | break; |
jah128 | 15:66be5ec52c3b | 571 | case 6: //Demo Menu |
jah128 | 16:50686c07ad07 | 572 | if(sub_menu == 5) sub_menu = 0; |
jah128 | 0:d6269d17c8cf | 573 | else sub_menu ++; |
jah128 | 0:d6269d17c8cf | 574 | break; |
jah128 | 15:66be5ec52c3b | 575 | case 7: //Calibrate Menu |
jah128 | 4:1c621cb8cf0d | 576 | if(sub_menu == 2) sub_menu = 0; |
jah128 | 4:1c621cb8cf0d | 577 | else sub_menu ++; |
jah128 | 4:1c621cb8cf0d | 578 | break; |
jah128 | 15:66be5ec52c3b | 579 | case 8: //PsiBasic Menu |
jah128 | 0:d6269d17c8cf | 580 | if(sub_menu == psi_basic_file_count) sub_menu = 0; |
jah128 | 0:d6269d17c8cf | 581 | else sub_menu ++; |
jah128 | 0:d6269d17c8cf | 582 | } |
jah128 | 0:d6269d17c8cf | 583 | break; |
jah128 | 0:d6269d17c8cf | 584 | } |
jah128 | 0:d6269d17c8cf | 585 | break; |
jah128 | 0:d6269d17c8cf | 586 | } |
jah128 | 0:d6269d17c8cf | 587 | } else started = 1; |
jah128 | 0:d6269d17c8cf | 588 | display.clear_display(); |
jah128 | 0:d6269d17c8cf | 589 | switch(level) { |
jah128 | 0:d6269d17c8cf | 590 | case 0: |
jah128 | 0:d6269d17c8cf | 591 | //Top level menu |
jah128 | 0:d6269d17c8cf | 592 | switch(top_menu) { |
jah128 | 0:d6269d17c8cf | 593 | case 0: |
jah128 | 15:66be5ec52c3b | 594 | strcpy(topline,"---QUICK TEST---"); |
jah128 | 15:66be5ec52c3b | 595 | break; |
jah128 | 15:66be5ec52c3b | 596 | case 1: |
jah128 | 0:d6269d17c8cf | 597 | strcpy(topline,"---TEST LEDS----"); |
jah128 | 0:d6269d17c8cf | 598 | break; |
jah128 | 15:66be5ec52c3b | 599 | case 2: |
jah128 | 0:d6269d17c8cf | 600 | strcpy(topline,"--TEST SENSORS--"); |
jah128 | 0:d6269d17c8cf | 601 | break; |
jah128 | 15:66be5ec52c3b | 602 | case 3: |
jah128 | 0:d6269d17c8cf | 603 | strcpy(topline,"--TEST MOTORS---"); |
jah128 | 0:d6269d17c8cf | 604 | break; |
jah128 | 0:d6269d17c8cf | 605 | case 4: |
jah128 | 15:66be5ec52c3b | 606 | strcpy(topline,"---TEST RADIO---"); |
jah128 | 0:d6269d17c8cf | 607 | break; |
jah128 | 0:d6269d17c8cf | 608 | case 5: |
jah128 | 15:66be5ec52c3b | 609 | strcpy(topline,"------INFO------"); |
jah128 | 0:d6269d17c8cf | 610 | break; |
jah128 | 0:d6269d17c8cf | 611 | case 6: |
jah128 | 15:66be5ec52c3b | 612 | strcpy(topline,"---CODE DEMOS---"); |
jah128 | 0:d6269d17c8cf | 613 | break; |
jah128 | 0:d6269d17c8cf | 614 | case 7: |
jah128 | 17:bf614e28668f | 615 | strcpy(topline,"---CALIBRATION--"); |
jah128 | 15:66be5ec52c3b | 616 | break; |
jah128 | 15:66be5ec52c3b | 617 | case 8: |
jah128 | 0:d6269d17c8cf | 618 | strcpy(topline,"---PSI BASIC----"); |
jah128 | 0:d6269d17c8cf | 619 | break; |
jah128 | 15:66be5ec52c3b | 620 | case 9: |
jah128 | 4:1c621cb8cf0d | 621 | strcpy(topline,"------EXIT------"); |
jah128 | 4:1c621cb8cf0d | 622 | break; |
jah128 | 0:d6269d17c8cf | 623 | } |
jah128 | 0:d6269d17c8cf | 624 | strcpy(bottomline,""); |
jah128 | 0:d6269d17c8cf | 625 | break; |
jah128 | 0:d6269d17c8cf | 626 | case 1: |
jah128 | 0:d6269d17c8cf | 627 | //Sub level menu |
jah128 | 0:d6269d17c8cf | 628 | switch(top_menu) { |
jah128 | 15:66be5ec52c3b | 629 | case 8: |
jah128 | 0:d6269d17c8cf | 630 | strcpy(topline,"-PSI BASIC MENU-"); |
jah128 | 0:d6269d17c8cf | 631 | if(sub_menu == psi_basic_file_count) strcpy(bottomline,"EXIT"); |
jah128 | 0:d6269d17c8cf | 632 | else strcpy(bottomline,basic_filenames.at(sub_menu).c_str()); |
jah128 | 0:d6269d17c8cf | 633 | break; |
jah128 | 15:66be5ec52c3b | 634 | case 1: |
jah128 | 0:d6269d17c8cf | 635 | strcpy(topline,"----LED MENU----"); |
jah128 | 0:d6269d17c8cf | 636 | char led_status[7]; |
jah128 | 0:d6269d17c8cf | 637 | if(sub_menu<9) { |
jah128 | 0:d6269d17c8cf | 638 | switch(led_state[sub_menu]) { |
jah128 | 0:d6269d17c8cf | 639 | case 0: |
jah128 | 0:d6269d17c8cf | 640 | strcpy(led_status,"OFF"); |
jah128 | 0:d6269d17c8cf | 641 | break; |
jah128 | 0:d6269d17c8cf | 642 | case 1: |
jah128 | 0:d6269d17c8cf | 643 | strcpy(led_status,"RED"); |
jah128 | 0:d6269d17c8cf | 644 | break; |
jah128 | 0:d6269d17c8cf | 645 | case 2: |
jah128 | 0:d6269d17c8cf | 646 | strcpy(led_status,"GREEN"); |
jah128 | 0:d6269d17c8cf | 647 | break; |
jah128 | 0:d6269d17c8cf | 648 | case 3: |
jah128 | 0:d6269d17c8cf | 649 | strcpy(led_status,"YELLOW"); |
jah128 | 0:d6269d17c8cf | 650 | break; |
jah128 | 0:d6269d17c8cf | 651 | } |
jah128 | 0:d6269d17c8cf | 652 | } |
jah128 | 0:d6269d17c8cf | 653 | if(sub_menu < 8) sprintf(bottomline,"OUTER %d: %s",(sub_menu + 1),led_status); |
jah128 | 0:d6269d17c8cf | 654 | if(sub_menu == 8) sprintf(bottomline,"CENTER: %s",led_status); |
jah128 | 0:d6269d17c8cf | 655 | if(sub_menu == 9) { |
jah128 | 0:d6269d17c8cf | 656 | switch(all_led_state) { |
jah128 | 0:d6269d17c8cf | 657 | case 0: |
jah128 | 0:d6269d17c8cf | 658 | strcpy(led_status,"OFF"); |
jah128 | 0:d6269d17c8cf | 659 | break; |
jah128 | 0:d6269d17c8cf | 660 | case 1: |
jah128 | 0:d6269d17c8cf | 661 | strcpy(led_status,"RED"); |
jah128 | 0:d6269d17c8cf | 662 | break; |
jah128 | 0:d6269d17c8cf | 663 | case 2: |
jah128 | 0:d6269d17c8cf | 664 | strcpy(led_status,"GREEN"); |
jah128 | 0:d6269d17c8cf | 665 | break; |
jah128 | 0:d6269d17c8cf | 666 | case 3: |
jah128 | 0:d6269d17c8cf | 667 | strcpy(led_status,"YELLOW"); |
jah128 | 0:d6269d17c8cf | 668 | break; |
jah128 | 0:d6269d17c8cf | 669 | } |
jah128 | 0:d6269d17c8cf | 670 | sprintf(bottomline,"SET ALL %s", led_status); |
jah128 | 0:d6269d17c8cf | 671 | } |
jah128 | 0:d6269d17c8cf | 672 | if(sub_menu == 10) { |
jah128 | 0:d6269d17c8cf | 673 | if(base_led_state == 0) strcpy(led_status,"OFF"); |
jah128 | 0:d6269d17c8cf | 674 | else strcpy(led_status,"ON"); |
jah128 | 0:d6269d17c8cf | 675 | sprintf(bottomline,"BASE: %s",led_status); |
jah128 | 0:d6269d17c8cf | 676 | } |
jah128 | 0:d6269d17c8cf | 677 | if(sub_menu == 11) sprintf(bottomline,"CLED BNESS %d%%", brightness); |
jah128 | 0:d6269d17c8cf | 678 | if(sub_menu == 12) sprintf(bottomline,"DISP BNESS %d%%", bl_brightness); |
jah128 | 0:d6269d17c8cf | 679 | if(sub_menu == 13) strcpy(bottomline,"EXIT"); |
jah128 | 0:d6269d17c8cf | 680 | break; |
jah128 | 0:d6269d17c8cf | 681 | |
jah128 | 15:66be5ec52c3b | 682 | case 2: |
jah128 | 0:d6269d17c8cf | 683 | strcpy(topline,"--SENSORS MENU--"); |
jah128 | 0:d6269d17c8cf | 684 | switch(sub_menu) { |
jah128 | 0:d6269d17c8cf | 685 | case 0: { |
jah128 | 10:e58323951c08 | 686 | float battery = sensors.get_battery_voltage (); |
jah128 | 0:d6269d17c8cf | 687 | sprintf(bottomline,"BATTERY: %1.3fV",battery); |
jah128 | 0:d6269d17c8cf | 688 | break; |
jah128 | 0:d6269d17c8cf | 689 | } |
jah128 | 0:d6269d17c8cf | 690 | case 1: { |
jah128 | 10:e58323951c08 | 691 | float dc = sensors.get_dc_voltage (); |
jah128 | 0:d6269d17c8cf | 692 | sprintf(bottomline,"DC: %1.3fV",dc); |
jah128 | 0:d6269d17c8cf | 693 | break; |
jah128 | 0:d6269d17c8cf | 694 | } |
jah128 | 0:d6269d17c8cf | 695 | case 2: { |
jah128 | 10:e58323951c08 | 696 | float current = sensors.get_current (); |
jah128 | 0:d6269d17c8cf | 697 | sprintf(bottomline,"CURRENT: %1.3fA",current); |
jah128 | 0:d6269d17c8cf | 698 | break; |
jah128 | 0:d6269d17c8cf | 699 | } |
jah128 | 0:d6269d17c8cf | 700 | case 3: { |
jah128 | 10:e58323951c08 | 701 | float temperature = sensors.get_temperature(); |
jah128 | 0:d6269d17c8cf | 702 | sprintf(bottomline,"TEMP: %3.2fC", temperature); |
jah128 | 0:d6269d17c8cf | 703 | break; |
jah128 | 0:d6269d17c8cf | 704 | } |
jah128 | 0:d6269d17c8cf | 705 | case 4: |
jah128 | 10:e58323951c08 | 706 | sensors.store_background_base_ir_values(); |
jah128 | 10:e58323951c08 | 707 | sprintf(bottomline,"BIR%dB:%d",base_ir_index+1,sensors.get_background_base_ir_value(base_ir_index)); |
jah128 | 0:d6269d17c8cf | 708 | break; |
jah128 | 0:d6269d17c8cf | 709 | case 5: |
jah128 | 10:e58323951c08 | 710 | sensors.store_illuminated_base_ir_values(); |
jah128 | 10:e58323951c08 | 711 | sprintf(bottomline,"BIR%dR:%d",base_ir_index+1,sensors.get_illuminated_base_ir_value(base_ir_index)); |
jah128 | 0:d6269d17c8cf | 712 | break; |
jah128 | 0:d6269d17c8cf | 713 | case 6: |
jah128 | 17:bf614e28668f | 714 | sensors.store_illuminated_base_ir_values(); |
jah128 | 17:bf614e28668f | 715 | sprintf(bottomline,"BIC%dR:%1.3f",base_ir_index+1,sensors.get_calibrated_base_ir_value(base_ir_index)); |
jah128 | 17:bf614e28668f | 716 | break; |
jah128 | 17:bf614e28668f | 717 | case 7: |
jah128 | 10:e58323951c08 | 718 | sensors.store_background_raw_ir_values(); |
jah128 | 10:e58323951c08 | 719 | sprintf(bottomline,"SIR%dB:%d",side_ir_index+1,sensors.get_background_raw_ir_value(side_ir_index)); |
jah128 | 0:d6269d17c8cf | 720 | break; |
jah128 | 17:bf614e28668f | 721 | case 8: |
jah128 | 10:e58323951c08 | 722 | sensors.store_illuminated_raw_ir_values(); |
jah128 | 10:e58323951c08 | 723 | sprintf(bottomline,"SIR%dR:%d",side_ir_index+1,sensors.get_illuminated_raw_ir_value(side_ir_index)); |
jah128 | 0:d6269d17c8cf | 724 | break; |
jah128 | 17:bf614e28668f | 725 | case 9: |
jah128 | 0:d6269d17c8cf | 726 | sprintf(bottomline,"SIR%dD:%3.1f",side_ir_index+1,0.0); |
jah128 | 0:d6269d17c8cf | 727 | break; |
jah128 | 17:bf614e28668f | 728 | case 10: |
jah128 | 0:d6269d17c8cf | 729 | if(ultrasonic_distance_updated == 1) { |
jah128 | 0:d6269d17c8cf | 730 | sprintf(bottomline,"USONIC:%3dcm",ultrasonic_distance); |
jah128 | 0:d6269d17c8cf | 731 | } else sprintf(bottomline,"USONIC:---------"); |
jah128 | 10:e58323951c08 | 732 | sensors.update_ultrasonic_measure(); |
jah128 | 0:d6269d17c8cf | 733 | break; |
jah128 | 17:bf614e28668f | 734 | case 11: |
jah128 | 10:e58323951c08 | 735 | sensors.store_line_position(); |
jah128 | 0:d6269d17c8cf | 736 | if(line_found == 1)sprintf(bottomline,"LINE:%1.3f",line_position); |
jah128 | 0:d6269d17c8cf | 737 | else sprintf(bottomline,"LINE:---------"); |
jah128 | 0:d6269d17c8cf | 738 | break; |
jah128 | 18:9204f74069b4 | 739 | |
jah128 | 17:bf614e28668f | 740 | case 12: |
jah128 | 16:50686c07ad07 | 741 | sprintf(bottomline,"COLOUR: %s",colour.get_colour_string(colour.detect_colour_once())); |
jah128 | 16:50686c07ad07 | 742 | break; |
jah128 | 17:bf614e28668f | 743 | case 13: |
jah128 | 0:d6269d17c8cf | 744 | sprintf(bottomline,"EXIT"); |
jah128 | 0:d6269d17c8cf | 745 | break; |
jah128 | 0:d6269d17c8cf | 746 | } |
jah128 | 0:d6269d17c8cf | 747 | break; |
jah128 | 15:66be5ec52c3b | 748 | case 3: |
jah128 | 0:d6269d17c8cf | 749 | strcpy(topline,"--MOTORS MENU---"); |
jah128 | 0:d6269d17c8cf | 750 | switch(sub_menu) { |
jah128 | 0:d6269d17c8cf | 751 | case 0: |
jah128 | 0:d6269d17c8cf | 752 | sprintf(bottomline,"LEFT: %d%%", left_speed); |
jah128 | 0:d6269d17c8cf | 753 | break; |
jah128 | 0:d6269d17c8cf | 754 | case 1: |
jah128 | 0:d6269d17c8cf | 755 | sprintf(bottomline,"RIGHT: %d%%", right_speed); |
jah128 | 0:d6269d17c8cf | 756 | break; |
jah128 | 0:d6269d17c8cf | 757 | case 2: |
jah128 | 0:d6269d17c8cf | 758 | char both_mode_string[16]; |
jah128 | 0:d6269d17c8cf | 759 | switch(both_motor_mode) { |
jah128 | 0:d6269d17c8cf | 760 | case 0: |
jah128 | 0:d6269d17c8cf | 761 | strcpy(both_mode_string,"OFF"); |
jah128 | 0:d6269d17c8cf | 762 | break; |
jah128 | 0:d6269d17c8cf | 763 | case 1: |
jah128 | 0:d6269d17c8cf | 764 | strcpy(both_mode_string,"BRAKE"); |
jah128 | 0:d6269d17c8cf | 765 | break; |
jah128 | 0:d6269d17c8cf | 766 | case 2: |
jah128 | 0:d6269d17c8cf | 767 | strcpy(both_mode_string,"+50%"); |
jah128 | 0:d6269d17c8cf | 768 | break; |
jah128 | 0:d6269d17c8cf | 769 | case 3: |
jah128 | 0:d6269d17c8cf | 770 | strcpy(both_mode_string,"+100%"); |
jah128 | 0:d6269d17c8cf | 771 | break; |
jah128 | 0:d6269d17c8cf | 772 | case 4: |
jah128 | 0:d6269d17c8cf | 773 | strcpy(both_mode_string,"-50%"); |
jah128 | 0:d6269d17c8cf | 774 | break; |
jah128 | 0:d6269d17c8cf | 775 | case 5: |
jah128 | 0:d6269d17c8cf | 776 | strcpy(both_mode_string,"-100%"); |
jah128 | 0:d6269d17c8cf | 777 | break; |
jah128 | 0:d6269d17c8cf | 778 | } |
jah128 | 0:d6269d17c8cf | 779 | sprintf(bottomline,"BOTH TO %s",both_mode_string); |
jah128 | 0:d6269d17c8cf | 780 | break; |
jah128 | 0:d6269d17c8cf | 781 | case 3: |
jah128 | 0:d6269d17c8cf | 782 | sprintf(bottomline,"EXIT"); |
jah128 | 0:d6269d17c8cf | 783 | break; |
jah128 | 0:d6269d17c8cf | 784 | } |
jah128 | 0:d6269d17c8cf | 785 | break; |
jah128 | 15:66be5ec52c3b | 786 | case 4: |
jah128 | 0:d6269d17c8cf | 787 | strcpy(topline,"---RADIO MENU---"); |
jah128 | 0:d6269d17c8cf | 788 | switch(sub_menu) { |
jah128 | 0:d6269d17c8cf | 789 | |
jah128 | 0:d6269d17c8cf | 790 | case 0: |
jah128 | 0:d6269d17c8cf | 791 | sprintf(bottomline,"EXIT"); |
jah128 | 0:d6269d17c8cf | 792 | break; |
jah128 | 0:d6269d17c8cf | 793 | } |
jah128 | 0:d6269d17c8cf | 794 | break; |
jah128 | 15:66be5ec52c3b | 795 | case 5: |
jah128 | 0:d6269d17c8cf | 796 | strcpy(topline,"---INFO MENU----"); |
jah128 | 0:d6269d17c8cf | 797 | switch(sub_menu) { |
jah128 | 0:d6269d17c8cf | 798 | case 0: |
jah128 | 0:d6269d17c8cf | 799 | sprintf(bottomline,"ROBOT ID: %d",robot_id); |
jah128 | 0:d6269d17c8cf | 800 | break; |
jah128 | 0:d6269d17c8cf | 801 | case 1: |
jah128 | 0:d6269d17c8cf | 802 | sprintf(bottomline,"SOFTWARE: %1.2f",SOFTWARE_VERSION_CODE); |
jah128 | 0:d6269d17c8cf | 803 | break; |
jah128 | 0:d6269d17c8cf | 804 | case 2: |
jah128 | 0:d6269d17c8cf | 805 | if(firmware_version > 0) sprintf(bottomline,"FIRMWARE: %1.2f",firmware_version); |
jah128 | 0:d6269d17c8cf | 806 | else sprintf(bottomline,"FIRMWARE: ?????"); |
jah128 | 0:d6269d17c8cf | 807 | break; |
jah128 | 0:d6269d17c8cf | 808 | case 3: |
jah128 | 0:d6269d17c8cf | 809 | sprintf(bottomline,"PROG:%s",program_name); |
jah128 | 0:d6269d17c8cf | 810 | break; |
jah128 | 0:d6269d17c8cf | 811 | case 4: |
jah128 | 0:d6269d17c8cf | 812 | sprintf(bottomline,"AUTH:%s",author_name); |
jah128 | 0:d6269d17c8cf | 813 | break; |
jah128 | 0:d6269d17c8cf | 814 | case 5: |
jah128 | 0:d6269d17c8cf | 815 | sprintf(bottomline,"VER:%s",version_name); |
jah128 | 0:d6269d17c8cf | 816 | break; |
jah128 | 0:d6269d17c8cf | 817 | case 6: |
jah128 | 0:d6269d17c8cf | 818 | sprintf(bottomline,"EXIT"); |
jah128 | 0:d6269d17c8cf | 819 | break; |
jah128 | 0:d6269d17c8cf | 820 | } |
jah128 | 0:d6269d17c8cf | 821 | break; |
jah128 | 15:66be5ec52c3b | 822 | case 6: |
jah128 | 0:d6269d17c8cf | 823 | strcpy(topline,"---CODE DEMOS---"); |
jah128 | 0:d6269d17c8cf | 824 | switch(sub_menu) { |
jah128 | 0:d6269d17c8cf | 825 | case 0: |
jah128 | 0:d6269d17c8cf | 826 | sprintf(bottomline,"LINE FOLLOW"); |
jah128 | 0:d6269d17c8cf | 827 | break; |
jah128 | 0:d6269d17c8cf | 828 | case 1: |
jah128 | 0:d6269d17c8cf | 829 | sprintf(bottomline,"OBST. AVOID"); |
jah128 | 0:d6269d17c8cf | 830 | break; |
jah128 | 0:d6269d17c8cf | 831 | case 2: |
jah128 | 0:d6269d17c8cf | 832 | sprintf(bottomline,"COLOUR SPIN"); |
jah128 | 0:d6269d17c8cf | 833 | break; |
jah128 | 0:d6269d17c8cf | 834 | case 3: |
jah128 | 0:d6269d17c8cf | 835 | sprintf(bottomline,"STRESS TEST"); |
jah128 | 0:d6269d17c8cf | 836 | break; |
jah128 | 0:d6269d17c8cf | 837 | case 4: |
jah128 | 16:50686c07ad07 | 838 | sprintf(bottomline,"COLOUR WALK"); |
jah128 | 18:9204f74069b4 | 839 | break; |
jah128 | 16:50686c07ad07 | 840 | case 5: |
jah128 | 0:d6269d17c8cf | 841 | sprintf(bottomline,"EXIT"); |
jah128 | 0:d6269d17c8cf | 842 | break; |
jah128 | 0:d6269d17c8cf | 843 | } |
jah128 | 0:d6269d17c8cf | 844 | break; |
jah128 | 15:66be5ec52c3b | 845 | case 7: |
jah128 | 17:bf614e28668f | 846 | strcpy(topline,"---CALIB. MENU--"); |
jah128 | 4:1c621cb8cf0d | 847 | switch(sub_menu) { |
jah128 | 4:1c621cb8cf0d | 848 | case 0: |
jah128 | 17:bf614e28668f | 849 | sprintf(bottomline,"BASE SENSOR"); |
jah128 | 4:1c621cb8cf0d | 850 | break; |
jah128 | 4:1c621cb8cf0d | 851 | case 1: |
jah128 | 17:bf614e28668f | 852 | sprintf(bottomline,"MOTOR"); |
jah128 | 15:66be5ec52c3b | 853 | break; |
jah128 | 4:1c621cb8cf0d | 854 | case 2: |
jah128 | 4:1c621cb8cf0d | 855 | sprintf(bottomline,"EXIT"); |
jah128 | 4:1c621cb8cf0d | 856 | break; |
jah128 | 4:1c621cb8cf0d | 857 | } |
jah128 | 0:d6269d17c8cf | 858 | break; |
jah128 | 0:d6269d17c8cf | 859 | } |
jah128 | 0:d6269d17c8cf | 860 | break; |
jah128 | 0:d6269d17c8cf | 861 | } |
jah128 | 0:d6269d17c8cf | 862 | display.write_string(topline); |
jah128 | 0:d6269d17c8cf | 863 | display.set_position(1,0); |
jah128 | 0:d6269d17c8cf | 864 | display.write_string(bottomline); |
jah128 | 16:50686c07ad07 | 865 | // Periodically update when on sensors menu |
jah128 | 16:50686c07ad07 | 866 | if(top_menu == 2 && level == 1) { |
jah128 | 11:312663037b8c | 867 | demo_event.attach(this,&Demo::demo_event_thread, 0.25); |
jah128 | 0:d6269d17c8cf | 868 | } |
jah128 | 0:d6269d17c8cf | 869 | } |
jah128 | 0:d6269d17c8cf | 870 | |
jah128 | 15:66be5ec52c3b | 871 | char test_step = 0; |
jah128 | 15:66be5ec52c3b | 872 | char test_substep = 0; |
jah128 | 15:66be5ec52c3b | 873 | char test_warnings = 0; |
jah128 | 15:66be5ec52c3b | 874 | |
jah128 | 15:66be5ec52c3b | 875 | |
jah128 | 15:66be5ec52c3b | 876 | void Demo::quick_test_cycle() |
jah128 | 15:66be5ec52c3b | 877 | { |
jah128 | 15:66be5ec52c3b | 878 | char next_step [] = {4,5,8,3}; |
jah128 | 15:66be5ec52c3b | 879 | char test_message [17]; |
jah128 | 15:66be5ec52c3b | 880 | int wait_period = SELF_TEST_PERIOD * 10; |
jah128 | 18:9204f74069b4 | 881 | |
jah128 | 15:66be5ec52c3b | 882 | if(test_substep == 0) { |
jah128 | 15:66be5ec52c3b | 883 | display.clear_display(); |
jah128 | 15:66be5ec52c3b | 884 | switch(test_step) { |
jah128 | 15:66be5ec52c3b | 885 | case 0: |
jah128 | 15:66be5ec52c3b | 886 | display.write_string("01 - Power "); |
jah128 | 15:66be5ec52c3b | 887 | pc.printf("\nTest 01: Power quick tests [%f]\n",psi.get_uptime()); |
jah128 | 15:66be5ec52c3b | 888 | break; |
jah128 | 15:66be5ec52c3b | 889 | case 1: |
jah128 | 15:66be5ec52c3b | 890 | display.write_string("02 - Base IR "); |
jah128 | 15:66be5ec52c3b | 891 | pc.printf("\nTest 02: Base infrared tests [%f]\n",psi.get_uptime()); |
jah128 | 15:66be5ec52c3b | 892 | break; |
jah128 | 15:66be5ec52c3b | 893 | case 2: |
jah128 | 15:66be5ec52c3b | 894 | display.write_string("03 - Side IR "); |
jah128 | 15:66be5ec52c3b | 895 | pc.printf("\nTest 03: Side infrared tests [%f]\n",psi.get_uptime()); |
jah128 | 15:66be5ec52c3b | 896 | break; |
jah128 | 15:66be5ec52c3b | 897 | case 3: |
jah128 | 15:66be5ec52c3b | 898 | display.write_string("04 - LEDs "); |
jah128 | 15:66be5ec52c3b | 899 | pc.printf("\nTest 04: LED quick tests [%f]\n",psi.get_uptime()); |
jah128 | 15:66be5ec52c3b | 900 | break; |
jah128 | 15:66be5ec52c3b | 901 | } |
jah128 | 15:66be5ec52c3b | 902 | } |
jah128 | 18:9204f74069b4 | 903 | if(test_step == 1) { |
jah128 | 18:9204f74069b4 | 904 | //Base IR tests |
jah128 | 18:9204f74069b4 | 905 | sensors.store_background_base_ir_values(); |
jah128 | 18:9204f74069b4 | 906 | wait(0.05); |
jah128 | 18:9204f74069b4 | 907 | sensors.store_illuminated_base_ir_values(); |
jah128 | 18:9204f74069b4 | 908 | pc.printf("Sample %d 1: %04d-%04d-%1.2f 2: %04d-%04d-%1.2f 3: %04d-%04d-%1.2f 4: %04d-%04d-%1.2f 5: %04d-%04d-%1.2f\n", (test_substep+1), |
jah128 | 18:9204f74069b4 | 909 | sensors.get_background_base_ir_value(0), sensors.get_illuminated_base_ir_value(0), sensors.get_calibrated_base_ir_value (0), |
jah128 | 18:9204f74069b4 | 910 | sensors.get_background_base_ir_value(1), sensors.get_illuminated_base_ir_value(1),sensors.get_calibrated_base_ir_value (1), |
jah128 | 18:9204f74069b4 | 911 | sensors.get_background_base_ir_value(2), sensors.get_illuminated_base_ir_value(2),sensors.get_calibrated_base_ir_value (2), |
jah128 | 18:9204f74069b4 | 912 | sensors.get_background_base_ir_value(3), sensors.get_illuminated_base_ir_value(3),sensors.get_calibrated_base_ir_value (3), |
jah128 | 18:9204f74069b4 | 913 | sensors.get_background_base_ir_value(4), sensors.get_illuminated_base_ir_value(4),sensors.get_calibrated_base_ir_value (4)); |
jah128 | 18:9204f74069b4 | 914 | sprintf(test_message,"%d:%4d-%4d-%1.2f",test_substep+1,sensors.get_background_base_ir_value(test_substep),sensors.get_illuminated_base_ir_value(test_substep),sensors.get_calibrated_base_ir_value(test_substep)); |
jah128 | 18:9204f74069b4 | 915 | wait_us(SELF_TEST_PERIOD); |
jah128 | 18:9204f74069b4 | 916 | } |
jah128 | 18:9204f74069b4 | 917 | if(test_step == 2) { |
jah128 | 18:9204f74069b4 | 918 | //Side IR tests |
jah128 | 18:9204f74069b4 | 919 | sensors.store_background_raw_ir_values(); |
jah128 | 18:9204f74069b4 | 920 | wait(0.05); |
jah128 | 18:9204f74069b4 | 921 | sensors.store_illuminated_raw_ir_values(); |
jah128 | 18:9204f74069b4 | 922 | pc.printf("Sample %d 1: %04d-%04d 2: %04d-%04d 3: %04d-%04d 4: %04d-%04d 5: %04d-%04d 6: %04d-%04d 7: %04d-%04d 8: %04d-%04d\n", (test_substep+1), |
jah128 | 18:9204f74069b4 | 923 | sensors.get_background_raw_ir_value(0), sensors.get_illuminated_raw_ir_value(0), |
jah128 | 18:9204f74069b4 | 924 | sensors.get_background_raw_ir_value(1), sensors.get_illuminated_raw_ir_value(1), |
jah128 | 18:9204f74069b4 | 925 | sensors.get_background_raw_ir_value(2), sensors.get_illuminated_raw_ir_value(2), |
jah128 | 18:9204f74069b4 | 926 | sensors.get_background_raw_ir_value(3), sensors.get_illuminated_raw_ir_value(3), |
jah128 | 18:9204f74069b4 | 927 | sensors.get_background_raw_ir_value(4), sensors.get_illuminated_raw_ir_value(4), |
jah128 | 18:9204f74069b4 | 928 | sensors.get_background_raw_ir_value(5), sensors.get_illuminated_raw_ir_value(5), |
jah128 | 18:9204f74069b4 | 929 | sensors.get_background_raw_ir_value(6), sensors.get_illuminated_raw_ir_value(6), |
jah128 | 18:9204f74069b4 | 930 | sensors.get_background_raw_ir_value(7), sensors.get_illuminated_raw_ir_value(7)); |
jah128 | 18:9204f74069b4 | 931 | sprintf(test_message,"%d:%4d-%4d",test_substep+1,sensors.get_background_raw_ir_value(test_substep),sensors.get_illuminated_raw_ir_value(test_substep)); |
jah128 | 18:9204f74069b4 | 932 | wait_us(SELF_TEST_PERIOD); |
jah128 | 18:9204f74069b4 | 933 | } |
jah128 | 15:66be5ec52c3b | 934 | if(test_step == 0) { |
jah128 | 15:66be5ec52c3b | 935 | // Power self-test |
jah128 | 15:66be5ec52c3b | 936 | switch(test_substep) { |
jah128 | 15:66be5ec52c3b | 937 | case 0: { // Battery Voltage |
jah128 | 15:66be5ec52c3b | 938 | float battery_voltages [SAMPLE_SIZE]; |
jah128 | 15:66be5ec52c3b | 939 | float mean_battery_voltage = 0; |
jah128 | 15:66be5ec52c3b | 940 | float sd_battery_voltage = 0; |
jah128 | 15:66be5ec52c3b | 941 | for(int i=0; i<SAMPLE_SIZE; i++) { |
jah128 | 15:66be5ec52c3b | 942 | battery_voltages[i]=sensors.get_battery_voltage (); |
jah128 | 15:66be5ec52c3b | 943 | mean_battery_voltage += battery_voltages[i]; |
jah128 | 15:66be5ec52c3b | 944 | wait_us(SELF_TEST_PERIOD); |
jah128 | 15:66be5ec52c3b | 945 | } |
jah128 | 15:66be5ec52c3b | 946 | mean_battery_voltage /= SAMPLE_SIZE; |
jah128 | 15:66be5ec52c3b | 947 | for(int i=0; i<SAMPLE_SIZE; ++i) sd_battery_voltage += pow(battery_voltages[i] - mean_battery_voltage, 2); |
jah128 | 15:66be5ec52c3b | 948 | sd_battery_voltage = sqrt(sd_battery_voltage/SAMPLE_SIZE); |
jah128 | 15:66be5ec52c3b | 949 | |
jah128 | 15:66be5ec52c3b | 950 | sprintf(test_message,"BATTERY: %1.3fV",mean_battery_voltage); |
jah128 | 15:66be5ec52c3b | 951 | pc.printf(" - Battery Voltage : %1.4fV [SD = % 1.4f]\n",mean_battery_voltage,sd_battery_voltage); |
jah128 | 15:66be5ec52c3b | 952 | if(mean_battery_voltage < 3.6) { |
jah128 | 15:66be5ec52c3b | 953 | pc.printf(" - WARNING : Battery voltage low\n"); |
jah128 | 15:66be5ec52c3b | 954 | test_warnings++; |
jah128 | 15:66be5ec52c3b | 955 | } |
jah128 | 15:66be5ec52c3b | 956 | break; |
jah128 | 15:66be5ec52c3b | 957 | } |
jah128 | 15:66be5ec52c3b | 958 | case 1: {// DC Voltage |
jah128 | 15:66be5ec52c3b | 959 | float dc_voltages [SAMPLE_SIZE]; |
jah128 | 15:66be5ec52c3b | 960 | float mean_dc_voltage = 0; |
jah128 | 15:66be5ec52c3b | 961 | float sd_dc_voltage = 0; |
jah128 | 15:66be5ec52c3b | 962 | for(int i=0; i<SAMPLE_SIZE; i++) { |
jah128 | 15:66be5ec52c3b | 963 | dc_voltages[i]=sensors.get_dc_voltage (); |
jah128 | 15:66be5ec52c3b | 964 | mean_dc_voltage += dc_voltages[i]; |
jah128 | 15:66be5ec52c3b | 965 | wait_us(SELF_TEST_PERIOD); |
jah128 | 15:66be5ec52c3b | 966 | } |
jah128 | 15:66be5ec52c3b | 967 | mean_dc_voltage /= SAMPLE_SIZE; |
jah128 | 15:66be5ec52c3b | 968 | for(int i=0; i<SAMPLE_SIZE; ++i) sd_dc_voltage += pow(dc_voltages[i] - mean_dc_voltage, 2); |
jah128 | 15:66be5ec52c3b | 969 | sd_dc_voltage = sqrt(sd_dc_voltage/SAMPLE_SIZE); |
jah128 | 15:66be5ec52c3b | 970 | |
jah128 | 15:66be5ec52c3b | 971 | sprintf(test_message,"DC : %1.3fV",mean_dc_voltage); |
jah128 | 15:66be5ec52c3b | 972 | pc.printf(" - DC Input Voltage : %1.4fV [SD = % 1.4f]\n",mean_dc_voltage,sd_dc_voltage); |
jah128 | 15:66be5ec52c3b | 973 | if(mean_dc_voltage < 0.5) { |
jah128 | 15:66be5ec52c3b | 974 | pc.printf(" - WARNING : DC voltage low - check charging resistor\n"); |
jah128 | 15:66be5ec52c3b | 975 | test_warnings++; |
jah128 | 15:66be5ec52c3b | 976 | } |
jah128 | 15:66be5ec52c3b | 977 | break; |
jah128 | 15:66be5ec52c3b | 978 | } |
jah128 | 15:66be5ec52c3b | 979 | |
jah128 | 15:66be5ec52c3b | 980 | |
jah128 | 15:66be5ec52c3b | 981 | case 2: { // Current |
jah128 | 15:66be5ec52c3b | 982 | float currents [SAMPLE_SIZE]; |
jah128 | 15:66be5ec52c3b | 983 | float mean_current = 0; |
jah128 | 15:66be5ec52c3b | 984 | float sd_current = 0; |
jah128 | 15:66be5ec52c3b | 985 | for(int i=0; i<SAMPLE_SIZE; i++) { |
jah128 | 15:66be5ec52c3b | 986 | currents[i]=sensors.get_current (); |
jah128 | 15:66be5ec52c3b | 987 | mean_current += currents[i]; |
jah128 | 15:66be5ec52c3b | 988 | wait_us(SELF_TEST_PERIOD); |
jah128 | 15:66be5ec52c3b | 989 | } |
jah128 | 15:66be5ec52c3b | 990 | mean_current /= SAMPLE_SIZE; |
jah128 | 15:66be5ec52c3b | 991 | for(int i=0; i<SAMPLE_SIZE; ++i) sd_current += pow(currents[i] - mean_current, 2); |
jah128 | 15:66be5ec52c3b | 992 | sd_current = sqrt(sd_current/SAMPLE_SIZE); |
jah128 | 15:66be5ec52c3b | 993 | |
jah128 | 15:66be5ec52c3b | 994 | sprintf(test_message,"CURRENT: %1.3fV",mean_current); |
jah128 | 18:9204f74069b4 | 995 | pc.printf(" - Load Current : %1.4fA [SD = % 1.4f]\n",mean_current,sd_current); |
jah128 | 15:66be5ec52c3b | 996 | if(mean_current > 0.2) { |
jah128 | 15:66be5ec52c3b | 997 | pc.printf(" - WARNING : Higher than expected load current\n"); |
jah128 | 15:66be5ec52c3b | 998 | test_warnings++; |
jah128 | 15:66be5ec52c3b | 999 | } |
jah128 | 15:66be5ec52c3b | 1000 | break; |
jah128 | 15:66be5ec52c3b | 1001 | } |
jah128 | 18:9204f74069b4 | 1002 | |
jah128 | 15:66be5ec52c3b | 1003 | case 3: {// System temperature |
jah128 | 15:66be5ec52c3b | 1004 | float temps[SAMPLE_SIZE]; |
jah128 | 15:66be5ec52c3b | 1005 | float mean_temp = 0; |
jah128 | 15:66be5ec52c3b | 1006 | float sd_temp = 0; |
jah128 | 15:66be5ec52c3b | 1007 | for(int i=0; i<SAMPLE_SIZE; i++) { |
jah128 | 15:66be5ec52c3b | 1008 | temps[i]=sensors.get_temperature(); |
jah128 | 15:66be5ec52c3b | 1009 | mean_temp += temps[i]; |
jah128 | 15:66be5ec52c3b | 1010 | wait_us(SELF_TEST_PERIOD); |
jah128 | 15:66be5ec52c3b | 1011 | } |
jah128 | 15:66be5ec52c3b | 1012 | mean_temp /= SAMPLE_SIZE; |
jah128 | 15:66be5ec52c3b | 1013 | for(int i=0; i<SAMPLE_SIZE; ++i) sd_temp += pow(temps[i] - mean_temp, 2); |
jah128 | 15:66be5ec52c3b | 1014 | sd_temp = sqrt(sd_temp/SAMPLE_SIZE); |
jah128 | 15:66be5ec52c3b | 1015 | |
jah128 | 15:66be5ec52c3b | 1016 | sprintf(test_message,"TEMP : %3.2fC",mean_temp); |
jah128 | 18:9204f74069b4 | 1017 | pc.printf(" - System Temperature : %3.2fC [SD = % 1.4f]\n",mean_temp,sd_temp); |
jah128 | 15:66be5ec52c3b | 1018 | if(mean_temp > 32) { |
jah128 | 15:66be5ec52c3b | 1019 | pc.printf(" - WARNING : High system temperature detected\n"); |
jah128 | 15:66be5ec52c3b | 1020 | test_warnings++; |
jah128 | 15:66be5ec52c3b | 1021 | } |
jah128 | 15:66be5ec52c3b | 1022 | if(mean_temp < 10) { |
jah128 | 15:66be5ec52c3b | 1023 | pc.printf(" - WARNING : Low system temperature detected\n"); |
jah128 | 15:66be5ec52c3b | 1024 | test_warnings++; |
jah128 | 15:66be5ec52c3b | 1025 | } |
jah128 | 15:66be5ec52c3b | 1026 | break; |
jah128 | 15:66be5ec52c3b | 1027 | } |
jah128 | 15:66be5ec52c3b | 1028 | } |
jah128 | 15:66be5ec52c3b | 1029 | } |
jah128 | 15:66be5ec52c3b | 1030 | |
jah128 | 15:66be5ec52c3b | 1031 | display.set_position(1,0); |
jah128 | 15:66be5ec52c3b | 1032 | display.write_string(" "); |
jah128 | 15:66be5ec52c3b | 1033 | display.set_position(1,0); |
jah128 | 15:66be5ec52c3b | 1034 | display.write_string(test_message); |
jah128 | 15:66be5ec52c3b | 1035 | test_substep++; |
jah128 | 15:66be5ec52c3b | 1036 | if(test_substep >= next_step[test_step]) { |
jah128 | 15:66be5ec52c3b | 1037 | test_substep = 0; |
jah128 | 15:66be5ec52c3b | 1038 | test_step ++; |
jah128 | 15:66be5ec52c3b | 1039 | if(test_step == 4) test_step = 0; |
jah128 | 15:66be5ec52c3b | 1040 | } |
jah128 | 15:66be5ec52c3b | 1041 | |
jah128 | 15:66be5ec52c3b | 1042 | demo_timeout.attach_us(this,&Demo::quick_test_cycle, wait_period); |
jah128 | 15:66be5ec52c3b | 1043 | } |
jah128 | 15:66be5ec52c3b | 1044 | |
jah128 | 15:66be5ec52c3b | 1045 | void Demo::toggle_quick_test() |
jah128 | 15:66be5ec52c3b | 1046 | { |
jah128 | 15:66be5ec52c3b | 1047 | quick_test = 1 - quick_test; |
jah128 | 15:66be5ec52c3b | 1048 | if(quick_test == 0) { |
jah128 | 15:66be5ec52c3b | 1049 | pc.printf("________________________________________\n"); |
jah128 | 15:66be5ec52c3b | 1050 | pc.printf("Self test stopped at %f with %d warnings\n\n",psi.get_uptime(),test_warnings); |
jah128 | 15:66be5ec52c3b | 1051 | demo_running = 0; |
jah128 | 15:66be5ec52c3b | 1052 | demo_timeout.detach(); |
jah128 | 15:66be5ec52c3b | 1053 | display.set_backlight_brightness(1); |
jah128 | 15:66be5ec52c3b | 1054 | display.clear_display(); |
jah128 | 15:66be5ec52c3b | 1055 | display.write_string("---QUICK TEST---"); |
jah128 | 15:66be5ec52c3b | 1056 | |
jah128 | 15:66be5ec52c3b | 1057 | |
jah128 | 15:66be5ec52c3b | 1058 | } else { |
jah128 | 15:66be5ec52c3b | 1059 | // Reset all LEDs, motors, display |
jah128 | 15:66be5ec52c3b | 1060 | pc.printf("\n________________________________________\n"); |
jah128 | 15:66be5ec52c3b | 1061 | pc.printf("Self test started at %f\n\n",psi.get_uptime(),test_warnings); |
jah128 | 15:66be5ec52c3b | 1062 | display.clear_display(); |
jah128 | 15:66be5ec52c3b | 1063 | test_step = 0; |
jah128 | 15:66be5ec52c3b | 1064 | test_substep = 0; |
jah128 | 15:66be5ec52c3b | 1065 | demo_running = 1; |
jah128 | 15:66be5ec52c3b | 1066 | demo_timeout.attach_us(this,&Demo::quick_test_cycle,1000); |
jah128 | 15:66be5ec52c3b | 1067 | } |
jah128 | 15:66be5ec52c3b | 1068 | } |
jah128 | 15:66be5ec52c3b | 1069 | |
jah128 | 11:312663037b8c | 1070 | void Demo::start_line_demo() |
jah128 | 0:d6269d17c8cf | 1071 | { |
jah128 | 0:d6269d17c8cf | 1072 | display.set_backlight_brightness(0); |
jah128 | 0:d6269d17c8cf | 1073 | time_out = 0.25f; |
jah128 | 0:d6269d17c8cf | 1074 | demo_timer.start(); |
jah128 | 0:d6269d17c8cf | 1075 | state = 0; |
jah128 | 0:d6269d17c8cf | 1076 | speed = 0; |
jah128 | 0:d6269d17c8cf | 1077 | led_step = 0; |
jah128 | 0:d6269d17c8cf | 1078 | demo_running = 1; |
jah128 | 11:312663037b8c | 1079 | demo_timeout.attach_us(this,&Demo::line_demo_cycle,1000); |
jah128 | 0:d6269d17c8cf | 1080 | } |
jah128 | 0:d6269d17c8cf | 1081 | |
jah128 | 11:312663037b8c | 1082 | void Demo::start_obstacle_demo() |
jah128 | 0:d6269d17c8cf | 1083 | { |
jah128 | 0:d6269d17c8cf | 1084 | display.set_backlight_brightness(0); |
jah128 | 0:d6269d17c8cf | 1085 | time_out = 0.25f; |
jah128 | 0:d6269d17c8cf | 1086 | demo_timer.start(); |
jah128 | 0:d6269d17c8cf | 1087 | state = 0; |
jah128 | 0:d6269d17c8cf | 1088 | speed = 0; |
jah128 | 0:d6269d17c8cf | 1089 | led_step = 0; |
jah128 | 0:d6269d17c8cf | 1090 | demo_running = 1; |
jah128 | 11:312663037b8c | 1091 | demo_timeout.attach_us(this,&Demo::obstacle_demo_cycle,1000); |
jah128 | 0:d6269d17c8cf | 1092 | } |
jah128 | 0:d6269d17c8cf | 1093 | |
jah128 | 16:50686c07ad07 | 1094 | void Demo::start_colour_demo() |
jah128 | 16:50686c07ad07 | 1095 | { |
jah128 | 16:50686c07ad07 | 1096 | display.set_backlight_brightness(0); |
jah128 | 16:50686c07ad07 | 1097 | time_out = 0.25f; |
jah128 | 16:50686c07ad07 | 1098 | demo_timer.start(); |
jah128 | 16:50686c07ad07 | 1099 | state = 0; |
jah128 | 16:50686c07ad07 | 1100 | speed = 0; |
jah128 | 16:50686c07ad07 | 1101 | led_step = 0; |
jah128 | 16:50686c07ad07 | 1102 | demo_running = 1; |
jah128 | 16:50686c07ad07 | 1103 | colour.start_colour_ticker(100); |
jah128 | 16:50686c07ad07 | 1104 | demo_timeout.attach_us(this,&Demo::colour_demo_cycle,1000); |
jah128 | 16:50686c07ad07 | 1105 | } |
jah128 | 16:50686c07ad07 | 1106 | |
jah128 | 11:312663037b8c | 1107 | void Demo::start_stress_demo() |
jah128 | 0:d6269d17c8cf | 1108 | { |
jah128 | 0:d6269d17c8cf | 1109 | display.set_backlight_brightness(0.25); |
jah128 | 0:d6269d17c8cf | 1110 | display.write_string("STRESS TEST"); |
jah128 | 0:d6269d17c8cf | 1111 | display.set_position(1,0); |
jah128 | 0:d6269d17c8cf | 1112 | display.write_string("----25%----"); |
jah128 | 0:d6269d17c8cf | 1113 | time_out = 0.04f; |
jah128 | 0:d6269d17c8cf | 1114 | demo_timer.start(); |
jah128 | 0:d6269d17c8cf | 1115 | state = 0; |
jah128 | 0:d6269d17c8cf | 1116 | speed = 0; |
jah128 | 0:d6269d17c8cf | 1117 | stress_step = 0; |
jah128 | 0:d6269d17c8cf | 1118 | spin_step = 0; |
jah128 | 0:d6269d17c8cf | 1119 | demo_running = 1; |
jah128 | 11:312663037b8c | 1120 | demo_timeout.attach_us(this,&Demo::stress_demo_cycle,1000); |
jah128 | 0:d6269d17c8cf | 1121 | } |
jah128 | 0:d6269d17c8cf | 1122 | |
jah128 | 11:312663037b8c | 1123 | void Demo::start_spinning_demo() |
jah128 | 0:d6269d17c8cf | 1124 | { |
jah128 | 0:d6269d17c8cf | 1125 | display.set_backlight_brightness(0); |
jah128 | 0:d6269d17c8cf | 1126 | time_out = 0.0f; |
jah128 | 0:d6269d17c8cf | 1127 | demo_timer.start(); |
jah128 | 0:d6269d17c8cf | 1128 | state = 0; |
jah128 | 0:d6269d17c8cf | 1129 | speed = 0; |
jah128 | 0:d6269d17c8cf | 1130 | led_step = 0; |
jah128 | 0:d6269d17c8cf | 1131 | spin_step = 0; |
jah128 | 0:d6269d17c8cf | 1132 | demo_running = 1; |
jah128 | 11:312663037b8c | 1133 | demo_timeout.attach_us(this,&Demo::spinning_demo_cycle,1000); |
jah128 | 0:d6269d17c8cf | 1134 | } |
jah128 | 0:d6269d17c8cf | 1135 | |
jah128 | 11:312663037b8c | 1136 | void Demo::line_demo_cycle() |
jah128 | 0:d6269d17c8cf | 1137 | { |
jah128 | 0:d6269d17c8cf | 1138 | if(demo_timer.read() > time_out) { |
jah128 | 10:e58323951c08 | 1139 | sensors.store_line_position(); |
jah128 | 0:d6269d17c8cf | 1140 | if(line_found) { |
jah128 | 0:d6269d17c8cf | 1141 | time_out = 0.01f; |
jah128 | 0:d6269d17c8cf | 1142 | state = 0; |
jah128 | 0:d6269d17c8cf | 1143 | // Get the position of the line. |
jah128 | 0:d6269d17c8cf | 1144 | lf_current_pos_of_line = line_position; |
jah128 | 0:d6269d17c8cf | 1145 | lf_proportional = lf_current_pos_of_line; |
jah128 | 0:d6269d17c8cf | 1146 | |
jah128 | 0:d6269d17c8cf | 1147 | // Compute the derivative |
jah128 | 0:d6269d17c8cf | 1148 | lf_derivative = lf_current_pos_of_line - lf_previous_pos_of_line; |
jah128 | 0:d6269d17c8cf | 1149 | |
jah128 | 0:d6269d17c8cf | 1150 | // Compute the integral |
jah128 | 0:d6269d17c8cf | 1151 | lf_integral += lf_proportional; |
jah128 | 0:d6269d17c8cf | 1152 | |
jah128 | 0:d6269d17c8cf | 1153 | // Remember the last position. |
jah128 | 0:d6269d17c8cf | 1154 | lf_previous_pos_of_line = lf_current_pos_of_line; |
jah128 | 0:d6269d17c8cf | 1155 | |
jah128 | 0:d6269d17c8cf | 1156 | // Compute the power |
jah128 | 0:d6269d17c8cf | 1157 | lf_power = (lf_proportional * (LF_P_TERM) ) + (lf_integral*(LF_I_TERM)) + (lf_derivative*(LF_D_TERM)) ; |
jah128 | 0:d6269d17c8cf | 1158 | |
jah128 | 0:d6269d17c8cf | 1159 | // Compute new speeds |
jah128 | 0:d6269d17c8cf | 1160 | lf_right = lf_speed-lf_power; |
jah128 | 0:d6269d17c8cf | 1161 | lf_left = lf_speed+lf_power; |
jah128 | 0:d6269d17c8cf | 1162 | |
jah128 | 0:d6269d17c8cf | 1163 | // limit checks |
jah128 | 0:d6269d17c8cf | 1164 | if (lf_right < 0) |
jah128 | 0:d6269d17c8cf | 1165 | lf_right = 0; |
jah128 | 0:d6269d17c8cf | 1166 | else if (lf_right > 1.0f) |
jah128 | 0:d6269d17c8cf | 1167 | lf_right = 1.0f; |
jah128 | 0:d6269d17c8cf | 1168 | |
jah128 | 0:d6269d17c8cf | 1169 | if (lf_left < 0) |
jah128 | 0:d6269d17c8cf | 1170 | lf_left = 0; |
jah128 | 0:d6269d17c8cf | 1171 | else if (lf_left > 1.0f) |
jah128 | 0:d6269d17c8cf | 1172 | lf_left = 1.0f; |
jah128 | 15:66be5ec52c3b | 1173 | } else { |
jah128 | 15:66be5ec52c3b | 1174 | //Cannot see line: hunt for it |
jah128 | 15:66be5ec52c3b | 1175 | if(lf_left > lf_right) { |
jah128 | 15:66be5ec52c3b | 1176 | //Currently turning left, keep turning left |
jah128 | 15:66be5ec52c3b | 1177 | state ++; |
jah128 | 15:66be5ec52c3b | 1178 | float d_step = state * 0.04; |
jah128 | 15:66be5ec52c3b | 1179 | lf_left = 0.2 + d_step; |
jah128 | 15:66be5ec52c3b | 1180 | lf_right = -0.2 - d_step; |
jah128 | 15:66be5ec52c3b | 1181 | if(state > 20) { |
jah128 | 15:66be5ec52c3b | 1182 | state = 0; |
jah128 | 15:66be5ec52c3b | 1183 | lf_right = 0.2; |
jah128 | 15:66be5ec52c3b | 1184 | lf_left = -0.2; |
jah128 | 15:66be5ec52c3b | 1185 | time_out += 0.01f; |
jah128 | 15:66be5ec52c3b | 1186 | if(time_out > 0.1f) demo_running = 0; |
jah128 | 15:66be5ec52c3b | 1187 | } |
jah128 | 15:66be5ec52c3b | 1188 | } else { |
jah128 | 15:66be5ec52c3b | 1189 | //Currently turning right, keep turning right |
jah128 | 15:66be5ec52c3b | 1190 | state ++; |
jah128 | 15:66be5ec52c3b | 1191 | float d_step = state * 0.04; |
jah128 | 15:66be5ec52c3b | 1192 | lf_left = -0.2 - d_step; |
jah128 | 15:66be5ec52c3b | 1193 | lf_right = 0.2 + d_step; |
jah128 | 15:66be5ec52c3b | 1194 | if(state > 20) { |
jah128 | 15:66be5ec52c3b | 1195 | state = 0; |
jah128 | 15:66be5ec52c3b | 1196 | lf_right = -0.2; |
jah128 | 15:66be5ec52c3b | 1197 | lf_left = 0.2; |
jah128 | 15:66be5ec52c3b | 1198 | time_out += 0.01f; |
jah128 | 15:66be5ec52c3b | 1199 | if(time_out > 0.1f) demo_running = 0; |
jah128 | 15:66be5ec52c3b | 1200 | } |
jah128 | 0:d6269d17c8cf | 1201 | } |
jah128 | 0:d6269d17c8cf | 1202 | } |
jah128 | 0:d6269d17c8cf | 1203 | // set speed |
jah128 | 8:6c92789d5f87 | 1204 | motors.set_left_motor_speed(lf_left); |
jah128 | 8:6c92789d5f87 | 1205 | motors.set_right_motor_speed(lf_right); |
jah128 | 0:d6269d17c8cf | 1206 | |
jah128 | 0:d6269d17c8cf | 1207 | |
jah128 | 0:d6269d17c8cf | 1208 | demo_timer.reset(); |
jah128 | 0:d6269d17c8cf | 1209 | } |
jah128 | 11:312663037b8c | 1210 | if(demo_running == 1)demo_timeout.attach_us(this,&Demo::line_demo_cycle,500); |
jah128 | 0:d6269d17c8cf | 1211 | else { |
jah128 | 8:6c92789d5f87 | 1212 | motors.stop(); |
jah128 | 0:d6269d17c8cf | 1213 | display.set_backlight_brightness(bl_brightness * 0.01f); |
jah128 | 0:d6269d17c8cf | 1214 | } |
jah128 | 0:d6269d17c8cf | 1215 | } |
jah128 | 0:d6269d17c8cf | 1216 | |
jah128 | 11:312663037b8c | 1217 | void Demo::stress_demo_cycle() |
jah128 | 0:d6269d17c8cf | 1218 | { |
jah128 | 0:d6269d17c8cf | 1219 | if(demo_timer.read() > time_out) { |
jah128 | 0:d6269d17c8cf | 1220 | float pct = 0.25 + (0.25 * stress_step); |
jah128 | 0:d6269d17c8cf | 1221 | switch(state) { |
jah128 | 0:d6269d17c8cf | 1222 | case 0: |
jah128 | 0:d6269d17c8cf | 1223 | if(spin_step % 2 == 0) { |
jah128 | 8:6c92789d5f87 | 1224 | motors.forward(pct); |
jah128 | 9:dde9e21030eb | 1225 | led.set_leds(0xFF,0xFF); |
jah128 | 0:d6269d17c8cf | 1226 | } else { |
jah128 | 8:6c92789d5f87 | 1227 | motors.backward(pct); |
jah128 | 9:dde9e21030eb | 1228 | led.set_leds(0,0xFF); |
jah128 | 0:d6269d17c8cf | 1229 | } |
jah128 | 0:d6269d17c8cf | 1230 | spin_step ++; |
jah128 | 0:d6269d17c8cf | 1231 | if(spin_step > 199) { |
jah128 | 0:d6269d17c8cf | 1232 | state ++; |
jah128 | 0:d6269d17c8cf | 1233 | spin_step = 0; |
jah128 | 0:d6269d17c8cf | 1234 | } |
jah128 | 0:d6269d17c8cf | 1235 | break; |
jah128 | 0:d6269d17c8cf | 1236 | case 1: |
jah128 | 0:d6269d17c8cf | 1237 | if(stress_step < 3) stress_step ++; |
jah128 | 0:d6269d17c8cf | 1238 | float pct = 0.25 + (0.25 * stress_step); |
jah128 | 0:d6269d17c8cf | 1239 | display.set_backlight_brightness(pct); |
jah128 | 0:d6269d17c8cf | 1240 | display.set_position(1,0); |
jah128 | 0:d6269d17c8cf | 1241 | switch(stress_step) { |
jah128 | 0:d6269d17c8cf | 1242 | case 1: |
jah128 | 0:d6269d17c8cf | 1243 | display.write_string("----50%----"); |
jah128 | 0:d6269d17c8cf | 1244 | break; |
jah128 | 0:d6269d17c8cf | 1245 | case 2: |
jah128 | 0:d6269d17c8cf | 1246 | display.write_string("----75%----"); |
jah128 | 0:d6269d17c8cf | 1247 | break; |
jah128 | 0:d6269d17c8cf | 1248 | case 3: |
jah128 | 0:d6269d17c8cf | 1249 | display.write_string("---100%----"); |
jah128 | 0:d6269d17c8cf | 1250 | break; |
jah128 | 0:d6269d17c8cf | 1251 | } |
jah128 | 0:d6269d17c8cf | 1252 | state = 0; |
jah128 | 0:d6269d17c8cf | 1253 | break; |
jah128 | 0:d6269d17c8cf | 1254 | } |
jah128 | 0:d6269d17c8cf | 1255 | demo_timer.reset(); |
jah128 | 0:d6269d17c8cf | 1256 | } |
jah128 | 11:312663037b8c | 1257 | if(demo_running == 1)demo_timeout.attach_us(this,&Demo::stress_demo_cycle,500); |
jah128 | 0:d6269d17c8cf | 1258 | else { |
jah128 | 8:6c92789d5f87 | 1259 | motors.stop(); |
jah128 | 0:d6269d17c8cf | 1260 | display.set_backlight_brightness(bl_brightness * 0.01f); |
jah128 | 0:d6269d17c8cf | 1261 | } |
jah128 | 0:d6269d17c8cf | 1262 | } |
jah128 | 0:d6269d17c8cf | 1263 | |
jah128 | 11:312663037b8c | 1264 | void Demo::spinning_demo_cycle() |
jah128 | 0:d6269d17c8cf | 1265 | { |
jah128 | 0:d6269d17c8cf | 1266 | if(demo_timer.read() > time_out) { |
jah128 | 0:d6269d17c8cf | 1267 | switch(state) { |
jah128 | 0:d6269d17c8cf | 1268 | case 0: //Robot is stopped |
jah128 | 9:dde9e21030eb | 1269 | led.set_leds(0,0xFF); |
jah128 | 9:dde9e21030eb | 1270 | led.set_center_led(1,1); |
jah128 | 0:d6269d17c8cf | 1271 | speed = 0.1f; |
jah128 | 8:6c92789d5f87 | 1272 | motors.brake(); |
jah128 | 0:d6269d17c8cf | 1273 | time_out = 0.5; |
jah128 | 0:d6269d17c8cf | 1274 | state = 1; |
jah128 | 0:d6269d17c8cf | 1275 | led_step = 0; |
jah128 | 0:d6269d17c8cf | 1276 | break; |
jah128 | 0:d6269d17c8cf | 1277 | case 1: //Motor is turning right, accelerating |
jah128 | 0:d6269d17c8cf | 1278 | time_out = 0.1; |
jah128 | 9:dde9e21030eb | 1279 | led.set_center_led(2,1); |
jah128 | 0:d6269d17c8cf | 1280 | switch(led_step) { |
jah128 | 0:d6269d17c8cf | 1281 | case 0: |
jah128 | 9:dde9e21030eb | 1282 | led.set_leds(0x01,0); |
jah128 | 0:d6269d17c8cf | 1283 | break; |
jah128 | 0:d6269d17c8cf | 1284 | case 1: |
jah128 | 9:dde9e21030eb | 1285 | led.set_leds(0x02,0); |
jah128 | 0:d6269d17c8cf | 1286 | break; |
jah128 | 0:d6269d17c8cf | 1287 | case 2: |
jah128 | 9:dde9e21030eb | 1288 | led.set_leds(0x04,0); |
jah128 | 0:d6269d17c8cf | 1289 | break; |
jah128 | 0:d6269d17c8cf | 1290 | case 3: |
jah128 | 9:dde9e21030eb | 1291 | led.set_leds(0x08,0); |
jah128 | 0:d6269d17c8cf | 1292 | break; |
jah128 | 0:d6269d17c8cf | 1293 | case 4: |
jah128 | 9:dde9e21030eb | 1294 | led.set_leds(0x10,0); |
jah128 | 0:d6269d17c8cf | 1295 | break; |
jah128 | 0:d6269d17c8cf | 1296 | case 5: |
jah128 | 9:dde9e21030eb | 1297 | led.set_leds(0x20,0); |
jah128 | 0:d6269d17c8cf | 1298 | break; |
jah128 | 0:d6269d17c8cf | 1299 | case 6: |
jah128 | 9:dde9e21030eb | 1300 | led.set_leds(0x40,0); |
jah128 | 0:d6269d17c8cf | 1301 | break; |
jah128 | 0:d6269d17c8cf | 1302 | case 7: |
jah128 | 9:dde9e21030eb | 1303 | led.set_leds(0x80,0); |
jah128 | 0:d6269d17c8cf | 1304 | break; |
jah128 | 0:d6269d17c8cf | 1305 | } |
jah128 | 0:d6269d17c8cf | 1306 | led_step ++; |
jah128 | 0:d6269d17c8cf | 1307 | if(led_step == 8) led_step =0; |
jah128 | 0:d6269d17c8cf | 1308 | if(speed < 1) { |
jah128 | 0:d6269d17c8cf | 1309 | speed += 0.0125; |
jah128 | 8:6c92789d5f87 | 1310 | motors.turn(speed); |
jah128 | 0:d6269d17c8cf | 1311 | } else { |
jah128 | 0:d6269d17c8cf | 1312 | state = 2; |
jah128 | 0:d6269d17c8cf | 1313 | spin_step = 0; |
jah128 | 0:d6269d17c8cf | 1314 | led_step =0; |
jah128 | 0:d6269d17c8cf | 1315 | } |
jah128 | 0:d6269d17c8cf | 1316 | break; |
jah128 | 0:d6269d17c8cf | 1317 | case 2: //Motor is turning right, full speed |
jah128 | 9:dde9e21030eb | 1318 | led.set_center_led(3,1); |
jah128 | 0:d6269d17c8cf | 1319 | switch(led_step) { |
jah128 | 0:d6269d17c8cf | 1320 | case 0: |
jah128 | 9:dde9e21030eb | 1321 | led.set_leds(0x33,0x33); |
jah128 | 0:d6269d17c8cf | 1322 | break; |
jah128 | 0:d6269d17c8cf | 1323 | case 1: |
jah128 | 9:dde9e21030eb | 1324 | led.set_leds(0x66,0x66); |
jah128 | 0:d6269d17c8cf | 1325 | break; |
jah128 | 0:d6269d17c8cf | 1326 | case 2: |
jah128 | 9:dde9e21030eb | 1327 | led.set_leds(0xCC,0xCC); |
jah128 | 0:d6269d17c8cf | 1328 | break; |
jah128 | 0:d6269d17c8cf | 1329 | case 3: |
jah128 | 9:dde9e21030eb | 1330 | led.set_leds(0x99,0x99); |
jah128 | 0:d6269d17c8cf | 1331 | break; |
jah128 | 0:d6269d17c8cf | 1332 | } |
jah128 | 0:d6269d17c8cf | 1333 | led_step ++; |
jah128 | 0:d6269d17c8cf | 1334 | if(led_step == 4) led_step = 0; |
jah128 | 0:d6269d17c8cf | 1335 | spin_step ++; |
jah128 | 0:d6269d17c8cf | 1336 | if(spin_step == 40) { |
jah128 | 0:d6269d17c8cf | 1337 | state = 3; |
jah128 | 0:d6269d17c8cf | 1338 | led_step = 0; |
jah128 | 0:d6269d17c8cf | 1339 | } |
jah128 | 0:d6269d17c8cf | 1340 | break; |
jah128 | 0:d6269d17c8cf | 1341 | case 3: //Motor is turning right, decelerating |
jah128 | 9:dde9e21030eb | 1342 | led.set_center_led(2,1); |
jah128 | 0:d6269d17c8cf | 1343 | switch(led_step) { |
jah128 | 0:d6269d17c8cf | 1344 | case 0: |
jah128 | 9:dde9e21030eb | 1345 | led.set_leds(0x01,0); |
jah128 | 0:d6269d17c8cf | 1346 | break; |
jah128 | 0:d6269d17c8cf | 1347 | case 1: |
jah128 | 9:dde9e21030eb | 1348 | led.set_leds(0x02,0); |
jah128 | 0:d6269d17c8cf | 1349 | break; |
jah128 | 0:d6269d17c8cf | 1350 | case 2: |
jah128 | 9:dde9e21030eb | 1351 | led.set_leds(0x04,0); |
jah128 | 0:d6269d17c8cf | 1352 | break; |
jah128 | 0:d6269d17c8cf | 1353 | case 3: |
jah128 | 9:dde9e21030eb | 1354 | led.set_leds(0x08,0); |
jah128 | 0:d6269d17c8cf | 1355 | break; |
jah128 | 0:d6269d17c8cf | 1356 | case 4: |
jah128 | 9:dde9e21030eb | 1357 | led.set_leds(0x10,0); |
jah128 | 0:d6269d17c8cf | 1358 | break; |
jah128 | 0:d6269d17c8cf | 1359 | case 5: |
jah128 | 9:dde9e21030eb | 1360 | led.set_leds(0x20,0); |
jah128 | 0:d6269d17c8cf | 1361 | break; |
jah128 | 0:d6269d17c8cf | 1362 | case 6: |
jah128 | 9:dde9e21030eb | 1363 | led.set_leds(0x40,0); |
jah128 | 0:d6269d17c8cf | 1364 | break; |
jah128 | 0:d6269d17c8cf | 1365 | case 7: |
jah128 | 9:dde9e21030eb | 1366 | led.set_leds(0x80,0); |
jah128 | 0:d6269d17c8cf | 1367 | break; |
jah128 | 0:d6269d17c8cf | 1368 | } |
jah128 | 0:d6269d17c8cf | 1369 | if(led_step == 0) led_step =8; |
jah128 | 0:d6269d17c8cf | 1370 | led_step --; |
jah128 | 0:d6269d17c8cf | 1371 | if(speed > 0.1) { |
jah128 | 0:d6269d17c8cf | 1372 | speed -= 0.025; |
jah128 | 8:6c92789d5f87 | 1373 | motors.turn(speed); |
jah128 | 0:d6269d17c8cf | 1374 | } else { |
jah128 | 0:d6269d17c8cf | 1375 | state = 4; |
jah128 | 0:d6269d17c8cf | 1376 | spin_step = 0; |
jah128 | 0:d6269d17c8cf | 1377 | led_step =0; |
jah128 | 0:d6269d17c8cf | 1378 | } |
jah128 | 0:d6269d17c8cf | 1379 | break; |
jah128 | 0:d6269d17c8cf | 1380 | case 4: //Robot is stopped |
jah128 | 9:dde9e21030eb | 1381 | led.set_leds(0,0xFF); |
jah128 | 9:dde9e21030eb | 1382 | led.set_center_led(1,1); |
jah128 | 0:d6269d17c8cf | 1383 | speed = 0.1f; |
jah128 | 8:6c92789d5f87 | 1384 | motors.brake(); |
jah128 | 0:d6269d17c8cf | 1385 | time_out = 0.5; |
jah128 | 0:d6269d17c8cf | 1386 | led_step =0; |
jah128 | 0:d6269d17c8cf | 1387 | state = 5; |
jah128 | 0:d6269d17c8cf | 1388 | break; |
jah128 | 0:d6269d17c8cf | 1389 | case 5: //Motor is turning left, accelerating |
jah128 | 0:d6269d17c8cf | 1390 | time_out = 0.1; |
jah128 | 9:dde9e21030eb | 1391 | led.set_center_led(2,1); |
jah128 | 0:d6269d17c8cf | 1392 | switch(led_step) { |
jah128 | 0:d6269d17c8cf | 1393 | case 0: |
jah128 | 9:dde9e21030eb | 1394 | led.set_leds(0x01,0); |
jah128 | 0:d6269d17c8cf | 1395 | break; |
jah128 | 0:d6269d17c8cf | 1396 | case 1: |
jah128 | 9:dde9e21030eb | 1397 | led.set_leds(0x02,0); |
jah128 | 0:d6269d17c8cf | 1398 | break; |
jah128 | 0:d6269d17c8cf | 1399 | case 2: |
jah128 | 9:dde9e21030eb | 1400 | led.set_leds(0x04,0); |
jah128 | 0:d6269d17c8cf | 1401 | break; |
jah128 | 0:d6269d17c8cf | 1402 | case 3: |
jah128 | 9:dde9e21030eb | 1403 | led.set_leds(0x08,0); |
jah128 | 0:d6269d17c8cf | 1404 | break; |
jah128 | 0:d6269d17c8cf | 1405 | case 4: |
jah128 | 9:dde9e21030eb | 1406 | led.set_leds(0x10,0); |
jah128 | 0:d6269d17c8cf | 1407 | break; |
jah128 | 0:d6269d17c8cf | 1408 | case 5: |
jah128 | 9:dde9e21030eb | 1409 | led.set_leds(0x20,0); |
jah128 | 0:d6269d17c8cf | 1410 | break; |
jah128 | 0:d6269d17c8cf | 1411 | case 6: |
jah128 | 9:dde9e21030eb | 1412 | led.set_leds(0x40,0); |
jah128 | 0:d6269d17c8cf | 1413 | break; |
jah128 | 0:d6269d17c8cf | 1414 | case 7: |
jah128 | 9:dde9e21030eb | 1415 | led.set_leds(0x80,0); |
jah128 | 0:d6269d17c8cf | 1416 | break; |
jah128 | 0:d6269d17c8cf | 1417 | } |
jah128 | 0:d6269d17c8cf | 1418 | if(led_step == 0) led_step =8; |
jah128 | 0:d6269d17c8cf | 1419 | led_step --; |
jah128 | 0:d6269d17c8cf | 1420 | if(speed < 1) { |
jah128 | 0:d6269d17c8cf | 1421 | speed += 0.0125; |
jah128 | 8:6c92789d5f87 | 1422 | motors.turn(-speed); |
jah128 | 0:d6269d17c8cf | 1423 | } else { |
jah128 | 0:d6269d17c8cf | 1424 | state = 6; |
jah128 | 0:d6269d17c8cf | 1425 | spin_step = 0; |
jah128 | 0:d6269d17c8cf | 1426 | led_step = 0; |
jah128 | 0:d6269d17c8cf | 1427 | } |
jah128 | 0:d6269d17c8cf | 1428 | break; |
jah128 | 0:d6269d17c8cf | 1429 | case 6: //Motor is turning left, full speed |
jah128 | 9:dde9e21030eb | 1430 | led.set_center_led(3,1); |
jah128 | 0:d6269d17c8cf | 1431 | switch(led_step) { |
jah128 | 0:d6269d17c8cf | 1432 | case 0: |
jah128 | 9:dde9e21030eb | 1433 | led.set_leds(0x33,0x33); |
jah128 | 0:d6269d17c8cf | 1434 | break; |
jah128 | 0:d6269d17c8cf | 1435 | case 1: |
jah128 | 9:dde9e21030eb | 1436 | led.set_leds(0x66,0x66); |
jah128 | 0:d6269d17c8cf | 1437 | break; |
jah128 | 0:d6269d17c8cf | 1438 | case 2: |
jah128 | 9:dde9e21030eb | 1439 | led.set_leds(0xCC,0xCC); |
jah128 | 0:d6269d17c8cf | 1440 | break; |
jah128 | 0:d6269d17c8cf | 1441 | case 3: |
jah128 | 9:dde9e21030eb | 1442 | led.set_leds(0x99,0x99); |
jah128 | 0:d6269d17c8cf | 1443 | break; |
jah128 | 0:d6269d17c8cf | 1444 | } |
jah128 | 0:d6269d17c8cf | 1445 | if(led_step == 0) led_step = 4; |
jah128 | 0:d6269d17c8cf | 1446 | led_step --; |
jah128 | 0:d6269d17c8cf | 1447 | spin_step ++; |
jah128 | 0:d6269d17c8cf | 1448 | if(spin_step == 40) { |
jah128 | 0:d6269d17c8cf | 1449 | state = 7; |
jah128 | 0:d6269d17c8cf | 1450 | led_step = 0; |
jah128 | 0:d6269d17c8cf | 1451 | } |
jah128 | 0:d6269d17c8cf | 1452 | break; |
jah128 | 0:d6269d17c8cf | 1453 | case 7: //Motor is turning left, decelerating |
jah128 | 9:dde9e21030eb | 1454 | led.set_center_led(2,1); |
jah128 | 0:d6269d17c8cf | 1455 | switch(led_step) { |
jah128 | 0:d6269d17c8cf | 1456 | case 0: |
jah128 | 9:dde9e21030eb | 1457 | led.set_leds(0x01,0); |
jah128 | 0:d6269d17c8cf | 1458 | break; |
jah128 | 0:d6269d17c8cf | 1459 | case 1: |
jah128 | 9:dde9e21030eb | 1460 | led.set_leds(0x02,0); |
jah128 | 0:d6269d17c8cf | 1461 | break; |
jah128 | 0:d6269d17c8cf | 1462 | case 2: |
jah128 | 9:dde9e21030eb | 1463 | led.set_leds(0x04,0); |
jah128 | 0:d6269d17c8cf | 1464 | break; |
jah128 | 0:d6269d17c8cf | 1465 | case 3: |
jah128 | 9:dde9e21030eb | 1466 | led.set_leds(0x08,0); |
jah128 | 0:d6269d17c8cf | 1467 | break; |
jah128 | 0:d6269d17c8cf | 1468 | case 4: |
jah128 | 9:dde9e21030eb | 1469 | led.set_leds(0x10,0); |
jah128 | 0:d6269d17c8cf | 1470 | break; |
jah128 | 0:d6269d17c8cf | 1471 | case 5: |
jah128 | 9:dde9e21030eb | 1472 | led.set_leds(0x20,0); |
jah128 | 0:d6269d17c8cf | 1473 | break; |
jah128 | 0:d6269d17c8cf | 1474 | case 6: |
jah128 | 9:dde9e21030eb | 1475 | led.set_leds(0x40,0); |
jah128 | 0:d6269d17c8cf | 1476 | break; |
jah128 | 0:d6269d17c8cf | 1477 | case 7: |
jah128 | 9:dde9e21030eb | 1478 | led.set_leds(0x80,0); |
jah128 | 0:d6269d17c8cf | 1479 | break; |
jah128 | 0:d6269d17c8cf | 1480 | } |
jah128 | 0:d6269d17c8cf | 1481 | led_step ++; |
jah128 | 0:d6269d17c8cf | 1482 | if(led_step == 8) led_step =0; |
jah128 | 0:d6269d17c8cf | 1483 | if(speed > 0.1) { |
jah128 | 0:d6269d17c8cf | 1484 | speed -= 0.025; |
jah128 | 8:6c92789d5f87 | 1485 | motors.turn(-speed); |
jah128 | 0:d6269d17c8cf | 1486 | } else { |
jah128 | 0:d6269d17c8cf | 1487 | state = 0; |
jah128 | 0:d6269d17c8cf | 1488 | spin_step = 0; |
jah128 | 0:d6269d17c8cf | 1489 | led_step = 0; |
jah128 | 0:d6269d17c8cf | 1490 | } |
jah128 | 0:d6269d17c8cf | 1491 | break; |
jah128 | 0:d6269d17c8cf | 1492 | } |
jah128 | 0:d6269d17c8cf | 1493 | demo_timer.reset(); |
jah128 | 0:d6269d17c8cf | 1494 | } |
jah128 | 11:312663037b8c | 1495 | if(demo_running == 1)demo_timeout.attach_us(this,&Demo::spinning_demo_cycle,500); |
jah128 | 0:d6269d17c8cf | 1496 | else { |
jah128 | 8:6c92789d5f87 | 1497 | motors.stop(); |
jah128 | 0:d6269d17c8cf | 1498 | display.set_backlight_brightness(bl_brightness * 0.01f); |
jah128 | 0:d6269d17c8cf | 1499 | } |
jah128 | 0:d6269d17c8cf | 1500 | } |
jah128 | 0:d6269d17c8cf | 1501 | |
jah128 | 16:50686c07ad07 | 1502 | void Demo::colour_demo_cycle() |
jah128 | 16:50686c07ad07 | 1503 | { |
jah128 | 16:50686c07ad07 | 1504 | if(demo_timer.read() > time_out) { |
jah128 | 16:50686c07ad07 | 1505 | int col = colour.get_detected_colour(); |
jah128 | 18:9204f74069b4 | 1506 | switch(col) { |
jah128 | 18:9204f74069b4 | 1507 | case 0: |
jah128 | 18:9204f74069b4 | 1508 | led.set_leds(0,0xFF); |
jah128 | 18:9204f74069b4 | 1509 | led.set_center_led(1,1); |
jah128 | 18:9204f74069b4 | 1510 | break; |
jah128 | 18:9204f74069b4 | 1511 | case 1: |
jah128 | 18:9204f74069b4 | 1512 | led.set_leds(0xFF,0xFF); |
jah128 | 18:9204f74069b4 | 1513 | led.set_center_led(3,1); |
jah128 | 18:9204f74069b4 | 1514 | break; |
jah128 | 18:9204f74069b4 | 1515 | case 2: |
jah128 | 18:9204f74069b4 | 1516 | led.set_leds(0xFF,0); |
jah128 | 18:9204f74069b4 | 1517 | led.set_center_led(2,1); |
jah128 | 18:9204f74069b4 | 1518 | break; |
jah128 | 18:9204f74069b4 | 1519 | default: |
jah128 | 18:9204f74069b4 | 1520 | led.set_leds(0,0); |
jah128 | 18:9204f74069b4 | 1521 | led.set_center_led(0,0); |
jah128 | 18:9204f74069b4 | 1522 | break; |
jah128 | 16:50686c07ad07 | 1523 | } |
jah128 | 16:50686c07ad07 | 1524 | switch(state) { |
jah128 | 16:50686c07ad07 | 1525 | case 0: //Robot is stopped |
jah128 | 16:50686c07ad07 | 1526 | speed = 0.2f; |
jah128 | 16:50686c07ad07 | 1527 | motors.forward(speed); |
jah128 | 16:50686c07ad07 | 1528 | time_out = 0.05; |
jah128 | 16:50686c07ad07 | 1529 | state = 1; |
jah128 | 16:50686c07ad07 | 1530 | break; |
jah128 | 16:50686c07ad07 | 1531 | case 1: { //Motor is moving forward |
jah128 | 16:50686c07ad07 | 1532 | sensors.store_ir_values(); |
jah128 | 16:50686c07ad07 | 1533 | int front_right = sensors.read_illuminated_raw_ir_value(0); |
jah128 | 16:50686c07ad07 | 1534 | int front_left = sensors.read_illuminated_raw_ir_value(7); |
jah128 | 16:50686c07ad07 | 1535 | if(front_left > 400 || front_right > 400) { |
jah128 | 16:50686c07ad07 | 1536 | motors.brake(); |
jah128 | 16:50686c07ad07 | 1537 | time_out = 0.04; |
jah128 | 16:50686c07ad07 | 1538 | if(front_left > front_right)state=2; |
jah128 | 16:50686c07ad07 | 1539 | else state=3; |
jah128 | 16:50686c07ad07 | 1540 | } else { |
jah128 | 16:50686c07ad07 | 1541 | if(speed < 0.5) { |
jah128 | 16:50686c07ad07 | 1542 | speed += 0.03; |
jah128 | 16:50686c07ad07 | 1543 | motors.forward(speed); |
jah128 | 16:50686c07ad07 | 1544 | } |
jah128 | 16:50686c07ad07 | 1545 | } |
jah128 | 16:50686c07ad07 | 1546 | break; |
jah128 | 16:50686c07ad07 | 1547 | } |
jah128 | 16:50686c07ad07 | 1548 | case 2: //Turn right |
jah128 | 16:50686c07ad07 | 1549 | motors.set_left_motor_speed(0.35); |
jah128 | 16:50686c07ad07 | 1550 | motors.set_right_motor_speed(-0.35); |
jah128 | 16:50686c07ad07 | 1551 | time_out = 0.5; |
jah128 | 16:50686c07ad07 | 1552 | state = 0; |
jah128 | 16:50686c07ad07 | 1553 | break; |
jah128 | 16:50686c07ad07 | 1554 | case 3: //Turn left |
jah128 | 16:50686c07ad07 | 1555 | motors.set_left_motor_speed(-0.35); |
jah128 | 16:50686c07ad07 | 1556 | motors.set_right_motor_speed(0.35); |
jah128 | 16:50686c07ad07 | 1557 | time_out = 0.5; |
jah128 | 16:50686c07ad07 | 1558 | state = 0; |
jah128 | 16:50686c07ad07 | 1559 | break; |
jah128 | 16:50686c07ad07 | 1560 | } |
jah128 | 16:50686c07ad07 | 1561 | demo_timer.reset(); |
jah128 | 16:50686c07ad07 | 1562 | } |
jah128 | 16:50686c07ad07 | 1563 | if(demo_running == 1)demo_timeout.attach_us(this,&Demo::colour_demo_cycle,200); |
jah128 | 16:50686c07ad07 | 1564 | else { |
jah128 | 16:50686c07ad07 | 1565 | motors.stop(); |
jah128 | 16:50686c07ad07 | 1566 | display.set_backlight_brightness(bl_brightness * 0.01f); |
jah128 | 16:50686c07ad07 | 1567 | } |
jah128 | 16:50686c07ad07 | 1568 | } |
jah128 | 16:50686c07ad07 | 1569 | |
jah128 | 16:50686c07ad07 | 1570 | |
jah128 | 11:312663037b8c | 1571 | void Demo::obstacle_demo_cycle() |
jah128 | 0:d6269d17c8cf | 1572 | { |
jah128 | 18:9204f74069b4 | 1573 | |
jah128 | 0:d6269d17c8cf | 1574 | if(demo_timer.read() > time_out) { |
jah128 | 0:d6269d17c8cf | 1575 | switch(state) { |
jah128 | 0:d6269d17c8cf | 1576 | case 0: //Robot is stopped |
jah128 | 9:dde9e21030eb | 1577 | led.set_leds(0,0xFF); |
jah128 | 9:dde9e21030eb | 1578 | led.set_center_led(1,0.4); |
jah128 | 0:d6269d17c8cf | 1579 | speed = 0.3f; |
jah128 | 8:6c92789d5f87 | 1580 | motors.forward(speed); |
jah128 | 0:d6269d17c8cf | 1581 | time_out = 0.05; |
jah128 | 0:d6269d17c8cf | 1582 | state = 1; |
jah128 | 0:d6269d17c8cf | 1583 | break; |
jah128 | 0:d6269d17c8cf | 1584 | case 1: { //Motor is moving forward |
jah128 | 10:e58323951c08 | 1585 | sensors.store_ir_values(); |
jah128 | 10:e58323951c08 | 1586 | int front_right = sensors.read_illuminated_raw_ir_value(0); |
jah128 | 10:e58323951c08 | 1587 | int front_left = sensors.read_illuminated_raw_ir_value(7); |
jah128 | 0:d6269d17c8cf | 1588 | if(front_left > 400 || front_right > 400) { |
jah128 | 8:6c92789d5f87 | 1589 | motors.brake(); |
jah128 | 0:d6269d17c8cf | 1590 | time_out = 0.04; |
jah128 | 0:d6269d17c8cf | 1591 | if(front_left > front_right)state=2; |
jah128 | 0:d6269d17c8cf | 1592 | else state=3; |
jah128 | 0:d6269d17c8cf | 1593 | } else { |
jah128 | 0:d6269d17c8cf | 1594 | if(speed < 0.5) { |
jah128 | 0:d6269d17c8cf | 1595 | speed += 0.03; |
jah128 | 8:6c92789d5f87 | 1596 | motors.forward(speed); |
jah128 | 0:d6269d17c8cf | 1597 | } |
jah128 | 0:d6269d17c8cf | 1598 | switch(led_step) { |
jah128 | 0:d6269d17c8cf | 1599 | case 0: |
jah128 | 9:dde9e21030eb | 1600 | led.set_leds(0x01,0); |
jah128 | 0:d6269d17c8cf | 1601 | break; |
jah128 | 0:d6269d17c8cf | 1602 | case 1: |
jah128 | 9:dde9e21030eb | 1603 | led.set_leds(0x38,0); |
jah128 | 0:d6269d17c8cf | 1604 | break; |
jah128 | 0:d6269d17c8cf | 1605 | case 2: |
jah128 | 9:dde9e21030eb | 1606 | led.set_leds(0x6C,0); |
jah128 | 0:d6269d17c8cf | 1607 | break; |
jah128 | 0:d6269d17c8cf | 1608 | case 3: |
jah128 | 9:dde9e21030eb | 1609 | led.set_leds(0xC6,0); |
jah128 | 0:d6269d17c8cf | 1610 | break; |
jah128 | 0:d6269d17c8cf | 1611 | case 4: |
jah128 | 9:dde9e21030eb | 1612 | led.set_leds(0x83,0); |
jah128 | 0:d6269d17c8cf | 1613 | break; |
jah128 | 0:d6269d17c8cf | 1614 | } |
jah128 | 9:dde9e21030eb | 1615 | led.set_center_led(2, 0.6); |
jah128 | 0:d6269d17c8cf | 1616 | led_step ++; |
jah128 | 0:d6269d17c8cf | 1617 | if(led_step == 5) led_step = 0; |
jah128 | 0:d6269d17c8cf | 1618 | } |
jah128 | 0:d6269d17c8cf | 1619 | break; |
jah128 | 0:d6269d17c8cf | 1620 | } |
jah128 | 0:d6269d17c8cf | 1621 | case 2: //Turn right |
jah128 | 8:6c92789d5f87 | 1622 | motors.set_left_motor_speed(0.85); |
jah128 | 8:6c92789d5f87 | 1623 | motors.set_right_motor_speed(-0.85); |
jah128 | 0:d6269d17c8cf | 1624 | time_out = 0.4; |
jah128 | 0:d6269d17c8cf | 1625 | state = 0; |
jah128 | 9:dde9e21030eb | 1626 | led.set_leds(0x0E,0x0E); |
jah128 | 9:dde9e21030eb | 1627 | led.set_center_led(3,0.5); |
jah128 | 0:d6269d17c8cf | 1628 | break; |
jah128 | 0:d6269d17c8cf | 1629 | case 3: //Turn left |
jah128 | 8:6c92789d5f87 | 1630 | motors.set_left_motor_speed(-0.85); |
jah128 | 8:6c92789d5f87 | 1631 | motors.set_right_motor_speed(0.85); |
jah128 | 0:d6269d17c8cf | 1632 | time_out = 0.4; |
jah128 | 0:d6269d17c8cf | 1633 | state = 0; |
jah128 | 9:dde9e21030eb | 1634 | led.set_leds(0xE0,0xE0); |
jah128 | 9:dde9e21030eb | 1635 | led.set_center_led(3,0.5); |
jah128 | 0:d6269d17c8cf | 1636 | break; |
jah128 | 0:d6269d17c8cf | 1637 | } |
jah128 | 0:d6269d17c8cf | 1638 | demo_timer.reset(); |
jah128 | 0:d6269d17c8cf | 1639 | } |
jah128 | 11:312663037b8c | 1640 | if(demo_running == 1)demo_timeout.attach_us(this,&Demo::obstacle_demo_cycle,200); |
jah128 | 0:d6269d17c8cf | 1641 | else { |
jah128 | 8:6c92789d5f87 | 1642 | motors.stop(); |
jah128 | 0:d6269d17c8cf | 1643 | display.set_backlight_brightness(bl_brightness * 0.01f); |
jah128 | 0:d6269d17c8cf | 1644 | } |
jah128 | 0:d6269d17c8cf | 1645 | } |
jah128 | 0:d6269d17c8cf | 1646 | |
jah128 | 16:50686c07ad07 | 1647 | |
jah128 | 11:312663037b8c | 1648 | void Demo::demo_update_leds() |
jah128 | 0:d6269d17c8cf | 1649 | { |
jah128 | 0:d6269d17c8cf | 1650 | char red = 0; |
jah128 | 0:d6269d17c8cf | 1651 | char green = 0; |
jah128 | 0:d6269d17c8cf | 1652 | for(int i=0; i<8; i++) { |
jah128 | 0:d6269d17c8cf | 1653 | if(led_state[i]==1 || led_state[i]==3) red+=(1<<i); |
jah128 | 0:d6269d17c8cf | 1654 | if(led_state[i]==2 || led_state[i]==3) green+=(1<<i); |
jah128 | 0:d6269d17c8cf | 1655 | } |
jah128 | 9:dde9e21030eb | 1656 | led.set_leds(green,red); |
jah128 | 0:d6269d17c8cf | 1657 | float brightness_f = brightness / 100.0f; |
jah128 | 9:dde9e21030eb | 1658 | led.set_center_led(led_state[8], brightness_f); |
jah128 | 9:dde9e21030eb | 1659 | led.set_base_led(base_led_state); |
jah128 | 0:d6269d17c8cf | 1660 | } |