Skip to content

Commit

Permalink
Basic USB host support and keyboard workflow
Browse files Browse the repository at this point in the history
Connects up read, write and ctrl_transfer to TinyUSB. USB Host
support is available on iMX RT and RP2040.

Fixes micropython#6527 (imx) and fixes micropython#5986 (rp2).
  • Loading branch information
tannewt committed Jul 10, 2023
1 parent 95535a8 commit 2686bea
Show file tree
Hide file tree
Showing 32 changed files with 812 additions and 63 deletions.
4 changes: 4 additions & 0 deletions .gitmodules
Original file line number Diff line number Diff line change
Expand Up @@ -341,3 +341,7 @@
[submodule "frozen/Adafruit_CircuitPython_Wave"]
path = frozen/Adafruit_CircuitPython_Wave
url = http://github.com/adafruit/Adafruit_CircuitPython_Wave.git
[submodule "ports/raspberrypi/lib/Pico-PIO-USB"]
path = ports/raspberrypi/lib/Pico-PIO-USB
url = https://github.com/sekigon-gonnoc/Pico-PIO-USB.git
branch = main
2 changes: 1 addition & 1 deletion lib/tinyusb
Submodule tinyusb updated 462 files
9 changes: 5 additions & 4 deletions locale/circuitpython.pot
Original file line number Diff line number Diff line change
Expand Up @@ -471,12 +471,17 @@ msgstr ""
msgid "All channels in use"
msgstr ""

#: ports/raspberrypi/common-hal/usb_host/Port.c
msgid "All dma channels in use"
msgstr ""

#: ports/atmel-samd/common-hal/audioio/AudioOut.c
msgid "All event channels in use"
msgstr ""

#: ports/raspberrypi/common-hal/picodvi/Framebuffer.c
#: ports/raspberrypi/common-hal/rp2pio/StateMachine.c
#: ports/raspberrypi/common-hal/usb_host/Port.c
msgid "All state machines in use"
msgstr ""

Expand Down Expand Up @@ -1950,10 +1955,6 @@ msgstr ""
msgid "Size not supported"
msgstr ""

#: ports/raspberrypi/common-hal/alarm/SleepMemory.c
msgid "Sleep Memory not available"
msgstr ""

#: shared-bindings/alarm/SleepMemory.c shared-bindings/memorymap/AddressRange.c
#: shared-bindings/nvm/ByteArray.c
msgid "Slice and value different lengths."
Expand Down
25 changes: 16 additions & 9 deletions ports/mimxrt10xx/Makefile
Original file line number Diff line number Diff line change
Expand Up @@ -229,12 +229,19 @@ include $(TOP)/py/mkrules.mk
print-%:
@echo $* = $($*)

ifeq ($(CHIP_FAMILY), MIMXRT1062)
PYOCD_TARGET = mimxrt1060
endif

# Flash using pyocd
PYOCD_OPTION ?=
flash: $(BUILD)/firmware.hex
pyocd flash -t $(PYOCD_TARGET) $(PYOCD_OPTION) $<
pyocd reset -t $(PYOCD_TARGET)
# Flash using jlink
define jlink_script
halt
loadfile $^
r
go
exit
endef
export jlink_script

JLINKEXE = JLinkExe
flash-jlink: $(BUILD)/firmware.elf
@echo "$$jlink_script" > $(BUILD)/firmware.jlink
$(JLINKEXE) -device $(CHIP_FAMILY)xxx5A -if swd -JTAGConf -1,-1 -speed auto -CommandFile $(BUILD)/firmware.jlink

flash: flash-jlink
4 changes: 2 additions & 2 deletions ports/mimxrt10xx/boards/imxrt1060_evk/mpconfigboard.h
Original file line number Diff line number Diff line change
Expand Up @@ -21,5 +21,5 @@

