Basic USB host support and keyboard workflow
Connects up read, write and ctrl_transfer to TinyUSB. USB Host support is available on iMX RT and RP2040. Fixes #6527 (imx) and fixes #5986 (rp2).
This commit is contained in:
parent
95535a8cd0
commit
2686beab36
|
@ -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
|
||||
|
|
|
@ -1 +1 @@
|
|||
Subproject commit e3b3229d61676585879c81d5f2e3393a2a1f1b16
|
||||
Subproject commit f1e006d09bd32088ab421d0b519eb89c531eda4e
|
|
@ -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 ""
|
||||
|
||||
|
@ -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."
|
||||
|
|
|
@ -229,12 +229,19 @@ include $(TOP)/py/mkrules.mk
|
|||
print-%:
|
||||
@echo $* = $($*)
|
||||
|
||||
ifeq ($(CHIP_FAMILY), MIMXRT1062)
|
||||
PYOCD_TARGET = mimxrt1060
|
||||
endif
|
||||
# Flash using jlink
|
||||
define jlink_script
|
||||
halt
|
||||
loadfile $^
|
||||
r
|
||||
go
|
||||
exit
|
||||
endef
|
||||
export jlink_script
|
||||
|
||||
# Flash using pyocd
|
||||
PYOCD_OPTION ?=
|
||||
flash: $(BUILD)/firmware.hex
|
||||
pyocd flash -t $(PYOCD_TARGET) $(PYOCD_OPTION) $<
|
||||
pyocd reset -t $(PYOCD_TARGET)
|
||||
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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -72,6 +72,7 @@ SECTIONS
|
|||
*(EXCLUDE_FILE(
|
||||
*fsl_flexspi.o
|
||||
*dcd_ci_hs.o
|
||||
*ehci.o
|
||||
*tusb_fifo.o
|
||||
*usbd.o
|
||||
*string0.o
|
||||
|
@ -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.*)
|
||||
|
@ -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*)
|
||||
|
|
|
@ -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)
|
||||
|
@ -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 \
|
||||
|
|
|
@ -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);
|
||||
}
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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;
|
||||
}
|
|
@ -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;
|
|
@ -0,0 +1,27 @@
|
|||
/*
|
||||
* 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.
|
||||
*/
|
||||
|
||||
// Nothing
|
|
@ -0,0 +1 @@
|
|||
Subproject commit 5a7aa8d4e78f9a50e4fb9defcf3488b3fc44aff1
|
|
@ -80,7 +80,9 @@ SECTIONS
|
|||
*(.property_getset)
|
||||
__property_getset_end = .;
|
||||
|
||||
*(EXCLUDE_FILE(*libgcc.a: *libc.a:*lib_a-mem*.o *libm.a: *interp.o *divider.o) .text*)
|
||||
*(EXCLUDE_FILE(*libgcc.a: *libc.a:*lib_a-mem*.o *libm.a: *interp.o *divider.o *tusb_fifo.o *mem_ops_aeabi.o *usbh.o) .text*)
|
||||
/* Allow everything in usbh.o except tuh_task_event_ready because we read it from core 1. */
|
||||
*usbh.o (.text.[_uphc]* .text.tuh_[cmvied]* .text.tuh_task_ext*)
|
||||
*(.fini)
|
||||
/* Pull all c'tors into .text */
|
||||
*crtbegin.o(.ctors)
|
||||
|
@ -169,7 +171,7 @@ SECTIONS
|
|||
. = ALIGN(4);
|
||||
/* init data */
|
||||
PROVIDE_HIDDEN (__init_array_start = .);
|
||||
KEEP(*(SORT(.init_array.*)))
|
||||
KEEP(*(SORT(.init_array*)))
|
||||
KEEP(*(.init_array))
|
||||
PROVIDE_HIDDEN (__init_array_end = .);
|
||||
|
||||
|
@ -248,6 +250,7 @@ SECTIONS
|
|||
__scratch_x_start__ = .;
|
||||
*(.scratch_x.*)
|
||||
*tmds_encode.o (.time_critical*)
|
||||
*timer.o (.text.hardware_alarm_irq_handler)
|
||||
. = ALIGN(4);
|
||||
__scratch_x_end__ = .;
|
||||
} > SCRATCH_X AT > FLASH_FIRMWARE
|
||||
|
|
|
@ -48,6 +48,10 @@
|
|||
|
||||
#define CIRCUITPY_PROCESSOR_COUNT (2)
|
||||
|
||||
#if CIRCUITPY_USB_HOST
|
||||
#define CIRCUITPY_USB_HOST_INSTANCE 1
|
||||
#endif
|
||||
|
||||
// This also includes mpconfigboard.h.
|
||||
#include "py/circuitpy_mpconfig.h"
|
||||
|
||||
|
@ -64,4 +68,11 @@
|
|||
#define MICROPY_PY_LWIP_EXIT cyw43_arch_lwip_end();
|
||||
#endif
|
||||
|
||||
// Protect the background queue with a lock because both cores may modify it.
|
||||
#include "pico/critical_section.h"
|
||||
extern critical_section_t background_queue_lock;
|
||||
#define CALLBACK_CRITICAL_BEGIN (critical_section_enter_blocking(&background_queue_lock))
|
||||
#define CALLBACK_CRITICAL_END (critical_section_exit(&background_queue_lock))
|
||||
|
||||
|
||||
#endif // __INCLUDED_MPCONFIGPORT_H
|
||||
|
|
|
@ -20,6 +20,7 @@ CIRCUITPY_RGBMATRIX ?= $(CIRCUITPY_DISPLAYIO)
|
|||
CIRCUITPY_ROTARYIO ?= 1
|
||||
CIRCUITPY_ROTARYIO_SOFTENCODER = 1
|
||||
CIRCUITPY_SYNTHIO_MAX_CHANNELS = 12
|
||||
CIRCUITPY_USB_HOST ?= 1
|
||||
|
||||
# Things that need to be implemented.
|
||||
# Use PWM internally
|
||||
|
|
|
@ -76,6 +76,8 @@
|
|||
#include "tusb.h"
|
||||
#include <cmsis_compiler.h>
|
||||
|
||||
critical_section_t background_queue_lock;
|
||||
|
||||
extern volatile bool mp_msc_enabled;
|
||||
|
||||
STATIC void _tick_callback(uint alarm_num);
|
||||
|
@ -128,6 +130,9 @@ safe_mode_t port_init(void) {
|
|||
(&_ld_dtcm_bss_start)[i] = 0;
|
||||
}
|
||||
|
||||
// Set up the critical section to protect the background task queue.
|
||||
critical_section_init(&background_queue_lock);
|
||||
|
||||
#if CIRCUITPY_CYW43
|
||||
never_reset_pin_number(23);
|
||||
never_reset_pin_number(24);
|
||||
|
@ -299,7 +304,7 @@ void port_interrupt_after_ticks(uint32_t ticks) {
|
|||
|
||||
void port_idle_until_interrupt(void) {
|
||||
common_hal_mcu_disable_interrupts();
|
||||
if (!background_callback_pending() && !tud_task_event_ready() && !_woken_up) {
|
||||
if (!background_callback_pending() && !tud_task_event_ready() && !tuh_task_event_ready() && !_woken_up) {
|
||||
__DSB();
|
||||
__WFI();
|
||||
}
|
||||
|
|
|
@ -525,6 +525,9 @@ CFLAGS += -DCIRCUITPY_USB_HOST=$(CIRCUITPY_USB_HOST)
|
|||
CIRCUITPY_USB_IDENTIFICATION ?= $(CIRCUITPY_USB)
|
||||
CFLAGS += -DCIRCUITPY_USB_IDENTIFICATION=$(CIRCUITPY_USB_IDENTIFICATION)
|
||||
|
||||
CIRCUITPY_USB_KEYBOARD_WORKFLOW ?= $(CIRCUITPY_USB_HOST)
|
||||
CFLAGS += -DCIRCUITPY_USB_KEYBOARD_WORKFLOW=$(CIRCUITPY_USB_KEYBOARD_WORKFLOW)
|
||||
|
||||
# MIDI is available by default, but is not turned on if there are fewer than 8 endpoints.
|
||||
CIRCUITPY_USB_MIDI ?= $(CIRCUITPY_USB)
|
||||
CFLAGS += -DCIRCUITPY_USB_MIDI=$(CIRCUITPY_USB_MIDI)
|
||||
|
|
|
@ -123,6 +123,30 @@ MP_DEFINE_CONST_FUN_OBJ_1(usb_core_device_get_manufacturer_obj, usb_core_device_
|
|||
MP_PROPERTY_GETTER(usb_core_device_manufacturer_obj,
|
||||
(mp_obj_t)&usb_core_device_get_manufacturer_obj);
|
||||
|
||||
//| def set_configuration(self, configuration=None):
|
||||
//| """Set the active configuration.
|
||||
//|
|
||||
//| The configuration parameter is the bConfigurationValue field of the
|
||||
//| configuration you want to set as active. If you call this method
|
||||
//| without parameter, it will use the first configuration found. As a
|
||||
//| device hardly ever has more than one configuration, calling the method
|
||||
//| without arguments is enough to get the device ready.
|
||||
//| """
|
||||
//| ...
|
||||
STATIC mp_obj_t usb_core_device_set_configuration(size_t n_args, const mp_obj_t *pos_args, mp_map_t *kw_args) {
|
||||
enum { ARG_configuration };
|
||||
static const mp_arg_t allowed_args[] = {
|
||||
{ MP_QSTR_configuration, MP_ARG_INT, {.u_int = 0x100} },
|
||||
};
|
||||
usb_core_device_obj_t *self = MP_OBJ_TO_PTR(pos_args[0]);
|
||||
mp_arg_val_t args[MP_ARRAY_SIZE(allowed_args)];
|
||||
mp_arg_parse_all(n_args - 1, pos_args + 1, kw_args, MP_ARRAY_SIZE(allowed_args), allowed_args, args);
|
||||
|
||||
common_hal_usb_core_device_set_configuration(self, args[ARG_configuration].u_int);
|
||||
return mp_const_none;
|
||||
}
|
||||
MP_DEFINE_CONST_FUN_OBJ_KW(usb_core_device_set_configuration_obj, 1, usb_core_device_set_configuration);
|
||||
|
||||
//| def write(self, endpoint: int, data: ReadableBuffer, timeout: Optional[int] = None) -> int:
|
||||
//| """Write data to a specific endpoint on the device.
|
||||
//|
|
||||
|
@ -223,7 +247,10 @@ STATIC mp_obj_t usb_core_device_ctrl_transfer(size_t n_args, const mp_obj_t *pos
|
|||
|
||||
mp_buffer_info_t bufinfo;
|
||||
// check request type
|
||||
if ((args[ARG_bmRequestType].u_int & 0x80) != 0) {
|
||||
if (args[ARG_data_or_wLength].u_obj == mp_const_none) {
|
||||
bufinfo.len = 0;
|
||||
bufinfo.buf = NULL;
|
||||
} else if ((args[ARG_bmRequestType].u_int & 0x80) != 0) {
|
||||
mp_get_buffer_raise(args[ARG_data_or_wLength].u_obj, &bufinfo, MP_BUFFER_WRITE);
|
||||
} else {
|
||||
mp_get_buffer_raise(args[ARG_data_or_wLength].u_obj, &bufinfo, MP_BUFFER_READ);
|
||||
|
@ -292,6 +319,7 @@ STATIC const mp_rom_map_elem_t usb_core_device_locals_dict_table[] = {
|
|||
{ MP_ROM_QSTR(MP_QSTR_product), MP_ROM_PTR(&usb_core_device_product_obj) },
|
||||
{ MP_ROM_QSTR(MP_QSTR_manufacturer), MP_ROM_PTR(&usb_core_device_manufacturer_obj) },
|
||||
|
||||
{ MP_ROM_QSTR(MP_QSTR_set_configuration),MP_ROM_PTR(&usb_core_device_set_configuration_obj) },
|
||||
{ MP_ROM_QSTR(MP_QSTR_write), MP_ROM_PTR(&usb_core_device_write_obj) },
|
||||
{ MP_ROM_QSTR(MP_QSTR_read), MP_ROM_PTR(&usb_core_device_read_obj) },
|
||||
{ MP_ROM_QSTR(MP_QSTR_ctrl_transfer), MP_ROM_PTR(&usb_core_device_ctrl_transfer_obj) },
|
||||
|
|
|
@ -39,8 +39,9 @@ uint16_t common_hal_usb_core_device_get_idProduct(usb_core_device_obj_t *self);
|
|||
mp_obj_t common_hal_usb_core_device_get_serial_number(usb_core_device_obj_t *self);
|
||||
mp_obj_t common_hal_usb_core_device_get_product(usb_core_device_obj_t *self);
|
||||
mp_obj_t common_hal_usb_core_device_get_manufacturer(usb_core_device_obj_t *self);
|
||||
mp_obj_t common_hal_usb_core_device_write(usb_core_device_obj_t *self, mp_int_t endpoint, const uint8_t *buffer, mp_int_t len, mp_int_t timeout);
|
||||
mp_obj_t common_hal_usb_core_device_read(usb_core_device_obj_t *self, mp_int_t endpoint, uint8_t *buffer, mp_int_t len, mp_int_t timeout);
|
||||
void common_hal_usb_core_device_set_configuration(usb_core_device_obj_t *self, mp_int_t configuration);
|
||||
mp_int_t common_hal_usb_core_device_write(usb_core_device_obj_t *self, mp_int_t endpoint, const uint8_t *buffer, mp_int_t len, mp_int_t timeout);
|
||||
mp_int_t common_hal_usb_core_device_read(usb_core_device_obj_t *self, mp_int_t endpoint, uint8_t *buffer, mp_int_t len, mp_int_t timeout);
|
||||
mp_int_t common_hal_usb_core_device_ctrl_transfer(usb_core_device_obj_t *self,
|
||||
mp_int_t bmRequestType, mp_int_t bRequest,
|
||||
mp_int_t wValue, mp_int_t wIndex,
|
||||
|
|
|
@ -49,10 +49,15 @@
|
|||
//|
|
||||
MP_DEFINE_USB_CORE_EXCEPTION(USBError, OSError)
|
||||
NORETURN void mp_raise_usb_core_USBError(const compressed_string_t *fmt, ...) {
|
||||
mp_obj_t exception;
|
||||
if (fmt == NULL) {
|
||||
exception = mp_obj_new_exception(&mp_type_usb_core_USBError);
|
||||
} else {
|
||||
va_list argptr;
|
||||
va_start(argptr,fmt);
|
||||
mp_obj_t exception = mp_obj_new_exception_msg_vlist(&mp_type_usb_core_USBError, fmt, argptr);
|
||||
exception = mp_obj_new_exception_msg_vlist(&mp_type_usb_core_USBError, fmt, argptr);
|
||||
va_end(argptr);
|
||||
}
|
||||
nlr_raise(exception);
|
||||
}
|
||||
|
||||
|
|
|
@ -34,15 +34,30 @@
|
|||
#include "shared-bindings/usb/core/__init__.h"
|
||||
#include "shared-module/usb/utf16le.h"
|
||||
#include "supervisor/shared/tick.h"
|
||||
#include "supervisor/usb.h"
|
||||
|
||||
// Track what device numbers are mounted. We can't use tuh_ready() because it is
|
||||
// true before enumeration completes and TinyUSB drivers are started.
|
||||
STATIC size_t _mounted_devices = 0;
|
||||
|
||||
void tuh_mount_cb(uint8_t dev_addr) {
|
||||
_mounted_devices |= 1 << dev_addr;
|
||||
}
|
||||
|
||||
void tuh_umount_cb(uint8_t dev_addr) {
|
||||
_mounted_devices &= ~(1 << dev_addr);
|
||||
}
|
||||
|
||||
STATIC xfer_result_t _xfer_result;
|
||||
bool common_hal_usb_core_device_construct(usb_core_device_obj_t *self, uint8_t device_number) {
|
||||
if (device_number == 0 || device_number > CFG_TUH_DEVICE_MAX + CFG_TUH_HUB) {
|
||||
return false;
|
||||
}
|
||||
if (!tuh_ready(device_number)) {
|
||||
if ((_mounted_devices & (1 << device_number)) == 0) {
|
||||
return false;
|
||||
}
|
||||
self->device_number = device_number;
|
||||
_xfer_result = 0xff;
|
||||
return true;
|
||||
}
|
||||
|
||||
|
@ -60,19 +75,21 @@ uint16_t common_hal_usb_core_device_get_idProduct(usb_core_device_obj_t *self) {
|
|||
return pid;
|
||||
}
|
||||
|
||||
STATIC xfer_result_t _get_string_result;
|
||||
STATIC void _transfer_done_cb(tuh_xfer_t *xfer) {
|
||||
// Store the result so we stop waiting for the transfer.
|
||||
_get_string_result = xfer->result;
|
||||
_xfer_result = xfer->result;
|
||||
}
|
||||
|
||||
STATIC void _wait_for_callback(void) {
|
||||
STATIC bool _wait_for_callback(void) {
|
||||
while (!mp_hal_is_interrupted() &&
|
||||
_get_string_result == 0xff) {
|
||||
_xfer_result == 0xff) {
|
||||
// The background tasks include TinyUSB which will call the function
|
||||
// we provided above. In other words, the callback isn't in an interrupt.
|
||||
RUN_BACKGROUND_TASKS;
|
||||
}
|
||||
xfer_result_t result = _xfer_result;
|
||||
_xfer_result = 0xff;
|
||||
return result == XFER_RESULT_SUCCESS;
|
||||
}
|
||||
|
||||
STATIC mp_obj_t _get_string(const uint16_t *temp_buf) {
|
||||
|
@ -84,46 +101,145 @@ STATIC mp_obj_t _get_string(const uint16_t *temp_buf) {
|
|||
}
|
||||
|
||||
mp_obj_t common_hal_usb_core_device_get_serial_number(usb_core_device_obj_t *self) {
|
||||
_get_string_result = 0xff;
|
||||
uint16_t temp_buf[127];
|
||||
if (!tuh_descriptor_get_serial_string(self->device_number, 0, temp_buf, MP_ARRAY_SIZE(temp_buf), _transfer_done_cb, 0)) {
|
||||
if (!tuh_descriptor_get_serial_string(self->device_number, 0, temp_buf, MP_ARRAY_SIZE(temp_buf), _transfer_done_cb, 0) ||
|
||||
!_wait_for_callback()) {
|
||||
return mp_const_none;
|
||||
}
|
||||
_wait_for_callback();
|
||||
return _get_string(temp_buf);
|
||||
}
|
||||
|
||||
mp_obj_t common_hal_usb_core_device_get_product(usb_core_device_obj_t *self) {
|
||||
_get_string_result = 0xff;
|
||||
uint16_t temp_buf[127];
|
||||
if (!tuh_descriptor_get_product_string(self->device_number, 0, temp_buf, MP_ARRAY_SIZE(temp_buf), _transfer_done_cb, 0)) {
|
||||
if (!tuh_descriptor_get_product_string(self->device_number, 0, temp_buf, MP_ARRAY_SIZE(temp_buf), _transfer_done_cb, 0) ||
|
||||
!_wait_for_callback()) {
|
||||
return mp_const_none;
|
||||
}
|
||||
_wait_for_callback();
|
||||
return _get_string(temp_buf);
|
||||
}
|
||||
|
||||
mp_obj_t common_hal_usb_core_device_get_manufacturer(usb_core_device_obj_t *self) {
|
||||
_get_string_result = 0xff;
|
||||
uint16_t temp_buf[127];
|
||||
if (!tuh_descriptor_get_manufacturer_string(self->device_number, 0, temp_buf, MP_ARRAY_SIZE(temp_buf), _transfer_done_cb, 0)) {
|
||||
if (!tuh_descriptor_get_manufacturer_string(self->device_number, 0, temp_buf, MP_ARRAY_SIZE(temp_buf), _transfer_done_cb, 0) ||
|
||||
!_wait_for_callback()) {
|
||||
return mp_const_none;
|
||||
}
|
||||
_wait_for_callback();
|
||||
return _get_string(temp_buf);
|
||||
}
|
||||
|
||||
mp_obj_t common_hal_usb_core_device_write(usb_core_device_obj_t *self, mp_int_t endpoint, const uint8_t *buffer, mp_int_t len, mp_int_t timeout) {
|
||||
return mp_const_none;
|
||||
void common_hal_usb_core_device_set_configuration(usb_core_device_obj_t *self, mp_int_t configuration) {
|
||||
if (configuration == 0x100) {
|
||||
tusb_desc_configuration_t desc;
|
||||
if (!tuh_descriptor_get_configuration(self->device_number, 0, &desc, sizeof(desc), _transfer_done_cb, 0) ||
|
||||
!_wait_for_callback()) {
|
||||
return;
|
||||
}
|
||||
configuration = desc.bConfigurationValue;
|
||||
}
|
||||
tuh_configuration_set(self->device_number, configuration, _transfer_done_cb, 0);
|
||||
_wait_for_callback();
|
||||
}
|
||||
|
||||
mp_obj_t common_hal_usb_core_device_read(usb_core_device_obj_t *self, mp_int_t endpoint, uint8_t *buffer, mp_int_t len, mp_int_t timeout) {
|
||||
return mp_const_none;
|
||||
STATIC size_t _xfer(tuh_xfer_t *xfer, mp_int_t timeout) {
|
||||
_xfer_result = 0xff;
|
||||
xfer->complete_cb = _transfer_done_cb;
|
||||
if (!tuh_edpt_xfer(xfer)) {
|
||||
mp_raise_usb_core_USBError(NULL);
|
||||
}
|
||||
uint32_t start_time = supervisor_ticks_ms32();
|
||||
while ((timeout == 0 || supervisor_ticks_ms32() - start_time < (uint32_t)timeout) &&
|
||||
!mp_hal_is_interrupted() &&
|
||||
_xfer_result == 0xff) {
|
||||
// The background tasks include TinyUSB which will call the function
|
||||
// we provided above. In other words, the callback isn't in an interrupt.
|
||||
RUN_BACKGROUND_TASKS;
|
||||
}
|
||||
if (mp_hal_is_interrupted()) {
|
||||
return 0;
|
||||
}
|
||||
xfer_result_t result = _xfer_result;
|
||||
_xfer_result = 0xff;
|
||||
if (result == XFER_RESULT_STALLED || result == 0xff) {
|
||||
mp_raise_usb_core_USBTimeoutError();
|
||||
}
|
||||
if (result == XFER_RESULT_SUCCESS) {
|
||||
return xfer->actual_len;
|
||||
}
|
||||
|
||||
xfer_result_t control_result;
|
||||
STATIC void _control_complete_cb(tuh_xfer_t *xfer) {
|
||||
control_result = xfer->result;
|
||||
return 0;
|
||||
}
|
||||
|
||||
STATIC bool _open_endpoint(usb_core_device_obj_t *self, mp_int_t endpoint) {
|
||||
bool endpoint_open = false;
|
||||
size_t open_size = sizeof(self->open_endpoints);
|
||||
size_t first_free = open_size;
|
||||
for (size_t i = 0; i < open_size; i++) {
|
||||
if (self->open_endpoints[i] == endpoint) {
|
||||
endpoint_open = true;
|
||||
} else if (first_free == open_size && self->open_endpoints[i] == 0) {
|
||||
first_free = i;
|
||||
}
|
||||
}
|
||||
if (endpoint_open) {
|
||||
return true;
|
||||
}
|
||||
|
||||
// Fetch the full configuration descriptor and search for the endpoint's descriptor.
|
||||
uint8_t desc_buf[128];
|
||||
if (!tuh_descriptor_get_configuration(self->device_number, self->configuration_index, &desc_buf, sizeof(desc_buf), _transfer_done_cb, 0) ||
|
||||
!_wait_for_callback()) {
|
||||
return false;
|
||||
}
|
||||
tusb_desc_configuration_t *desc_cfg = (tusb_desc_configuration_t *)desc_buf;
|
||||
|
||||
uint8_t const *desc_end = ((uint8_t const *)desc_cfg) + tu_le16toh(desc_cfg->wTotalLength);
|
||||
uint8_t const *p_desc = tu_desc_next(desc_cfg);
|
||||
|
||||
// parse each interfaces
|
||||
while (p_desc < desc_end) {
|
||||
if (TUSB_DESC_ENDPOINT == tu_desc_type(p_desc)) {
|
||||
tusb_desc_endpoint_t const *desc_ep = (tusb_desc_endpoint_t const *)p_desc;
|
||||
if (desc_ep->bEndpointAddress == endpoint) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
p_desc = tu_desc_next(p_desc);
|
||||
}
|
||||
if (p_desc >= desc_end) {
|
||||
return false;
|
||||
}
|
||||
tusb_desc_endpoint_t const *desc_ep = (tusb_desc_endpoint_t const *)p_desc;
|
||||
|
||||
bool open = tuh_edpt_open(self->device_number, desc_ep);
|
||||
if (open) {
|
||||
self->open_endpoints[first_free] = endpoint;
|
||||
}
|
||||
return open;
|
||||
}
|
||||
|
||||
mp_int_t common_hal_usb_core_device_write(usb_core_device_obj_t *self, mp_int_t endpoint, const uint8_t *buffer, mp_int_t len, mp_int_t timeout) {
|
||||
if (!_open_endpoint(self, endpoint)) {
|
||||
mp_raise_usb_core_USBError(NULL);
|
||||
}
|
||||
tuh_xfer_t xfer;
|
||||
xfer.daddr = self->device_number;
|
||||
xfer.ep_addr = endpoint;
|
||||
xfer.buffer = (uint8_t *)buffer;
|
||||
xfer.buflen = len;
|
||||
return _xfer(&xfer, timeout);
|
||||
}
|
||||
|
||||
mp_int_t common_hal_usb_core_device_read(usb_core_device_obj_t *self, mp_int_t endpoint, uint8_t *buffer, mp_int_t len, mp_int_t timeout) {
|
||||
if (!_open_endpoint(self, endpoint)) {
|
||||
mp_raise_usb_core_USBError(NULL);
|
||||
}
|
||||
tuh_xfer_t xfer;
|
||||
xfer.daddr = self->device_number;
|
||||
xfer.ep_addr = endpoint;
|
||||
xfer.buffer = buffer;
|
||||
xfer.buflen = len;
|
||||
return _xfer(&xfer, timeout);
|
||||
}
|
||||
|
||||
mp_int_t common_hal_usb_core_device_ctrl_transfer(usb_core_device_obj_t *self,
|
||||
|
@ -144,27 +260,31 @@ mp_int_t common_hal_usb_core_device_ctrl_transfer(usb_core_device_obj_t *self,
|
|||
.ep_addr = 0,
|
||||
.setup = &request,
|
||||
.buffer = buffer,
|
||||
.complete_cb = _control_complete_cb,
|
||||
.complete_cb = _transfer_done_cb,
|
||||
};
|
||||
|
||||
control_result = XFER_RESULT_STALLED;
|
||||
_xfer_result = 0xff;
|
||||
|
||||
bool result = tuh_control_xfer(&xfer);
|
||||
if (!result) {
|
||||
if (!tuh_control_xfer(&xfer)) {
|
||||
mp_raise_usb_core_USBError(NULL);
|
||||
}
|
||||
uint32_t start_time = supervisor_ticks_ms32();
|
||||
while (supervisor_ticks_ms32() - start_time < (uint32_t)timeout &&
|
||||
while ((timeout == 0 || supervisor_ticks_ms32() - start_time < (uint32_t)timeout) &&
|
||||
!mp_hal_is_interrupted() &&
|
||||
control_result == XFER_RESULT_STALLED) {
|
||||
_xfer_result == 0xff) {
|
||||
// The background tasks include TinyUSB which will call the function
|
||||
// we provided above. In other words, the callback isn't in an interrupt.
|
||||
RUN_BACKGROUND_TASKS;
|
||||
}
|
||||
if (control_result == XFER_RESULT_STALLED) {
|
||||
if (mp_hal_is_interrupted()) {
|
||||
return 0;
|
||||
}
|
||||
xfer_result_t result = _xfer_result;
|
||||
_xfer_result = 0xff;
|
||||
if (result == XFER_RESULT_STALLED || result == 0xff) {
|
||||
mp_raise_usb_core_USBTimeoutError();
|
||||
}
|
||||
if (control_result == XFER_RESULT_SUCCESS) {
|
||||
if (result == XFER_RESULT_SUCCESS) {
|
||||
return len;
|
||||
}
|
||||
|
||||
|
@ -172,14 +292,22 @@ mp_int_t common_hal_usb_core_device_ctrl_transfer(usb_core_device_obj_t *self,
|
|||
}
|
||||
|
||||
bool common_hal_usb_core_device_is_kernel_driver_active(usb_core_device_obj_t *self, mp_int_t interface) {
|
||||
// TODO: Implement this when CP natively uses a keyboard.
|
||||
#if CIRCUITPY_USB_KEYBOARD_WORKFLOW
|
||||
if (usb_keyboard_in_use(self->device_number, interface)) {
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
return false;
|
||||
}
|
||||
|
||||
void common_hal_usb_core_device_detach_kernel_driver(usb_core_device_obj_t *self, mp_int_t interface) {
|
||||
// TODO: Implement this when CP natively uses a keyboard.
|
||||
#if CIRCUITPY_USB_KEYBOARD_WORKFLOW
|
||||
usb_keyboard_detach(self->device_number, interface);
|
||||
#endif
|
||||
}
|
||||
|
||||
void common_hal_usb_core_device_attach_kernel_driver(usb_core_device_obj_t *self, mp_int_t interface) {
|
||||
// TODO: Implement this when CP natively uses a keyboard.
|
||||
#if CIRCUITPY_USB_KEYBOARD_WORKFLOW
|
||||
usb_keyboard_attach(self->device_number, interface);
|
||||
#endif
|
||||
}
|
||||
|
|
|
@ -32,6 +32,8 @@
|
|||
typedef struct {
|
||||
mp_obj_base_t base;
|
||||
uint8_t device_number;
|
||||
uint8_t configuration_index; // not number
|
||||
uint8_t open_endpoints[8];
|
||||
} usb_core_device_obj_t;
|
||||
|
||||
#endif // MICROPY_INCLUDED_SHARED_MODULE_USB_CORE_DEVICE_H
|
||||
|
|
|
@ -36,10 +36,14 @@
|
|||
|
||||
STATIC volatile background_callback_t *volatile callback_head, *volatile callback_tail;
|
||||
|
||||
#ifndef CALLBACK_CRITICAL_BEGIN
|
||||
#define CALLBACK_CRITICAL_BEGIN (common_hal_mcu_disable_interrupts())
|
||||
#endif
|
||||
#ifndef CALLBACK_CRITICAL_END
|
||||
#define CALLBACK_CRITICAL_END (common_hal_mcu_enable_interrupts())
|
||||
#endif
|
||||
|
||||
MP_WEAK void port_wake_main_task(void) {
|
||||
MP_WEAK void PLACE_IN_ITCM(port_wake_main_task)(void) {
|
||||
}
|
||||
|
||||
void PLACE_IN_ITCM(background_callback_add_core)(background_callback_t * cb) {
|
||||
|
|
|
@ -238,6 +238,12 @@ char serial_read(void) {
|
|||
}
|
||||
#endif
|
||||
|
||||
#if CIRCUITPY_USB_KEYBOARD_WORKFLOW
|
||||
if (usb_keyboard_chars_available() > 0) {
|
||||
return usb_keyboard_read_char();
|
||||
}
|
||||
#endif
|
||||
|
||||
if (port_serial_bytes_available() > 0) {
|
||||
return port_serial_read();
|
||||
}
|
||||
|
@ -279,6 +285,12 @@ bool serial_bytes_available(void) {
|
|||
}
|
||||
#endif
|
||||
|
||||
#if CIRCUITPY_USB_KEYBOARD_WORKFLOW
|
||||
if (usb_keyboard_chars_available() > 0) {
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if CIRCUITPY_USB_CDC
|
||||
if (usb_cdc_console_enabled() && tud_cdc_available() > 0) {
|
||||
return true;
|
||||
|
|
|
@ -0,0 +1,241 @@
|
|||
/*
|
||||
* This file is part of the MicroPython project, http://micropython.org/
|
||||
*
|
||||
* The MIT License (MIT)
|
||||
*
|
||||
* Copyright (c) 2023 Scott Shawcroft for Adafruit Industries
|
||||
* Copyright (c) 2023 Jeff Epler 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 "tusb.h"
|
||||
|
||||
#include "py/ringbuf.h"
|
||||
#include "py/runtime.h"
|
||||
#include "shared/runtime/interrupt_char.h"
|
||||
#include "supervisor/usb.h"
|
||||
|
||||
// Buffer the incoming serial data in the background so that we can look for the
|
||||
// interrupt character.
|
||||
STATIC ringbuf_t _incoming_ringbuf;
|
||||
STATIC uint8_t _buf[16];
|
||||
|
||||
uint8_t _dev_addr;
|
||||
uint8_t _interface;
|
||||
|
||||
#define FLAG_ALPHABETIC (1)
|
||||
#define FLAG_SHIFT (2)
|
||||
#define FLAG_NUMLOCK (4)
|
||||
#define FLAG_CTRL (8)
|
||||
#define FLAG_LUT (16)
|
||||
|
||||
const char *const lut[] = {
|
||||
"!@#$%^&*()", /* 0 - shifted numeric keys */
|
||||
"\r\x1b\10\t -=[]\\#;'`,./", /* 1 - symbol keys */
|
||||
"\n\x1b\177\t _+{}|~:\"~<>?", /* 2 - shifted */
|
||||
"\12\13\10\22", /* 3 - arrow keys RLDU */
|
||||
"/*-+\n1234567890.", /* 4 - keypad w/numlock */
|
||||
"/*-+\n\xff\2\xff\4\xff\3\xff\1\xff\xff.", /* 5 - keypad w/o numlock */
|
||||
};
|
||||
|
||||
struct keycode_mapper {
|
||||
uint8_t first, last, code, flags;
|
||||
} keycode_to_ascii[] = {
|
||||
{ HID_KEY_A, HID_KEY_Z, 'a', FLAG_ALPHABETIC, },
|
||||
|
||||
{ HID_KEY_1, HID_KEY_9, 0, FLAG_SHIFT | FLAG_LUT, },
|
||||
{ HID_KEY_1, HID_KEY_9, '1', 0, },
|
||||
{ HID_KEY_0, HID_KEY_0, ')', FLAG_SHIFT, },
|
||||
{ HID_KEY_0, HID_KEY_0, '0', 0, },
|
||||
|
||||
{ HID_KEY_ENTER, HID_KEY_ENTER, '\n', FLAG_CTRL },
|
||||
{ HID_KEY_ENTER, HID_KEY_SLASH, 2, FLAG_SHIFT | FLAG_LUT, },
|
||||
{ HID_KEY_ENTER, HID_KEY_SLASH, 1, FLAG_LUT, },
|
||||
|
||||
{ HID_KEY_F1, HID_KEY_F1, 0x1e, 0, }, // help key on xerox 820 kbd
|
||||
|
||||
{ HID_KEY_ARROW_RIGHT, HID_KEY_ARROW_UP, 3, FLAG_LUT },
|
||||
|
||||
{ HID_KEY_KEYPAD_DIVIDE, HID_KEY_KEYPAD_DECIMAL, 4, FLAG_NUMLOCK | FLAG_LUT },
|
||||
{ HID_KEY_KEYPAD_DIVIDE, HID_KEY_KEYPAD_DECIMAL, 5, FLAG_LUT },
|
||||
};
|
||||
|
||||
STATIC bool report_contains(const hid_keyboard_report_t *report, uint8_t key) {
|
||||
for (int i = 0; i < 6; i++) {
|
||||
if (report->keycode[i] == key) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
int old_ascii = -1;
|
||||
uint32_t repeat_timeout;
|
||||
// this matches Linux default of 500ms to first repeat, 1/20s thereafter
|
||||
const uint32_t default_repeat_time = 50;
|
||||
const uint32_t initial_repeat_time = 500;
|
||||
|
||||
STATIC void send_ascii(uint8_t code, uint32_t repeat_time) {
|
||||
old_ascii = code;
|
||||
// repeat_timeout = millis() + repeat_time;
|
||||
if (code == mp_interrupt_char) {
|
||||
mp_sched_keyboard_interrupt();
|
||||
return;
|
||||
}
|
||||
if (ringbuf_num_empty(&_incoming_ringbuf) == 0) {
|
||||
// Drop on the floor
|
||||
return;
|
||||
}
|
||||
ringbuf_put(&_incoming_ringbuf, code);
|
||||
}
|
||||
|
||||
hid_keyboard_report_t old_report;
|
||||
|
||||
STATIC void process_event(uint8_t dev_addr, uint8_t instance, const hid_keyboard_report_t *report) {
|
||||
bool alt = report->modifier & 0x44;
|
||||
bool shift = report->modifier & 0x22;
|
||||
bool ctrl = report->modifier & 0x11;
|
||||
bool caps = old_report.reserved & 1;
|
||||
bool num = old_report.reserved & 2;
|
||||
uint8_t code = 0;
|
||||
|
||||
if (report->keycode[0] == 1 && report->keycode[1] == 1) {
|
||||
// keyboard says it has exceeded max kro
|
||||
return;
|
||||
}
|
||||
|
||||
// something was pressed or release, so cancel any key repeat
|
||||
old_ascii = -1;
|
||||
|
||||
for (int i = 0; i < 6; i++) {
|
||||
uint8_t keycode = report->keycode[i];
|
||||
if (keycode == 0) {
|
||||
continue;
|
||||
}
|
||||
if (report_contains(&old_report, keycode)) {
|
||||
continue;
|
||||
}
|
||||
|
||||
/* key is newly pressed */
|
||||
if (keycode == HID_KEY_NUM_LOCK) {
|
||||
num = !num;
|
||||
} else if (keycode == HID_KEY_CAPS_LOCK) {
|
||||
caps = !caps;
|
||||
} else {
|
||||
for (size_t j = 0; j < MP_ARRAY_SIZE(keycode_to_ascii); j++) {
|
||||
struct keycode_mapper *mapper = &keycode_to_ascii[j];
|
||||
if (!(keycode >= mapper->first && keycode <= mapper->last)) {
|
||||
continue;
|
||||
}
|
||||
if (mapper->flags & FLAG_SHIFT && !shift) {
|
||||
continue;
|
||||
}
|
||||
if (mapper->flags & FLAG_NUMLOCK && !num) {
|
||||
continue;
|
||||
}
|
||||
if (mapper->flags & FLAG_CTRL && !ctrl) {
|
||||
continue;
|
||||
}
|
||||
if (mapper->flags & FLAG_LUT) {
|
||||
code = lut[mapper->code][keycode - mapper->first];
|
||||
} else {
|
||||
code = keycode - mapper->first + mapper->code;
|
||||
}
|
||||
if (mapper->flags & FLAG_ALPHABETIC) {
|
||||
if (shift ^ caps) {
|
||||
code ^= ('a' ^ 'A');
|
||||
}
|
||||
}
|
||||
if (ctrl) {
|
||||
code &= 0x1f;
|
||||
}
|
||||
if (alt) {
|
||||
code ^= 0x80;
|
||||
}
|
||||
send_ascii(code, initial_repeat_time);
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t leds = (caps | (num << 1));
|
||||
if (leds != old_report.reserved) {
|
||||
tuh_hid_set_report(dev_addr, instance /*idx*/, 0 /*report_id*/, HID_REPORT_TYPE_OUTPUT /*report_type*/, &leds, sizeof(leds));
|
||||
}
|
||||
old_report = *report;
|
||||
old_report.reserved = leds;
|
||||
}
|
||||
|
||||
bool usb_keyboard_in_use(uint8_t dev_addr, uint8_t interface) {
|
||||
return _dev_addr == dev_addr && _interface == interface;
|
||||
}
|
||||
|
||||
void usb_keyboard_detach(uint8_t dev_addr, uint8_t interface) {
|
||||
if (!usb_keyboard_in_use(dev_addr, interface)) {
|
||||
return;
|
||||
}
|
||||
_dev_addr = 0;
|
||||
_interface = 0;
|
||||
}
|
||||
|
||||
void usb_keyboard_attach(uint8_t dev_addr, uint8_t interface) {
|
||||
if (usb_keyboard_in_use(dev_addr, interface) || _dev_addr != 0) {
|
||||
return;
|
||||
}
|
||||
uint8_t const itf_protocol = tuh_hid_interface_protocol(dev_addr, interface);
|
||||
if (itf_protocol == HID_ITF_PROTOCOL_KEYBOARD) {
|
||||
_dev_addr = dev_addr;
|
||||
_interface = interface;
|
||||
tuh_hid_receive_report(dev_addr, interface);
|
||||
}
|
||||
}
|
||||
|
||||
void tuh_hid_mount_cb(uint8_t dev_addr, uint8_t interface, uint8_t const *desc_report, uint16_t desc_len) {
|
||||
usb_keyboard_attach(dev_addr, interface);
|
||||
}
|
||||
|
||||
void tuh_hid_umount_cb(uint8_t dev_addr, uint8_t interface) {
|
||||
usb_keyboard_detach(dev_addr, interface);
|
||||
}
|
||||
|
||||
void tuh_hid_report_received_cb(uint8_t dev_addr, uint8_t instance, uint8_t const *report, uint16_t len) {
|
||||
if (len != sizeof(hid_keyboard_report_t)) {
|
||||
return;
|
||||
} else {
|
||||
process_event(dev_addr, instance, (hid_keyboard_report_t *)report);
|
||||
}
|
||||
// continue to request to receive report
|
||||
tuh_hid_receive_report(dev_addr, instance);
|
||||
}
|
||||
|
||||
void usb_keyboard_init(void) {
|
||||
ringbuf_init(&_incoming_ringbuf, _buf, sizeof(_buf) - 1);
|
||||
}
|
||||
|
||||
bool usb_keyboard_chars_available(void) {
|
||||
return ringbuf_num_filled(&_incoming_ringbuf) > 0;
|
||||
}
|
||||
|
||||
char usb_keyboard_read_char(void) {
|
||||
if (ringbuf_num_filled(&_incoming_ringbuf) > 0) {
|
||||
return ringbuf_get(&_incoming_ringbuf);
|
||||
}
|
||||
return -1;
|
||||
}
|
|
@ -51,7 +51,7 @@ extern "C" {
|
|||
// When debugging TinyUSB, only output to the console UART link.
|
||||
#if CIRCUITPY_DEBUG_TINYUSB > 0 && defined(CIRCUITPY_CONSOLE_UART)
|
||||
#define CFG_TUSB_DEBUG CIRCUITPY_DEBUG_TINYUSB
|
||||
#define CFG_TUSB_DEBUG_PRINTF debug_uart_printf
|
||||
#define CFG_TUSB_DEBUG_PRINTF console_uart_printf
|
||||
#endif
|
||||
|
||||
/*------------- RTOS -------------*/
|
||||
|
@ -127,6 +127,10 @@ extern "C" {
|
|||
// --------------------------------------------------------------------
|
||||
|
||||
#if CIRCUITPY_USB_HOST
|
||||
#define CFG_TUH_ENABLED 1
|
||||
|
||||
// Always use PIO to do host on RP2.
|
||||
#define CFG_TUH_RPI_PIO_USB 1
|
||||
|
||||
#if CIRCUITPY_USB_HOST_INSTANCE == 0
|
||||
#if USB_HIGHSPEED
|
||||
|
@ -147,10 +151,12 @@ extern "C" {
|
|||
#define CFG_TUH_ENUMERATION_BUFSIZE 256
|
||||
#endif
|
||||
|
||||
#define CFG_TUH_HID 2
|
||||
#define CFG_TUH_HUB 1
|
||||
#define CFG_TUH_CDC 0
|
||||
#define CFG_TUH_MSC 0
|
||||
#define CFG_TUH_VENDOR 0
|
||||
#define CFG_TUH_API_EDPT_XFER 1
|
||||
|
||||
// max device support (excluding hub device)
|
||||
#define CFG_TUH_DEVICE_MAX (CFG_TUH_HUB ? 4 : 1) // hub typically has 4 ports
|
||||
|
|
|
@ -87,7 +87,8 @@ MP_WEAK void post_usb_init(void) {
|
|||
void usb_init(void) {
|
||||
init_usb_hardware();
|
||||
|
||||
tusb_init();
|
||||
// Only init device. Host gets inited by the `usb_host` module common-hal.
|
||||
tud_init(TUD_OPT_RHPORT);
|
||||
|
||||
post_usb_init();
|
||||
|
||||
|
@ -199,7 +200,7 @@ void usb_disconnect(void) {
|
|||
|
||||
void usb_background(void) {
|
||||
if (usb_enabled()) {
|
||||
#if CFG_TUSB_OS == OPT_OS_NONE
|
||||
#if CFG_TUSB_OS == OPT_OS_NONE || CFG_TUSB_OS == OPT_OS_PICO
|
||||
tud_task();
|
||||
#if CIRCUITPY_USB_HOST
|
||||
tuh_task();
|
||||
|
|
|
@ -112,6 +112,9 @@ void supervisor_workflow_start(void) {
|
|||
}
|
||||
#endif
|
||||
|
||||
#if CIRCUITPY_USB_KEYBOARD_WORKFLOW
|
||||
usb_keyboard_init();
|
||||
#endif
|
||||
}
|
||||
|
||||
FRESULT supervisor_workflow_mkdir_parents(FATFS *fs, char *path) {
|
||||
|
|
|
@ -161,8 +161,10 @@ ifeq ($(CIRCUITPY_USB),1)
|
|||
|
||||
ifeq ($(CIRCUITPY_USB_HOST), 1)
|
||||
SRC_SUPERVISOR += \
|
||||
lib/tinyusb/src/class/hid/hid_host.c \
|
||||
lib/tinyusb/src/host/hub.c \
|
||||
lib/tinyusb/src/host/usbh.c \
|
||||
supervisor/shared/usb/host_keyboard.c \
|
||||
|
||||
endif
|
||||
endif
|
||||
|
|
|
@ -96,4 +96,14 @@ bool usb_msc_lock(void);
|
|||
void usb_msc_unlock(void);
|
||||
#endif
|
||||
|
||||
#if CIRCUITPY_USB_KEYBOARD_WORKFLOW
|
||||
void usb_keyboard_init(void);
|
||||
bool usb_keyboard_chars_available(void);
|
||||
char usb_keyboard_read_char(void);
|
||||
|
||||
bool usb_keyboard_in_use(uint8_t dev_addr, uint8_t interface);
|
||||
void usb_keyboard_detach(uint8_t dev_addr, uint8_t interface);
|
||||
void usb_keyboard_attach(uint8_t dev_addr, uint8_t interface);
|
||||
#endif
|
||||
|
||||
#endif // MICROPY_INCLUDED_SUPERVISOR_USB_H
|
||||
|
|
Loading…
Reference in New Issue