2018 revision to classic DataBus AVC code.

Dependencies:   LSM303DLM Servo SerialGraphicLCD L3G4200D IncrementalEncoder SimpleShell

Committer:
shimniok
Date:
Wed Jan 02 18:40:29 2019 +0000
Revision:
38:6fec81f85221
Parent:
37:b8259500dbd3
Child:
39:465213249f71
display gps data

Who changed what in which revision?

UserRevisionLine numberNew contents of line
shimniok 0:7e98bbfd102a 1 /* mbed Microcontroller Library
shimniok 0:7e98bbfd102a 2 * Copyright (c) 2018 ARM Limited
shimniok 0:7e98bbfd102a 3 * SPDX-License-Identifier: Apache-2.0
shimniok 0:7e98bbfd102a 4 */
shimniok 0:7e98bbfd102a 5
shimniok 0:7e98bbfd102a 6 #include "mbed.h"
shimniok 0:7e98bbfd102a 7 #include <stdio.h>
shimniok 0:7e98bbfd102a 8 #include <errno.h>
shimniok 16:eb28d0f64a9b 9 #include "pinouts.h"
shimniok 0:7e98bbfd102a 10 #include "stats_report.h"
shimniok 0:7e98bbfd102a 11 #include "SDBlockDevice.h"
shimniok 0:7e98bbfd102a 12 #include "FATFileSystem.h"
shimniok 35:c42e7e29c3bd 13 #include "Servo.h"
shimniok 0:7e98bbfd102a 14 #include "SimpleShell.h"
shimniok 4:de7feb458652 15 #include "Config.h"
shimniok 11:8ec858b7c6d1 16 #include "Updater.h"
shimniok 16:eb28d0f64a9b 17 #include "Ublox6.h"
shimniok 24:a7f92dfc5310 18 #include "Logger.h"
shimniok 24:a7f92dfc5310 19 #include "SystemState.h"
shimniok 37:b8259500dbd3 20 #include "Display.h"
shimniok 0:7e98bbfd102a 21
shimniok 24:a7f92dfc5310 22 ///////////////////////////////////////////////////////////////////////////////
shimniok 24:a7f92dfc5310 23 // Config
shimniok 24:a7f92dfc5310 24 Config config;
shimniok 24:a7f92dfc5310 25
shimniok 24:a7f92dfc5310 26 ///////////////////////////////////////////////////////////////////////////////
shimniok 24:a7f92dfc5310 27 // Devices
shimniok 30:ed791f1f7f7d 28 DigitalOut led1(LED1);
shimniok 30:ed791f1f7f7d 29 DigitalOut led2(LED2);
shimniok 30:ed791f1f7f7d 30 DigitalOut led3(LED3);
shimniok 30:ed791f1f7f7d 31 DigitalOut led4(LED4);
shimniok 37:b8259500dbd3 32 Display display(UART3TX, UART3RX);
shimniok 0:7e98bbfd102a 33 LocalFileSystem lfs("etc");
shimniok 24:a7f92dfc5310 34 SDBlockDevice bd(p5, p6, p7, p8); // MOSI, MISO, CLK, CS
shimniok 24:a7f92dfc5310 35 FATFileSystem ffs("log", &bd);
shimniok 24:a7f92dfc5310 36 Serial pc(USBTX, USBRX);
shimniok 20:043987d06f8d 37 RawSerial s(UART1TX, UART1RX, 38400);
shimniok 33:74c514aea0a1 38 InterruptIn lbutton(LBUTTON, PullUp); // button interrupts
shimniok 33:74c514aea0a1 39 InterruptIn cbutton(CBUTTON, PullUp);
shimniok 33:74c514aea0a1 40 InterruptIn rbutton(RBUTTON, PullUp);
shimniok 35:c42e7e29c3bd 41 Servo steer(STEERING);
shimniok 35:c42e7e29c3bd 42 Servo esc(THROTTLE);
shimniok 20:043987d06f8d 43
shimniok 24:a7f92dfc5310 44 ///////////////////////////////////////////////////////////////////////////////
shimniok 24:a7f92dfc5310 45 // Idle hook
shimniok 24:a7f92dfc5310 46 void idler() {
shimniok 24:a7f92dfc5310 47 while(1) {
shimniok 24:a7f92dfc5310 48 led1 = !led1;
shimniok 24:a7f92dfc5310 49 wait(0.1);
shimniok 24:a7f92dfc5310 50 }
shimniok 24:a7f92dfc5310 51 }
shimniok 19:0d1728091519 52
shimniok 24:a7f92dfc5310 53 ///////////////////////////////////////////////////////////////////////////////
shimniok 24:a7f92dfc5310 54 // Logging
shimniok 29:cb2f55fbfe9c 55 EventQueue logQueue(16 * EVENTS_EVENT_SIZE);
shimniok 31:20a95043adb0 56 Logger logger;
shimniok 25:b8176ebb96c6 57
shimniok 25:b8176ebb96c6 58 ///////////////////////////////////////////////////////////////////////////////
shimniok 25:b8176ebb96c6 59 // Updater
shimniok 25:b8176ebb96c6 60 Updater *u = Updater::instance();
shimniok 26:2dc31a801cc8 61 EventQueue updaterQueue(8 * EVENTS_EVENT_SIZE);
shimniok 25:b8176ebb96c6 62
shimniok 25:b8176ebb96c6 63 void updater_callback() {
shimniok 30:ed791f1f7f7d 64 SensorData d;
shimniok 30:ed791f1f7f7d 65 float dt;
shimniok 30:ed791f1f7f7d 66
shimniok 25:b8176ebb96c6 67 led1 = !led1;
shimniok 30:ed791f1f7f7d 68 d.timestamp = Kernel::get_ms_count();
shimniok 30:ed791f1f7f7d 69 d.encoder = u->encoder();
shimniok 32:eb673f6f5734 70 u->imu(d.gyro, d.accel, d.mag, dt);
shimniok 30:ed791f1f7f7d 71 logQueue.call(&logger, &Logger::log_sensors, d);
shimniok 37:b8259500dbd3 72 //lcdQueue.call ...
shimniok 25:b8176ebb96c6 73 }
shimniok 25:b8176ebb96c6 74
shimniok 24:a7f92dfc5310 75 ///////////////////////////////////////////////////////////////////////////////
shimniok 30:ed791f1f7f7d 76 // Buttons
shimniok 30:ed791f1f7f7d 77
shimniok 30:ed791f1f7f7d 78 //enum button_mask { LEFT = 0x01, CENTER = 0x02, RIGHT = 0x04 };
shimniok 30:ed791f1f7f7d 79 EventQueue buttonQueue(16 * EVENTS_EVENT_SIZE);
shimniok 33:74c514aea0a1 80 const int BUTTON_DEBOUNCE_SAMPLES = 20;
shimniok 33:74c514aea0a1 81 const int BUTTON_DEBOUNCE_THRESH = 8;
shimniok 33:74c514aea0a1 82 const int BUTTON_SAMPLE_MS = 0.005;
shimniok 30:ed791f1f7f7d 83
shimniok 30:ed791f1f7f7d 84 void button_event() {
shimniok 33:74c514aea0a1 85 int samples = 0;
shimniok 33:74c514aea0a1 86
shimniok 33:74c514aea0a1 87 // disable subsequent interrupts
shimniok 33:74c514aea0a1 88 lbutton.fall(NULL);
shimniok 33:74c514aea0a1 89
shimniok 33:74c514aea0a1 90 // sample repeatedly to debounce
shimniok 33:74c514aea0a1 91 for (int i=0; i < BUTTON_DEBOUNCE_SAMPLES; i++) {
shimniok 33:74c514aea0a1 92 if (lbutton == 0) samples++;
shimniok 33:74c514aea0a1 93 wait(BUTTON_SAMPLE_MS);
shimniok 33:74c514aea0a1 94 }
shimniok 33:74c514aea0a1 95
shimniok 33:74c514aea0a1 96 if (samples > BUTTON_DEBOUNCE_THRESH) {
shimniok 30:ed791f1f7f7d 97 if (logger.enabled()) {
shimniok 30:ed791f1f7f7d 98 logQueue.call(&logger, &Logger::stop);
shimniok 30:ed791f1f7f7d 99 led3 = 0;
shimniok 30:ed791f1f7f7d 100 } else {
shimniok 30:ed791f1f7f7d 101 logQueue.call(&logger, &Logger::start);
shimniok 30:ed791f1f7f7d 102 led3 = 1;
shimniok 30:ed791f1f7f7d 103 }
shimniok 30:ed791f1f7f7d 104 }
shimniok 33:74c514aea0a1 105
shimniok 33:74c514aea0a1 106 lbutton.fall(buttonQueue.event(button_event));
shimniok 30:ed791f1f7f7d 107 }
shimniok 30:ed791f1f7f7d 108
shimniok 30:ed791f1f7f7d 109
shimniok 30:ed791f1f7f7d 110 ///////////////////////////////////////////////////////////////////////////////
shimniok 24:a7f92dfc5310 111 // GPS
shimniok 24:a7f92dfc5310 112 Ublox6 ublox;
shimniok 24:a7f92dfc5310 113 EventQueue gpsQueue(8 * EVENTS_EVENT_SIZE);
shimniok 38:6fec81f85221 114 EventQueue lcdQueue(8 * EVENTS_EVENT_SIZE);
shimniok 23:5e61cf4a8c34 115
shimniok 23:5e61cf4a8c34 116 // Callback for gps parse data ready
shimniok 23:5e61cf4a8c34 117 void gps_callback() {
shimniok 24:a7f92dfc5310 118 GpsData d;
shimniok 24:a7f92dfc5310 119
shimniok 25:b8176ebb96c6 120 led2 = !led2;
shimniok 24:a7f92dfc5310 121 ublox.read(d.latitude, d.longitude, d.course, d.speed, d.hdop, d.svcount);
shimniok 30:ed791f1f7f7d 122 d.timestamp = Kernel::get_ms_count();
shimniok 29:cb2f55fbfe9c 123 logQueue.call(&logger, &Logger::log_gps, d);
shimniok 38:6fec81f85221 124 //lcdQueue.call(&display, &Display::gps, d);
shimniok 38:6fec81f85221 125 display.gps(d);
shimniok 23:5e61cf4a8c34 126 }
shimniok 29:cb2f55fbfe9c 127
shimniok 22:4d62bd16f037 128 // ISR for GPS serial, passes off to thread
shimniok 20:043987d06f8d 129 void gps_handler() {
shimniok 22:4d62bd16f037 130 while (s.readable()) {
shimniok 22:4d62bd16f037 131 int c = s.getc();
shimniok 22:4d62bd16f037 132 gpsQueue.call(&ublox, &Ublox6::parse, c);
shimniok 16:eb28d0f64a9b 133 }
shimniok 19:0d1728091519 134 }
shimniok 16:eb28d0f64a9b 135
shimniok 24:a7f92dfc5310 136 ///////////////////////////////////////////////////////////////////////////////
shimniok 24:a7f92dfc5310 137 // Shell
shimniok 30:ed791f1f7f7d 138 SimpleShell sh("/log");
shimniok 9:fc3575d2cbbf 139
shimniok 24:a7f92dfc5310 140 void test(int argc, char **argv) {
shimniok 35:c42e7e29c3bd 141 //printf("Hello world!\n");
shimniok 35:c42e7e29c3bd 142 char file[32];
shimniok 35:c42e7e29c3bd 143
shimniok 35:c42e7e29c3bd 144 for (int i=30; i < 40; i++) {
shimniok 35:c42e7e29c3bd 145 sprintf(file, "/log/%04d.csv", i);
shimniok 35:c42e7e29c3bd 146 printf("removing <%s>\n", file);
shimniok 35:c42e7e29c3bd 147 int stat = remove(file);
shimniok 35:c42e7e29c3bd 148 printf("return: %d\n", stat);
shimniok 35:c42e7e29c3bd 149 }
shimniok 1:7019a60fd585 150 }
shimniok 1:7019a60fd585 151
shimniok 24:a7f92dfc5310 152 void stats(int argc, char **argv) {
shimniok 24:a7f92dfc5310 153 SystemReport r(200);
shimniok 24:a7f92dfc5310 154 r.report_state();
shimniok 24:a7f92dfc5310 155 return;
shimniok 24:a7f92dfc5310 156 }
shimniok 24:a7f92dfc5310 157
shimniok 24:a7f92dfc5310 158 void read_gps(int argc, char **argv)
shimniok 18:3f8a8f6e3cc1 159 {
shimniok 18:3f8a8f6e3cc1 160 double lat=0;
shimniok 18:3f8a8f6e3cc1 161 double lon=0;
shimniok 18:3f8a8f6e3cc1 162 float course=0;
shimniok 18:3f8a8f6e3cc1 163 float speed=0;
shimniok 18:3f8a8f6e3cc1 164 float hdop=0.0;
shimniok 18:3f8a8f6e3cc1 165 int svcount=0;
shimniok 18:3f8a8f6e3cc1 166
shimniok 18:3f8a8f6e3cc1 167 ublox.read(lat, lon, course, speed, hdop, svcount);
shimniok 18:3f8a8f6e3cc1 168 printf("%3.7f %3.7f\n", lat, lon);
shimniok 18:3f8a8f6e3cc1 169 printf("hdg=%03.1f deg spd=%3.1f m/s\n", course, speed);
shimniok 18:3f8a8f6e3cc1 170 printf("%d %f\n", svcount, hdop);
shimniok 18:3f8a8f6e3cc1 171 }
shimniok 18:3f8a8f6e3cc1 172
shimniok 32:eb673f6f5734 173 void read_imu(int argc, char **argv)
shimniok 9:fc3575d2cbbf 174 {
shimniok 12:3cd91e150d9c 175 int g[3];
shimniok 32:eb673f6f5734 176 int a[3];
shimniok 32:eb673f6f5734 177 int m[3];
shimniok 13:5566df1250f1 178 float dt;
shimniok 12:3cd91e150d9c 179
shimniok 11:8ec858b7c6d1 180 Updater *u = Updater::instance();
shimniok 11:8ec858b7c6d1 181
shimniok 32:eb673f6f5734 182 u->imu(g, a, m, dt);
shimniok 32:eb673f6f5734 183
shimniok 32:eb673f6f5734 184 printf(" Gyro: %d, %d, %d\n", g[0], g[1], g[2]);
shimniok 32:eb673f6f5734 185 printf(" Accel: %d, %d, %d\n", a[0], a[1], a[2]);
shimniok 32:eb673f6f5734 186 printf(" Mag: %d, %d, %d\n", m[0], m[1], m[2]);
shimniok 32:eb673f6f5734 187 printf(" dt: %f\n", dt);
shimniok 12:3cd91e150d9c 188 }
shimniok 12:3cd91e150d9c 189
shimniok 24:a7f92dfc5310 190 void read_enc(int argc, char **argv)
shimniok 14:1dd83e626153 191 {
shimniok 14:1dd83e626153 192 Updater *u = Updater::instance();
shimniok 14:1dd83e626153 193
shimniok 14:1dd83e626153 194 printf("Encoder: %d\n", u->encoder());
shimniok 14:1dd83e626153 195 }
shimniok 14:1dd83e626153 196
shimniok 29:cb2f55fbfe9c 197 void log(int argc, char **argv)
shimniok 29:cb2f55fbfe9c 198 {
shimniok 29:cb2f55fbfe9c 199 char *usage = "usage: log [start|stop]";
shimniok 29:cb2f55fbfe9c 200
shimniok 29:cb2f55fbfe9c 201 if (argc == 1) {
shimniok 29:cb2f55fbfe9c 202 printf("logging ");
shimniok 29:cb2f55fbfe9c 203 if (logger.enabled())
shimniok 29:cb2f55fbfe9c 204 printf("enabled");
shimniok 29:cb2f55fbfe9c 205 else
shimniok 29:cb2f55fbfe9c 206 printf("disabled");
shimniok 29:cb2f55fbfe9c 207 printf("\n");
shimniok 29:cb2f55fbfe9c 208 } else if (argc == 2) {
shimniok 29:cb2f55fbfe9c 209 if (!strcmp("start", argv[1])) {
shimniok 29:cb2f55fbfe9c 210 logger.start();
shimniok 29:cb2f55fbfe9c 211 } else if (!strcmp("stop", argv[1])) {
shimniok 29:cb2f55fbfe9c 212 logger.stop();
shimniok 29:cb2f55fbfe9c 213 } else {
shimniok 29:cb2f55fbfe9c 214 puts(usage);
shimniok 29:cb2f55fbfe9c 215 }
shimniok 29:cb2f55fbfe9c 216 } else {
shimniok 29:cb2f55fbfe9c 217 puts(usage);
shimniok 29:cb2f55fbfe9c 218 }
shimniok 29:cb2f55fbfe9c 219 }
shimniok 29:cb2f55fbfe9c 220
shimniok 29:cb2f55fbfe9c 221
shimniok 24:a7f92dfc5310 222 void bridge_uart1(int argc, char **argv) {
shimniok 20:043987d06f8d 223 RawSerial s(UART1TX, UART1RX, 38400);
shimniok 20:043987d06f8d 224 while (1) {
shimniok 20:043987d06f8d 225 if (pc.readable()) s.putc(pc.getc());
shimniok 20:043987d06f8d 226 if (s.readable()) pc.putc(s.getc());
shimniok 20:043987d06f8d 227 }
shimniok 20:043987d06f8d 228 }
shimniok 20:043987d06f8d 229
shimniok 24:a7f92dfc5310 230 void reset(int argc, char **argv)
shimniok 12:3cd91e150d9c 231 {
shimniok 12:3cd91e150d9c 232 NVIC_SystemReset();
shimniok 9:fc3575d2cbbf 233 }
shimniok 9:fc3575d2cbbf 234
shimniok 24:a7f92dfc5310 235 ///////////////////////////////////////////////////////////////////////////////
shimniok 24:a7f92dfc5310 236 // MAIN
shimniok 1:7019a60fd585 237
shimniok 0:7e98bbfd102a 238 // main() runs in its own thread in the OS
shimniok 0:7e98bbfd102a 239 int main()
shimniok 11:8ec858b7c6d1 240 {
shimniok 20:043987d06f8d 241 //bridge_uart1();
shimniok 24:a7f92dfc5310 242
shimniok 25:b8176ebb96c6 243 //Kernel::attach_idle_hook(idler);
shimniok 20:043987d06f8d 244
shimniok 37:b8259500dbd3 245 display.status("Bootup...");
shimniok 0:7e98bbfd102a 246 printf("Bootup...\n");
shimniok 0:7e98bbfd102a 247 fflush(stdout);
shimniok 1:7019a60fd585 248
shimniok 35:c42e7e29c3bd 249 steer = 0.50;
shimniok 35:c42e7e29c3bd 250 esc = 0.00;
shimniok 35:c42e7e29c3bd 251
shimniok 4:de7feb458652 252 printf("Loading config...\n");
shimniok 37:b8259500dbd3 253 display.status("Loading config");
shimniok 7:1f2661b840ed 254 config.add("intercept_distance", Config::DOUBLE);
shimniok 7:1f2661b840ed 255 config.add("waypoint_threshold", Config::DOUBLE);
shimniok 7:1f2661b840ed 256 config.add("minimum_turning_radius", Config::DOUBLE);
shimniok 7:1f2661b840ed 257 config.add("wheelbase", Config::DOUBLE);
shimniok 7:1f2661b840ed 258 config.add("track_width", Config::DOUBLE);
shimniok 7:1f2661b840ed 259 config.add("tire_circumference", Config::DOUBLE);
shimniok 7:1f2661b840ed 260 config.add("encoder_stripes", Config::INT);
shimniok 7:1f2661b840ed 261 config.add("esc_brake", Config::INT);
shimniok 7:1f2661b840ed 262 config.add("esc_off", Config::INT);
shimniok 7:1f2661b840ed 263 config.add("esc_max", Config::INT);
shimniok 7:1f2661b840ed 264 config.add("turn_speed", Config::DOUBLE);
shimniok 7:1f2661b840ed 265 config.add("turn_distance", Config::DOUBLE);
shimniok 7:1f2661b840ed 266 config.add("start_speed", Config::DOUBLE);
shimniok 7:1f2661b840ed 267 config.add("cruise_speed", Config::DOUBLE);
shimniok 7:1f2661b840ed 268 config.add("speed_kp", Config::DOUBLE);
shimniok 7:1f2661b840ed 269 config.add("speed_ki", Config::DOUBLE);
shimniok 7:1f2661b840ed 270 config.add("speed_kd", Config::DOUBLE);
shimniok 7:1f2661b840ed 271 config.add("steer_center", Config::DOUBLE);
shimniok 7:1f2661b840ed 272 config.add("steer_scale", Config::DOUBLE);
shimniok 7:1f2661b840ed 273 config.add("gyro_scale", Config::DOUBLE);
shimniok 7:1f2661b840ed 274 config.add("gps_valid_speed", Config::DOUBLE);
shimniok 35:c42e7e29c3bd 275
shimniok 4:de7feb458652 276 if (config.load("/etc/2018cfg.txt")) {
shimniok 4:de7feb458652 277 printf("error loading config\n");
shimniok 37:b8259500dbd3 278 display.status("config load error");
shimniok 4:de7feb458652 279 }
shimniok 10:9fb3feb38746 280
shimniok 38:6fec81f85221 281 printf("Starting display...\n");
shimniok 38:6fec81f85221 282 Thread lcdThread(osPriorityLow, 2048, 0, "lcd");
shimniok 38:6fec81f85221 283 lcdThread.start(callback(&lcdQueue, &EventQueue::dispatch_forever));
shimniok 38:6fec81f85221 284
shimniok 30:ed791f1f7f7d 285 printf("Starting buttons...\n");
shimniok 37:b8259500dbd3 286 display.status("Starting buttons");
shimniok 33:74c514aea0a1 287 lbutton.fall(buttonQueue.event(button_event));
shimniok 30:ed791f1f7f7d 288 //cbutton.rise(buttonQueue.event(button_event));
shimniok 30:ed791f1f7f7d 289 //rbutton.rise(buttonQueue.event(button_event));
shimniok 30:ed791f1f7f7d 290 Thread buttonThread(osPriorityNormal, 256, 0, "buttons");
shimniok 30:ed791f1f7f7d 291 buttonThread.start(callback(&buttonQueue, &EventQueue::dispatch_forever));
shimniok 30:ed791f1f7f7d 292
shimniok 24:a7f92dfc5310 293 printf("Starting updater...\n");
shimniok 37:b8259500dbd3 294 display.status("Starting updater");
shimniok 25:b8176ebb96c6 295 u->attach(updater_callback);
shimniok 24:a7f92dfc5310 296 Thread updaterThread(osPriorityRealtime, 512, 0, "updater");
shimniok 26:2dc31a801cc8 297 updaterQueue.call_every(20, u, &Updater::update);
shimniok 26:2dc31a801cc8 298 updaterThread.start(callback(&updaterQueue, &EventQueue::dispatch_forever));
shimniok 24:a7f92dfc5310 299
shimniok 24:a7f92dfc5310 300 printf("Starting gps...\n");
shimniok 37:b8259500dbd3 301 display.status("Starting gps");
shimniok 29:cb2f55fbfe9c 302 Thread gpsThread(osPriorityHigh, 2048, 0, "gps");
shimniok 24:a7f92dfc5310 303 gpsThread.start(callback(&gpsQueue, &EventQueue::dispatch_forever));
shimniok 24:a7f92dfc5310 304 ublox.subscribe(gps_callback);
shimniok 24:a7f92dfc5310 305 s.attach(gps_handler);
shimniok 24:a7f92dfc5310 306
shimniok 37:b8259500dbd3 307 printf("Starting logging...\n");
shimniok 37:b8259500dbd3 308 display.status("Starting logging");
shimniok 29:cb2f55fbfe9c 309 Thread logThread(osPriorityNormal, 2048, 0, "log");
shimniok 24:a7f92dfc5310 310 logThread.start(callback(&logQueue, &EventQueue::dispatch_forever));
shimniok 24:a7f92dfc5310 311
shimniok 13:5566df1250f1 312 printf("Starting shell...\n");
shimniok 37:b8259500dbd3 313 display.status("Starting shell");
shimniok 30:ed791f1f7f7d 314 sh.command(test, "test");
shimniok 32:eb673f6f5734 315 sh.command(read_imu, "imu");
shimniok 30:ed791f1f7f7d 316 sh.command(read_enc, "enc");
shimniok 30:ed791f1f7f7d 317 sh.command(read_gps, "gps");
shimniok 30:ed791f1f7f7d 318 sh.command(reset, "reset");
shimniok 30:ed791f1f7f7d 319 sh.command(stats, "stats");
shimniok 30:ed791f1f7f7d 320 sh.command(log, "log");
shimniok 37:b8259500dbd3 321
shimniok 37:b8259500dbd3 322 display.status("DataBus 2018");
shimniok 24:a7f92dfc5310 323 sh.run();
shimniok 22:4d62bd16f037 324
shimniok 0:7e98bbfd102a 325 while (true) {
shimniok 0:7e98bbfd102a 326 // Blink LED and wait 0.5 seconds
shimniok 0:7e98bbfd102a 327 led1 = !led1;
shimniok 0:7e98bbfd102a 328 wait(0.5f);
shimniok 0:7e98bbfd102a 329 }
shimniok 0:7e98bbfd102a 330 }