Merge branch 'master' into feature/feedback_format

This commit is contained in:
Valentin Milea 2022-01-07 15:12:07 +02:00
commit c2533a45bd
135 changed files with 2977 additions and 231 deletions

View File

@ -18,7 +18,7 @@ jobs:
matrix:
family:
# Alphabetical order
- 'raspberrypi4'
- 'broadcom_64bit'
steps:
- name: Setup Python
uses: actions/setup-python@v2

View File

@ -39,6 +39,7 @@ jobs:
matrix:
family:
# Alphabetical order
- 'broadcom_32bit'
- 'imxrt'
- 'lpc15'
- 'lpc18'
@ -114,7 +115,7 @@ jobs:
done
# ---------------------------------------
# Build all no-family (opharned) boards
# Build all no-family (orphaned) boards
# ---------------------------------------
build-board:
runs-on: ubuntu-latest

View File

@ -18,7 +18,7 @@ jobs:
# ESP32-S2
- 'espressif_saola_1'
# ESP32-S3
#- 'espressif_addax_1'
#- 'espressif_s3_devkitm'
# S3 compile error with "dangerous relocation: call8: call target out of range: memcpy"
steps:

2
.gitignore vendored
View File

@ -26,3 +26,5 @@ cov-int
# cppcheck build directories
*-build-dir
/_bin/
__pycache__

View File

@ -50,7 +50,7 @@ The stack supports the following MCUs:
- **Renesas:** RX63N, RX65N, RX72N
- **Silabs:** EFM32GG
- **Sony:** CXD56
- **ST:** STM32 series: F0, F1, F2, F3, F4, F7, H7, L0, L1, L4, L4+
- **ST:** STM32 series: F0, F1, F2, F3, F4, F7, H7, G4, L0, L1, L4, L4+
- **TI:** MSP430, MSP432E4, TM4C123
- **ValentyUSB:** eptri

View File

@ -82,6 +82,8 @@ Supported MCUs
| +-----------------------+--------+------+-----------+-------------------+--------------+
| | H7 | ✔ | | ✔ | dwc2 | |
| +-----------------------+--------+------+-----------+-------------------+--------------+
| | G4 | ✔ | ✖ | ✖ | stm32_fsdev | |
| +-----------------------+--------+------+-----------+-------------------+--------------+
| | L0, L1 | ✔ | ✖ | ✖ | stm32_fsdev | |
| +----+------------------+--------+------+-----------+-------------------+--------------+
| | L4 | 4x2, 4x3 | ✔ | ✖ | ✖ | stm32_fsdev | |
@ -243,6 +245,7 @@ Kinetis
- `Freedom FRDM-KL25Z <https://www.nxp.com/design/development-boards/freedom-development-boards/mcu-boards/freedom-development-platform-for-kinetis-kl14-kl15-kl24-kl25-mcus:FRDM-KL25Z>`__
- `Freedom FRDM-K32L2B3 <https://www.nxp.com/design/development-boards/freedom-development-boards/mcu-boards/nxp-freedom-development-platform-for-k32-l2b-mcus:FRDM-K32L2B3>`__
- `KUIIC <https://github.com/nxf58843/kuiic>`__
LPC 11-13-15
^^^^^^^^^^^^
@ -341,6 +344,7 @@ F4
- `STM32 F411ve Discovery <https://www.st.com/en/evaluation-tools/32f411ediscovery.html>`__
- `STM32 F412zg Discovery <https://www.st.com/en/evaluation-tools/32f412gdiscovery.html>`__
- `STM32 F412zg Nucleo <https://www.st.com/en/evaluation-tools/nucleo-f412zg.html>`__
- `STM32 F439zi Nucleo <https://www.st.com/en/evaluation-tools/nucleo-f439zi.html>`__
F7
^^
@ -352,6 +356,17 @@ F7
- `STM32 F767zi Nucleo <https://www.st.com/en/evaluation-tools/nucleo-f767zi.html>`__
- `STM32 F769i Discovery <https://www.st.com/en/evaluation-tools/32f769idiscovery.html>`__
H7
^^
- `STM32 H743zi Nucleo <https://www.st.com/en/evaluation-tools/nucleo-h743zi.html>`__
- `STM32 H743i Evaluation <https://www.st.com/en/evaluation-tools/stm32h743i-eval.html>`__
- `STM32 H745i Discovery <https://www.st.com/en/evaluation-tools/stm32h745i-disco.html>`__
- `Waveshare OpenH743I-C <https://www.waveshare.com/openh743i-c-standard.htm>`__
G4
^^
- `STM32 G474RE Nucleo <https://www.st.com/en/evaluation-tools/nucleo-g474re.html>`__
L0
^^
- `STM32 L035c8 Discovery <https://www.st.com/en/evaluation-tools/32l0538discovery.html>`__
@ -362,13 +377,6 @@ L4
- `STM32 L4P5zg Nucleo <https://www.st.com/en/evaluation-tools/nucleo-l4p5zg.html>`__
- `STM32 L4R5zi Nucleo <https://www.st.com/en/evaluation-tools/nucleo-l4r5zi.html>`__
H7
^^
- `STM32 H743zi Nucleo <https://www.st.com/en/evaluation-tools/nucleo-h743zi.html>`__
- `STM32 H743i Evaluation <https://www.st.com/en/evaluation-tools/stm32h743i-eval.html>`__
- `STM32 H745i Discovery <https://www.st.com/en/evaluation-tools/stm32h745i-disco.html>`__
- `Waveshare OpenH743I-C <https://www.waveshare.com/openh743i-c-standard.htm>`__
TI
--

