]> mj.ucw.cz Git - home-hw.git/commitdiff
Waiting room: Moved to a separate repo master
authorMartin Mares <mj@ucw.cz>
Fri, 25 Apr 2025 22:57:41 +0000 (00:57 +0200)
committerMartin Mares <mj@ucw.cz>
Fri, 25 Apr 2025 22:57:41 +0000 (00:57 +0200)
waiting/README [deleted file]
waiting/bootloader/Makefile [deleted file]
waiting/bootloader/config.h [deleted file]
waiting/firmware/Makefile [deleted file]
waiting/firmware/config.h [deleted file]
waiting/firmware/interface.h [deleted file]
waiting/firmware/main.c [deleted file]
waiting/microbit/README [deleted file]
waiting/microbit/Wukong.py [deleted file]
waiting/microbit/main.py [deleted file]

diff --git a/waiting/README b/waiting/README
deleted file mode 100644 (file)
index 44c88a9..0000000
+++ /dev/null
@@ -1,33 +0,0 @@
-Assignment of peripherals and pins
-==================================
-
-USART1 debugging
-TIM1   microsecond timing
-TIM4   Neopixel control
-DMA1   Neopixel control
-I2C2   display 1602: HD44780U controller via PCF8574 expander, needs pull-up to 5V
-
-
-                          Blue Pill pinout
-                       +--------------------+
-                       | VBATT         3.3V |
-BluePill LED           | PC13           GND |
-                       | PC14            5V |
-                       | PC15           PB9 |
-kbd2 - col 1           | PA0            PB8 |  TIM4_CH3 - Neopixel data (needs pull-up)
-kbd3 - col 2           | PA1            PB7 |
-kbd4 - col 3           | PA2            PB6 |
-kbd5 - col 4           | PA3            PB5 |
-kbd6 - row 1           | PA4            PB4 |
-kbd7 - row 2           | PA5            PB3 |
-kbd8 - row 3           | PA6           PA15 |
-kbd9 - row 4           | PA7           PA12 |
-                       | PB0           PA11 |
-                       | PB1           PA10 |  RXD1 - debugging console
-I2C2_SCL - display (pu)        | PB10           PA9 |  TXD1 - debugging console
-I2C2_SDA - display (pu)        | PB11           PA8 |
-                       | RESET         PB15 |
-                       | 3.3 V         PB14 |
-                       | GND           PB13 |
-                       | GND           PB12 |
-                       +--------------------+
diff --git a/waiting/bootloader/Makefile b/waiting/bootloader/Makefile
deleted file mode 100644 (file)
index 9ba9617..0000000
+++ /dev/null
@@ -1,7 +0,0 @@
-ROOT=../..
-BINARY=bootloader
-OBJS=
-LIB_OBJS=util-debug.o dfu-bootloader.o
-MAX_SIZE=8192
-
-include $(ROOT)/mk/bluepill.mk
diff --git a/waiting/bootloader/config.h b/waiting/bootloader/config.h
deleted file mode 100644 (file)
index e87ab40..0000000
+++ /dev/null
@@ -1,24 +0,0 @@
-/*
- *     Waiting Room Controller Bootloader -- Configuration
- *
- *     (c) 2025 Martin Mareš <mj@ucw.cz>
- */
-
-// Processor clock
-
-#define CPU_CLOCK_MHZ 48
-
-// Debugging port
-
-#define DEBUG_USART USART1
-#define DEBUG_LED_BLUEPILL
-
-// Bootloader settings
-
-#undef BOOTLOADER_DEBUG
-#define BOOTLOADER_APP_START 0x08002000
-#define BOOTLOADER_MFG_ID 0x4242
-#define BOOTLOADER_PROD_ID 0x0012
-#define BOOTLOADER_PROD_VERSION 0x0100
-#define BOOTLOADER_MFG_NAME "United Computer Wizards"
-#define BOOTLOADER_PROD_NAME "Waiting Room Controller (boot-loader)"
diff --git a/waiting/firmware/Makefile b/waiting/firmware/Makefile
deleted file mode 100644 (file)
index cd12b41..0000000
+++ /dev/null
@@ -1,10 +0,0 @@
-ROOT=../..
-BINARY=firmware
-OBJS=main.o
-LIB_OBJS=util-debug.o
-
-WITH_BOOT_LOADER=1
-WITH_DFU_FLASH=1
-DFU_ARGS=-d 4242:0013,4242:0012
-
-include $(ROOT)/mk/bluepill.mk
diff --git a/waiting/firmware/config.h b/waiting/firmware/config.h
deleted file mode 100644 (file)
index 7c6d1e4..0000000
+++ /dev/null
@@ -1,14 +0,0 @@
-/*
- *     Waiting Room Controller -- Configuration
- *
- *     (c) 2025 Martin Mareš <mj@ucw.cz>
- */
-
-// Processor clock
-
-#define CPU_CLOCK_MHZ 72
-
-// Debugging port
-
-#define DEBUG_USART USART1
-#define DEBUG_LED_BLUEPILL
diff --git a/waiting/firmware/interface.h b/waiting/firmware/interface.h
deleted file mode 100644 (file)
index c1e2318..0000000
+++ /dev/null
@@ -1,15 +0,0 @@
-/*
- *     Waiting Room Controller -- Interface Definitions
- *
- *     (c) 2025 Martin Mareš <mj@ucw.cz>
- */
-
-#define NPIX_USB_VENDOR 0x4242
-#define NPIX_USB_PRODUCT 0x0013
-#define NPIX_USB_VERSION 0x0100
-
-/*
- *     Endpoints:
- *
- *     0x01 = bulk endpoint
- */
diff --git a/waiting/firmware/main.c b/waiting/firmware/main.c
deleted file mode 100644 (file)
index f0c552c..0000000
+++ /dev/null
@@ -1,680 +0,0 @@
-/*
- *     Waiting Room Controller
- *
- *     (c) 2025 Martin Mareš <mj@ucw.cz>
- */
-
-#include "util.h"
-
-#include <libopencm3/cm3/cortex.h>
-#include <libopencm3/cm3/nvic.h>
-#include <libopencm3/cm3/systick.h>
-#include <libopencm3/cm3/scb.h>
-#include <libopencm3/stm32/dma.h>
-#include <libopencm3/stm32/gpio.h>
-#include <libopencm3/stm32/i2c.h>
-#include <libopencm3/stm32/rcc.h>
-#include <libopencm3/stm32/timer.h>
-#include <libopencm3/stm32/usart.h>
-#include <libopencm3/usb/dfu.h>
-#include <libopencm3/usb/usbd.h>
-
-#include <string.h>
-
-#include "interface.h"
-
-/*** Hardware init ***/
-
-static void clock_init(void)
-{
-       rcc_clock_setup_pll(&rcc_hse_configs[RCC_CLOCK_HSE8_72MHZ]);
-
-       rcc_periph_clock_enable(RCC_GPIOA);
-       rcc_periph_clock_enable(RCC_GPIOB);
-       rcc_periph_clock_enable(RCC_GPIOC);
-       rcc_periph_clock_enable(RCC_USART1);
-       rcc_periph_clock_enable(RCC_TIM1);
-       // rcc_periph_clock_enable(RCC_TIM4);
-       // rcc_periph_clock_enable(RCC_DMA1);
-       rcc_periph_clock_enable(RCC_I2C2);
-
-       rcc_periph_reset_pulse(RST_GPIOA);
-       rcc_periph_reset_pulse(RST_GPIOB);
-       rcc_periph_reset_pulse(RST_GPIOC);
-       rcc_periph_reset_pulse(RST_USART1);
-       rcc_periph_reset_pulse(RST_TIM1);
-       // rcc_periph_reset_pulse(RST_TIM4);
-       rcc_periph_reset_pulse(RST_I2C2);
-}
-
-static void gpio_init(void)
-{
-       // PA9 = TXD1 for debugging console
-       // PA10 = RXD1 for debugging console
-       gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ, GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO9);
-       gpio_set_mode(GPIOA, GPIO_MODE_INPUT, GPIO_CNF_INPUT_FLOAT, GPIO10);
-
-       // PC13 = BluePill LED
-       gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_50_MHZ, GPIO_CNF_OUTPUT_PUSHPULL, GPIO13);
-       gpio_clear(GPIOC, GPIO13);
-
-       // PA0-7 = keyboard
-       gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ, GPIO_CNF_OUTPUT_OPENDRAIN, 0xf0);
-       gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ, GPIO_CNF_INPUT_FLOAT, 0x0f);
-       gpio_set(GPIOA, 0xff);
-
-       // PB8 = data for Neopixel
-       gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ, GPIO_CNF_OUTPUT_ALTFN_OPENDRAIN, GPIO8);
-
-       // PB10 and PB11 = I2C to display
-       gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ, GPIO_CNF_OUTPUT_ALTFN_OPENDRAIN, GPIO10 | GPIO11);
-}
-
-static void usart_init(void)
-{
-       usart_set_baudrate(USART1, 115200);
-       usart_set_databits(USART1, 8);
-       usart_set_stopbits(USART1, USART_STOPBITS_1);
-       usart_set_mode(USART1, USART_MODE_TX);
-       usart_set_parity(USART1, USART_PARITY_NONE);
-       usart_set_flow_control(USART1, USART_FLOWCONTROL_NONE);
-
-       usart_enable(USART1);
-}
-
-/*** System ticks ***/
-
-static volatile u32 ms_ticks;
-
-void sys_tick_handler(void)
-{
-       ms_ticks++;
-}
-
-static void tick_init(void)
-{
-       systick_set_frequency(1000, CPU_CLOCK_MHZ * 1000000);
-       systick_counter_enable();
-       systick_interrupt_enable();
-}
-
-static void delay_ms(uint ms)
-{
-       u32 start_ticks = ms_ticks;
-       while (ms_ticks - start_ticks < ms)
-               ;
-}
-
-/*** Microsecond delays via TIM1 ***/
-
-static void delay_init(void)
-{
-       timer_set_prescaler(TIM1, CPU_CLOCK_MHZ - 1);   // 1 MHz
-       timer_set_mode(TIM1, TIM_CR1_CKD_CK_INT, TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP);
-       timer_update_on_overflow(TIM1);
-       timer_disable_preload(TIM1);
-       timer_one_shot_mode(TIM1);
-}
-
-static void delay_us(uint us)
-{
-       timer_set_period(TIM1, us - 1);
-       timer_generate_event(TIM1, TIM_EGR_UG);
-       timer_enable_counter(TIM1);
-       while (TIM_CR1(TIM1) & TIM_CR1_CEN)
-               ;
-}
-
-/*** Display ***/
-
-/*
- *     The display is connected via the PCF8574 I2C I/O expander.
- *     Expander I/O lines are connected to the display as follows:
- *
- *     bit 0   RS (0=instruction input, 1=data input)
- *     bit 1   R/W*
- *     bit 2   E (enable)
- *     bit 3   backlight enable
- *     b. 4-7  DB4-7
- */
-
-enum lcd_bit {
-       LCD_BIT_RS = 0x01,
-       LCD_BIT_R = 0x02,
-       LCD_BIT_E = 0x04,
-       LCD_BIT_BACKLIGHT = 0x08,
-};
-
-enum lcd_command {
-       LCD_CMD_CLEAR_DISPLAY = 0x01,
-       LCD_CMD_RETURN_HOME = 0x02,
-       LCD_CMD_ENTRY_MODE_SET = 0x04,
-       LCD_CMD_DISPLAY_CONTROL = 0x08,
-       LCD_CMD_CURSOR_SHIFT = 0x10,
-       LCD_CMD_FUNCTION_SET = 0x20,
-       LCD_CMD_SET_CGRAM_ADDR = 0x40,
-       LCD_CMD_SET_DDRAM_ADDR = 0x80,
-};
-
-enum lcd_entry_mode {
-       LCD_ENTRY_INCREMENT = 0x02,
-       LCD_ENTRY_DECREMENT = 0x00,
-       LCD_ENTRY_SHIFT = 0x01,
-};
-
-enum lcd_control {
-       LCD_CTRL_DISPLAY_ON = 0x04,
-       LCD_CTRL_DISPLAY_OFF = 0x00,
-       LCD_CTRL_CURSOR_ON = 0x02,
-       LCD_CTRL_CURSOR_OFF = 0x00,
-       LCD_CTRL_BLINK_ON = 0x01,
-       LCD_CTRL_BLINK_OFF = 0x00,
-};
-
-// flags for display/cursor shift
-enum lcd_cursor_shift {
-       LCD_CURSOR_DISPLAY_MOVE = 0x08,
-       LCD_CURSOR_CURSOR_MOVE = 0x00,
-       LCD_CURSOR_MOVE_RIGHT = 0x04,
-       LCD_CURSOR_MOVE_LEFT = 0x00,
-};
-
-enum lcd_mode {
-       LCD_MODE_8BITMODE = 0x10,
-       LCD_MODE_4BITMODE = 0x00,
-       LCD_MODE_2LINE = 0x08,
-       LCD_MODE_1LINE = 0x00,
-       LCD_MODE_5x10DOTS = 0x04,
-       LCD_MODE_5x8DOTS = 0x00,
-};
-
-static byte display_backlight = LCD_BIT_BACKLIGHT;     // or 0
-
-static void display_pcf_write(byte value)
-{
-       value |= display_backlight;
-       i2c_transfer7(I2C2, 0x27, &value, 1, NULL, 0);
-}
-
-static void display_write_nibble(byte value)
-{
-       // Sends a nibble of data with a combination of control signals
-       display_pcf_write(value);
-       display_pcf_write(value | LCD_BIT_E);
-       delay_us(50);
-       display_pcf_write(value);
-       delay_us(50);
-}
-
-static void display_command(byte cmd)
-{
-       display_write_nibble(cmd & 0xf0);
-       display_write_nibble((cmd << 4) & 0xf0);
-}
-
-static void display_goto(uint row, uint col)
-{
-       display_command(LCD_CMD_SET_DDRAM_ADDR | (row * 0x40) | col);
-}
-
-static void display_char(byte ch)
-{
-       display_write_nibble((ch & 0xf0) | LCD_BIT_RS);
-       display_write_nibble(((ch << 4) & 0xf0) | LCD_BIT_RS);
-}
-
-static void display_hex8(uint x)
-{
-       uint h = (x >> 4) & 0x0f, l = x & 0x0f;
-       display_char('0' + h + (h >= 10 ? 7 : 0));
-       display_char('0' + l + (l >= 10 ? 7 : 0));
-}
-
-static void display_string(const char *str)
-{
-       while (*str)
-               display_char(*str++);
-}
-
-static void display_init(void)
-{
-       debug_puts("Display init\n");
-       i2c_peripheral_disable(I2C2);
-       i2c_set_speed(I2C2, i2c_speed_sm_100k, rcc_apb1_frequency / 1000000);
-       i2c_peripheral_enable(I2C2);
-
-       // We follow initialization sequence described in the datasheet.
-       // We need to wait at least 40ms after power rises above 2.7V.
-       delay_ms(50);
-
-       // RS and R/W should be low
-       display_pcf_write(0);
-       delay_ms(1000);
-
-       // Put display controller to 4-bit mode
-       display_write_nibble(0x30);
-       delay_ms(5);
-       display_write_nibble(0x30);
-       delay_ms(5);
-       display_write_nibble(0x30);
-       delay_ms(1);
-       display_write_nibble(0x20);
-
-       // Set mode
-       display_command(LCD_CMD_FUNCTION_SET | LCD_MODE_4BITMODE | LCD_MODE_2LINE | LCD_MODE_5x8DOTS);
-
-       // Turn display on and set cursor
-       display_command(LCD_CMD_DISPLAY_CONTROL | LCD_CTRL_DISPLAY_ON | LCD_CTRL_CURSOR_ON | LCD_CTRL_BLINK_ON);
-
-       // Configure text direction
-       display_command(LCD_CMD_ENTRY_MODE_SET | LCD_ENTRY_INCREMENT);
-
-       // Clear the display (this takes a long time)
-       display_command(LCD_CMD_CLEAR_DISPLAY);
-       delay_ms(2);
-
-       display_goto(0, 0);
-       display_string("Mnauky!");
-       display_goto(1, 0);
-
-       debug_puts("Display ready\n");
-}
-
-/*** Keyboard ***/
-
-static byte keyboard_step;
-static u16 keyboard_tmp;
-static u16 keyboard_debounce_mask;
-static byte keyboard_debounce_cnt;
-static u16 keyboard_mask;
-static char keyboard_char;
-
-#define KEYBOARD_DEBOUNCE_CYCLES 5
-
-static const char keyboard_map[] = "123A456B789C*0#D";
-
-static void keyboard_scan(void)
-{
-       // The first step does nothing since no row is activated.
-       uint cols = gpio_get(GPIOA, 0x0f) ^ 0x0f;
-       keyboard_tmp |= cols << 4 * keyboard_step;
-
-       if (++keyboard_step == 4) {
-               if (keyboard_tmp == keyboard_debounce_mask) {
-                       if (keyboard_debounce_cnt == KEYBOARD_DEBOUNCE_CYCLES) {
-                               keyboard_debounce_cnt++;
-                               keyboard_mask = keyboard_tmp;
-                               if (keyboard_mask && !(keyboard_mask & (keyboard_mask - 1))) {
-                                       for (uint i=0; i<16; i++)
-                                               if (keyboard_mask & (1 << i)) {
-                                                       keyboard_char = keyboard_map[i];
-                                                       break;
-                                               }
-                               } else {
-                                       keyboard_char = 0;
-                               }
-                       } else if (keyboard_debounce_cnt < KEYBOARD_DEBOUNCE_CYCLES) {
-                               keyboard_debounce_cnt++;
-                       }
-               } else {
-                       keyboard_debounce_mask = keyboard_tmp;
-                       keyboard_debounce_cnt = 0;
-               }
-               keyboard_step = 0;
-               keyboard_tmp = 0;
-       }
-
-       gpio_set(GPIOA, 0xf0);
-       gpio_clear(GPIOA, 0x10 << keyboard_step);
-}
-
-/*** Neopixels ***/
-
-#if 0
-
-#define NPIX_PERIOD 90         // timer runs on 72 MHz, so 90 periods = 1250 ns
-#define NPIX_RESET 64          // the chip needs longer reset pulse than documented
-#define NPIX_B0 30
-#define NPIX_B1 60
-
-static byte led_rgb[NPIX_NUM_LEDS][3];
-
-static byte neopixel_buf[NPIX_RESET + NPIX_NUM_LEDS*24 + 1];
-static bool neopixel_dma_running;
-static bool neopixel_want_send;
-
-static void neopixel_run_dma(void)
-{
-       // When STM32 is programmed using ST-Link, the DMA sometimes keeps running.
-       dma_channel_reset(DMA1, 7);
-
-       // This order of register writes is recommended in the manual.
-       dma_set_peripheral_address(DMA1, 7, (u32) &TIM_CCR3(TIM4));
-       dma_set_memory_address(DMA1, 7, (u32) neopixel_buf);
-       dma_set_number_of_data(DMA1, 7, ARRAY_SIZE(neopixel_buf));
-       dma_set_priority(DMA1, 7, DMA_CCR_PL_VERY_HIGH);
-
-       dma_set_read_from_memory(DMA1, 7);
-
-       dma_set_memory_size(DMA1, 7, DMA_CCR_MSIZE_8BIT);
-       dma_enable_memory_increment_mode(DMA1, 7);
-
-       dma_set_peripheral_size(DMA1, 7, DMA_CCR_PSIZE_16BIT);
-       dma_disable_peripheral_increment_mode(DMA1, 7);
-
-       dma_clear_interrupt_flags(DMA1, 7, DMA_TCIF);
-       dma_enable_channel(DMA1, 7);
-       neopixel_dma_running = 1;
-}
-
-static void neopixel_recalc(void)
-{
-       byte *buf = neopixel_buf;
-       for (uint i = 0; i < NPIX_RESET; i++)
-               *buf++ = 0;
-       for (uint i = 0; i < NPIX_NUM_LEDS; i++) {
-               // The order is GRB, MSB first
-               for (uint m = 0x80; m; m >>= 1)
-                       *buf++ = ((led_rgb[i][1] & m) ? NPIX_B1 : NPIX_B0);
-               for (uint m = 0x80; m; m >>= 1)
-                       *buf++ = ((led_rgb[i][0] & m) ? NPIX_B1 : NPIX_B0);
-               for (uint m = 0x80; m; m >>= 1)
-                       *buf++ = ((led_rgb[i][2] & m) ? NPIX_B1 : NPIX_B0);
-       }
-       *buf++ = NPIX_PERIOD;
-
-       neopixel_run_dma();
-       neopixel_want_send = 0;
-}
-
-static void neopixel_init(void)
-{
-       // TIM4 is always running and producing DMA requests on each update
-       // (connected to DMA1 channel 7). When we have something to send,
-       // the DMA is enabled.
-
-       timer_set_prescaler(TIM4, 0);
-       timer_set_mode(TIM4, TIM_CR1_CKD_CK_INT, TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP);
-       timer_disable_preload(TIM4);
-       timer_set_period(TIM4, NPIX_PERIOD - 1);
-
-       timer_set_oc_mode(TIM4, TIM_OC3, TIM_OCM_PWM1);
-       timer_set_oc_value(TIM4, TIM_OC3, 0);
-       timer_set_oc_polarity_high(TIM4, TIM_OC3);
-       timer_enable_oc_output(TIM4, TIM_OC3);
-
-       timer_set_dma_on_update_event(TIM4);
-       TIM_DIER(TIM4) |= TIM_DIER_UDE;
-
-       led_rgb[NPIX_NUM_LEDS-1][1] = 0xaa;
-
-       timer_enable_counter(TIM4);
-       neopixel_recalc();
-}
-
-static bool neopixel_ready(void)
-{
-       if (!neopixel_dma_running)
-               return 1;
-
-       if (!dma_get_interrupt_flag(DMA1, 7, DMA_TCIF))
-               return 0;
-
-       dma_disable_channel(DMA1, 7);
-       neopixel_dma_running = 0;
-       return 1;
-}
-
-#endif
-
-/*** USB ***/
-
-static usbd_device *usbd_dev;
-
-enum usb_string {
-       STR_MANUFACTURER = 1,
-       STR_PRODUCT,
-       STR_SERIAL,
-};
-
-static char usb_serial_number[13];
-
-static const char *usb_strings[] = {
-       "United Computer Wizards",
-       "Waiting Room Controller",
-       usb_serial_number,
-};
-
-static const struct usb_device_descriptor device = {
-       .bLength = USB_DT_DEVICE_SIZE,
-       .bDescriptorType = USB_DT_DEVICE,
-       .bcdUSB = 0x0200,
-       .bDeviceClass = 0xFF,
-       .bDeviceSubClass = 0,
-       .bDeviceProtocol = 0,
-       .bMaxPacketSize0 = 64,
-       .idVendor = NPIX_USB_VENDOR,
-       .idProduct = NPIX_USB_PRODUCT,
-       .bcdDevice = NPIX_USB_VERSION,
-       .iManufacturer = STR_MANUFACTURER,
-       .iProduct = STR_PRODUCT,
-       .iSerialNumber = STR_SERIAL,
-       .bNumConfigurations = 1,
-};
-
-static const struct usb_endpoint_descriptor endpoints[] = {{
-       // Bulk end-point
-       .bLength = USB_DT_ENDPOINT_SIZE,
-       .bDescriptorType = USB_DT_ENDPOINT,
-       .bEndpointAddress = 0x01,
-       .bmAttributes = USB_ENDPOINT_ATTR_BULK,
-       .wMaxPacketSize = 64,
-       .bInterval = 1,
-}};
-
-static const struct usb_interface_descriptor iface = {
-       .bLength = USB_DT_INTERFACE_SIZE,
-       .bDescriptorType = USB_DT_INTERFACE,
-       .bInterfaceNumber = 0,
-       .bAlternateSetting = 0,
-       .bNumEndpoints = 1,
-       .bInterfaceClass = 0xFF,
-       .bInterfaceSubClass = 0,
-       .bInterfaceProtocol = 0,
-       .iInterface = 0,
-       .endpoint = endpoints,
-};
-
-static const struct usb_dfu_descriptor dfu_function = {
-       .bLength = sizeof(struct usb_dfu_descriptor),
-       .bDescriptorType = DFU_FUNCTIONAL,
-       .bmAttributes = USB_DFU_CAN_DOWNLOAD | USB_DFU_WILL_DETACH,
-       .wDetachTimeout = 255,
-       .wTransferSize = 1024,
-       .bcdDFUVersion = 0x0100,
-};
-
-static const struct usb_interface_descriptor dfu_iface = {
-       .bLength = USB_DT_INTERFACE_SIZE,
-       .bDescriptorType = USB_DT_INTERFACE,
-       .bInterfaceNumber = 1,
-       .bAlternateSetting = 0,
-       .bNumEndpoints = 0,
-       .bInterfaceClass = 0xFE,
-       .bInterfaceSubClass = 1,
-       .bInterfaceProtocol = 1,
-       .iInterface = 0,
-
-       .extra = &dfu_function,
-       .extralen = sizeof(dfu_function),
-};
-
-static const struct usb_interface ifaces[] = {{
-       .num_altsetting = 1,
-       .altsetting = &iface,
-}, {
-       .num_altsetting = 1,
-       .altsetting = &dfu_iface,
-}};
-
-static const struct usb_config_descriptor config = {
-       .bLength = USB_DT_CONFIGURATION_SIZE,
-       .bDescriptorType = USB_DT_CONFIGURATION,
-       .wTotalLength = 0,
-       .bNumInterfaces = 2,
-       .bConfigurationValue = 1,
-       .iConfiguration = 0,
-       .bmAttributes = 0x80,
-       .bMaxPower = 100,       // multiplied by 2 mA
-       .interface = ifaces,
-};
-
-static byte usb_configured;
-static uint8_t usbd_control_buffer[64];
-
-static void dfu_detach_complete(usbd_device *dev UNUSED, struct usb_setup_data *req UNUSED)
-{
-       // Reset to bootloader, which implements the rest of DFU
-       debug_printf("Switching to DFU\n");
-       debug_flush();
-       scb_reset_core();
-}
-
-static enum usbd_request_return_codes dfu_control_cb(usbd_device *dev UNUSED,
-       struct usb_setup_data *req,
-       uint8_t **buf UNUSED,
-       uint16_t *len UNUSED,
-       void (**complete)(usbd_device *dev, struct usb_setup_data *req))
-{
-       if (req->bmRequestType != 0x21 || req->bRequest != DFU_DETACH)
-               return USBD_REQ_NOTSUPP;
-
-       *complete = dfu_detach_complete;
-       return USBD_REQ_HANDLED;
-}
-
-static byte usb_rx_buf[64];
-
-static void ep01_cb(usbd_device *dev, uint8_t ep UNUSED)
-{
-       // We received a frame from the USB host
-       uint len = usbd_ep_read_packet(dev, 0x01, usb_rx_buf, sizeof(usb_rx_buf));
-       debug_printf("USB: Host sent %u bytes\n", len);
-}
-
-static void set_config_cb(usbd_device *dev, uint16_t wValue UNUSED)
-{
-       usbd_register_control_callback(
-               dev,
-               USB_REQ_TYPE_CLASS | USB_REQ_TYPE_INTERFACE,
-               USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT,
-               dfu_control_cb);
-       usbd_ep_setup(dev, 0x01, USB_ENDPOINT_ATTR_BULK, 64, ep01_cb);
-       usb_configured = 1;
-}
-
-static void reset_cb(void)
-{
-       debug_printf("USB: Reset\n");
-       usb_configured = 0;
-}
-
-static volatile bool usb_event_pending;
-
-void usb_lp_can_rx0_isr(void)
-{
-       /*
-        *  We handle USB in the main loop to avoid race conditions between
-        *  USB interrupts and other code. However, we need an interrupt to
-        *  up the main loop from sleep.
-        *
-        *  We set up only the low-priority ISR, because high-priority ISR handles
-        *  only double-buffered bulk transfers and isochronous transfers.
-        */
-       nvic_disable_irq(NVIC_USB_LP_CAN_RX0_IRQ);
-       usb_event_pending = 1;
-}
-
-static void usb_init(void)
-{
-       // Simulate USB disconnect
-       gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ, GPIO_CNF_OUTPUT_OPENDRAIN, GPIO11 | GPIO12);
-       gpio_clear(GPIOA, GPIO11 | GPIO12);
-       delay_ms(100);
-
-       usbd_dev = usbd_init(
-               &st_usbfs_v1_usb_driver,
-               &device,
-               &config,
-               usb_strings,
-               ARRAY_SIZE(usb_strings),
-               usbd_control_buffer,
-               sizeof(usbd_control_buffer)
-       );
-       usbd_register_reset_callback(usbd_dev, reset_cb);
-       usbd_register_set_config_callback(usbd_dev, set_config_cb);
-       usb_event_pending = 1;
-}
-
-/*** Main ***/
-
-int main(void)
-{
-       clock_init();
-       gpio_init();
-       usart_init();
-       tick_init();
-       delay_init();
-       display_init();
-       // neopixel_init();
-       usb_init();
-
-       u32 last_blink = 0;
-       // u32 last_send = 0;
-       uint key_column = 0;
-
-       for (;;) {
-               keyboard_scan();
-#if 0
-               if (keyboard_mask != last_key_mask) {
-                       last_key_mask = keyboard_mask;
-                       display_goto(1, 0);
-                       display_hex8((keyboard_mask >> 8) & 0xff);
-                       display_hex8(keyboard_mask & 0xff);
-               }
-#endif
-               if (keyboard_char) {
-                       if (key_column < 15) {
-                               display_goto(1, key_column++);
-                               display_char(keyboard_char);
-                       }
-                       keyboard_char = 0;
-               }
-
-               if (ms_ticks - last_blink >= 300) {
-                       debug_led_toggle();
-                       last_blink = ms_ticks;
-               }
-
-               if (usb_event_pending) {
-                       usbd_poll(usbd_dev);
-                       usb_event_pending = 0;
-                       nvic_clear_pending_irq(NVIC_USB_LP_CAN_RX0_IRQ);
-                       nvic_enable_irq(NVIC_USB_LP_CAN_RX0_IRQ);
-               }
-
-#if 0
-               if (neopixel_ready()) {
-                       if (neopixel_want_send || ms_ticks - last_send >= 100) {
-                               // Re-send every 100 ms
-                               neopixel_recalc();
-                               last_send = ms_ticks;
-                       }
-               }
-#endif
-
-               wait_for_interrupt();
-       }
-
-       return 0;
-}
diff --git a/waiting/microbit/README b/waiting/microbit/README
deleted file mode 100644 (file)
index 07ba8e6..0000000
+++ /dev/null
@@ -1,18 +0,0 @@
-pip install uflash ufs
-# Download latest release from https://github.com/microbit-foundation/micropython-microbit-v2
-
-(venv) mj@albireo:/tmp/upython$ pmount /dev/sdh
-(venv) mj@albireo:/tmp/upython$ cp micropython-microbit-v2.1.2.hex /media/sdh/
-# v1 není kompatibilní s deskami v2
-(venv) mj@albireo:/tmp/upython$ pumount /dev/sdh
-
-# REPL
-./kerm
-
-ufs put main.py
-
-# MicroPython doc:
-https://microbit-micropython.readthedocs.io/en/latest/
-
-# Wukong doc:
-https://www.elecfreaks.com/learn-en/microbitExtensionModule/wukong.html#software-programming-python-editor
diff --git a/waiting/microbit/Wukong.py b/waiting/microbit/Wukong.py
deleted file mode 100644 (file)
index a2d7216..0000000
+++ /dev/null
@@ -1,90 +0,0 @@
-from microbit import *
-
-WUKONG_ADDR = 0x10
-
-
-class WUKONG(object):
-    """基本描述
-
-    悟空多功能主控板
-
-    """
-
-    def __init__(self):
-        i2c.init()
-
-    def set_motors(self, motor, speed):
-        """基本描述
-
-        选择电机并且设置速度
-
-        Args:
-            motor (number): 选择第几个电机 1,2
-            speed (number): 设置电机速度 -100~100
-        """
-        if speed > 100 or speed < -100:
-            raise ValueError('speed error,-100~100')
-        if motor > 2 or motor < 1:
-            raise ValueError('select motor error,1,2,3,4')
-        if speed < 0:
-            i2c.write(WUKONG_ADDR, bytearray([motor, 0x02, speed * -1, 0]))
-        else:
-            i2c.write(WUKONG_ADDR, bytearray([motor, 0x01, speed, 0]))
-
-    def set_servo(self, servo, angle):
-        """基本描述
-
-        选择伺服电机并且设置角度/速度
-
-        Args:
-            servo (number): 选择第几个舵机(伺服电机)0,1,2,3,4,5,6,7
-            angle (number): 设置舵机角度 0~180
-        """
-        if servo > 7 or servo < 0:
-            raise ValueError('select servo error')
-        if angle > 180 or angle < 0:
-            raise ValueError('angle error,0~180')
-        if servo == 7:
-            i2c.write(WUKONG_ADDR, bytearray([0x10, angle, 0, 0]))
-        else:
-            i2c.write(WUKONG_ADDR, bytearray([servo + 3, angle, 0, 0]))
-
-    def set_light(self, light):
-        """基本描述
-
-        设置氛围灯亮度
-
-        Args:
-            light (number): 氛围灯亮度
-        """
-        i2c.write(WUKONG_ADDR, bytearray([0x12, light, 0, 0]))
-        sleep(100)
-        i2c.write(WUKONG_ADDR, bytearray([0x11, 160, 0, 0]))
-
-    def set_light_breath(self, br: bool):
-        """基本描述
-
-        设置氛围灯呼吸模式
-
-        Args:
-            br (bool): 氛围灯呼吸模式开关
-        """
-        if br:
-            i2c.write(WUKONG_ADDR, bytearray([0x11, 0, 0, 0]))
-            sleep(100)
-            i2c.write(WUKONG_ADDR, bytearray([0x12, 150, 0, 0]))
-        else:
-            i2c.write(WUKONG_ADDR, bytearray([0x12, 0, 0, 0]))
-            sleep(100)
-            i2c.write(WUKONG_ADDR, bytearray([0x11, 160, 0, 0]))
-
-
-if __name__ == '__main__':
-    wk = WUKONG()
-
-    wk.set_motors(1, 100)
-    wk.set_servo(1, 90)
-    if button_a.is_pressed():
-        wk.set_light_breath(False)
-    else:
-        wk.set_light_breath(True)
diff --git a/waiting/microbit/main.py b/waiting/microbit/main.py
deleted file mode 100644 (file)
index 46b20c0..0000000
+++ /dev/null
@@ -1,32 +0,0 @@
-from microbit import *
-import neopixel
-import Wukong
-
-display.show(Image.HAPPY)
-
-np = neopixel.NeoPixel(pin16, 4)
-np[0] = (0, 15, 0)
-np.show()
-
-wk = Wukong.WUKONG()
-wk.set_light(10)
-wk.set_motors(1, 0)
-
-def gate_open():
-    display.show(Image.HEART)
-    wk.set_servo(0, 90 // 2)
-    np[1] = (15, 0, 0)
-    np.show()
-
-def gate_close():
-    display.show(Image.HAPPY)
-    wk.set_servo(0, 0)
-    np[1] = (0, 0, 0)
-    np.show()
-
-while True:
-    if button_a.is_pressed():
-        gate_open()
-    if button_b.is_pressed():
-        gate_close()
-    sleep(100)