// Put host on the first USB so that right angle OTG adapters can fit. This is
// the right port when looking at the board.
#define CIRCUITPY_USB_DEVICE_INSTANCE 1
#define CIRCUITPY_USB_HOST_INSTANCE 0
#define CIRCUITPY_USB_DEVICE_INSTANCE 0
#define CIRCUITPY_USB_HOST_INSTANCE 1
7 changes: 7 additions & 0 deletions ports/mimxrt10xx/linking/common.ld
Original file line number Diff line number Diff line change
Expand Up @@ -72,6 +72,7 @@ SECTIONS
*(EXCLUDE_FILE(
*fsl_flexspi.o
*dcd_ci_hs.o
*ehci.o
*tusb_fifo.o
*usbd.o
*string0.o
Expand All @@ -88,6 +89,11 @@ SECTIONS
We try to only keep USB interrupt related functions. */
*dcd_ci_hs.o(.text.process_*_request .text.dcd_edpt* .text.dcd_init .text.dcd_set_address)
*usbd.o(.text.process_*_request .text.process_[gs]et* .text.tud_* .text.usbd_* .text.configuration_reset .text.invoke_*)
*ehci.o(.text.hcd_edpt* .text.hcd_setup* .text.ehci_init* .text.hcd_port* .text.hcd_device* .text.qtd_init* .text.list_remove*)

/* Less critical portions of the runtime. */
*runtime.o(.text.mp_import* .text.mp_resume* .text.mp_make_raise* .text.mp_init)
*gc.o(.text.gc_never_free .text.gc_make_long_lived)

/* Anything marked cold/unlikely should be in flash. */
*(.text.unlikely.*)
Expand Down Expand Up @@ -146,6 +152,7 @@ SECTIONS
*(.itcm.*)
*fsl_flexspi.o(.text*)
*dcd_ci_hs.o(.text*)
*ehci.o(.text*)
*tusb_fifo.o(.text*)
*py/objboundmeth.o(.text*)
*py/objtype.o(.text*)
Expand Down
14 changes: 13 additions & 1 deletion ports/raspberrypi/Makefile
Original file line number Diff line number Diff line change
Expand Up @@ -148,7 +148,7 @@ INC += \
CFLAGS += -DRASPBERRYPI -DPICO_ON_DEVICE=1 -DPICO_NO_BINARY_INFO=0 -DPICO_TIME_DEFAULT_ALARM_POOL_DISABLED=0 -DPICO_DIVIDER_CALL_IDIV0=0 -DPICO_DIVIDER_CALL_LDIV0=0 -DPICO_DIVIDER_HARDWARE=1 -DPICO_DOUBLE_ROM=1 -DPICO_FLOAT_ROM=1 -DPICO_MULTICORE=1 -DPICO_BITS_IN_RAM=0 -DPICO_DIVIDER_IN_RAM=0 -DPICO_DOUBLE_PROPAGATE_NANS=0 -DPICO_DOUBLE_IN_RAM=0 -DPICO_MEM_IN_RAM=0 -DPICO_FLOAT_IN_RAM=0 -DPICO_FLOAT_PROPAGATE_NANS=1 -DPICO_NO_FLASH=0 -DPICO_COPY_TO_RAM=0 -DPICO_DISABLE_SHARED_IRQ_HANDLERS=0 -DPICO_NO_BI_BOOTSEL_VIA_DOUBLE_RESET=0 -DDVI_1BPP_BIT_REVERSE=0
OPTIMIZATION_FLAGS ?= -O3
# TinyUSB defines
CFLAGS += -DTUD_OPT_RP2040_USB_DEVICE_ENUMERATION_FIX=1 -DCFG_TUSB_MCU=OPT_MCU_RP2040 -DCFG_TUD_MIDI_RX_BUFSIZE=128 -DCFG_TUD_CDC_RX_BUFSIZE=256 -DCFG_TUD_MIDI_TX_BUFSIZE=128 -DCFG_TUD_CDC_TX_BUFSIZE=256 -DCFG_TUD_MSC_BUFSIZE=1024
CFLAGS += -DCFG_TUSB_OS=OPT_OS_PICO -DTUD_OPT_RP2040_USB_DEVICE_ENUMERATION_FIX=1 -DCFG_TUSB_MCU=OPT_MCU_RP2040 -DCFG_TUD_MIDI_RX_BUFSIZE=128 -DCFG_TUD_CDC_RX_BUFSIZE=256 -DCFG_TUD_MIDI_TX_BUFSIZE=128 -DCFG_TUD_CDC_TX_BUFSIZE=256 -DCFG_TUD_MSC_BUFSIZE=1024

# option to override default optimization level, set in boards/$(BOARD)/mpconfigboard.mk
CFLAGS += $(OPTIMIZATION_FLAGS)
Expand Down Expand Up @@ -258,6 +258,18 @@ SRC_C += \
$(SRC_CYW43) \
$(SRC_LWIP) \


ifeq ($(CIRCUITPY_USB_HOST), 1)
SRC_C += \
lib/tinyusb/src/portable/raspberrypi/pio_usb/hcd_pio_usb.c \
lib/Pico-PIO-USB/src/pio_usb.c \
lib/Pico-PIO-USB/src/pio_usb_host.c \
lib/Pico-PIO-USB/src/usb_crc.c \

INC += \
-isystem lib/Pico-PIO-USB/src
endif

ifeq ($(CIRCUITPY_PICODVI),1)
SRC_C += \
bindings/picodvi/__init__.c \
Expand Down
14 changes: 14 additions & 0 deletions ports/raspberrypi/boards/adafruit_feather_rp2040_usb_host/board.c
Original file line number Diff line number Diff line change
Expand Up @@ -26,4 +26,18 @@

#include "supervisor/board.h"

#include "shared-bindings/digitalio/DigitalInOut.h"
#include "shared-bindings/usb_host/Port.h"

// Use the MP_WEAK supervisor/shared/board.c versions of routines not defined here.

usb_host_port_obj_t _host_port;
digitalio_digitalinout_obj_t _host_power;

void board_init(void) {
common_hal_digitalio_digitalinout_construct(&_host_power, &pin_GPIO18);
common_hal_digitalio_digitalinout_never_reset(&_host_power);
common_hal_digitalio_digitalinout_switch_to_output(&_host_power, true, DRIVE_MODE_PUSH_PULL);

common_hal_usb_host_port_construct(&_host_port, &pin_GPIO16, &pin_GPIO17);
}
Original file line number Diff line number Diff line change
Expand Up @@ -12,3 +12,8 @@

#define DEFAULT_UART_BUS_RX (&pin_GPIO1)
#define DEFAULT_UART_BUS_TX (&pin_GPIO0)

#define CIRCUITPY_CONSOLE_UART_RX DEFAULT_UART_BUS_RX
#define CIRCUITPY_CONSOLE_UART_TX DEFAULT_UART_BUS_TX

#define CIRCUITPY_USB_HOST_INSTANCE 1
2 changes: 2 additions & 0 deletions ports/raspberrypi/common-hal/rp2pio/StateMachine.h
Original file line number Diff line number Diff line change
Expand Up @@ -98,6 +98,8 @@ void rp2pio_statemachine_dma_complete(rp2pio_statemachine_obj_t *self, int chann
void rp2pio_statemachine_reset_ok(PIO pio, int sm);
void rp2pio_statemachine_never_reset(PIO pio, int sm);

uint8_t rp2pio_statemachine_find_pio(int program_size, int sm_count);

extern const mp_obj_type_t rp2pio_statemachine_type;

#endif // MICROPY_INCLUDED_RASPBERRYPI_COMMON_HAL_RP2PIO_STATEMACHINE_H
165 changes: 165 additions & 0 deletions ports/raspberrypi/common-hal/usb_host/Port.c
Original file line number Diff line number Diff line change
@@ -0,0 +1,165 @@
/*
* This file is part of the Micro Python project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2022 Scott Shawcroft for Adafruit Industries
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/

#include "bindings/rp2pio/StateMachine.h"
#include "shared-bindings/microcontroller/Pin.h"
#include "shared-bindings/microcontroller/Processor.h"
#include "shared-bindings/usb_host/Port.h"
#include "supervisor/usb.h"

#include "src/common/pico_time/include/pico/time.h"
#include "src/rp2040/hardware_structs/include/hardware/structs/mpu.h"
#include "src/rp2_common/cmsis/stub/CMSIS/Device/RaspberryPi/RP2040/Include/RP2040.h"
#include "src/rp2_common/hardware_dma/include/hardware/dma.h"
#include "src/rp2_common/pico_multicore/include/pico/multicore.h"

#include "py/runtime.h"

#include "tusb.h"

#include "lib/Pico-PIO-USB/src/pio_usb.h"
#include "lib/Pico-PIO-USB/src/pio_usb_configuration.h"

#include "supervisor/serial.h"

bool usb_host_init;

STATIC PIO pio_instances[2] = {pio0, pio1};
volatile bool _core1_ready = false;

static void __not_in_flash_func(core1_main)(void) {
// The MPU is reset before this starts.
SysTick->LOAD = (uint32_t)((common_hal_mcu_processor_get_frequency() / 1000) - 1UL);
SysTick->VAL = 0UL; /* Load the SysTick Counter Value */
SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | // Processor clock.
SysTick_CTRL_ENABLE_Msk;

// Turn off flash access. After this, it will hard fault. Better than messing
// up CIRCUITPY.
MPU->CTRL = MPU_CTRL_PRIVDEFENA_Msk | MPU_CTRL_ENABLE_Msk;
MPU->RNR = 6; // 7 is used by pico-sdk stack protection.
MPU->RBAR = XIP_MAIN_BASE | MPU_RBAR_VALID_Msk;
MPU->RASR = MPU_RASR_XN_Msk | // Set execute never and everything else is restricted.
MPU_RASR_ENABLE_Msk |
(0x1b << MPU_RASR_SIZE_Pos); // Size is 0x10000000 which masks up to SRAM region.
MPU->RNR = 7;

_core1_ready = true;

while (true) {
pio_usb_host_frame();
if (tuh_task_event_ready()) {
// Queue the tinyusb background task.
usb_background_schedule();
}
// Wait for systick to reload.
while ((SysTick->CTRL & SysTick_CTRL_COUNTFLAG_Msk) == 0) {
}
}
}

STATIC uint8_t _sm_free_count(uint8_t pio_index) {
PIO pio = pio_instances[pio_index];
uint8_t free_count = 0;
for (size_t j = 0; j < NUM_PIO_STATE_MACHINES; j++) {
if (!pio_sm_is_claimed(pio, j)) {
free_count++;
}
}
return free_count;
}

STATIC bool _has_program_room(uint8_t pio_index, uint8_t program_size) {
PIO pio = pio_instances[pio_index];
pio_program_t program_struct = {
.instructions = NULL,
.length = program_size,
.origin = -1
};
return pio_can_add_program(pio, &program_struct);
}

void common_hal_usb_host_port_construct(usb_host_port_obj_t *self, const mcu_pin_obj_t *dp, const mcu_pin_obj_t *dm) {
if (dp->number + 1 != dm->number) {
raise_ValueError_invalid_pins();
}
pio_usb_configuration_t pio_cfg = PIO_USB_DEFAULT_CONFIG;
pio_cfg.skip_alarm_pool = true;
pio_cfg.pin_dp = dp->number;
pio_cfg.pio_tx_num = 0;
pio_cfg.pio_rx_num = 1;
// PIO with room for 22 instructions
// PIO with room for 31 instructions and two free SM.
if (!_has_program_room(pio_cfg.pio_tx_num, 22) || _sm_free_count(pio_cfg.pio_tx_num) < 1 ||
!_has_program_room(pio_cfg.pio_rx_num, 31) || _sm_free_count(pio_cfg.pio_rx_num) < 2) {
mp_raise_RuntimeError(translate("All state machines in use"));
}
pio_cfg.tx_ch = dma_claim_unused_channel(false); // DMA channel
if (pio_cfg.tx_ch < 0) {
mp_raise_RuntimeError(translate("All dma channels in use"));
}

PIO tx_pio = pio_instances[pio_cfg.pio_tx_num];
pio_cfg.sm_tx = pio_claim_unused_sm(tx_pio, false);
PIO rx_pio = pio_instances[pio_cfg.pio_rx_num];
pio_cfg.sm_rx = pio_claim_unused_sm(rx_pio, false);
pio_cfg.sm_eop = pio_claim_unused_sm(rx_pio, false);

// Unclaim everything so that the library can.
dma_channel_unclaim(pio_cfg.tx_ch);
pio_sm_unclaim(tx_pio, pio_cfg.sm_tx);
pio_sm_unclaim(rx_pio, pio_cfg.sm_rx);
pio_sm_unclaim(rx_pio, pio_cfg.sm_eop);

// Set all of the state machines to never reset.
rp2pio_statemachine_never_reset(tx_pio, pio_cfg.sm_tx);
rp2pio_statemachine_never_reset(rx_pio, pio_cfg.sm_rx);
rp2pio_statemachine_never_reset(rx_pio, pio_cfg.sm_eop);

common_hal_never_reset_pin(dp);
common_hal_never_reset_pin(dm);

// Core 1 will run the SOF interrupt directly.
_core1_ready = false;
multicore_launch_core1(core1_main);
while (!_core1_ready) {
}

tuh_configure(TUH_OPT_RHPORT, TUH_CFGID_RPI_PIO_USB_CONFIGURATION, &pio_cfg);
tuh_init(TUH_OPT_RHPORT);

self->init = true;
usb_host_init = true;
}

void common_hal_usb_host_port_deinit(usb_host_port_obj_t *self) {
self->init = false;
usb_host_init = false;
}

bool common_hal_usb_host_port_deinited(usb_host_port_obj_t *self) {
return !self->init;
}
38 changes: 38 additions & 0 deletions ports/raspberrypi/common-hal/usb_host/Port.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
/*
* This file is part of the Micro Python project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2023 Scott Shawcroft for Adafruit Industries
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/

#pragma once

#include "py/obj.h"

typedef struct {
mp_obj_base_t base;
bool init;
} usb_host_port_obj_t;

// Cheater state so that the usb module knows if it should return the TinyUSB
// state.
extern bool usb_host_init;
Loading

0 comments on commit 2686bea

Please sign in to comment.