View File

@ -0,0 +1,3 @@
mcu:SAMD11
mcu:SAME5X
mcu:SAMG

View File

@ -0,0 +1,3 @@
mcu:SAMD11
mcu:SAME5X
mcu:SAMG

View File

@ -0,0 +1 @@
mcu:SAMD11

View File

@ -0,0 +1,10 @@
mcu:CXD56
mcu:MSP430x5xx
mcu:SAMD11
mcu:VALENTYUSB_EPTRI
mcu:MKL25ZXX
mcu:RP2040
mcu:SAMX7X
mcu:GD32VF103
family:broadcom_64bit
family:broadcom_32bit

View File

@ -1,4 +0,0 @@
LINK _build/ek-tm4c123gxl/dfu.elf
/home/runner/cache/toolchain/xpack-arm-none-eabi-gcc-10.2.1-1.1/bin/../lib/gcc/arm-none-eabi/10.2.1/../../../../arm-none-eabi/bin/ld: section .ARM.exidx.text._close LMA [0000000000002980,0000000000002987] overlaps section .data LMA [0000000000002980,0000000000002a03]
collect2: error: ld returned 1 exit status
make: *** [../../rules.mk:94: _build/ek-tm4c123gxl/dfu.elf] Error 1

View File

@ -0,0 +1,2 @@
mcu:TM4C123
mcu:BCM2835

View File

@ -0,0 +1 @@
mcu:SAMD11

View File

@ -0,0 +1,9 @@
mcu:CXD56
mcu:MSP430x5xx
mcu:SAMD11
mcu:VALENTYUSB_EPTRI
mcu:RP2040
mcu:SAMX7X
mcu:GD32VF103
family:broadcom_64bit
family:broadcom_32bit

View File

@ -1,11 +1,13 @@
# Install python3 HID package https://pypi.org/project/hid/
import hid
USB_VID = 0xcafe
# default is TinyUSB (0xcafe), Adafruit (0x239a), RaspberryPi (0x2e8a), Espressif (0x303a) VID
USB_VID = (0xcafe, 0x239a, 0x2e8a, 0x303a)
print("Openning HID device with VID = 0x%X" % USB_VID)
print("VID list: " + ", ".join('%02x' % v for v in USB_VID))
for dict in hid.enumerate(USB_VID):
for vid in USB_VID:
for dict in hid.enumerate(vid):
print(dict)
dev = hid.Device(dict['vendor_id'], dict['product_id'])
if dev:

View File

@ -0,0 +1,2 @@
mcu:SAMD11
mcu:MKL25ZXX

View File

@ -1 +0,0 @@
tinyusb/lib/lwip/src/include/lwip/arch.h:202:13: error: conflicting types for 'ssize_t'

View File

@ -1 +0,0 @@
too many warnings for 16-bit integer overflow

View File

