mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-24 16:55:36 +03:00
PICO: Adding tinyUSB library
This commit is contained in:
parent
1774693395
commit
0109f50909
1507 changed files with 299535 additions and 0 deletions
149
lib/main/tinyUSB/hw/bsp/nrf/FreeRTOSConfig/FreeRTOSConfig.h
Normal file
149
lib/main/tinyUSB/hw/bsp/nrf/FreeRTOSConfig/FreeRTOSConfig.h
Normal file
|
@ -0,0 +1,149 @@
|
|||
/*
|
||||
* FreeRTOS Kernel V10.0.0
|
||||
* Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved.
|
||||
*
|
||||
* 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. If you wish to use our Amazon
|
||||
* FreeRTOS name, please do so in a fair use way that does not cause confusion.
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* http://www.FreeRTOS.org
|
||||
* http://aws.amazon.com/freertos
|
||||
*
|
||||
* 1 tab == 4 spaces!
|
||||
*/
|
||||
|
||||
|
||||
#ifndef FREERTOS_CONFIG_H
|
||||
#define FREERTOS_CONFIG_H
|
||||
|
||||
/*-----------------------------------------------------------
|
||||
* Application specific definitions.
|
||||
*
|
||||
* These definitions should be adjusted for your particular hardware and
|
||||
* application requirements.
|
||||
*
|
||||
* THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE
|
||||
* FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE.
|
||||
*
|
||||
* See http://www.freertos.org/a00110.html.
|
||||
*----------------------------------------------------------*/
|
||||
|
||||
// skip if included from IAR assembler
|
||||
#ifndef __IASMARM__
|
||||
#include "nrf.h"
|
||||
#endif
|
||||
|
||||
/* Cortex M23/M33 port configuration. */
|
||||
#define configENABLE_MPU 0
|
||||
#define configENABLE_FPU 1
|
||||
#define configENABLE_TRUSTZONE 0
|
||||
#define configMINIMAL_SECURE_STACK_SIZE (1024)
|
||||
|
||||
#define configUSE_PREEMPTION 1
|
||||
#define configUSE_PORT_OPTIMISED_TASK_SELECTION 0
|
||||
#define configCPU_CLOCK_HZ SystemCoreClock
|
||||
#define configTICK_RATE_HZ ( 1000 )
|
||||
#define configMAX_PRIORITIES ( 5 )
|
||||
#define configMINIMAL_STACK_SIZE ( 128 )
|
||||
#define configTOTAL_HEAP_SIZE ( configSUPPORT_DYNAMIC_ALLOCATION*4*1024 )
|
||||
#define configMAX_TASK_NAME_LEN 16
|
||||
#define configUSE_16_BIT_TICKS 0
|
||||
#define configIDLE_SHOULD_YIELD 1
|
||||
#define configUSE_MUTEXES 1
|
||||
#define configUSE_RECURSIVE_MUTEXES 1
|
||||
#define configUSE_COUNTING_SEMAPHORES 1
|
||||
#define configQUEUE_REGISTRY_SIZE 4
|
||||
#define configUSE_QUEUE_SETS 0
|
||||
#define configUSE_TIME_SLICING 0
|
||||
#define configUSE_NEWLIB_REENTRANT 0
|
||||
#define configENABLE_BACKWARD_COMPATIBILITY 1
|
||||
#define configSTACK_ALLOCATION_FROM_SEPARATE_HEAP 0
|
||||
|
||||
#define configSUPPORT_STATIC_ALLOCATION 1
|
||||
#define configSUPPORT_DYNAMIC_ALLOCATION 0
|
||||
|
||||
/* Hook function related definitions. */
|
||||
#define configUSE_IDLE_HOOK 0
|
||||
#define configUSE_TICK_HOOK 0
|
||||
#define configUSE_MALLOC_FAILED_HOOK 0 // cause nested extern warning
|
||||
#define configCHECK_FOR_STACK_OVERFLOW 2
|
||||
#define configCHECK_HANDLER_INSTALLATION 0
|
||||
|
||||
/* Run time and task stats gathering related definitions. */
|
||||
#define configGENERATE_RUN_TIME_STATS 0
|
||||
#define configRECORD_STACK_HIGH_ADDRESS 1
|
||||
#define configUSE_TRACE_FACILITY 1 // legacy trace
|
||||
#define configUSE_STATS_FORMATTING_FUNCTIONS 0
|
||||
|
||||
/* Co-routine definitions. */
|
||||
#define configUSE_CO_ROUTINES 0
|
||||
#define configMAX_CO_ROUTINE_PRIORITIES 2
|
||||
|
||||
/* Software timer related definitions. */
|
||||
#define configUSE_TIMERS 1
|
||||
#define configTIMER_TASK_PRIORITY (configMAX_PRIORITIES-2)
|
||||
#define configTIMER_QUEUE_LENGTH 32
|
||||
#define configTIMER_TASK_STACK_DEPTH configMINIMAL_STACK_SIZE
|
||||
|
||||
/* Optional functions - most linkers will remove unused functions anyway. */
|
||||
#define INCLUDE_vTaskPrioritySet 0
|
||||
#define INCLUDE_uxTaskPriorityGet 0
|
||||
#define INCLUDE_vTaskDelete 0
|
||||
#define INCLUDE_vTaskSuspend 1 // required for queue, semaphore, mutex to be blocked indefinitely with portMAX_DELAY
|
||||
#define INCLUDE_xResumeFromISR 0
|
||||
#define INCLUDE_vTaskDelayUntil 1
|
||||
#define INCLUDE_vTaskDelay 1
|
||||
#define INCLUDE_xTaskGetSchedulerState 0
|
||||
#define INCLUDE_xTaskGetCurrentTaskHandle 1
|
||||
#define INCLUDE_uxTaskGetStackHighWaterMark 0
|
||||
#define INCLUDE_xTaskGetIdleTaskHandle 0
|
||||
#define INCLUDE_xTimerGetTimerDaemonTaskHandle 0
|
||||
#define INCLUDE_pcTaskGetTaskName 0
|
||||
#define INCLUDE_eTaskGetState 0
|
||||
#define INCLUDE_xEventGroupSetBitFromISR 0
|
||||
#define INCLUDE_xTimerPendFunctionCall 0
|
||||
|
||||
/* FreeRTOS hooks to NVIC vectors */
|
||||
#define xPortPendSVHandler PendSV_Handler
|
||||
#define xPortSysTickHandler SysTick_Handler
|
||||
#define vPortSVCHandler SVC_Handler
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// Interrupt nesting behavior configuration.
|
||||
//--------------------------------------------------------------------+
|
||||
|
||||
// For Cortex-M specific: __NVIC_PRIO_BITS is defined in mcu header
|
||||
#define configPRIO_BITS 3
|
||||
|
||||
/* The lowest interrupt priority that can be used in a call to a "set priority" function. */
|
||||
#define configLIBRARY_LOWEST_INTERRUPT_PRIORITY ((1<<configPRIO_BITS) - 1)
|
||||
|
||||
/* The highest interrupt priority that can be used by any interrupt service
|
||||
routine that makes calls to interrupt safe FreeRTOS API functions. DO NOT CALL
|
||||
INTERRUPT SAFE FREERTOS API FUNCTIONS FROM ANY INTERRUPT THAT HAS A HIGHER
|
||||
PRIORITY THAN THIS! (higher priorities are lower numeric values. */
|
||||
#define configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY 2
|
||||
|
||||
/* Interrupt priorities used by the kernel port layer itself. These are generic
|
||||
to all Cortex-M ports, and do not rely on any particular library functions. */
|
||||
#define configKERNEL_INTERRUPT_PRIORITY ( configLIBRARY_LOWEST_INTERRUPT_PRIORITY << (8 - configPRIO_BITS) )
|
||||
|
||||
/* !!!! configMAX_SYSCALL_INTERRUPT_PRIORITY must not be set to zero !!!!
|
||||
See http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html. */
|
||||
#define configMAX_SYSCALL_INTERRUPT_PRIORITY ( configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY << (8 - configPRIO_BITS) )
|
||||
|
||||
#endif
|
|
@ -0,0 +1,5 @@
|
|||
set(MCU_VARIANT nrf52840)
|
||||
set(LD_FILE_GNU ${CMAKE_CURRENT_LIST_DIR}/../../linker/nrf52840_s140_v6.ld)
|
||||
|
||||
function(update_board TARGET)
|
||||
endfunction()
|
52
lib/main/tinyUSB/hw/bsp/nrf/boards/adafruit_clue/board.h
Normal file
52
lib/main/tinyUSB/hw/bsp/nrf/boards/adafruit_clue/board.h
Normal file
|
@ -0,0 +1,52 @@
|
|||
/*
|
||||
* 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 _PINNUM(port, pin) ((port)*32 + (pin))
|
||||
|
||||
// LED
|
||||
#define LED_PIN _PINNUM(1, 1)
|
||||
#define LED_STATE_ON 1
|
||||
|
||||
// Button
|
||||
#define BUTTON_PIN _PINNUM(1, 02)
|
||||
#define BUTTON_STATE_ACTIVE 0
|
||||
|
||||
// UART
|
||||
#define UART_RX_PIN 4
|
||||
#define UART_TX_PIN 5
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* BOARD_H_ */
|
13
lib/main/tinyUSB/hw/bsp/nrf/boards/adafruit_clue/board.mk
Normal file
13
lib/main/tinyUSB/hw/bsp/nrf/boards/adafruit_clue/board.mk
Normal file
|
@ -0,0 +1,13 @@
|
|||
MCU_VARIANT = nrf52840
|
||||
CFLAGS += -DNRF52840_XXAA
|
||||
|
||||
# All source paths should be relative to the top level.
|
||||
LD_FILE = hw/bsp/nrf/linker/nrf52840_s140_v6.ld
|
||||
|
||||
$(BUILD)/$(PROJECT).zip: $(BUILD)/$(PROJECT).hex
|
||||
adafruit-nrfutil dfu genpkg --dev-type 0x0052 --sd-req 0xFFFE --application $^ $@
|
||||
|
||||
# flash using adafruit-nrfutil dfu
|
||||
flash: $(BUILD)/$(PROJECT).zip
|
||||
@:$(call check_defined, SERIAL, example: SERIAL=/dev/ttyACM0)
|
||||
adafruit-nrfutil --verbose dfu serial --package $^ -p $(SERIAL) -b 115200 --singlebank --touch 1200
|
|
@ -0,0 +1,32 @@
|
|||
/* Linker script to configure memory regions. */
|
||||
|
||||
SEARCH_DIR(.)
|
||||
/*GROUP(-lgcc -lc -lnosys) not compatible with clang*/
|
||||
|
||||
MEMORY
|
||||
{
|
||||
FLASH (rx) : ORIGIN = 0x10000, LENGTH = 0xf0000
|
||||
RAM_NVIC (rwx) : ORIGIN = 0x20000000, LENGTH = 0x100
|
||||
RAM_CRASH_DATA (rwx) : ORIGIN = (0x20000000 + 0x100), LENGTH = 0x100
|
||||
RAM (rwx) : ORIGIN = ((0x20000000 + 0x100) + 0x100), LENGTH = (0x40000 - (0x100 + 0x100))
|
||||
}
|
||||
|
||||
SECTIONS
|
||||
{
|
||||
. = ALIGN(4);
|
||||
.svc_data :
|
||||
{
|
||||
PROVIDE(__start_svc_data = .);
|
||||
KEEP(*(.svc_data))
|
||||
PROVIDE(__stop_svc_data = .);
|
||||
} > RAM
|
||||
|
||||
.fs_data :
|
||||
{
|
||||
PROVIDE(__start_fs_data = .);
|
||||
KEEP(*(.fs_data))
|
||||
PROVIDE(__stop_fs_data = .);
|
||||
} > RAM
|
||||
} INSERT AFTER .data;
|
||||
|
||||
INCLUDE "nrf_common.ld"
|
|
@ -0,0 +1,5 @@
|
|||
set(MCU_VARIANT nrf52840)
|
||||
set(LD_FILE_GNU ${CMAKE_CURRENT_LIST_DIR}/arduino_nano33_ble.ld)
|
||||
|
||||
function(update_board TARGET)
|
||||
endfunction()
|
|
@ -0,0 +1,52 @@
|
|||
/*
|
||||
* 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 _PINNUM(port, pin) ((port)*32 + (pin))
|
||||
|
||||
// LED
|
||||
#define LED_PIN _PINNUM(0, 24)
|
||||
#define LED_STATE_ON 0
|
||||
|
||||
// Button
|
||||
#define BUTTON_PIN _PINNUM(1, 11) // D2
|
||||
#define BUTTON_STATE_ACTIVE 0
|
||||
|
||||
// UART
|
||||
#define UART_RX_PIN _PINNUM(1, 10)
|
||||
#define UART_TX_PIN _PINNUM(1, 3)
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* BOARD_H_ */
|
|
@ -0,0 +1,13 @@
|
|||
MCU_VARIANT = nrf52840
|
||||
CFLAGS += -DNRF52840_XXAA
|
||||
|
||||
LD_FILE = $(BOARD_PATH)/$(BOARD).ld
|
||||
|
||||
# flash using bossac (as part of Nano33 BSP tools)
|
||||
# can be found in arduino15/packages/arduino/tools/bossac/
|
||||
# Add it to your PATH or change BOSSAC variable to match your installation
|
||||
BOSSAC = bossac
|
||||
|
||||
flash: $(BUILD)/$(PROJECT).bin
|
||||
@:$(call check_defined, SERIAL, example: SERIAL=/dev/ttyACM0)
|
||||
$(BOSSAC) --port=$(SERIAL) -U -i -e -w $^ -R
|
|
@ -0,0 +1,5 @@
|
|||
set(MCU_VARIANT nrf52840)
|
||||
set(LD_FILE_GNU ${CMAKE_CURRENT_LIST_DIR}/../../linker/nrf52840_s140_v6.ld)
|
||||
|
||||
function(update_board TARGET)
|
||||
endfunction()
|
|
@ -0,0 +1,52 @@
|
|||
/*
|
||||
* 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 _PINNUM(port, pin) ((port)*32 + (pin))
|
||||
|
||||
// LED
|
||||
#define LED_PIN _PINNUM(1, 14)
|
||||
#define LED_STATE_ON 1
|
||||
|
||||
// Button
|
||||
#define BUTTON_PIN _PINNUM(1, 15)
|
||||
#define BUTTON_STATE_ACTIVE 1
|
||||
|
||||
// UART
|
||||
#define UART_RX_PIN 30
|
||||
#define UART_TX_PIN 14
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* BOARD_H_ */
|
|
@ -0,0 +1,13 @@
|
|||
MCU_VARIANT = nrf52840
|
||||
CFLAGS += -DNRF52840_XXAA
|
||||
|
||||
# All source paths should be relative to the top level.
|
||||
LD_FILE = hw/bsp/nrf/linker/nrf52840_s140_v6.ld
|
||||
|
||||
$(BUILD)/$(PROJECT).zip: $(BUILD)/$(PROJECT).hex
|
||||
adafruit-nrfutil dfu genpkg --dev-type 0x0052 --sd-req 0xFFFE --application $^ $@
|
||||
|
||||
# flash using adafruit-nrfutil dfu
|
||||
flash: $(BUILD)/$(PROJECT).zip
|
||||
@:$(call check_defined, SERIAL, example: SERIAL=/dev/ttyACM0)
|
||||
adafruit-nrfutil --verbose dfu serial --package $^ -p $(SERIAL) -b 115200 --singlebank --touch 1200
|
|
@ -0,0 +1,8 @@
|
|||
set(MCU_VARIANT nrf52840)
|
||||
set(LD_FILE_GNU ${CMAKE_CURRENT_LIST_DIR}/../../linker/nrf52840_s140_v6.ld)
|
||||
|
||||
# enable max3421 host driver for this board
|
||||
# set(MAX3421_HOST 1)
|
||||
|
||||
function(update_board TARGET)
|
||||
endfunction()
|
|
@ -0,0 +1,59 @@
|
|||
/*
|
||||
* 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 _PINNUM(port, pin) ((port)*32 + (pin))
|
||||
|
||||
// LED
|
||||
#define LED_PIN _PINNUM(1, 15)
|
||||
#define LED_STATE_ON 1
|
||||
|
||||
// Button
|
||||
#define BUTTON_PIN _PINNUM(1, 02)
|
||||
#define BUTTON_STATE_ACTIVE 0
|
||||
|
||||
// UART
|
||||
#define UART_RX_PIN 24
|
||||
#define UART_TX_PIN 25
|
||||
|
||||
// SPI for USB host shield
|
||||
#define MAX3421_SCK_PIN 14
|
||||
#define MAX3421_MOSI_PIN 13
|
||||
#define MAX3421_MISO_PIN 15
|
||||
#define MAX3421_CS_PIN 27 // D10
|
||||
#define MAX3421_INTR_PIN 26 // D9
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* BOARD_H_ */
|
|
@ -0,0 +1,16 @@
|
|||
MCU_VARIANT = nrf52840
|
||||
CFLAGS += -DNRF52840_XXAA
|
||||
|
||||
# enable max3421 host driver for this board
|
||||
MAX3421_HOST = 1
|
||||
|
||||
# All source paths should be relative to the top level.
|
||||
LD_FILE = hw/bsp/nrf/linker/nrf52840_s140_v6.ld
|
||||
|
||||
$(BUILD)/$(PROJECT).zip: $(BUILD)/$(PROJECT).hex
|
||||
adafruit-nrfutil dfu genpkg --dev-type 0x0052 --sd-req 0xFFFE --application $^ $@
|
||||
|
||||
# flash using adafruit-nrfutil dfu
|
||||
flash: $(BUILD)/$(PROJECT).zip
|
||||
@:$(call check_defined, SERIAL, example: SERIAL=/dev/ttyACM0)
|
||||
adafruit-nrfutil --verbose dfu serial --package $^ -p $(SERIAL) -b 115200 --singlebank --touch 1200
|
|
@ -0,0 +1,5 @@
|
|||
set(MCU_VARIANT nrf52840)
|
||||
set(LD_FILE_GNU ${CMAKE_CURRENT_LIST_DIR}/../../linker/nrf52840_s140_v6.ld)
|
||||
|
||||
function(update_board TARGET)
|
||||
endfunction()
|
|
@ -0,0 +1,52 @@
|
|||
/*
|
||||
* 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 _PINNUM(port, pin) ((port)*32 + (pin))
|
||||
|
||||
// LED
|
||||
#define LED_PIN _PINNUM(1, 9)
|
||||
#define LED_STATE_ON 1
|
||||
|
||||
// Button
|
||||
#define BUTTON_PIN _PINNUM(1, 02)
|
||||
#define BUTTON_STATE_ACTIVE 0
|
||||
|
||||
// UART
|
||||
#define UART_RX_PIN 24
|
||||
#define UART_TX_PIN 25
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* BOARD_H_ */
|
|
@ -0,0 +1,13 @@
|
|||
MCU_VARIANT = nrf52840
|
||||
CFLAGS += -DNRF52840_XXAA
|
||||
|
||||
# All source paths should be relative to the top level.
|
||||
LD_FILE = hw/bsp/nrf/linker/nrf52840_s140_v6.ld
|
||||
|
||||
$(BUILD)/$(PROJECT).zip: $(BUILD)/$(PROJECT).hex
|
||||
adafruit-nrfutil dfu genpkg --dev-type 0x0052 --sd-req 0xFFFE --application $^ $@
|
||||
|
||||
# flash using adafruit-nrfutil dfu
|
||||
flash: $(BUILD)/$(PROJECT).zip
|
||||
@:$(call check_defined, SERIAL, example: SERIAL=/dev/ttyACM0)
|
||||
adafruit-nrfutil --verbose dfu serial --package $^ -p $(SERIAL) -b 115200 --singlebank --touch 1200
|
|
@ -0,0 +1,5 @@
|
|||
set(MCU_VARIANT nrf52840)
|
||||
set(LD_FILE_GNU ${CMAKE_CURRENT_LIST_DIR}/../../linker/nrf52840_s140_v6.ld)
|
||||
|
||||
function(update_board TARGET)
|
||||
endfunction()
|
|
@ -0,0 +1,52 @@
|
|||
/*
|
||||
* 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 _PINNUM(port, pin) ((port)*32 + (pin))
|
||||
|
||||
// LED
|
||||
#define LED_PIN _PINNUM(0, 6)
|
||||
#define LED_STATE_ON 1
|
||||
|
||||
// Button
|
||||
#define BUTTON_PIN _PINNUM(0, 29)
|
||||
#define BUTTON_STATE_ACTIVE 0
|
||||
|
||||
// UART
|
||||
#define UART_RX_PIN 25
|
||||
#define UART_TX_PIN 24
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* BOARD_H_ */
|
|
@ -0,0 +1,13 @@
|
|||
MCU_VARIANT = nrf52840
|
||||
CFLAGS += -DNRF52840_XXAA
|
||||
|
||||
# All source paths should be relative to the top level.
|
||||
LD_FILE = hw/bsp/nrf/linker/nrf52840_s140_v6.ld
|
||||
|
||||
$(BUILD)/$(PROJECT).zip: $(BUILD)/$(PROJECT).hex
|
||||
adafruit-nrfutil dfu genpkg --dev-type 0x0052 --sd-req 0xFFFE --application $^ $@
|
||||
|
||||
# flash using adafruit-nrfutil dfu
|
||||
flash: $(BUILD)/$(PROJECT).zip
|
||||
@:$(call check_defined, SERIAL, example: SERIAL=/dev/ttyACM0)
|
||||
adafruit-nrfutil --verbose dfu serial --package $^ -p $(SERIAL) -b 115200 --singlebank --touch 1200
|
4
lib/main/tinyUSB/hw/bsp/nrf/boards/pca10056/board.cmake
Normal file
4
lib/main/tinyUSB/hw/bsp/nrf/boards/pca10056/board.cmake
Normal file
|
@ -0,0 +1,4 @@
|
|||
set(MCU_VARIANT nrf52840)
|
||||
|
||||
function(update_board TARGET)
|
||||
endfunction()
|
60
lib/main/tinyUSB/hw/bsp/nrf/boards/pca10056/board.h
Normal file
60
lib/main/tinyUSB/hw/bsp/nrf/boards/pca10056/board.h
Normal file
|
@ -0,0 +1,60 @@
|
|||
/*
|
||||
* 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 _PINNUM(port, pin) ((port)*32 + (pin))
|
||||
|
||||
// LED
|
||||
#define LED_PIN 13
|
||||
#define LED_STATE_ON 0
|
||||
|
||||
// Button
|
||||
#define BUTTON_PIN 25 // button 4
|
||||
#define BUTTON_STATE_ACTIVE 0
|
||||
|
||||
// UART
|
||||
#define UART_RX_PIN 8
|
||||
#define UART_TX_PIN 6
|
||||
|
||||
// SPI for USB host shield
|
||||
// Pin is correct but not working probably due to signal incompatible (1.8V 3v3) with MAC3421E !?
|
||||
//#define MAX3421_SCK_PIN _PINNUM(1, 15)
|
||||
//#define MAX3421_MOSI_PIN _PINNUM(1, 13)
|
||||
//#define MAX3421_MISO_PIN _PINNUM(1, 14)
|
||||
//#define MAX3421_CS_PIN _PINNUM(1, 12)
|
||||
//#define MAX3421_INTR_PIN _PINNUM(1, 11)
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* BOARD_H_ */
|
7
lib/main/tinyUSB/hw/bsp/nrf/boards/pca10056/board.mk
Normal file
7
lib/main/tinyUSB/hw/bsp/nrf/boards/pca10056/board.mk
Normal file
|
@ -0,0 +1,7 @@
|
|||
MCU_VARIANT = nrf52840
|
||||
CFLAGS += -DNRF52840_XXAA
|
||||
|
||||
LD_FILE = hw/mcu/nordic/nrfx/mdk/nrf52840_xxaa.ld
|
||||
|
||||
# flash using jlink
|
||||
flash: flash-jlink
|
|
@ -0,0 +1,238 @@
|
|||
|
||||
/*********************************************************************
|
||||
*
|
||||
* OnProjectLoad
|
||||
*
|
||||
* Function description
|
||||
* Project load routine. Required.
|
||||
*
|
||||
**********************************************************************
|
||||
*/
|
||||
void OnProjectLoad (void) {
|
||||
// Dialog-generated settings
|
||||
Project.AddSvdFile ("$(InstallDir)/Config/CPU/Cortex-M4F.svd");
|
||||
Project.AddSvdFile ("$(InstallDir)/Config/Peripherals/ARMv7M.svd");
|
||||
|
||||
Project.SetDevice ("nRF52840_xxAA");
|
||||
Project.SetHostIF ("USB", "");
|
||||
Project.SetTargetIF ("SWD");
|
||||
Project.SetTIFSpeed ("8 MHz");
|
||||
Project.SetTraceSource ("Trace Pins");
|
||||
Project.SetTracePortWidth (4);
|
||||
|
||||
// User settings
|
||||
File.Open ("../../../../../../examples/device/cdc_msc/cmake-build-pca10056/cdc_msc.elf");
|
||||
}
|
||||
|
||||
/*********************************************************************
|
||||
*
|
||||
* TargetReset
|
||||
*
|
||||
* Function description
|
||||
* Replaces the default target device reset routine. Optional.
|
||||
*
|
||||
* Notes
|
||||
* This example demonstrates the usage when
|
||||
* debugging a RAM program on a Cortex-M target device
|
||||
*
|
||||
**********************************************************************
|
||||
*/
|
||||
//void TargetReset (void) {
|
||||
//
|
||||
// unsigned int SP;
|
||||
// unsigned int PC;
|
||||
// unsigned int VectorTableAddr;
|
||||
//
|
||||
// Exec.Reset();
|
||||
//
|
||||
// VectorTableAddr = Elf.GetBaseAddr();
|
||||
//
|
||||
// if (VectorTableAddr != 0xFFFFFFFF) {
|
||||
//
|
||||
// Util.Log("Resetting Program.");
|
||||
//
|
||||
// SP = Target.ReadU32(VectorTableAddr);
|
||||
// Target.SetReg("SP", SP);
|
||||
//
|
||||
// PC = Target.ReadU32(VectorTableAddr + 4);
|
||||
// Target.SetReg("PC", PC);
|
||||
// }
|
||||
//}
|
||||
|
||||
/*********************************************************************
|
||||
*
|
||||
* BeforeTargetReset
|
||||
*
|
||||
* Function description
|
||||
* Event handler routine. Optional.
|
||||
*
|
||||
**********************************************************************
|
||||
*/
|
||||
//void BeforeTargetReset (void) {
|
||||
//}
|
||||
|
||||
/*********************************************************************
|
||||
*
|
||||
* AfterTargetReset
|
||||
*
|
||||
* Function description
|
||||
* Event handler routine.
|
||||
* - Sets the PC register to program reset value.
|
||||
* - Sets the SP register to program reset value on Cortex-M.
|
||||
*
|
||||
**********************************************************************
|
||||
*/
|
||||
void AfterTargetReset (void) {
|
||||
unsigned int SP;
|
||||
unsigned int PC;
|
||||
unsigned int VectorTableAddr;
|
||||
|
||||
VectorTableAddr = Elf.GetBaseAddr();
|
||||
|
||||
if (VectorTableAddr == 0xFFFFFFFF) {
|
||||
Util.Log("Project file error: failed to get program base");
|
||||
} else {
|
||||
SP = Target.ReadU32(VectorTableAddr);
|
||||
Target.SetReg("SP", SP);
|
||||
|
||||
PC = Target.ReadU32(VectorTableAddr + 4);
|
||||
Target.SetReg("PC", PC);
|
||||
}
|
||||
}
|
||||
|
||||
/*********************************************************************
|
||||
*
|
||||
* DebugStart
|
||||
*
|
||||
* Function description
|
||||
* Replaces the default debug session startup routine. Optional.
|
||||
*
|
||||
**********************************************************************
|
||||
*/
|
||||
//void DebugStart (void) {
|
||||
//}
|
||||
|
||||
/*********************************************************************
|
||||
*
|
||||
* TargetConnect
|
||||
*
|
||||
* Function description
|
||||
* Replaces the default target IF connection routine. Optional.
|
||||
*
|
||||
**********************************************************************
|
||||
*/
|
||||
//void TargetConnect (void) {
|
||||
//}
|
||||
|
||||
/*********************************************************************
|
||||
*
|
||||
* BeforeTargetConnect
|
||||
*
|
||||
* Function description
|
||||
* Event handler routine. Optional.
|
||||
*
|
||||
**********************************************************************
|
||||
*/
|
||||
void BeforeTargetConnect (void) {
|
||||
}
|
||||
|
||||
/*********************************************************************
|
||||
*
|
||||
* AfterTargetConnect
|
||||
*
|
||||
* Function description
|
||||
* Event handler routine. Optional.
|
||||
*
|
||||
**********************************************************************
|
||||
*/
|
||||
//void AfterTargetConnect (void) {
|
||||
//}
|
||||
|
||||
/*********************************************************************
|
||||
*
|
||||
* TargetDownload
|
||||
*
|
||||
* Function description
|
||||
* Replaces the default program download routine. Optional.
|
||||
*
|
||||
**********************************************************************
|
||||
*/
|
||||
//void TargetDownload (void) {
|
||||
//}
|
||||
|
||||
/*********************************************************************
|
||||
*
|
||||
* BeforeTargetDownload
|
||||
*
|
||||
* Function description
|
||||
* Event handler routine. Optional.
|
||||
*
|
||||
**********************************************************************
|
||||
*/
|
||||
//void BeforeTargetDownload (void) {
|
||||
//}
|
||||
|
||||
/*********************************************************************
|
||||
*
|
||||
* AfterTargetDownload
|
||||
*
|
||||
* Function description
|
||||
* Event handler routine.
|
||||
* - Sets the PC register to program reset value.
|
||||
* - Sets the SP register to program reset value on Cortex-M.
|
||||
*
|
||||
**********************************************************************
|
||||
*/
|
||||
void AfterTargetDownload (void) {
|
||||
unsigned int SP;
|
||||
unsigned int PC;
|
||||
unsigned int VectorTableAddr;
|
||||
|
||||
VectorTableAddr = Elf.GetBaseAddr();
|
||||
|
||||
if (VectorTableAddr == 0xFFFFFFFF) {
|
||||
Util.Log("Project file error: failed to get program base");
|
||||
} else {
|
||||
SP = Target.ReadU32(VectorTableAddr);
|
||||
Target.SetReg("SP", SP);
|
||||
|
||||
PC = Target.ReadU32(VectorTableAddr + 4);
|
||||
Target.SetReg("PC", PC);
|
||||
}
|
||||
}
|
||||
|
||||
/*********************************************************************
|
||||
*
|
||||
* BeforeTargetDisconnect
|
||||
*
|
||||
* Function description
|
||||
* Event handler routine. Optional.
|
||||
*
|
||||
**********************************************************************
|
||||
*/
|
||||
//void BeforeTargetDisconnect (void) {
|
||||
//}
|
||||
|
||||
/*********************************************************************
|
||||
*
|
||||
* AfterTargetDisconnect
|
||||
*
|
||||
* Function description
|
||||
* Event handler routine. Optional.
|
||||
*
|
||||
**********************************************************************
|
||||
*/
|
||||
//void AfterTargetDisconnect (void) {
|
||||
//}
|
||||
|
||||
/*********************************************************************
|
||||
*
|
||||
* AfterTargetHalt
|
||||
*
|
||||
* Function description
|
||||
* Event handler routine. Optional.
|
||||
*
|
||||
**********************************************************************
|
||||
*/
|
||||
//void AfterTargetHalt (void) {
|
||||
//}
|
5
lib/main/tinyUSB/hw/bsp/nrf/boards/pca10059/board.cmake
Normal file
5
lib/main/tinyUSB/hw/bsp/nrf/boards/pca10059/board.cmake
Normal file
|
@ -0,0 +1,5 @@
|
|||
set(MCU_VARIANT nrf52840)
|
||||
set(LD_FILE_GNU ${CMAKE_CURRENT_LIST_DIR}/pca10059.ld)
|
||||
|
||||
function(update_board TARGET)
|
||||
endfunction()
|
52
lib/main/tinyUSB/hw/bsp/nrf/boards/pca10059/board.h
Normal file
52
lib/main/tinyUSB/hw/bsp/nrf/boards/pca10059/board.h
Normal file
|
@ -0,0 +1,52 @@
|
|||
/*
|
||||
* 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 _PINNUM(port, pin) ((port)*32 + (pin))
|
||||
|
||||
// LED
|
||||
#define LED_PIN 8
|
||||
#define LED_STATE_ON 0
|
||||
|
||||
// Button
|
||||
#define BUTTON_PIN _PINNUM(1, 6)
|
||||
#define BUTTON_STATE_ACTIVE 0
|
||||
|
||||
// UART
|
||||
#define UART_RX_PIN 8
|
||||
#define UART_TX_PIN 6
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* BOARD_H_ */
|
15
lib/main/tinyUSB/hw/bsp/nrf/boards/pca10059/board.mk
Normal file
15
lib/main/tinyUSB/hw/bsp/nrf/boards/pca10059/board.mk
Normal file
|
@ -0,0 +1,15 @@
|
|||
MCU_VARIANT = nrf52840
|
||||
CFLAGS += -DNRF52840_XXAA
|
||||
|
||||
LD_FILE = $(BOARD_PATH)/$(BOARD).ld
|
||||
|
||||
# flash using Nordic nrfutil (pip2 install nrfutil)
|
||||
# make BOARD=pca10059 SERIAL=/dev/ttyACM0 all flash
|
||||
NRFUTIL = nrfutil
|
||||
|
||||
$(BUILD)/$(PROJECT).zip: $(BUILD)/$(PROJECT).hex
|
||||
$(NRFUTIL) pkg generate --hw-version 52 --sd-req 0x0000 --debug-mode --application $^ $@
|
||||
|
||||
flash: $(BUILD)/$(PROJECT).zip
|
||||
@:$(call check_defined, SERIAL, example: SERIAL=/dev/ttyACM0)
|
||||
$(NRFUTIL) dfu usb-serial --package $^ -p $(SERIAL) -b 115200
|
19
lib/main/tinyUSB/hw/bsp/nrf/boards/pca10059/pca10059.ld
Normal file
19
lib/main/tinyUSB/hw/bsp/nrf/boards/pca10059/pca10059.ld
Normal file
|
@ -0,0 +1,19 @@
|
|||
/* Linker script to configure memory regions. */
|
||||
|
||||
SEARCH_DIR(.)
|
||||
/*GROUP(-lgcc -lc -lnosys) not compatible with clang*/
|
||||
|
||||
MEMORY
|
||||
{
|
||||
FLASH (rx) : ORIGIN = 0x1000, LENGTH = 0xff000
|
||||
RAM (rwx) : ORIGIN = 0x20000008, LENGTH = 0x3fff8
|
||||
}
|
||||
|
||||
|
||||
INCLUDE "nrf_common.ld"
|
||||
|
||||
/* nrfx v2 linker does not define __tbss_start/end__ __sbss_start/end__*/
|
||||
__tbss_start__ = __tbss_start;
|
||||
__tbss_end__ = __tbss_end;
|
||||
__sbss_start__ = __sbss_start;
|
||||
__sbss_end__ = __sbss_end;
|
7
lib/main/tinyUSB/hw/bsp/nrf/boards/pca10095/board.cmake
Normal file
7
lib/main/tinyUSB/hw/bsp/nrf/boards/pca10095/board.cmake
Normal file
|
@ -0,0 +1,7 @@
|
|||
set(MCU_VARIANT nrf5340_application)
|
||||
|
||||
function(update_board TARGET)
|
||||
target_sources(${TARGET} PRIVATE
|
||||
${NRFX_DIR}/drivers/src/nrfx_usbreg.c
|
||||
)
|
||||
endfunction()
|
60
lib/main/tinyUSB/hw/bsp/nrf/boards/pca10095/board.h
Normal file
60
lib/main/tinyUSB/hw/bsp/nrf/boards/pca10095/board.h
Normal file
|
@ -0,0 +1,60 @@
|
|||
/*
|
||||
* 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 _PINNUM(port, pin) ((port)*32 + (pin))
|
||||
|
||||
// LED
|
||||
#define LED_PIN 28
|
||||
#define LED_STATE_ON 0
|
||||
|
||||
// Button
|
||||
#define BUTTON_PIN 23
|
||||
#define BUTTON_STATE_ACTIVE 0
|
||||
|
||||
// UART
|
||||
#define UART_RX_PIN 22
|
||||
#define UART_TX_PIN 20
|
||||
|
||||
// SPI for USB host shield
|
||||
// Pin is correct but not working probably due to signal incompatible (1.8V 3v3) with MAC3421E !?
|
||||
//#define MAX3421_SCK_PIN _PINNUM(1, 15)
|
||||
//#define MAX3421_MOSI_PIN _PINNUM(1, 13)
|
||||
//#define MAX3421_MISO_PIN _PINNUM(1, 14)
|
||||
//#define MAX3421_CS_PIN _PINNUM(1, 12)
|
||||
//#define MAX3421_INTR_PIN _PINNUM(1, 11)
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* BOARD_H_ */
|
17
lib/main/tinyUSB/hw/bsp/nrf/boards/pca10095/board.mk
Normal file
17
lib/main/tinyUSB/hw/bsp/nrf/boards/pca10095/board.mk
Normal file
|
@ -0,0 +1,17 @@
|
|||
CPU_CORE = cortex-m33
|
||||
MCU_VARIANT = nrf5340_application
|
||||
CFLAGS += -DNRF5340_XXAA -DNRF5340_XXAA_APPLICATION
|
||||
|
||||
# enable max3421 host driver for this board
|
||||
MAX3421_HOST = 1
|
||||
|
||||
LD_FILE = hw/mcu/nordic/nrfx/mdk/nrf5340_xxaa_application.ld
|
||||
|
||||
SRC_C += hw/mcu/nordic/nrfx/drivers/src/nrfx_usbreg.c
|
||||
|
||||
# caused by void SystemStoreFICRNS() (without void) in system_nrf5340_application.c
|
||||
CFLAGS += -Wno-error=strict-prototypes
|
||||
|
||||
# flash using jlink
|
||||
JLINK_DEVICE = nrf5340_xxaa_app
|
||||
flash: flash-jlink
|
335
lib/main/tinyUSB/hw/bsp/nrf/boards/pca10095/ozone/nrf5340.jdebug
Normal file
335
lib/main/tinyUSB/hw/bsp/nrf/boards/pca10095/ozone/nrf5340.jdebug
Normal file
|
@ -0,0 +1,335 @@
|
|||
/*********************************************************************
|
||||
* (c) SEGGER Microcontroller GmbH *
|
||||
* The Embedded Experts *
|
||||
* www.segger.com *
|
||||
**********************************************************************
|
||||
|
||||
File :
|
||||
Created : 30 Jun 2021 13:37
|
||||
Ozone Version : V3.24a
|
||||
*/
|
||||
|
||||
/*********************************************************************
|
||||
*
|
||||
* OnProjectLoad
|
||||
*
|
||||
* Function description
|
||||
* Project load routine. Required.
|
||||
*
|
||||
**********************************************************************
|
||||
*/
|
||||
void OnProjectLoad (void) {
|
||||
// Dialog-generated settings
|
||||
Project.AddSvdFile ("$(InstallDir)/Config/CPU/Cortex-M33F.svd");
|
||||
Project.AddSvdFile ("./nrf5340_application.svd");
|
||||
Project.SetDevice ("nRF5340_xxAA_APP");
|
||||
Project.SetHostIF ("USB", "");
|
||||
Project.SetTargetIF ("SWD");
|
||||
Project.SetTIFSpeed ("16 MHz");
|
||||
|
||||
Project.SetTraceSource ("Trace Pins");
|
||||
Project.SetTracePortWidth (4);
|
||||
|
||||
// User settings
|
||||
File.Open ("../../../../../../examples/device/cdc_msc/cmake-build-pca10095/cdc_msc.elf");
|
||||
}
|
||||
|
||||
/*********************************************************************
|
||||
*
|
||||
* OnStartupComplete
|
||||
*
|
||||
* Function description
|
||||
* Called when program execution has reached/passed
|
||||
* the startup completion point. Optional.
|
||||
*
|
||||
**********************************************************************
|
||||
*/
|
||||
//void OnStartupComplete (void) {
|
||||
//}
|
||||
|
||||
/*********************************************************************
|
||||
*
|
||||
* TargetReset
|
||||
*
|
||||
* Function description
|
||||
* Replaces the default target device reset routine. Optional.
|
||||
*
|
||||
* Notes
|
||||
* This example demonstrates the usage when
|
||||
* debugging an application in RAM on a Cortex-M target device.
|
||||
*
|
||||
**********************************************************************
|
||||
*/
|
||||
//void TargetReset (void) {
|
||||
//
|
||||
// unsigned int SP;
|
||||
// unsigned int PC;
|
||||
// unsigned int VectorTableAddr;
|
||||
//
|
||||
// VectorTableAddr = Elf.GetBaseAddr();
|
||||
// //
|
||||
// // Set up initial stack pointer
|
||||
// //
|
||||
// if (VectorTableAddr != 0xFFFFFFFF) {
|
||||
// SP = Target.ReadU32(VectorTableAddr);
|
||||
// Target.SetReg("SP", SP);
|
||||
// }
|
||||
// //
|
||||
// // Set up entry point PC
|
||||
// //
|
||||
// PC = Elf.GetEntryPointPC();
|
||||
//
|
||||
// if (PC != 0xFFFFFFFF) {
|
||||
// Target.SetReg("PC", PC);
|
||||
// } else if (VectorTableAddr != 0xFFFFFFFF) {
|
||||
// PC = Target.ReadU32(VectorTableAddr + 4);
|
||||
// Target.SetReg("PC", PC);
|
||||
// } else {
|
||||
// Util.Error("Project file error: failed to set entry point PC", 1);
|
||||
// }
|
||||
//}
|
||||
|
||||
/*********************************************************************
|
||||
*
|
||||
* BeforeTargetReset
|
||||
*
|
||||
* Function description
|
||||
* Event handler routine. Optional.
|
||||
*
|
||||
**********************************************************************
|
||||
*/
|
||||
//void BeforeTargetReset (void) {
|
||||
//}
|
||||
|
||||
/*********************************************************************
|
||||
*
|
||||
* AfterTargetReset
|
||||
*
|
||||
* Function description
|
||||
* Event handler routine. Optional.
|
||||
* The default implementation initializes SP and PC to reset values.
|
||||
**
|
||||
**********************************************************************
|
||||
*/
|
||||
void AfterTargetReset (void) {
|
||||
_SetupTarget();
|
||||
}
|
||||
|
||||
/*********************************************************************
|
||||
*
|
||||
* DebugStart
|
||||
*
|
||||
* Function description
|
||||
* Replaces the default debug session startup routine. Optional.
|
||||
*
|
||||
**********************************************************************
|
||||
*/
|
||||
//void DebugStart (void) {
|
||||
//}
|
||||
|
||||
/*********************************************************************
|
||||
*
|
||||
* TargetConnect
|
||||
*
|
||||
* Function description
|
||||
* Replaces the default target IF connection routine. Optional.
|
||||
*
|
||||
**********************************************************************
|
||||
*/
|
||||
//void TargetConnect (void) {
|
||||
//}
|
||||
|
||||
/*********************************************************************
|
||||
*
|
||||
* BeforeTargetConnect
|
||||
*
|
||||
* Function description
|
||||
* Event handler routine. Optional.
|
||||
*
|
||||
**********************************************************************
|
||||
*/
|
||||
void BeforeTargetConnect (void) {
|
||||
}
|
||||
|
||||
/*********************************************************************
|
||||
*
|
||||
* AfterTargetConnect
|
||||
*
|
||||
* Function description
|
||||
* Event handler routine. Optional.
|
||||
*
|
||||
**********************************************************************
|
||||
*/
|
||||
//void AfterTargetConnect (void) {
|
||||
//}
|
||||
|
||||
/*********************************************************************
|
||||
*
|
||||
* TargetDownload
|
||||
*
|
||||
* Function description
|
||||
* Replaces the default program download routine. Optional.
|
||||
*
|
||||
**********************************************************************
|
||||
*/
|
||||
//void TargetDownload (void) {
|
||||
//}
|
||||
|
||||
/*********************************************************************
|
||||
*
|
||||
* BeforeTargetDownload
|
||||
*
|
||||
* Function description
|
||||
* Event handler routine. Optional.
|
||||
*
|
||||
**********************************************************************
|
||||
*/
|
||||
//void BeforeTargetDownload (void) {
|
||||
//}
|
||||
|
||||
/*********************************************************************
|
||||
*
|
||||
* AfterTargetDownload
|
||||
*
|
||||
* Function description
|
||||
* Event handler routine. Optional.
|
||||
* The default implementation initializes SP and PC to reset values.
|
||||
*
|
||||
**********************************************************************
|
||||
*/
|
||||
void AfterTargetDownload (void) {
|
||||
_SetupTarget();
|
||||
}
|
||||
|
||||
/*********************************************************************
|
||||
*
|
||||
* BeforeTargetDisconnect
|
||||
*
|
||||
* Function description
|
||||
* Event handler routine. Optional.
|
||||
*
|
||||
**********************************************************************
|
||||
*/
|
||||
//void BeforeTargetDisconnect (void) {
|
||||
//}
|
||||
|
||||
/*********************************************************************
|
||||
*
|
||||
* AfterTargetDisconnect
|
||||
*
|
||||
* Function description
|
||||
* Event handler routine. Optional.
|
||||
*
|
||||
**********************************************************************
|
||||
*/
|
||||
//void AfterTargetDisconnect (void) {
|
||||
//}
|
||||
|
||||
/*********************************************************************
|
||||
*
|
||||
* AfterTargetHalt
|
||||
*
|
||||
* Function description
|
||||
* Event handler routine. Optional.
|
||||
*
|
||||
**********************************************************************
|
||||
*/
|
||||
//void AfterTargetHalt (void) {
|
||||
//}
|
||||
|
||||
/*********************************************************************
|
||||
*
|
||||
* BeforeTargetResume
|
||||
*
|
||||
* Function description
|
||||
* Event handler routine. Optional.
|
||||
*
|
||||
**********************************************************************
|
||||
*/
|
||||
//void BeforeTargetResume (void) {
|
||||
//}
|
||||
|
||||
/*********************************************************************
|
||||
*
|
||||
* OnSnapshotLoad
|
||||
*
|
||||
* Function description
|
||||
* Called upon loading a snapshot. Optional.
|
||||
*
|
||||
* Additional information
|
||||
* This function is used to restore the target state in cases
|
||||
* where values cannot simply be written to the target.
|
||||
* Typical use: GPIO clock needs to be enabled, before
|
||||
* GPIO is configured.
|
||||
*
|
||||
**********************************************************************
|
||||
*/
|
||||
//void OnSnapshotLoad (void) {
|
||||
//}
|
||||
|
||||
/*********************************************************************
|
||||
*
|
||||
* OnSnapshotSave
|
||||
*
|
||||
* Function description
|
||||
* Called upon saving a snapshot. Optional.
|
||||
*
|
||||
* Additional information
|
||||
* This function is usually used to save values of the target
|
||||
* state which can either not be trivially read,
|
||||
* or need to be restored in a specific way or order.
|
||||
* Typically use: Memory Mapped Registers,
|
||||
* such as PLL and GPIO configuration.
|
||||
*
|
||||
**********************************************************************
|
||||
*/
|
||||
//void OnSnapshotSave (void) {
|
||||
//}
|
||||
|
||||
/*********************************************************************
|
||||
*
|
||||
* OnError
|
||||
*
|
||||
* Function description
|
||||
* Called when an error occurred. Optional.
|
||||
*
|
||||
**********************************************************************
|
||||
*/
|
||||
//void OnError (void) {
|
||||
//}
|
||||
|
||||
/*********************************************************************
|
||||
*
|
||||
* _SetupTarget
|
||||
*
|
||||
* Function description
|
||||
* Setup the target.
|
||||
* Called by AfterTargetReset() and AfterTargetDownload().
|
||||
*
|
||||
* Auto-generated function. May be overridden by Ozone.
|
||||
*
|
||||
**********************************************************************
|
||||
*/
|
||||
void _SetupTarget(void) {
|
||||
unsigned int SP;
|
||||
unsigned int PC;
|
||||
unsigned int VectorTableAddr;
|
||||
|
||||
VectorTableAddr = Elf.GetBaseAddr();
|
||||
//
|
||||
// Set up initial stack pointer
|
||||
//
|
||||
SP = Target.ReadU32(VectorTableAddr);
|
||||
if (SP != 0xFFFFFFFF) {
|
||||
Target.SetReg("SP", SP);
|
||||
}
|
||||
//
|
||||
// Set up entry point PC
|
||||
//
|
||||
PC = Elf.GetEntryPointPC();
|
||||
if (PC != 0xFFFFFFFF) {
|
||||
Target.SetReg("PC", PC);
|
||||
} else {
|
||||
Util.Error("Project script error: failed to set up entry point PC", 1);
|
||||
}
|
||||
}
|
4
lib/main/tinyUSB/hw/bsp/nrf/boards/pca10100/board.cmake
Normal file
4
lib/main/tinyUSB/hw/bsp/nrf/boards/pca10100/board.cmake
Normal file
|
@ -0,0 +1,4 @@
|
|||
set(MCU_VARIANT nrf52833)
|
||||
|
||||
function(update_board TARGET)
|
||||
endfunction()
|
52
lib/main/tinyUSB/hw/bsp/nrf/boards/pca10100/board.h
Normal file
52
lib/main/tinyUSB/hw/bsp/nrf/boards/pca10100/board.h
Normal file
|
@ -0,0 +1,52 @@
|
|||
/*
|
||||
* 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 _PINNUM(port, pin) ((port)*32 + (pin))
|
||||
|
||||
// LED
|
||||
#define LED_PIN 13
|
||||
#define LED_STATE_ON 0
|
||||
|
||||
// Button
|
||||
#define BUTTON_PIN 11
|
||||
#define BUTTON_STATE_ACTIVE 0
|
||||
|
||||
// UART
|
||||
#define UART_RX_PIN 8
|
||||
#define UART_TX_PIN 6
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* BOARD_H_ */
|
7
lib/main/tinyUSB/hw/bsp/nrf/boards/pca10100/board.mk
Normal file
7
lib/main/tinyUSB/hw/bsp/nrf/boards/pca10100/board.mk
Normal file
|
@ -0,0 +1,7 @@
|
|||
MCU_VARIANT = nrf52833
|
||||
CFLAGS += -DNRF52833_XXAA
|
||||
|
||||
LD_FILE = hw/mcu/nordic/nrfx/mdk/nrf52833_xxaa.ld
|
||||
|
||||
# flash using jlink
|
||||
flash: flash-jlink
|
447
lib/main/tinyUSB/hw/bsp/nrf/family.c
Normal file
447
lib/main/tinyUSB/hw/bsp/nrf/family.c
Normal file
|
@ -0,0 +1,447 @@
|
|||
/*
|
||||
* 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_api.h"
|
||||
#include "board.h"
|
||||
|
||||
// Suppress warning caused by mcu driver
|
||||
#ifdef __GNUC__
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wcast-qual"
|
||||
#pragma GCC diagnostic ignored "-Wcast-align"
|
||||
#pragma GCC diagnostic ignored "-Wunused-parameter"
|
||||
#pragma GCC diagnostic ignored "-Wunused-variable"
|
||||
#pragma GCC diagnostic ignored "-Wundef"
|
||||
#pragma GCC diagnostic ignored "-Wredundant-decls"
|
||||
#endif
|
||||
|
||||
#include "nrfx.h"
|
||||
#include "hal/nrf_gpio.h"
|
||||
#include "drivers/include/nrfx_gpiote.h"
|
||||
#include "drivers/include/nrfx_power.h"
|
||||
#include "drivers/include/nrfx_uarte.h"
|
||||
#include "drivers/include/nrfx_spim.h"
|
||||
|
||||
#ifdef SOFTDEVICE_PRESENT
|
||||
#include "nrf_sdm.h"
|
||||
#include "nrf_soc.h"
|
||||
#endif
|
||||
|
||||
#ifdef __GNUC__
|
||||
#pragma GCC diagnostic pop
|
||||
#endif
|
||||
|
||||
|
||||
// There is API changes between nrfx v2 and v3
|
||||
#if 85301 >= (10000*MDK_MAJOR_VERSION + 100*MDK_MINOR_VERSION + MDK_MICRO_VERSION)
|
||||
// note MDK 8.53.1 is also used by nrfx v3.0.0, just skip this version and use later 3.x
|
||||
#define NRFX_VER 2
|
||||
#else
|
||||
#define NRFX_VER 3
|
||||
#endif
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// Forward USB interrupt events to TinyUSB IRQ Handler
|
||||
//--------------------------------------------------------------------+
|
||||
void USBD_IRQHandler(void) {
|
||||
tud_int_handler(0);
|
||||
}
|
||||
|
||||
/*------------------------------------------------------------------*/
|
||||
/* MACRO TYPEDEF CONSTANT ENUM
|
||||
*------------------------------------------------------------------*/
|
||||
|
||||
// Value is chosen to be as same as NRFX_POWER_USB_EVT_* in nrfx_power.h
|
||||
enum {
|
||||
USB_EVT_DETECTED = 0,
|
||||
USB_EVT_REMOVED = 1,
|
||||
USB_EVT_READY = 2
|
||||
};
|
||||
|
||||
#ifdef NRF5340_XXAA
|
||||
#define LFCLK_SRC_RC CLOCK_LFCLKSRC_SRC_LFRC
|
||||
#define VBUSDETECT_Msk USBREG_USBREGSTATUS_VBUSDETECT_Msk
|
||||
#define OUTPUTRDY_Msk USBREG_USBREGSTATUS_OUTPUTRDY_Msk
|
||||
#define GPIOTE_IRQn GPIOTE1_IRQn
|
||||
#else
|
||||
#define LFCLK_SRC_RC CLOCK_LFCLKSRC_SRC_RC
|
||||
#define VBUSDETECT_Msk POWER_USBREGSTATUS_VBUSDETECT_Msk
|
||||
#define OUTPUTRDY_Msk POWER_USBREGSTATUS_OUTPUTRDY_Msk
|
||||
#endif
|
||||
|
||||
static nrfx_uarte_t _uart_id = NRFX_UARTE_INSTANCE(0);
|
||||
|
||||
// tinyusb function that handles power event (detected, ready, removed)
|
||||
// We must call it within SD's SOC event handler, or set it as power event handler if SD is not enabled.
|
||||
extern void tusb_hal_nrf_power_event(uint32_t event);
|
||||
|
||||
// nrf power callback, could be unused if SD is enabled or usb is disabled (board_test example)
|
||||
TU_ATTR_UNUSED static void power_event_handler(nrfx_power_usb_evt_t event) {
|
||||
tusb_hal_nrf_power_event((uint32_t) event);
|
||||
}
|
||||
|
||||
//------------- Host using MAX2341E -------------//
|
||||
#if CFG_TUH_ENABLED && defined(CFG_TUH_MAX3421) && CFG_TUH_MAX3421
|
||||
static void max3421_init(void);
|
||||
static nrfx_spim_t _spi = NRFX_SPIM_INSTANCE(1);
|
||||
|
||||
#if NRFX_VER > 2
|
||||
static nrfx_gpiote_t _gpiote = NRFX_GPIOTE_INSTANCE(0);
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
//
|
||||
//--------------------------------------------------------------------+
|
||||
|
||||
void board_init(void) {
|
||||
// stop LF clock just in case we jump from application without reset
|
||||
NRF_CLOCK->TASKS_LFCLKSTOP = 1UL;
|
||||
|
||||
// Use Internal OSC to compatible with all boards
|
||||
NRF_CLOCK->LFCLKSRC = LFCLK_SRC_RC;
|
||||
NRF_CLOCK->TASKS_LFCLKSTART = 1UL;
|
||||
|
||||
// LED
|
||||
nrf_gpio_cfg_output(LED_PIN);
|
||||
board_led_write(false);
|
||||
|
||||
// Button
|
||||
nrf_gpio_cfg_input(BUTTON_PIN, NRF_GPIO_PIN_PULLUP);
|
||||
|
||||
// 1ms tick timer
|
||||
SysTick_Config(SystemCoreClock / 1000);
|
||||
|
||||
// UART
|
||||
#if NRFX_VER <= 2
|
||||
nrfx_uarte_config_t uart_cfg = {
|
||||
.pseltxd = UART_TX_PIN,
|
||||
.pselrxd = UART_RX_PIN,
|
||||
.pselcts = NRF_UARTE_PSEL_DISCONNECTED,
|
||||
.pselrts = NRF_UARTE_PSEL_DISCONNECTED,
|
||||
.p_context = NULL,
|
||||
.baudrate = NRF_UARTE_BAUDRATE_115200, // CFG_BOARD_UART_BAUDRATE
|
||||
.interrupt_priority = 7,
|
||||
.hal_cfg = {
|
||||
.hwfc = NRF_UARTE_HWFC_DISABLED,
|
||||
.parity = NRF_UARTE_PARITY_EXCLUDED,
|
||||
}
|
||||
};
|
||||
#else
|
||||
nrfx_uarte_config_t uart_cfg = {
|
||||
.txd_pin = UART_TX_PIN,
|
||||
.rxd_pin = UART_RX_PIN,
|
||||
.rts_pin = NRF_UARTE_PSEL_DISCONNECTED,
|
||||
.cts_pin = NRF_UARTE_PSEL_DISCONNECTED,
|
||||
.p_context = NULL,
|
||||
.baudrate = NRF_UARTE_BAUDRATE_115200, // CFG_BOARD_UART_BAUDRATE
|
||||
.interrupt_priority = 7,
|
||||
.config = {
|
||||
.hwfc = NRF_UARTE_HWFC_DISABLED,
|
||||
.parity = NRF_UARTE_PARITY_EXCLUDED,
|
||||
}
|
||||
};
|
||||
#endif
|
||||
|
||||
nrfx_uarte_init(&_uart_id, &uart_cfg, NULL); //uart_handler);
|
||||
|
||||
//------------- USB -------------//
|
||||
#if CFG_TUD_ENABLED
|
||||
// Priorities 0, 1, 4 (nRF52) are reserved for SoftDevice
|
||||
// 2 is highest for application
|
||||
NVIC_SetPriority(USBD_IRQn, 2);
|
||||
|
||||
// USB power may already be ready at this time -> no event generated
|
||||
// We need to invoke the handler based on the status initially
|
||||
uint32_t usb_reg;
|
||||
|
||||
#ifdef SOFTDEVICE_PRESENT
|
||||
uint8_t sd_en = false;
|
||||
sd_softdevice_is_enabled(&sd_en);
|
||||
|
||||
if ( sd_en ) {
|
||||
sd_power_usbdetected_enable(true);
|
||||
sd_power_usbpwrrdy_enable(true);
|
||||
sd_power_usbremoved_enable(true);
|
||||
|
||||
sd_power_usbregstatus_get(&usb_reg);
|
||||
}else
|
||||
#endif
|
||||
{
|
||||
// Power module init
|
||||
const nrfx_power_config_t pwr_cfg = {0};
|
||||
nrfx_power_init(&pwr_cfg);
|
||||
|
||||
// Register tusb function as USB power handler
|
||||
// cause cast-function-type warning
|
||||
const nrfx_power_usbevt_config_t config = {.handler = power_event_handler};
|
||||
nrfx_power_usbevt_init(&config);
|
||||
nrfx_power_usbevt_enable();
|
||||
|
||||
// USB power may already be ready at this time -> no event generated
|
||||
// We need to invoke the handler based on the status initially
|
||||
#ifdef NRF5340_XXAA
|
||||
usb_reg = NRF_USBREGULATOR->USBREGSTATUS;
|
||||
#else
|
||||
usb_reg = NRF_POWER->USBREGSTATUS;
|
||||
#endif
|
||||
}
|
||||
|
||||
if ( usb_reg & VBUSDETECT_Msk ) tusb_hal_nrf_power_event(USB_EVT_DETECTED);
|
||||
if ( usb_reg & OUTPUTRDY_Msk ) tusb_hal_nrf_power_event(USB_EVT_READY);
|
||||
#endif
|
||||
|
||||
#if CFG_TUH_ENABLED && defined(CFG_TUH_MAX3421) && CFG_TUH_MAX3421
|
||||
max3421_init();
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// Board porting API
|
||||
//--------------------------------------------------------------------+
|
||||
|
||||
void board_led_write(bool state) {
|
||||
nrf_gpio_pin_write(LED_PIN, state ? LED_STATE_ON : (1 - LED_STATE_ON));
|
||||
}
|
||||
|
||||
uint32_t board_button_read(void) {
|
||||
return BUTTON_STATE_ACTIVE == nrf_gpio_pin_read(BUTTON_PIN);
|
||||
}
|
||||
|
||||
size_t board_get_unique_id(uint8_t id[], size_t max_len) {
|
||||
(void) max_len;
|
||||
|
||||
#ifdef NRF5340_XXAA
|
||||
uintptr_t did_addr = (uintptr_t) NRF_FICR->INFO.DEVICEID;
|
||||
#else
|
||||
uintptr_t did_addr = (uintptr_t) NRF_FICR->DEVICEID;
|
||||
#endif
|
||||
|
||||
const uint8_t* device_id = (const uint8_t*) did_addr;
|
||||
for(uint8_t i=0; i<8; i++) {
|
||||
id[i] = device_id[i];
|
||||
}
|
||||
return 8;
|
||||
}
|
||||
|
||||
int board_uart_read(uint8_t* buf, int len) {
|
||||
(void) buf;
|
||||
(void) len;
|
||||
return 0;
|
||||
// nrfx_err_t err = nrfx_uarte_rx(&_uart_id, buf, (size_t) len);
|
||||
// return NRFX_SUCCESS == err ? len : 0;
|
||||
}
|
||||
|
||||
int board_uart_write(void const* buf, int len) {
|
||||
nrfx_err_t err = nrfx_uarte_tx(&_uart_id, (uint8_t const*) buf, (size_t) len
|
||||
#if NRFX_VER > 2
|
||||
,0
|
||||
#endif
|
||||
);
|
||||
return (NRFX_SUCCESS == err) ? len : 0;
|
||||
}
|
||||
|
||||
#if CFG_TUSB_OS == OPT_OS_NONE
|
||||
volatile uint32_t system_ticks = 0;
|
||||
|
||||
void SysTick_Handler(void) {
|
||||
system_ticks++;
|
||||
}
|
||||
|
||||
uint32_t board_millis(void) {
|
||||
return system_ticks;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifndef __ICCARM__
|
||||
// Implement _start() since we use linker flag '-nostartfiles'.
|
||||
// Requires defined __STARTUP_CLEAR_BSS,
|
||||
extern int main(void);
|
||||
TU_ATTR_UNUSED void _start(void) {
|
||||
// called by startup code
|
||||
main();
|
||||
while (1) {}
|
||||
}
|
||||
#endif
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// Softdevice running
|
||||
//--------------------------------------------------------------------+
|
||||
#ifdef SOFTDEVICE_PRESENT
|
||||
// process SOC event from SD
|
||||
uint32_t proc_soc(void) {
|
||||
uint32_t soc_evt;
|
||||
uint32_t err = sd_evt_get(&soc_evt);
|
||||
|
||||
if (NRF_SUCCESS == err)
|
||||
{
|
||||
/*------------- usb power event handler -------------*/
|
||||
int32_t usbevt = (soc_evt == NRF_EVT_POWER_USB_DETECTED ) ? NRFX_POWER_USB_EVT_DETECTED:
|
||||
(soc_evt == NRF_EVT_POWER_USB_POWER_READY) ? NRFX_POWER_USB_EVT_READY :
|
||||
(soc_evt == NRF_EVT_POWER_USB_REMOVED ) ? NRFX_POWER_USB_EVT_REMOVED : -1;
|
||||
|
||||
if ( usbevt >= 0) tusb_hal_nrf_power_event(usbevt);
|
||||
}
|
||||
|
||||
return err;
|
||||
}
|
||||
|
||||
uint32_t proc_ble(void) {
|
||||
// do nothing with ble
|
||||
return NRF_ERROR_NOT_FOUND;
|
||||
}
|
||||
|
||||
void SD_EVT_IRQHandler(void) {
|
||||
// process BLE and SOC until there is no more events
|
||||
while( (NRF_ERROR_NOT_FOUND != proc_ble()) || (NRF_ERROR_NOT_FOUND != proc_soc()) ) {
|
||||
}
|
||||
}
|
||||
|
||||
void nrf_error_cb(uint32_t id, uint32_t pc, uint32_t info) {
|
||||
(void) id;
|
||||
(void) pc;
|
||||
(void) info;
|
||||
}
|
||||
#endif
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// API: SPI transfer with MAX3421E, must be implemented by application
|
||||
//--------------------------------------------------------------------+
|
||||
#if CFG_TUH_ENABLED && defined(CFG_TUH_MAX3421) && CFG_TUH_MAX3421
|
||||
|
||||
#if NRFX_VER <= 2
|
||||
void max3421_int_handler(nrfx_gpiote_pin_t pin, nrf_gpiote_polarity_t action ) {
|
||||
if (action != NRF_GPIOTE_POLARITY_HITOLO) return;
|
||||
#else
|
||||
void max3421_int_handler(nrfx_gpiote_pin_t pin, nrfx_gpiote_trigger_t action, void* p_context) {
|
||||
(void) p_context;
|
||||
if (action != NRFX_GPIOTE_TRIGGER_HITOLO) return;
|
||||
#endif
|
||||
|
||||
if (pin != MAX3421_INTR_PIN) return;
|
||||
tuh_int_handler(1, true);
|
||||
}
|
||||
|
||||
static void max3421_init(void) {
|
||||
// Somehow pca10056/95 is not working probably due to signal incompatible (1.8V 3v3) with MAC3421E !?
|
||||
|
||||
// manually manage CS
|
||||
nrf_gpio_cfg_output(MAX3421_CS_PIN);
|
||||
nrf_gpio_pin_write(MAX3421_CS_PIN, 1);
|
||||
|
||||
// USB host using max3421e usb controller via SPI
|
||||
nrfx_spim_config_t cfg = {
|
||||
.sck_pin = MAX3421_SCK_PIN,
|
||||
.mosi_pin = MAX3421_MOSI_PIN,
|
||||
.miso_pin = MAX3421_MISO_PIN,
|
||||
#if NRFX_VER <= 2
|
||||
.ss_pin = NRFX_SPIM_PIN_NOT_USED,
|
||||
.frequency = NRF_SPIM_FREQ_4M,
|
||||
#else
|
||||
.ss_pin = NRF_SPIM_PIN_NOT_CONNECTED,
|
||||
.frequency = 4000000u,
|
||||
#endif
|
||||
.ss_active_high = false,
|
||||
.irq_priority = 3,
|
||||
.orc = 0xFF,
|
||||
// default setting 4 Mhz, Mode 0, MSB first
|
||||
.mode = NRF_SPIM_MODE_0,
|
||||
.bit_order = NRF_SPIM_BIT_ORDER_MSB_FIRST,
|
||||
.miso_pull = NRF_GPIO_PIN_NOPULL,
|
||||
};
|
||||
|
||||
// no handler --> blocking
|
||||
TU_ASSERT(NRFX_SUCCESS == nrfx_spim_init(&_spi, &cfg, NULL, NULL), );
|
||||
|
||||
// max3421e interrupt pin
|
||||
#if NRFX_VER <= 2
|
||||
nrfx_gpiote_init(1);
|
||||
nrfx_gpiote_in_config_t in_config = NRFX_GPIOTE_CONFIG_IN_SENSE_HITOLO(true);
|
||||
in_config.pull = NRF_GPIO_PIN_PULLUP;
|
||||
NVIC_SetPriority(GPIOTE_IRQn, 2);
|
||||
nrfx_gpiote_in_init(MAX3421_INTR_PIN, &in_config, max3421_int_handler);
|
||||
nrfx_gpiote_trigger_enable(MAX3421_INTR_PIN, true);
|
||||
#else
|
||||
nrf_gpio_pin_pull_t intr_pull = NRF_GPIO_PIN_PULLUP;
|
||||
nrfx_gpiote_trigger_config_t intr_trigger = {
|
||||
.trigger = NRFX_GPIOTE_TRIGGER_HITOLO,
|
||||
.p_in_channel = NULL, // sensing mechanism
|
||||
};
|
||||
nrfx_gpiote_handler_config_t intr_handler = {
|
||||
.handler = max3421_int_handler,
|
||||
.p_context = NULL,
|
||||
};
|
||||
nrfx_gpiote_input_pin_config_t intr_config = {
|
||||
.p_pull_config = &intr_pull,
|
||||
.p_trigger_config = &intr_trigger,
|
||||
.p_handler_config = &intr_handler,
|
||||
};
|
||||
|
||||
nrfx_gpiote_init(&_gpiote, 1);
|
||||
NVIC_SetPriority(GPIOTE_IRQn, 2);
|
||||
|
||||
nrfx_gpiote_input_configure(&_gpiote, MAX3421_INTR_PIN, &intr_config);
|
||||
nrfx_gpiote_trigger_enable(&_gpiote, MAX3421_INTR_PIN, true);
|
||||
#endif
|
||||
}
|
||||
|
||||
// API to enable/disable MAX3421 INTR pin interrupt
|
||||
void tuh_max3421_int_api(uint8_t rhport, bool enabled) {
|
||||
(void) rhport;
|
||||
|
||||
// use NVIC_Enable/Disable instead since nrfx_gpiote_trigger_enable/disable clear pending and can miss interrupt
|
||||
// when disabled and re-enabled.
|
||||
if (enabled) {
|
||||
NVIC_EnableIRQ(GPIOTE_IRQn);
|
||||
} else {
|
||||
NVIC_DisableIRQ(GPIOTE_IRQn);
|
||||
}
|
||||
}
|
||||
|
||||
// API to control MAX3421 SPI CS
|
||||
void tuh_max3421_spi_cs_api(uint8_t rhport, bool active) {
|
||||
(void) rhport;
|
||||
nrf_gpio_pin_write(MAX3421_CS_PIN, active ? 0 : 1);
|
||||
}
|
||||
|
||||
// API to transfer data with MAX3421 SPI
|
||||
// Either tx_buf or rx_buf can be NULL, which means transfer is write or read only
|
||||
bool tuh_max3421_spi_xfer_api(uint8_t rhport, uint8_t const* tx_buf, uint8_t* rx_buf, size_t xfer_bytes) {
|
||||
(void) rhport;
|
||||
|
||||
nrfx_spim_xfer_desc_t xfer = {
|
||||
.p_tx_buffer = tx_buf,
|
||||
.tx_length = tx_buf ? xfer_bytes : 0,
|
||||
.p_rx_buffer = rx_buf,
|
||||
.rx_length = rx_buf ? xfer_bytes : 0,
|
||||
};
|
||||
|
||||
return nrfx_spim_xfer(&_spi, &xfer, 0) == NRFX_SUCCESS;
|
||||
}
|
||||
|
||||
#endif
|
147
lib/main/tinyUSB/hw/bsp/nrf/family.cmake
Normal file
147
lib/main/tinyUSB/hw/bsp/nrf/family.cmake
Normal file
|
@ -0,0 +1,147 @@
|
|||
include_guard()
|
||||
|
||||
set(NRFX_DIR ${TOP}/hw/mcu/nordic/nrfx)
|
||||
set(CMSIS_DIR ${TOP}/lib/CMSIS_5)
|
||||
|
||||
# include board specific
|
||||
include(${CMAKE_CURRENT_LIST_DIR}/boards/${BOARD}/board.cmake)
|
||||
|
||||
# toolchain set up
|
||||
if (MCU_VARIANT STREQUAL "nrf5340_application")
|
||||
set(CMAKE_SYSTEM_PROCESSOR cortex-m33 CACHE INTERNAL "System Processor")
|
||||
set(JLINK_DEVICE nrf5340_xxaa_app)
|
||||
else ()
|
||||
set(CMAKE_SYSTEM_PROCESSOR cortex-m4 CACHE INTERNAL "System Processor")
|
||||
set(JLINK_DEVICE ${MCU_VARIANT}_xxaa)
|
||||
endif ()
|
||||
|
||||
set(CMAKE_TOOLCHAIN_FILE ${TOP}/examples/build_system/cmake/toolchain/arm_${TOOLCHAIN}.cmake)
|
||||
|
||||
set(FAMILY_MCUS NRF5X CACHE INTERNAL "")
|
||||
|
||||
|
||||
#------------------------------------
|
||||
# BOARD_TARGET
|
||||
#------------------------------------
|
||||
# only need to be built ONCE for all examples
|
||||
function(add_board_target BOARD_TARGET)
|
||||
if (TARGET ${BOARD_TARGET})
|
||||
return()
|
||||
endif ()
|
||||
|
||||
if (MCU_VARIANT STREQUAL "nrf5340_application")
|
||||
set(MCU_VARIANT_XXAA "nrf5340_xxaa_application")
|
||||
else ()
|
||||
set(MCU_VARIANT_XXAA "${MCU_VARIANT}_xxaa")
|
||||
endif ()
|
||||
|
||||
if (NOT DEFINED LD_FILE_GNU)
|
||||
set(LD_FILE_GNU ${CMAKE_CURRENT_FUNCTION_LIST_DIR}/linker/${MCU_VARIANT_XXAA}.ld)
|
||||
endif ()
|
||||
|
||||
if (NOT DEFINED STARTUP_FILE_${CMAKE_C_COMPILER_ID})
|
||||
set(STARTUP_FILE_GNU ${NRFX_DIR}/mdk/gcc_startup_${MCU_VARIANT}.S)
|
||||
set(STARTUP_FILE_Clang ${STARTUP_FILE_GNU})
|
||||
endif ()
|
||||
|
||||
add_library(${BOARD_TARGET} STATIC
|
||||
${NRFX_DIR}/helpers/nrfx_flag32_allocator.c
|
||||
${NRFX_DIR}/drivers/src/nrfx_gpiote.c
|
||||
${NRFX_DIR}/drivers/src/nrfx_power.c
|
||||
${NRFX_DIR}/drivers/src/nrfx_spim.c
|
||||
${NRFX_DIR}/drivers/src/nrfx_uarte.c
|
||||
${NRFX_DIR}/mdk/system_${MCU_VARIANT}.c
|
||||
${NRFX_DIR}/soc/nrfx_atomic.c
|
||||
${STARTUP_FILE_${CMAKE_C_COMPILER_ID}}
|
||||
)
|
||||
string(TOUPPER "${MCU_VARIANT_XXAA}" MCU_VARIANT_XXAA_UPPER)
|
||||
target_compile_definitions(${BOARD_TARGET} PUBLIC
|
||||
__STARTUP_CLEAR_BSS
|
||||
CONFIG_GPIO_AS_PINRESET
|
||||
${MCU_VARIANT_XXAA_UPPER}
|
||||
)
|
||||
|
||||
if (TRACE_ETM STREQUAL "1")
|
||||
# ENABLE_TRACE will cause system_nrf5x.c to set up ETM trace
|
||||
target_compile_definitions(${BOARD_TARGET} PUBLIC ENABLE_TRACE)
|
||||
endif ()
|
||||
|
||||
target_include_directories(${BOARD_TARGET} PUBLIC
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}
|
||||
${NRFX_DIR}
|
||||
${NRFX_DIR}/mdk
|
||||
${NRFX_DIR}/hal
|
||||
${NRFX_DIR}/drivers/include
|
||||
${NRFX_DIR}/drivers/src
|
||||
${CMSIS_DIR}/CMSIS/Core/Include
|
||||
)
|
||||
|
||||
update_board(${BOARD_TARGET})
|
||||
|
||||
if (CMAKE_C_COMPILER_ID STREQUAL "GNU")
|
||||
target_link_options(${BOARD_TARGET} PUBLIC
|
||||
"LINKER:--script=${LD_FILE_GNU}"
|
||||
-L${NRFX_DIR}/mdk
|
||||
--specs=nosys.specs --specs=nano.specs
|
||||
-nostartfiles
|
||||
)
|
||||
elseif (CMAKE_C_COMPILER_ID STREQUAL "Clang")
|
||||
target_link_options(${BOARD_TARGET} PUBLIC
|
||||
"LINKER:--script=${LD_FILE_GNU}"
|
||||
-L${NRFX_DIR}/mdk
|
||||
)
|
||||
elseif (CMAKE_C_COMPILER_ID STREQUAL "IAR")
|
||||
target_link_options(${BOARD_TARGET} PUBLIC
|
||||
"LINKER:--config=${LD_FILE_IAR}"
|
||||
)
|
||||
endif ()
|
||||
endfunction()
|
||||
|
||||
|
||||
#------------------------------------
|
||||
# Functions
|
||||
#------------------------------------
|
||||
|
||||
#function(family_flash_adafruit_nrfutil TARGET)
|
||||
# add_custom_target(${TARGET}-adafruit-nrfutil
|
||||
# DEPENDS ${TARGET}
|
||||
# COMMAND adafruit-nrfutil --verbose dfu serial --package $^ -p /dev/ttyACM0 -b 115200 --singlebank --touch 1200
|
||||
# )
|
||||
#endfunction()
|
||||
|
||||
|
||||
function(family_configure_example TARGET RTOS)
|
||||
family_configure_common(${TARGET} ${RTOS})
|
||||
|
||||
# Board target
|
||||
add_board_target(board_${BOARD})
|
||||
|
||||
#---------- Port Specific ----------
|
||||
# These files are built for each example since it depends on example's tusb_config.h
|
||||
target_sources(${TARGET} PUBLIC
|
||||
# BSP
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/family.c
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/../board.c
|
||||
)
|
||||
target_include_directories(${TARGET} PUBLIC
|
||||
# family, hw, board
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/../../
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/boards/${BOARD}
|
||||
)
|
||||
|
||||
# Add TinyUSB target and port source
|
||||
family_add_tinyusb(${TARGET} OPT_MCU_NRF5X ${RTOS})
|
||||
target_sources(${TARGET}-tinyusb PUBLIC
|
||||
${TOP}/src/portable/nordic/nrf5x/dcd_nrf5x.c
|
||||
)
|
||||
target_link_libraries(${TARGET}-tinyusb PUBLIC board_${BOARD})
|
||||
|
||||
# Link dependencies
|
||||
target_link_libraries(${TARGET} PUBLIC board_${BOARD} ${TARGET}-tinyusb)
|
||||
|
||||
# Flashing
|
||||
family_add_bin_hex(${TARGET})
|
||||
family_flash_jlink(${TARGET})
|
||||
# family_flash_adafruit_nrfutil(${TARGET})
|
||||
endfunction()
|
60
lib/main/tinyUSB/hw/bsp/nrf/family.mk
Normal file
60
lib/main/tinyUSB/hw/bsp/nrf/family.mk
Normal file
|
@ -0,0 +1,60 @@
|
|||
UF2_FAMILY_ID = 0xADA52840
|
||||
|
||||
NRFX_DIR = hw/mcu/nordic/nrfx
|
||||
|
||||
include $(TOP)/$(BOARD_PATH)/board.mk
|
||||
|
||||
# nRF52 is cortex-m4, nRF53 is cortex-m33
|
||||
CPU_CORE ?= cortex-m4
|
||||
|
||||
CFLAGS += \
|
||||
-DCFG_TUSB_MCU=OPT_MCU_NRF5X \
|
||||
-DCONFIG_GPIO_AS_PINRESET \
|
||||
-D__STARTUP_CLEAR_BSS
|
||||
|
||||
#CFLAGS += -nostdlib
|
||||
#CFLAGS += -D__START=main
|
||||
|
||||
# suppress warning caused by vendor mcu driver
|
||||
CFLAGS_GCC += \
|
||||
-flto \
|
||||
-Wno-error=undef \
|
||||
-Wno-error=unused-parameter \
|
||||
-Wno-error=unused-variable \
|
||||
-Wno-error=cast-align \
|
||||
-Wno-error=cast-qual \
|
||||
-Wno-error=redundant-decls \
|
||||
|
||||
LDFLAGS_GCC += \
|
||||
-nostartfiles \
|
||||
--specs=nosys.specs --specs=nano.specs \
|
||||
-L$(TOP)/${NRFX_DIR}/mdk
|
||||
|
||||
LDFLAGS_CLANG += \
|
||||
-L$(TOP)/${NRFX_DIR}/mdk \
|
||||
|
||||
SRC_C += \
|
||||
src/portable/nordic/nrf5x/dcd_nrf5x.c \
|
||||
${NRFX_DIR}/helpers/nrfx_flag32_allocator.c \
|
||||
${NRFX_DIR}/drivers/src/nrfx_gpiote.c \
|
||||
${NRFX_DIR}/drivers/src/nrfx_power.c \
|
||||
${NRFX_DIR}/drivers/src/nrfx_spim.c \
|
||||
${NRFX_DIR}/drivers/src/nrfx_uarte.c \
|
||||
${NRFX_DIR}/mdk/system_$(MCU_VARIANT).c \
|
||||
${NRFX_DIR}/soc/nrfx_atomic.c
|
||||
|
||||
INC += \
|
||||
$(TOP)/$(BOARD_PATH) \
|
||||
$(TOP)/lib/CMSIS_5/CMSIS/Core/Include \
|
||||
$(TOP)/${NRFX_DIR} \
|
||||
$(TOP)/${NRFX_DIR}/mdk \
|
||||
$(TOP)/${NRFX_DIR}/hal \
|
||||
$(TOP)/${NRFX_DIR}/drivers/include \
|
||||
$(TOP)/${NRFX_DIR}/drivers/src \
|
||||
|
||||
SRC_S += ${NRFX_DIR}/mdk/gcc_startup_$(MCU_VARIANT).S
|
||||
|
||||
ASFLAGS += -D__HEAP_SIZE=0
|
||||
|
||||
# For flash-jlink target
|
||||
JLINK_DEVICE ?= $(MCU_VARIANT)_xxaa
|
20
lib/main/tinyUSB/hw/bsp/nrf/linker/nrf52833_xxaa.ld
Normal file
20
lib/main/tinyUSB/hw/bsp/nrf/linker/nrf52833_xxaa.ld
Normal file
|
@ -0,0 +1,20 @@
|
|||
/* Linker script to configure memory regions. */
|
||||
|
||||
SEARCH_DIR(.)
|
||||
/*GROUP(-lgcc -lc -lnosys) not compatible with clang*/
|
||||
|
||||
MEMORY
|
||||
{
|
||||
FLASH (rx) : ORIGIN = 0x00000000, LENGTH = 0x80000
|
||||
RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 0x20000
|
||||
CODE_RAM (rwx) : ORIGIN = 0x800000, LENGTH = 0x20000
|
||||
}
|
||||
|
||||
|
||||
INCLUDE "nrf_common.ld"
|
||||
|
||||
/* nrfx v2 linker does not define __tbss_start/end__ __sbss_start/end__*/
|
||||
__tbss_start__ = __tbss_start;
|
||||
__tbss_end__ = __tbss_end;
|
||||
__sbss_start__ = __sbss_start;
|
||||
__sbss_end__ = __sbss_end;
|
44
lib/main/tinyUSB/hw/bsp/nrf/linker/nrf52840_s140_v6.ld
Normal file
44
lib/main/tinyUSB/hw/bsp/nrf/linker/nrf52840_s140_v6.ld
Normal file
|
@ -0,0 +1,44 @@
|
|||
/* Linker script to configure memory regions. */
|
||||
|
||||
SEARCH_DIR(.)
|
||||
/*GROUP(-lgcc -lc -lnosys) not compatible with clang*/
|
||||
|
||||
MEMORY
|
||||
{
|
||||
FLASH (rx) : ORIGIN = 0x26000, LENGTH = 0xED000 - 0x26000
|
||||
|
||||
/* SRAM required by S132 depend on
|
||||
* - Attribute Table Size
|
||||
* - Vendor UUID count
|
||||
* - Max ATT MTU
|
||||
* - Concurrent connection peripheral + central + secure links
|
||||
* - Event Len, HVN queue, Write CMD queue
|
||||
*/
|
||||
RAM (rwx) : ORIGIN = 0x20003400, LENGTH = 0x20040000 - 0x20003400
|
||||
}
|
||||
|
||||
SECTIONS
|
||||
{
|
||||
. = ALIGN(4);
|
||||
.svc_data :
|
||||
{
|
||||
PROVIDE(__start_svc_data = .);
|
||||
KEEP(*(.svc_data))
|
||||
PROVIDE(__stop_svc_data = .);
|
||||
} > RAM
|
||||
|
||||
.fs_data :
|
||||
{
|
||||
PROVIDE(__start_fs_data = .);
|
||||
KEEP(*(.fs_data))
|
||||
PROVIDE(__stop_fs_data = .);
|
||||
} > RAM
|
||||
} INSERT AFTER .data;
|
||||
|
||||
INCLUDE "nrf_common.ld"
|
||||
|
||||
/* nrfx v2 linker does not define __tbss_start/end__ __sbss_start/end__*/
|
||||
__tbss_start__ = __tbss_start;
|
||||
__tbss_end__ = __tbss_end;
|
||||
__sbss_start__ = __sbss_start;
|
||||
__sbss_end__ = __sbss_end;
|
20
lib/main/tinyUSB/hw/bsp/nrf/linker/nrf52840_xxaa.ld
Normal file
20
lib/main/tinyUSB/hw/bsp/nrf/linker/nrf52840_xxaa.ld
Normal file
|
@ -0,0 +1,20 @@
|
|||
/* Linker script to configure memory regions. */
|
||||
|
||||
SEARCH_DIR(.)
|
||||
/*GROUP(-lgcc -lc -lnosys) not compatible with clang*/
|
||||
|
||||
MEMORY
|
||||
{
|
||||
FLASH (rx) : ORIGIN = 0x00000000, LENGTH = 0x100000
|
||||
EXTFLASH (rx) : ORIGIN = 0x12000000, LENGTH = 0x8000000
|
||||
RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 0x40000
|
||||
CODE_RAM (rwx) : ORIGIN = 0x800000, LENGTH = 0x40000
|
||||
}
|
||||
|
||||
INCLUDE "nrf_common.ld"
|
||||
|
||||
/* nrfx v2 linker does not define __tbss_start/end__ __sbss_start/end__*/
|
||||
__tbss_start__ = __tbss_start;
|
||||
__tbss_end__ = __tbss_end;
|
||||
__sbss_start__ = __sbss_start;
|
||||
__sbss_end__ = __sbss_end;
|
|
@ -0,0 +1,21 @@
|
|||
/* Linker script to configure memory regions. */
|
||||
|
||||
SEARCH_DIR(.)
|
||||
/*GROUP(-lgcc -lc) not compatible with clang*/
|
||||
|
||||
MEMORY
|
||||
{
|
||||
FLASH (rx) : ORIGIN = 0x00000000, LENGTH = 0x100000
|
||||
EXTFLASH (rx) : ORIGIN = 0x10000000, LENGTH = 0x8000000
|
||||
RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 0x40000
|
||||
RAM1 (rwx) : ORIGIN = 0x20040000, LENGTH = 0x3F000
|
||||
}
|
||||
|
||||
|
||||
INCLUDE "nrf_common.ld"
|
||||
|
||||
/* nrfx v2 linker does not define __tbss_start/end__ __sbss_start/end__*/
|
||||
__tbss_start__ = __tbss_start;
|
||||
__tbss_end__ = __tbss_end;
|
||||
__sbss_start__ = __sbss_start;
|
||||
__sbss_end__ = __sbss_end;
|
46
lib/main/tinyUSB/hw/bsp/nrf/nrfx_config.h
Normal file
46
lib/main/tinyUSB/hw/bsp/nrf/nrfx_config.h
Normal file
|
@ -0,0 +1,46 @@
|
|||
#ifndef NRFX_CONFIG_H__
|
||||
#define NRFX_CONFIG_H__
|
||||
|
||||
#define NRFX_POWER_ENABLED 1
|
||||
#define NRFX_POWER_DEFAULT_CONFIG_IRQ_PRIORITY 7
|
||||
|
||||
#define NRFX_CLOCK_ENABLED 0
|
||||
#define NRFX_GPIOTE_ENABLED 1
|
||||
#define NRFX_GPIOTE0_ENABLED 1
|
||||
|
||||
#define NRFX_UARTE_ENABLED 1
|
||||
#define NRFX_UARTE0_ENABLED 1
|
||||
|
||||
#define NRFX_SPIM_ENABLED 1
|
||||
#define NRFX_SPIM1_ENABLED 1 // use SPI1 since nrf5340 share uart with spi
|
||||
|
||||
#define NRFX_PRS_ENABLED 0
|
||||
#define NRFX_USBREG_ENABLED 1
|
||||
|
||||
#if defined(NRF51)
|
||||
#include <templates/nrfx_config_nrf51.h>
|
||||
#elif defined(NRF52805_XXAA)
|
||||
#include <templates/nrfx_config_nrf52805.h>
|
||||
#elif defined(NRF52810_XXAA)
|
||||
#include <templates/nrfx_config_nrf52810.h>
|
||||
#elif defined(NRF52811_XXAA)
|
||||
#include <templates/nrfx_config_nrf52811.h>
|
||||
#elif defined(NRF52820_XXAA)
|
||||
#include <templates/nrfx_config_nrf52820.h>
|
||||
#elif defined(NRF52832_XXAA) || defined (NRF52832_XXAB)
|
||||
#include <templates/nrfx_config_nrf52832.h>
|
||||
#elif defined(NRF52833_XXAA)
|
||||
#include <templates/nrfx_config_nrf52833.h>
|
||||
#elif defined(NRF52840_XXAA)
|
||||
#include <templates/nrfx_config_nrf52840.h>
|
||||
#elif defined(NRF5340_XXAA_APPLICATION)
|
||||
#include <templates/nrfx_config_nrf5340_application.h>
|
||||
#elif defined(NRF5340_XXAA_NETWORK)
|
||||
#include <templates/nrfx_config_nrf5340_network.h>
|
||||
#elif defined(NRF9120_XXAA) || defined(NRF9160_XXAA)
|
||||
#include <templates/nrfx_config_nrf91.h>
|
||||
#else
|
||||
#error "Unknown device."
|
||||
#endif
|
||||
|
||||
#endif // NRFX_CONFIG_H__
|
296
lib/main/tinyUSB/hw/bsp/nrf/nrfx_glue.h
Normal file
296
lib/main/tinyUSB/hw/bsp/nrf/nrfx_glue.h
Normal file
|
@ -0,0 +1,296 @@
|
|||
/*
|
||||
* Copyright (c) 2017 - 2018, Nordic Semiconductor ASA
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice, this
|
||||
* list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in the
|
||||
* documentation and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. Neither the name of the copyright holder nor the names of its
|
||||
* contributors may be used to endorse or promote products derived from this
|
||||
* software without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
||||
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
||||
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
|
||||
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
|
||||
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
|
||||
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
|
||||
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
|
||||
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
||||
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
|
||||
#ifndef NRFX_GLUE_H__
|
||||
#define NRFX_GLUE_H__
|
||||
|
||||
// THIS IS A TEMPLATE FILE.
|
||||
// It should be copied to a suitable location within the host environment into
|
||||
// which nrfx is integrated, and the following macros should be provided with
|
||||
// appropriate implementations.
|
||||
// And this comment should be removed from the customized file.
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @defgroup nrfx_glue nrfx_glue.h
|
||||
* @{
|
||||
* @ingroup nrfx
|
||||
*
|
||||
* @brief This file contains macros that should be implemented according to
|
||||
* the needs of the host environment into which @em nrfx is integrated.
|
||||
*/
|
||||
|
||||
// Uncomment this line to use the standard MDK way of binding IRQ handlers
|
||||
// at linking time.
|
||||
#include <soc/nrfx_irqs.h>
|
||||
|
||||
//------------------------------------------------------------------------------
|
||||
|
||||
/**
|
||||
* @brief Macro for placing a runtime assertion.
|
||||
*
|
||||
* @param expression Expression to evaluate.
|
||||
*/
|
||||
#define NRFX_ASSERT(expression)
|
||||
|
||||
/**
|
||||
* @brief Macro for placing a compile time assertion.
|
||||
*
|
||||
* @param expression Expression to evaluate.
|
||||
*/
|
||||
#define NRFX_STATIC_ASSERT(expression)
|
||||
|
||||
//------------------------------------------------------------------------------
|
||||
|
||||
/**
|
||||
* @brief Macro for setting the priority of a specific IRQ.
|
||||
*
|
||||
* @param irq_number IRQ number.
|
||||
* @param priority Priority to set.
|
||||
*/
|
||||
#define NRFX_IRQ_PRIORITY_SET(irq_number, priority) _NRFX_IRQ_PRIORITY_SET(irq_number, priority)
|
||||
static inline void _NRFX_IRQ_PRIORITY_SET(IRQn_Type irq_number,
|
||||
uint8_t priority)
|
||||
{
|
||||
NRFX_ASSERT(INTERRUPT_PRIORITY_IS_VALID(priority));
|
||||
NVIC_SetPriority(irq_number, priority);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Macro for enabling a specific IRQ.
|
||||
*
|
||||
* @param irq_number IRQ number.
|
||||
*/
|
||||
#define NRFX_IRQ_ENABLE(irq_number) _NRFX_IRQ_ENABLE(irq_number)
|
||||
static inline void _NRFX_IRQ_ENABLE(IRQn_Type irq_number)
|
||||
{
|
||||
NVIC_ClearPendingIRQ(irq_number);
|
||||
NVIC_EnableIRQ(irq_number);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Macro for checking if a specific IRQ is enabled.
|
||||
*
|
||||
* @param irq_number IRQ number.
|
||||
*
|
||||
* @retval true If the IRQ is enabled.
|
||||
* @retval false Otherwise.
|
||||
*/
|
||||
#define NRFX_IRQ_IS_ENABLED(irq_number) _NRFX_IRQ_IS_ENABLED(irq_number)
|
||||
static inline bool _NRFX_IRQ_IS_ENABLED(IRQn_Type irq_number)
|
||||
{
|
||||
return 0 != (NVIC->ISER[irq_number / 32] & (1UL << (irq_number % 32)));
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Macro for disabling a specific IRQ.
|
||||
*
|
||||
* @param irq_number IRQ number.
|
||||
*/
|
||||
#define NRFX_IRQ_DISABLE(irq_number) _NRFX_IRQ_DISABLE(irq_number)
|
||||
static inline void _NRFX_IRQ_DISABLE(IRQn_Type irq_number)
|
||||
{
|
||||
NVIC_DisableIRQ(irq_number);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Macro for setting a specific IRQ as pending.
|
||||
*
|
||||
* @param irq_number IRQ number.
|
||||
*/
|
||||
#define NRFX_IRQ_PENDING_SET(irq_number) _NRFX_IRQ_PENDING_SET(irq_number)
|
||||
static inline void _NRFX_IRQ_PENDING_SET(IRQn_Type irq_number)
|
||||
{
|
||||
NVIC_SetPendingIRQ(irq_number);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Macro for clearing the pending status of a specific IRQ.
|
||||
*
|
||||
* @param irq_number IRQ number.
|
||||
*/
|
||||
#define NRFX_IRQ_PENDING_CLEAR(irq_number) _NRFX_IRQ_PENDING_CLEAR(irq_number)
|
||||
static inline void _NRFX_IRQ_PENDING_CLEAR(IRQn_Type irq_number)
|
||||
{
|
||||
NVIC_ClearPendingIRQ(irq_number);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Macro for checking the pending status of a specific IRQ.
|
||||
*
|
||||
* @retval true If the IRQ is pending.
|
||||
* @retval false Otherwise.
|
||||
*/
|
||||
#define NRFX_IRQ_IS_PENDING(irq_number) _NRFX_IRQ_IS_PENDING(irq_number)
|
||||
static inline bool _NRFX_IRQ_IS_PENDING(IRQn_Type irq_number)
|
||||
{
|
||||
return (NVIC_GetPendingIRQ(irq_number) == 1);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Macro for entering into a critical section.
|
||||
*/
|
||||
#define NRFX_CRITICAL_SECTION_ENTER()
|
||||
|
||||
/**
|
||||
* @brief Macro for exiting from a critical section.
|
||||
*/
|
||||
#define NRFX_CRITICAL_SECTION_EXIT()
|
||||
|
||||
//------------------------------------------------------------------------------
|
||||
|
||||
/**
|
||||
* @brief When set to a non-zero value, this macro specifies that
|
||||
* @ref nrfx_coredep_delay_us uses a precise DWT-based solution.
|
||||
* A compilation error is generated if the DWT unit is not present
|
||||
* in the SoC used.
|
||||
*/
|
||||
#define NRFX_DELAY_DWT_BASED 0
|
||||
|
||||
/**
|
||||
* @brief Macro for delaying the code execution for at least the specified time.
|
||||
*
|
||||
* @param us_time Number of microseconds to wait.
|
||||
*/
|
||||
#include <soc/nrfx_coredep.h>
|
||||
#define NRFX_DELAY_US(us_time) nrfx_coredep_delay_us(us_time)
|
||||
|
||||
//------------------------------------------------------------------------------
|
||||
|
||||
/**
|
||||
* @brief When set to a non-zero value, this macro specifies that the
|
||||
* @ref nrfx_error_codes and the @ref nrfx_err_t type itself are defined
|
||||
* in a customized way and the default definitions from @c <nrfx_error.h>
|
||||
* should not be used.
|
||||
*/
|
||||
#define NRFX_CUSTOM_ERROR_CODES 0
|
||||
|
||||
//------------------------------------------------------------------------------
|
||||
|
||||
/**
|
||||
* @brief Bitmask defining PPI channels reserved to be used outside of nrfx.
|
||||
*/
|
||||
#define NRFX_PPI_CHANNELS_USED 0
|
||||
|
||||
/**
|
||||
* @brief Bitmask defining PPI groups reserved to be used outside of nrfx.
|
||||
*/
|
||||
#define NRFX_PPI_GROUPS_USED 0
|
||||
|
||||
/**
|
||||
* @brief Bitmask defining SWI instances reserved to be used outside of nrfx.
|
||||
*/
|
||||
#define NRFX_SWI_USED 0
|
||||
|
||||
/**
|
||||
* @brief Bitmask defining TIMER instances reserved to be used outside of nrfx.
|
||||
*/
|
||||
#define NRFX_TIMERS_USED 0
|
||||
|
||||
/** @} */
|
||||
|
||||
//------------------------------------------------------------------------------
|
||||
|
||||
#include <soc/nrfx_atomic.h>
|
||||
|
||||
/**
|
||||
* @brief Atomic 32 bit unsigned type.
|
||||
*/
|
||||
#define nrfx_atomic_t nrfx_atomic_u32_t
|
||||
|
||||
/**
|
||||
* @brief Stores value to an atomic object and returns previously stored value.
|
||||
*
|
||||
* @param[in] p_data Atomic memory pointer.
|
||||
* @param[in] value Value to store.
|
||||
*
|
||||
* @return Old value stored into atomic object.
|
||||
*/
|
||||
#define NRFX_ATOMIC_FETCH_STORE(p_data, value) nrfx_atomic_u32_fetch_store(p_data, value)
|
||||
|
||||
/**
|
||||
* @brief Performs logical OR operation on an atomic object and returns previously stored value.
|
||||
*
|
||||
* @param[in] p_data Atomic memory pointer.
|
||||
* @param[in] value Value of second operand of OR operation.
|
||||
*
|
||||
* @return Old value stored into atomic object.
|
||||
*/
|
||||
#define NRFX_ATOMIC_FETCH_OR(p_data, value) nrfx_atomic_u32_fetch_or(p_data, value)
|
||||
|
||||
/**
|
||||
* @brief Performs logical AND operation on an atomic object and returns previously stored value.
|
||||
*
|
||||
* @param[in] p_data Atomic memory pointer.
|
||||
* @param[in] value Value of second operand of AND operation.
|
||||
*
|
||||
* @return Old value stored into atomic object.
|
||||
*/
|
||||
#define NRFX_ATOMIC_FETCH_AND(p_data, value) nrfx_atomic_u32_fetch_and(p_data, value)
|
||||
|
||||
/**
|
||||
* @brief Performs logical XOR operation on an atomic object and returns previously stored value.
|
||||
*
|
||||
* @param[in] p_data Atomic memory pointer.
|
||||
* @param[in] value Value of second operand of XOR operation.
|
||||
*
|
||||
* @return Old value stored into atomic object.
|
||||
*/
|
||||
#define NRFX_ATOMIC_FETCH_XOR(p_data, value) nrfx_atomic_u32_fetch_xor(p_data, value)
|
||||
|
||||
/**
|
||||
* @brief Performs logical ADD operation on an atomic object and returns previously stored value.
|
||||
*
|
||||
* @param[in] p_data Atomic memory pointer.
|
||||
* @param[in] value Value of second operand of ADD operation.
|
||||
*
|
||||
* @return Old value stored into atomic object.
|
||||
*/
|
||||
#define NRFX_ATOMIC_FETCH_ADD(p_data, value) nrfx_atomic_u32_fetch_add(p_data, value)
|
||||
|
||||
/**
|
||||
* @brief Performs logical SUB operation on an atomic object and returns previously stored value.
|
||||
*
|
||||
* @param[in] p_data Atomic memory pointer.
|
||||
* @param[in] value Value of second operand of SUB operation.
|
||||
*
|
||||
* @return Old value stored into atomic object.
|
||||
*/
|
||||
#define NRFX_ATOMIC_FETCH_SUB(p_data, value) nrfx_atomic_u32_fetch_sub(p_data, value)
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // NRFX_GLUE_H__
|
135
lib/main/tinyUSB/hw/bsp/nrf/nrfx_log.h
Normal file
135
lib/main/tinyUSB/hw/bsp/nrf/nrfx_log.h
Normal file
|
@ -0,0 +1,135 @@
|
|||
/*
|
||||
* Copyright (c) 2017 - 2019, Nordic Semiconductor ASA
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice, this
|
||||
* list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in the
|
||||
* documentation and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. Neither the name of the copyright holder nor the names of its
|
||||
* contributors may be used to endorse or promote products derived from this
|
||||
* software without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
||||
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
||||
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
|
||||
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
|
||||
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
|
||||
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
|
||||
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
|
||||
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
||||
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
|
||||
#ifndef NRFX_LOG_H__
|
||||
#define NRFX_LOG_H__
|
||||
|
||||
// THIS IS A TEMPLATE FILE.
|
||||
// It should be copied to a suitable location within the host environment into
|
||||
// which nrfx is integrated, and the following macros should be provided with
|
||||
// appropriate implementations.
|
||||
// And this comment should be removed from the customized file.
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @defgroup nrfx_log nrfx_log.h
|
||||
* @{
|
||||
* @ingroup nrfx
|
||||
*
|
||||
* @brief This file contains macros that should be implemented according to
|
||||
* the needs of the host environment into which @em nrfx is integrated.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Macro for logging a message with the severity level ERROR.
|
||||
*
|
||||
* @param format printf-style format string, optionally followed by arguments
|
||||
* to be formatted and inserted in the resulting string.
|
||||
*/
|
||||
#define NRFX_LOG_ERROR(format, ...)
|
||||
|
||||
/**
|
||||
* @brief Macro for logging a message with the severity level WARNING.
|
||||
*
|
||||
* @param format printf-style format string, optionally followed by arguments
|
||||
* to be formatted and inserted in the resulting string.
|
||||
*/
|
||||
#define NRFX_LOG_WARNING(format, ...)
|
||||
|
||||
/**
|
||||
* @brief Macro for logging a message with the severity level INFO.
|
||||
*
|
||||
* @param format printf-style format string, optionally followed by arguments
|
||||
* to be formatted and inserted in the resulting string.
|
||||
*/
|
||||
#define NRFX_LOG_INFO(format, ...)
|
||||
|
||||
/**
|
||||
* @brief Macro for logging a message with the severity level DEBUG.
|
||||
*
|
||||
* @param format printf-style format string, optionally followed by arguments
|
||||
* to be formatted and inserted in the resulting string.
|
||||
*/
|
||||
#define NRFX_LOG_DEBUG(format, ...)
|
||||
|
||||
|
||||
/**
|
||||
* @brief Macro for logging a memory dump with the severity level ERROR.
|
||||
*
|
||||
* @param[in] p_memory Pointer to the memory region to be dumped.
|
||||
* @param[in] length Length of the memory region in bytes.
|
||||
*/
|
||||
#define NRFX_LOG_HEXDUMP_ERROR(p_memory, length)
|
||||
|
||||
/**
|
||||
* @brief Macro for logging a memory dump with the severity level WARNING.
|
||||
*
|
||||
* @param[in] p_memory Pointer to the memory region to be dumped.
|
||||
* @param[in] length Length of the memory region in bytes.
|
||||
*/
|
||||
#define NRFX_LOG_HEXDUMP_WARNING(p_memory, length)
|
||||
|
||||
/**
|
||||
* @brief Macro for logging a memory dump with the severity level INFO.
|
||||
*
|
||||
* @param[in] p_memory Pointer to the memory region to be dumped.
|
||||
* @param[in] length Length of the memory region in bytes.
|
||||
*/
|
||||
#define NRFX_LOG_HEXDUMP_INFO(p_memory, length)
|
||||
|
||||
/**
|
||||
* @brief Macro for logging a memory dump with the severity level DEBUG.
|
||||
*
|
||||
* @param[in] p_memory Pointer to the memory region to be dumped.
|
||||
* @param[in] length Length of the memory region in bytes.
|
||||
*/
|
||||
#define NRFX_LOG_HEXDUMP_DEBUG(p_memory, length)
|
||||
|
||||
|
||||
/**
|
||||
* @brief Macro for getting the textual representation of a given error code.
|
||||
*
|
||||
* @param[in] error_code Error code.
|
||||
*
|
||||
* @return String containing the textual representation of the error code.
|
||||
*/
|
||||
#define NRFX_LOG_ERROR_STRING_GET(error_code)
|
||||
|
||||
/** @} */
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // NRFX_LOG_H__
|
Loading…
Add table
Add a link
Reference in a new issue