@ -0,0 +1,10 @@
mcu:LPC11UXX
mcu:LPC13XX
mcu:MSP430x5xx
mcu:NUC121
mcu:SAMD11
mcu:STM32L0
mcu:MKL25ZXX
family:broadcom_64bit
family:broadcom_32bit
board:curiosity_nano

View File

@ -0,0 +1,6 @@
mcu:LPC11UXX
mcu:LPC13XX
mcu:NUC121
mcu:SAMD11
mcu:SAME5X
mcu:SAMG

View File

@ -0,0 +1 @@
mcu:BCM2835

View File

@ -1 +0,0 @@
too many warnings for 16-bit integer overflow

View File

@ -0,0 +1,2 @@
mcu:MSP430x5xx
mcu:SAMD11

View File

@ -0,0 +1,8 @@
mcu:LPC175X_6X
mcu:LPC177X_8X
mcu:LPC18XX
mcu:LPC40XX
mcu:LPC43XX
mcu:MIMXRT10XX
mcu:RP2040
mcu:MSP432E4

View File

@ -0,0 +1,8 @@
mcu:LPC175X_6X
mcu:LPC177X_8X
mcu:LPC18XX
mcu:LPC40XX
mcu:LPC43XX
mcu:MIMXRT10XX
mcu:RP2040
mcu:MSP432E4

View File

@ -138,6 +138,8 @@ void hid_app_task(void)
// therefore report_desc = NULL, desc_len = 0
void tuh_hid_mount_cb(uint8_t dev_addr, uint8_t instance, uint8_t const* desc_report, uint16_t desc_len)
{
(void)desc_report;
(void)desc_len;
uint16_t vid, pid;
tuh_vid_pid_get(dev_addr, &vid, &pid);

View File

@ -54,6 +54,8 @@ endif
#-------------- Cross Compiler ------------
# Can be set by board, default to ARM GCC
CROSS_COMPILE ?= arm-none-eabi-
# Allow for -Os to be changed by board makefiles in case -Os is not allowed
CFLAGS_OPTIMIZED ?= -Os
CC = $(CROSS_COMPILE)gcc
CXX = $(CROSS_COMPILE)g++
@ -112,7 +114,7 @@ CFLAGS += \
ifeq ($(DEBUG), 1)
CFLAGS += -Og
else
CFLAGS += -Os
CFLAGS += $(CFLAGS_OPTIMIZED)
endif
# Log level is mapped to TUSB DEBUG option

View File

@ -12,8 +12,10 @@ ifeq (,$(findstring $(FAMILY),esp32s2 esp32s3 rp2040))
# Compiler Flags
# ---------------------------------------
LIBS_GCC ?= -lgcc -lm -lnosys
# libc
LIBS += -lgcc -lm -lnosys
LIBS += $(LIBS_GCC)
ifneq ($(BOARD), spresense)
LIBS += -lc
@ -49,7 +51,11 @@ ifeq ($(NO_LTO),1)
CFLAGS := $(filter-out -flto,$(CFLAGS))
endif
LDFLAGS += $(CFLAGS) -Wl,-T,$(TOP)/$(LD_FILE) -Wl,-Map=$@.map -Wl,-cref -Wl,-gc-sections
ifneq ($(LD_FILE),)
LDFLAGS_LD_FILE ?= -Wl,-T,$(TOP)/$(LD_FILE)
endif
LDFLAGS += $(CFLAGS) $(LDFLAGS_LD_FILE) -Wl,-Map=$@.map -Wl,-cref -Wl,-gc-sections
ifneq ($(SKIP_NANOLIB), 1)
LDFLAGS += -specs=nosys.specs -specs=nano.specs
endif

View File

@ -126,6 +126,8 @@ TU_ATTR_USED int sys_write (int fhdl, const void *buf, size_t count)
TU_ATTR_USED int sys_read (int fhdl, char *buf, size_t count)
{
(void) fhdl;
(void) buf;
(void) count;
return 0;
}

View File

@ -32,7 +32,7 @@
//--------------------------------------------------------------------+
// Low Level MCU header include. TinyUSB stack and example should be
// platform independent and mostly doens't need to include this file.
// platform independent and mostly doesn't need to include this file.
// However there are still certain situation where this file is needed:
// - FreeRTOSConfig.h to set up correct clock and NVIC interrupts for ARM Cortex
// - SWO logging for Cortex M with ITM_SendChar() / ITM_ReceiveChar()
@ -146,6 +146,9 @@
#elif CFG_TUSB_MCU == OPT_MCU_TM4C123
#include "TM4C123.h"
#elif TU_CHECK_MCU(OPT_MCU_BCM2711, OPT_MCU_BCM2835, OPT_MCU_BCM2837)
// no header needed
#else
#error "Missing MCU header"
#endif

View File

@ -0,0 +1,5 @@
CFLAGS += -mcpu=arm1176jzf-s \
-DBCM_VERSION=2835 \
-DCFG_TUSB_MCU=OPT_MCU_BCM2835
SUFFIX =

View File

@ -27,8 +27,9 @@
#include "bsp/board.h"
#include "board.h"
#include "broadcom/cpu.h"
#include "broadcom/gpio.h"
#include "broadcom/interrupts.h"
#include "broadcom/io.h"
#include "broadcom/mmu.h"
#include "broadcom/caches.h"
#include "broadcom/vcmailbox.h"
@ -37,9 +38,8 @@
#define LED_PIN 18
#define LED_STATE_ON 1
// Button
#define BUTTON_PIN 16
#define BUTTON_STATE_ACTIVE 0
// UART TX
#define UART_TX_PIN 14
//--------------------------------------------------------------------+
// Forward USB interrupt events to TinyUSB IRQ Handler
@ -62,14 +62,26 @@ void board_init(void)
init_caches();
// LED
gpio_initOutputPinWithPullNone(LED_PIN);
gpio_set_function(LED_PIN, GPIO_FUNCTION_OUTPUT);
gpio_set_pull(LED_PIN, BP_PULL_NONE);
board_led_write(true);
// Button
// TODO
// Uart
uart_init();
COMPLETE_MEMORY_READS;
AUX->ENABLES_b.UART_1 = true;
UART1->IER = 0;
UART1->CNTL = 0;
UART1->LCR_b.DATA_SIZE = UART1_LCR_DATA_SIZE_MODE_8BIT;
UART1->MCR = 0;
UART1->IER = 0;
uint32_t source_clock = vcmailbox_get_clock_rate_measured(VCMAILBOX_CLOCK_CORE);
UART1->BAUD = ((source_clock / (115200 * 8)) - 1);
UART1->CNTL |= UART1_CNTL_TX_ENABLE_Msk;
COMPLETE_MEMORY_READS;
gpio_set_function(UART_TX_PIN, GPIO_FUNCTION_ALT5);
// Turn on USB peripheral.
vcmailbox_set_power_state(VCMAILBOX_DEVICE_USB_HCD, true);
@ -87,7 +99,7 @@ void board_init(void)
void board_led_write(bool state)
{
gpio_setPinOutputBool(LED_PIN, state ? LED_STATE_ON : (1-LED_STATE_ON));
gpio_set_value(LED_PIN, state ? LED_STATE_ON : (1-LED_STATE_ON));
}
uint32_t board_button_read(void)

View File

@ -0,0 +1,46 @@
MCU_DIR = hw/mcu/broadcom
DEPS_SUBMODULES += $(MCU_DIR)
include $(TOP)/$(BOARD_PATH)/board.mk
CFLAGS += \
-Wall \
-O0 \
-ffreestanding \
-nostdlib \
-nostartfiles \
-mgeneral-regs-only \
-fno-exceptions \
-std=c17
CROSS_COMPILE = arm-none-eabi-
# mcu driver cause following warnings
CFLAGS += -Wno-error=cast-qual
SRC_C += \
src/portable/synopsys/dwc2/dcd_dwc2.c \
$(MCU_DIR)/broadcom/gen/interrupt_handlers.c \
$(MCU_DIR)/broadcom/gpio.c \
$(MCU_DIR)/broadcom/interrupts.c \
$(MCU_DIR)/broadcom/mmu.c \
$(MCU_DIR)/broadcom/caches.c \
$(MCU_DIR)/broadcom/vcmailbox.c
SKIP_NANOLIB = 1
LD_FILE = $(MCU_DIR)/broadcom/link$(SUFFIX).ld
INC += \
$(TOP)/$(BOARD_PATH) \
$(TOP)/$(MCU_DIR)
SRC_S += $(MCU_DIR)/broadcom/boot$(SUFFIX).S
$(BUILD)/kernel$(SUFFIX).img: $(BUILD)/$(PROJECT).elf
$(OBJCOPY) -O binary $^ $@
# Copy to kernel to netboot drive or SD card
# Change destinaation to fit your need
flash: $(BUILD)/kernel$(SUFFIX).img
@$(CP) $< /home/$(USER)/Documents/code/pi_tinyusb/boot_cpy

View File

@ -0,0 +1,38 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2020, Ha Thach (tinyusb.org)
*
* 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.
*
* This file is part of the TinyUSB stack.
*/
#ifndef BOARD_H_
#define BOARD_H_
#ifdef __cplusplus
extern "C" {
#endif
#ifdef __cplusplus
}
#endif
#endif /* BOARD_H_ */

View File

@ -0,0 +1,3 @@
CFLAGS += -mcpu=cortex-a72 \
-DBCM_VERSION=2711 \
-DCFG_TUSB_MCU=OPT_MCU_BCM2711

View File

@ -0,0 +1,38 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2020, Ha Thach (tinyusb.org)
*
* 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.
*
* This file is part of the TinyUSB stack.
*/
#ifndef BOARD_H_
#define BOARD_H_
#ifdef __cplusplus
extern "C" {
#endif
#ifdef __cplusplus
}
#endif
#endif /* BOARD_H_ */

View File

@ -0,0 +1,3 @@
CFLAGS += -mcpu=cortex-a53 \
-DBCM_VERSION=2837 \
-DCFG_TUSB_MCU=OPT_MCU_BCM2837

View File

@ -0,0 +1,156 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2019 Ha Thach (tinyusb.org)
*
* 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.
*
* This file is part of the TinyUSB stack.
*/
#include "bsp/board.h"
#include "board.h"
#include "broadcom/cpu.h"
#include "broadcom/gpio.h"
#include "broadcom/interrupts.h"
#include "broadcom/mmu.h"
#include "broadcom/caches.h"
#include "broadcom/vcmailbox.h"
// LED
#define LED_PIN 18
#define LED_STATE_ON 1
// UART TX
#define UART_TX_PIN 14
//--------------------------------------------------------------------+
// Forward USB interrupt events to TinyUSB IRQ Handler
//--------------------------------------------------------------------+
void USB_IRQHandler(void)
{
tud_int_handler(0);
}
//--------------------------------------------------------------------+
// MACRO TYPEDEF CONSTANT ENUM
//--------------------------------------------------------------------+
//--------------------------------------------------------------------+
// Board porting API
//--------------------------------------------------------------------+
void board_init(void)
{
setup_mmu_flat_map();
init_caches();
// LED
gpio_set_function(LED_PIN, GPIO_FUNCTION_OUTPUT);
gpio_set_pull(LED_PIN, BP_PULL_NONE);
board_led_write(true);
// Uart
COMPLETE_MEMORY_READS;
AUX->ENABLES_b.UART_1 = true;
UART1->IER = 0;
UART1->CNTL = 0;
UART1->LCR_b.DATA_SIZE = UART1_LCR_DATA_SIZE_MODE_8BIT;
UART1->MCR = 0;
UART1->IER = 0;
uint32_t source_clock = vcmailbox_get_clock_rate_measured(VCMAILBOX_CLOCK_CORE);
UART1->BAUD = ((source_clock / (115200 * 8)) - 1);
UART1->CNTL |= UART1_CNTL_TX_ENABLE_Msk;
COMPLETE_MEMORY_READS;
gpio_set_function(UART_TX_PIN, GPIO_FUNCTION_ALT5);
// Turn on USB peripheral.
vcmailbox_set_power_state(VCMAILBOX_DEVICE_USB_HCD, true);
// Timer 1/1024 second tick
SYSTMR->CS_b.M1 = 1;
SYSTMR->C1 = SYSTMR->CLO + 977;
BP_EnableIRQ(TIMER_1_IRQn);
BP_SetPriority(USB_IRQn, 0x00);
BP_ClearPendingIRQ(USB_IRQn);
BP_EnableIRQ(USB_IRQn);
BP_EnableIRQs();
}
void board_led_write(bool state)
{
gpio_set_value(LED_PIN, state ? LED_STATE_ON : (1-LED_STATE_ON));
}
uint32_t board_button_read(void)
{
return 0;
}
int board_uart_read(uint8_t* buf, int len)
{
(void) buf; (void) len;
return 0;
}
int board_uart_write(void const * buf, int len)
{
for (int i = 0; i < len; i++) {
const char* cbuf = buf;
while (!UART1->STAT_b.TX_READY) {}
if (cbuf[i] == '\n') {
UART1->IO = '\r';
while (!UART1->STAT_b.TX_READY) {}
}
UART1->IO = cbuf[i];
}
return len;
}
#if CFG_TUSB_OS == OPT_OS_NONE
volatile uint32_t system_ticks = 0;
void TIMER_1_IRQHandler(void)
{
system_ticks++;
SYSTMR->C1 += 977;
SYSTMR->CS_b.M1 = 1;
}
uint32_t board_millis(void)
{
return system_ticks;
}
#endif
void HardFault_Handler (void)
{
// asm("bkpt");
}
// Required by __libc_init_array in startup code if we are compiling using
// -nostdlib/-nostartfiles.
void _init(void)
{
}

View File

@ -3,18 +3,16 @@ DEPS_SUBMODULES += $(MCU_DIR)
include $(TOP)/$(BOARD_PATH)/board.mk
CC = clang
CFLAGS += \
-mcpu=cortex-a72 \
-Wall \
-O0 \
-ffreestanding \
-nostdlib \
-nostartfiles \
-std=c17 \
-mgeneral-regs-only \
-DCFG_TUSB_MCU=OPT_MCU_BCM2711
-std=c17
CROSS_COMPILE = aarch64-none-elf-
# mcu driver cause following warnings
CFLAGS += -Wno-error=cast-qual
@ -22,25 +20,22 @@ CFLAGS += -Wno-error=cast-qual
SRC_C += \
src/portable/synopsys/dwc2/dcd_dwc2.c \
$(MCU_DIR)/broadcom/gen/interrupt_handlers.c \
$(MCU_DIR)/broadcom/gpio.c \
$(MCU_DIR)/broadcom/interrupts.c \
$(MCU_DIR)/broadcom/io.c \
$(MCU_DIR)/broadcom/mmu.c \
$(MCU_DIR)/broadcom/caches.c \
$(MCU_DIR)/broadcom/vcmailbox.c
CROSS_COMPILE = aarch64-none-elf-
SKIP_NANOLIB = 1
LD_FILE = $(MCU_DIR)/broadcom/link.ld
LD_FILE = $(MCU_DIR)/broadcom/link8.ld
INC += \
$(TOP)/$(BOARD_PATH) \
$(TOP)/$(MCU_DIR) \
$(TOP)/lib/CMSIS_5/CMSIS/Core_A/Include
SRC_S += $(MCU_DIR)/broadcom/boot.S
SRC_S += $(MCU_DIR)/broadcom/boot8.S
$(BUILD)/kernel8.img: $(BUILD)/$(PROJECT).elf
$(OBJCOPY) -O binary $^ $@
@ -48,4 +43,4 @@ $(BUILD)/kernel8.img: $(BUILD)/$(PROJECT).elf
# Copy to kernel to netboot drive or SD card
# Change destinaation to fit your need
flash: $(BUILD)/kernel8.img
$(CP) $< /home/$(USER)/Documents/code/pi4_tinyusb/boot_cpy
@$(CP) $< /home/$(USER)/Documents/code/pi_tinyusb/boot_cpy

View File

@ -1,16 +1,6 @@
# Apply board specific content here
target_include_directories(${COMPONENT_LIB} PRIVATE .)
idf_build_get_property(idf_target IDF_TARGET)
message(STATUS "Apply ${BOARD}(${idf_target}) specific options for component: ${COMPONENT_TARGET}")
if(NOT ${idf_target} STREQUAL "esp32s3")
message(FATAL_ERROR "Incorrect target for board ${BOARD}: (${idf_target}), try to clean the build first." )
endif()
set(IDF_TARGET "esp32s3" FORCE)
target_compile_options(${COMPONENT_TARGET} PUBLIC
"-DCFG_TUSB_MCU=OPT_MCU_ESP32S3"
"-DCFG_TUSB_OS=OPT_OS_FREERTOS"

View File

@ -0,0 +1,7 @@
# Apply board specific content here
target_include_directories(${COMPONENT_LIB} PRIVATE .)
target_compile_options(${COMPONENT_TARGET} PUBLIC
"-DCFG_TUSB_MCU=OPT_MCU_ESP32S3"
"-DCFG_TUSB_OS=OPT_OS_FREERTOS"
)

View File

@ -0,0 +1,43 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2020, Ha Thach (tinyusb.org)
*
* 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.
*
* This file is part of the TinyUSB stack.
*/
#ifndef BOARD_H_
#define BOARD_H_
#ifdef __cplusplus
extern "C" {
#endif
#define NEOPIXEL_PIN 48
#define BUTTON_PIN 0
#define BUTTON_STATE_ACTIVE 0
#ifdef __cplusplus
}
#endif
#endif /* BOARD_H_ */

View File

@ -0,0 +1,7 @@
# Apply board specific content here
target_include_directories(${COMPONENT_LIB} PRIVATE .)
target_compile_options(${COMPONENT_TARGET} PUBLIC
"-DCFG_TUSB_MCU=OPT_MCU_ESP32S3"
"-DCFG_TUSB_OS=OPT_OS_FREERTOS"
)

View File

@ -0,0 +1,43 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2020, Ha Thach (tinyusb.org)
*
* 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.
*
* This file is part of the TinyUSB stack.
*/
#ifndef BOARD_H_
#define BOARD_H_
#ifdef __cplusplus
extern "C" {
#endif
#define NEOPIXEL_PIN 48
#define BUTTON_PIN 0
#define BUTTON_STATE_ACTIVE 0
#ifdef __cplusplus
}
#endif
#endif /* BOARD_H_ */

View File

@ -0,0 +1,217 @@
/*
** ###################################################################
** Processors: K32L2B31VFM0A
** K32L2B31VFT0A
** K32L2B31VLH0A
** K32L2B31VMP0A
**
** Compiler: GNU C Compiler
** Reference manual: K32L2B3xRM, Rev.0, July 2019
** Version: rev. 1.0, 2019-07-30
** Build: b190930
**
** Abstract:
** Linker file for the GNU C Compiler
**
** Copyright 2016 Freescale Semiconductor, Inc.
** Copyright 2016-2019 NXP
** All rights reserved.
**
** SPDX-License-Identifier: BSD-3-Clause
**
** http: www.nxp.com
** mail: support@nxp.com
**
** ###################################################################
*/
/* Entry Point */
ENTRY(Reset_Handler)
HEAP_SIZE = DEFINED(__heap_size__) ? __heap_size__ : 0x0400;
STACK_SIZE = DEFINED(__stack_size__) ? __stack_size__ : 0x0400;
/* Specify the memory areas */
MEMORY
{
m_interrupts (RX) : ORIGIN = 0x00008000, LENGTH = 0x00000200
m_flash_config (RX) : ORIGIN = 0x00008400, LENGTH = 0x00000010
m_text (RX) : ORIGIN = 0x00008410, LENGTH = 0x00037BF0
m_data (RW) : ORIGIN = 0x1FFFE000, LENGTH = 0x00008000
}
/* Define output sections */
SECTIONS
{
/* The startup code goes first into internal flash */
.interrupts :
{
. = ALIGN(4);
KEEP(*(.isr_vector)) /* Startup code */
. = ALIGN(4);
} > m_interrupts
.flash_config :
{
. = ALIGN(4);
KEEP(*(.FlashConfig)) /* Flash Configuration Field (FCF) */
. = ALIGN(4);
} > m_flash_config
/* The program code and other data goes into internal flash */
.text :
{
. = ALIGN(4);
*(.text) /* .text sections (code) */
*(.text*) /* .text* sections (code) */
*(.rodata) /* .rodata sections (constants, strings, etc.) */
*(.rodata*) /* .rodata* sections (constants, strings, etc.) */
*(.glue_7) /* glue arm to thumb code */
*(.glue_7t) /* glue thumb to arm code */
*(.eh_frame)
KEEP (*(.init))
KEEP (*(.fini))
. = ALIGN(4);
} > m_text
.ARM.extab :
{
*(.ARM.extab* .gnu.linkonce.armextab.*)
} > m_text
.ARM :
{
__exidx_start = .;
*(.ARM.exidx*)
__exidx_end = .;
} > m_text
.ctors :
{
__CTOR_LIST__ = .;
/* gcc uses crtbegin.o to find the start of
the constructors, so we make sure it is
first. Because this is a wildcard, it
doesn't matter if the user does not
actually link against crtbegin.o; the
linker won't look for a file to match a
wildcard. The wildcard also means that it
doesn't matter which directory crtbegin.o
is in. */
KEEP (*crtbegin.o(.ctors))
KEEP (*crtbegin?.o(.ctors))
/* We don't want to include the .ctor section from
from the crtend.o file until after the sorted ctors.
The .ctor section from the crtend file contains the
end of ctors marker and it must be last */
KEEP (*(EXCLUDE_FILE(*crtend?.o *crtend.o) .ctors))
KEEP (*(SORT(.ctors.*)))
KEEP (*(.ctors))
__CTOR_END__ = .;
} > m_text
.dtors :
{
__DTOR_LIST__ = .;
KEEP (*crtbegin.o(.dtors))
KEEP (*crtbegin?.o(.dtors))
KEEP (*(EXCLUDE_FILE(*crtend?.o *crtend.o) .dtors))
KEEP (*(SORT(.dtors.*)))
KEEP (*(.dtors))
__DTOR_END__ = .;
} > m_text
.preinit_array :
{
PROVIDE_HIDDEN (__preinit_array_start = .);
KEEP (*(.preinit_array*))
PROVIDE_HIDDEN (__preinit_array_end = .);
} > m_text
.init_array :
{
PROVIDE_HIDDEN (__init_array_start = .);
KEEP (*(SORT(.init_array.*)))
KEEP (*(.init_array*))
PROVIDE_HIDDEN (__init_array_end = .);
} > m_text
.fini_array :
{
PROVIDE_HIDDEN (__fini_array_start = .);
KEEP (*(SORT(.fini_array.*)))
KEEP (*(.fini_array*))
PROVIDE_HIDDEN (__fini_array_end = .);
} > m_text
__etext = .; /* define a global symbol at end of code */
__DATA_ROM = .; /* Symbol is used by startup for data initialization */
/* reserve MTB memory at the beginning of m_data */
.mtb : /* MTB buffer address as defined by the hardware */
{
. = ALIGN(8);
_mtb_start = .;
KEEP(*(.mtb_buf)) /* need to KEEP Micro Trace Buffer as not referenced by application */
. = ALIGN(8);
_mtb_end = .;
} > m_data
.data : AT(__DATA_ROM)
{
. = ALIGN(4);
__DATA_RAM = .;
__data_start__ = .; /* create a global symbol at data start */
*(.data) /* .data sections */
*(.data*) /* .data* sections */
KEEP(*(.jcr*))
. = ALIGN(4);
__data_end__ = .; /* define a global symbol at data end */
} > m_data
__DATA_END = __DATA_ROM + (__data_end__ - __data_start__);
text_end = ORIGIN(m_text) + LENGTH(m_text);
ASSERT(__DATA_END <= text_end, "region m_text overflowed with text and data")
/* Uninitialized data section */
.bss :
{
/* This is used by the startup in order to initialize the .bss section */
. = ALIGN(4);
__START_BSS = .;
__bss_start__ = .;
*(.bss)
*(.bss*)
*(COMMON)
. = ALIGN(4);
__bss_end__ = .;
__END_BSS = .;
} > m_data
.heap :
{
. = ALIGN(8);
__end__ = .;
PROVIDE(end = .);
__HeapBase = .;
. += HEAP_SIZE;
__HeapLimit = .;
__heap_limit = .; /* Add for _sbrk */
} > m_data
.stack :
{
. = ALIGN(8);
. += STACK_SIZE;
} > m_data
/* Initializes stack on the end of block */
__StackTop = ORIGIN(m_data) + LENGTH(m_data);
__StackLimit = __StackTop - STACK_SIZE;
PROVIDE(__stack = __StackTop);
.ARM.attributes 0 : { *(.ARM.attributes) }
ASSERT(__StackLimit >= __HeapLimit, "region m_data overflowed with stack and heap")
}

Some files were not shown because too many files have changed in this diff Show More