1
0
Fork 0
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:
blckmn 2025-01-12 07:56:01 +11:00
parent 1774693395
commit 0109f50909
1507 changed files with 299535 additions and 0 deletions

View 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 "chip.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

View file

@ -0,0 +1,16 @@
set(MCU_VARIANT LPC4357)
set(JLINK_DEVICE LPC4357_M4)
set(PYOCD_TARGET LPC4357)
set(NXPLINK_DEVICE LPC4357:LPC4357)
set(LD_FILE_GNU ${CMAKE_CURRENT_LIST_DIR}/lpc4357.ld)
function(update_board TARGET)
# EA4357 use I2C GPIO expander for LED
target_sources(${TARGET} PRIVATE
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/pca9532.c
${SDK_DIR}/src/i2c_18xx_43xx.c
${SDK_DIR}/src/i2cm_18xx_43xx.c
)
endfunction()

View file

@ -0,0 +1,85 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2023 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_EA4357_H
#define _BOARD_EA4357_H
#ifdef __cplusplus
extern "C" {
#endif
#include "pca9532.h"
// P9_1 joystick down
#define BUTTON_PORT 4
#define BUTTON_PIN 13
#define BUTTON_STATE_ACTIVE 0
#define UART_DEV LPC_USART0
#define UART_PORT 0x0f
#define UART_PIN_TX 10
#define UART_PIN_RX 11
//static const struct {
// uint8_t mux_port;
// uint8_t mux_pin;
//
// uint8_t gpio_port;
// uint8_t gpio_pin;
//}buttons[] =
//{
// {0x0a, 3, 4, 10 }, // Joystick up
// {0x09, 1, 4, 13 }, // Joystick down
// {0x0a, 2, 4, 9 }, // Joystick left
// {0x09, 0, 4, 12 }, // Joystick right
// {0x0a, 1, 4, 8 }, // Joystick press
// {0x02, 7, 0, 7 }, // SW6
//};
static const PINMUX_GRP_T pinmuxing[] = {
// Button ( Joystick down )
{ 0x9, 1, SCU_MODE_INBUFF_EN | SCU_MODE_INACT | SCU_MODE_FUNC0 | SCU_MODE_PULLUP },
// UART
{ UART_PORT, UART_PIN_TX, SCU_MODE_PULLDOWN | SCU_MODE_FUNC1 },
{ UART_PORT, UART_PIN_RX, SCU_MODE_INACT | SCU_MODE_INBUFF_EN | SCU_MODE_ZIF_DIS | SCU_MODE_FUNC1 },
// USB
};
/* Pin clock mux values, re-used structure, value in first index is meaningless */
//static const PINMUX_GRP_T pinclockmuxing[] = {
// { 0, 0, SCU_MODE_INACT | SCU_MODE_INBUFF_EN | SCU_MODE_ZIF_DIS | SCU_MODE_HIGHSPEEDSLEW_EN | SCU_MODE_FUNC0 },
// { 0, 1, SCU_MODE_INACT | SCU_MODE_INBUFF_EN | SCU_MODE_ZIF_DIS | SCU_MODE_HIGHSPEEDSLEW_EN | SCU_MODE_FUNC0 },
// { 0, 2, SCU_MODE_INACT | SCU_MODE_INBUFF_EN | SCU_MODE_ZIF_DIS | SCU_MODE_HIGHSPEEDSLEW_EN | SCU_MODE_FUNC0 },
// { 0, 3, SCU_MODE_INACT | SCU_MODE_INBUFF_EN | SCU_MODE_ZIF_DIS | SCU_MODE_HIGHSPEEDSLEW_EN | SCU_MODE_FUNC0 },
//};
#ifdef __cplusplus
}
#endif
#endif

View file

@ -0,0 +1,11 @@
# EA4357 use I2C GPIO expander for LED
SRC_C += \
${BOARD_PATH}/pca9532.c \
${SDK_DIR}/src/i2c_18xx_43xx.c \
${SDK_DIR}/src/i2cm_18xx_43xx.c \
LD_FILE = ${BOARD_PATH}/lpc4357.ld
JLINK_DEVICE = LPC4357_M4
flash: flash-jlink

View file

@ -0,0 +1,341 @@
/*
* GENERATED FILE - DO NOT EDIT
* (c) Code Red Technologies Ltd, 2008-2013
* (c) NXP Semiconductors 2013-2019
* Generated linker script file for LPC4357
* Created from linkscript.ldt by FMCreateLinkLibraries
* Using Freemarker v2.3.23
* MCUXpresso IDE v10.2.1 [Build 795] [2018-07-25] on May 15, 2019 5:48:43 PM
*/
MEMORY
{
/* Define each memory region */
MFlashA512 (rx) : ORIGIN = 0x1a000000, LENGTH = 0x80000 /* 512K bytes (alias Flash) */
MFlashB512 (rx) : ORIGIN = 0x1b000000, LENGTH = 0x80000 /* 512K bytes (alias Flash2) */
RamLoc32 (rwx) : ORIGIN = 0x10000000, LENGTH = 0x8000 /* 32K bytes (alias RAM) */
RamLoc40 (rwx) : ORIGIN = 0x10080000, LENGTH = 0xa000 /* 40K bytes (alias RAM2) */
RamAHB32 (rwx) : ORIGIN = 0x20000000, LENGTH = 0x8000 /* 32K bytes (alias RAM3) */
RamAHB16 (rwx) : ORIGIN = 0x20008000, LENGTH = 0x4000 /* 16K bytes (alias RAM4) */
RamAHB_ETB16 (rwx) : ORIGIN = 0x2000c000, LENGTH = 0x4000 /* 16K bytes (alias RAM5) */
}
/* Define a symbol for the top of each memory region */
__base_MFlashA512 = 0x1a000000 ; /* MFlashA512 */
__base_Flash = 0x1a000000 ; /* Flash */
__top_MFlashA512 = 0x1a000000 + 0x80000 ; /* 512K bytes */
__top_Flash = 0x1a000000 + 0x80000 ; /* 512K bytes */
__base_MFlashB512 = 0x1b000000 ; /* MFlashB512 */
__base_Flash2 = 0x1b000000 ; /* Flash2 */
__top_MFlashB512 = 0x1b000000 + 0x80000 ; /* 512K bytes */
__top_Flash2 = 0x1b000000 + 0x80000 ; /* 512K bytes */
__base_RamLoc32 = 0x10000000 ; /* RamLoc32 */
__base_RAM = 0x10000000 ; /* RAM */
__top_RamLoc32 = 0x10000000 + 0x8000 ; /* 32K bytes */
__top_RAM = 0x10000000 + 0x8000 ; /* 32K bytes */
__base_RamLoc40 = 0x10080000 ; /* RamLoc40 */
__base_RAM2 = 0x10080000 ; /* RAM2 */
__top_RamLoc40 = 0x10080000 + 0xa000 ; /* 40K bytes */
__top_RAM2 = 0x10080000 + 0xa000 ; /* 40K bytes */
__base_RamAHB32 = 0x20000000 ; /* RamAHB32 */
__base_RAM3 = 0x20000000 ; /* RAM3 */
__top_RamAHB32 = 0x20000000 + 0x8000 ; /* 32K bytes */
__top_RAM3 = 0x20000000 + 0x8000 ; /* 32K bytes */
__base_RamAHB16 = 0x20008000 ; /* RamAHB16 */
__base_RAM4 = 0x20008000 ; /* RAM4 */
__top_RamAHB16 = 0x20008000 + 0x4000 ; /* 16K bytes */
__top_RAM4 = 0x20008000 + 0x4000 ; /* 16K bytes */
__base_RamAHB_ETB16 = 0x2000c000 ; /* RamAHB_ETB16 */
__base_RAM5 = 0x2000c000 ; /* RAM5 */
__top_RamAHB_ETB16 = 0x2000c000 + 0x4000 ; /* 16K bytes */
__top_RAM5 = 0x2000c000 + 0x4000 ; /* 16K bytes */
ENTRY(ResetISR)
SECTIONS
{
.text_Flash2 : ALIGN(4)
{
FILL(0xff)
*(.text_Flash2*) /* for compatibility with previous releases */
*(.text_MFlashB512*) /* for compatibility with previous releases */
*(.text.$Flash2*)
*(.text.$MFlashB512*)
*(.rodata.$Flash2*)
*(.rodata.$MFlashB512*)
} > MFlashB512
/* MAIN TEXT SECTION */
.text : ALIGN(4)
{
FILL(0xff)
__vectors_start__ = ABSOLUTE(.) ;
KEEP(*(.isr_vector))
/* Global Section Table */
. = ALIGN(4) ;
__section_table_start = .;
__data_section_table = .;
LONG(LOADADDR(.data));
LONG( ADDR(.data));
LONG( SIZEOF(.data));
LONG(LOADADDR(.data_RAM2));
LONG( ADDR(.data_RAM2));
LONG( SIZEOF(.data_RAM2));
LONG(LOADADDR(.data_RAM3));
LONG( ADDR(.data_RAM3));
LONG( SIZEOF(.data_RAM3));
LONG(LOADADDR(.data_RAM4));
LONG( ADDR(.data_RAM4));
LONG( SIZEOF(.data_RAM4));
LONG(LOADADDR(.data_RAM5));
LONG( ADDR(.data_RAM5));
LONG( SIZEOF(.data_RAM5));
__data_section_table_end = .;
__bss_section_table = .;
LONG( ADDR(.bss));
LONG( SIZEOF(.bss));
LONG( ADDR(.bss_RAM2));
LONG( SIZEOF(.bss_RAM2));
LONG( ADDR(.bss_RAM3));
LONG( SIZEOF(.bss_RAM3));
LONG( ADDR(.bss_RAM4));
LONG( SIZEOF(.bss_RAM4));
LONG( ADDR(.bss_RAM5));
LONG( SIZEOF(.bss_RAM5));
__bss_section_table_end = .;
__section_table_end = . ;
/* End of Global Section Table */
*(.after_vectors*)
} > MFlashA512
.text : ALIGN(4)
{
*(.text*)
*(.rodata .rodata.* .constdata .constdata.*)
. = ALIGN(4);
} > MFlashA512
/*
* for exception handling/unwind - some Newlib functions (in common
* with C++ and STDC++) use this.
*/
.ARM.extab : ALIGN(4)
{
*(.ARM.extab* .gnu.linkonce.armextab.*)
} > MFlashA512
__exidx_start = .;
.ARM.exidx : ALIGN(4)
{
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
} > MFlashA512
__exidx_end = .;
_etext = .;
/* DATA section for RamLoc40 */
.data_RAM2 : ALIGN(4)
{
FILL(0xff)
PROVIDE(__start_data_RAM2 = .) ;
*(.ramfunc.$RAM2)
*(.ramfunc.$RamLoc40)
*(.data.$RAM2*)
*(.data.$RamLoc40*)
. = ALIGN(4) ;
PROVIDE(__end_data_RAM2 = .) ;
} > RamLoc40 AT>MFlashA512
/* DATA section for RamAHB32 */
.data_RAM3 : ALIGN(4)
{
FILL(0xff)
PROVIDE(__start_data_RAM3 = .) ;
*(.ramfunc.$RAM3)
*(.ramfunc.$RamAHB32)
*(.data.$RAM3*)
*(.data.$RamAHB32*)
. = ALIGN(4) ;
PROVIDE(__end_data_RAM3 = .) ;
} > RamAHB32 AT>MFlashA512
/* DATA section for RamAHB16 */
.data_RAM4 : ALIGN(4)
{
FILL(0xff)
PROVIDE(__start_data_RAM4 = .) ;
*(.ramfunc.$RAM4)
*(.ramfunc.$RamAHB16)
*(.data.$RAM4*)
*(.data.$RamAHB16*)
. = ALIGN(4) ;
PROVIDE(__end_data_RAM4 = .) ;
} > RamAHB16 AT>MFlashA512
/* DATA section for RamAHB_ETB16 */
.data_RAM5 : ALIGN(4)
{
FILL(0xff)
PROVIDE(__start_data_RAM5 = .) ;
*(.ramfunc.$RAM5)
*(.ramfunc.$RamAHB_ETB16)
*(.data.$RAM5*)
*(.data.$RamAHB_ETB16*)
. = ALIGN(4) ;
PROVIDE(__end_data_RAM5 = .) ;
} > RamAHB_ETB16 AT>MFlashA512
/* MAIN DATA SECTION */
.uninit_RESERVED : ALIGN(4)
{
KEEP(*(.bss.$RESERVED*))
. = ALIGN(4) ;
_end_uninit_RESERVED = .;
} > RamLoc32
/* Main DATA section (RamLoc32) */
.data : ALIGN(4)
{
FILL(0xff)
_data = . ;
*(vtable)
*(.ramfunc*)
*(.data*)
. = ALIGN(4) ;
_edata = . ;
} > RamLoc32 AT>MFlashA512
/* BSS section for RamLoc40 */
.bss_RAM2 : ALIGN(4)
{
PROVIDE(__start_bss_RAM2 = .) ;
*(.bss.$RAM2*)
*(.bss.$RamLoc40*)
. = ALIGN (. != 0 ? 4 : 1) ; /* avoid empty segment */
PROVIDE(__end_bss_RAM2 = .) ;
} > RamLoc40
/* BSS section for RamAHB32 */
.bss_RAM3 : ALIGN(4)
{
PROVIDE(__start_bss_RAM3 = .) ;
*(.bss.$RAM3*)
*(.bss.$RamAHB32*)
. = ALIGN (. != 0 ? 4 : 1) ; /* avoid empty segment */
PROVIDE(__end_bss_RAM3 = .) ;
} > RamAHB32
/* BSS section for RamAHB16 */
.bss_RAM4 : ALIGN(4)
{
PROVIDE(__start_bss_RAM4 = .) ;
*(.bss.$RAM4*)
*(.bss.$RamAHB16*)
. = ALIGN (. != 0 ? 4 : 1) ; /* avoid empty segment */
PROVIDE(__end_bss_RAM4 = .) ;
} > RamAHB16
/* BSS section for RamAHB_ETB16 */
.bss_RAM5 : ALIGN(4)
{
PROVIDE(__start_bss_RAM5 = .) ;
*(.bss.$RAM5*)
*(.bss.$RamAHB_ETB16*)
. = ALIGN (. != 0 ? 4 : 1) ; /* avoid empty segment */
PROVIDE(__end_bss_RAM5 = .) ;
} > RamAHB_ETB16
/* MAIN BSS SECTION: EDIT change to RamLoc40 */
.bss : ALIGN(4)
{
_bss = .;
*(.bss*)
*(COMMON)
. = ALIGN(4) ;
_ebss = .;
/* PROVIDE(end = .); */
} > RamLoc40 /* RamLoc32 */
/* NOINIT section for RamLoc40 */
.noinit_RAM2 (NOLOAD) : ALIGN(4)
{
*(.noinit.$RAM2*)
*(.noinit.$RamLoc40*)
. = ALIGN(4) ;
} > RamLoc40
/* hathach add heap section for clang */
.heap (NOLOAD): {
__heap_start = .;
__HeapBase = .;
__heap_base = .;
__end = .;
PROVIDE(end = .);
PROVIDE(_end = .);
PROVIDE(__end__ = .);
KEEP(*(.heap*))
__HeapLimit = .;
__heap_limit = .;
__heap_end = .;
} > RamLoc40
/* NOINIT section for RamAHB32 */
.noinit_RAM3 (NOLOAD) : ALIGN(4)
{
*(.noinit.$RAM3*)
*(.noinit.$RamAHB32*)
. = ALIGN(4) ;
} > RamAHB32
/* NOINIT section for RamAHB16 */
.noinit_RAM4 (NOLOAD) : ALIGN(4)
{
*(.noinit.$RAM4*)
*(.noinit.$RamAHB16*)
. = ALIGN(4) ;
} > RamAHB16
/* NOINIT section for RamAHB_ETB16 */
.noinit_RAM5 (NOLOAD) : ALIGN(4)
{
*(.noinit.$RAM5*)
*(.noinit.$RamAHB_ETB16*)
. = ALIGN(4) ;
} > RamAHB_ETB16
/* DEFAULT NOINIT SECTION */
.noinit (NOLOAD): ALIGN(4)
{
_noinit = .;
*(.noinit*)
. = ALIGN(4) ;
_end_noinit = .;
} > RamLoc32
/* PROVIDE(_pvHeapStart = DEFINED(__user_heap_base) ? __user_heap_base : .);*/
PROVIDE(_vStackTop = DEFINED(__user_stack_top) ? __user_stack_top : __top_RamLoc32 - 0);
/* ## Create checksum value (used in startup) ## */
/* This cause issue with clang linker, so it is disabled */
/* MemManage_Handler, BusFault_Handler, UsageFault_Hander may not be defined */
/* PROVIDE(__valid_user_code_checksum = 0 -*/
/* (_vStackTop*/
/* + (ResetISR + 1)*/
/* + (NMI_Handler + 1)*/
/* + (HardFault_Handler + 1)*/
/* + (( DEFINED(MemManage_Handler) ? MemManage_Handler : 0 ) + 1)*/
/* + (( DEFINED(BusFault_Handler) ? BusFault_Handler : 0 ) + 1)*/
/* + (( DEFINED(UsageFault_Handler) ? UsageFault_Handler : 0 ) + 1)*/
/* ) );*/
/* Provide basic symbols giving location and size of main text
* block, including initial values of RW data sections. Note that
* these will need extending to give a complete picture with
* complex images (e.g multiple Flash banks).
*/
_image_start = LOADADDR(.text);
_image_end = LOADADDR(.data) + SIZEOF(.data);
_image_size = _image_end - _image_start;
}

View file

@ -0,0 +1,352 @@
/*****************************************************************************
*
* Copyright(C) 2011, Embedded Artists AB
* All rights reserved.
*
******************************************************************************
* Software that is described herein is for illustrative purposes only
* which provides customers with programming information regarding the
* products. This software is supplied "AS IS" without any warranties.
* Embedded Artists AB assumes no responsibility or liability for the
* use of the software, conveys no license or title under any patent,
* copyright, or mask work right to the product. Embedded Artists AB
* reserves the right to make changes in the software without
* notification. Embedded Artists AB also make no representation or
* warranty that such application will be suitable for the specified
* use without further testing or modification.
*****************************************************************************/
/*
* NOTE: I2C must have been initialized before calling any functions in this
* file.
*/
/******************************************************************************
* Includes
*****************************************************************************/
//#include "board.h"
#include "chip.h"
#include "pca9532.h"
/******************************************************************************
* Defines and typedefs
*****************************************************************************/
#define I2C_PORT (LPC_I2C0)
#define LS_MODE_ON 0x01
#define LS_MODE_BLINK0 0x02
#define LS_MODE_BLINK1 0x03
/******************************************************************************
* External global variables
*****************************************************************************/
/******************************************************************************
* Local variables
*****************************************************************************/
static uint16_t blink0Shadow = 0;
static uint16_t blink1Shadow = 0;
static uint16_t ledStateShadow = 0;
/******************************************************************************
* Local Functions
*****************************************************************************/
static Status I2CWrite(uint32_t addr, uint8_t* buf, uint32_t len)
{
I2CM_XFER_T i2cData;
i2cData.slaveAddr = addr;
i2cData.options = 0;
i2cData.status = 0;
i2cData.txBuff = buf;
i2cData.txSz = len;
i2cData.rxBuff = NULL;
i2cData.rxSz = 0;
if (Chip_I2CM_XferBlocking(LPC_I2C0, &i2cData) == 0) {
return ERROR;
}
return SUCCESS;
}
static Status I2CRead(uint32_t addr, uint8_t* buf, uint32_t len)
{
I2CM_XFER_T i2cData;
i2cData.slaveAddr = addr;
i2cData.options = 0;
i2cData.status = 0;
i2cData.txBuff = NULL;
i2cData.txSz = 0;
i2cData.rxBuff = buf;
i2cData.rxSz = len;
if (Chip_I2CM_XferBlocking(LPC_I2C0, &i2cData) == 0) {
return ERROR;
}
return SUCCESS;
}
static void setLsStates(uint16_t states, uint8_t* ls, uint8_t mode)
{
#define IS_LED_SET(bit, x) ( ( ((x) & (bit)) != 0 ) ? 1 : 0 )
int i = 0;
for (i = 0; i < 4; i++) {
ls[i] |= ( (IS_LED_SET(0x0001, states)*mode << 0)
| (IS_LED_SET(0x0002, states)*mode << 2)
| (IS_LED_SET(0x0004, states)*mode << 4)
| (IS_LED_SET(0x0008, states)*mode << 6) );
states >>= 4;
}
}
static void setLeds(void)
{
uint8_t buf[5];
uint8_t ls[4] = {0,0,0,0};
uint16_t states = ledStateShadow;
/* LEDs in On/Off state */
setLsStates(states, ls, LS_MODE_ON);
/* set the LEDs that should blink */
setLsStates(blink0Shadow, ls, LS_MODE_BLINK0);
setLsStates(blink1Shadow, ls, LS_MODE_BLINK1);
buf[0] = PCA9532_LS0 | PCA9532_AUTO_INC;
buf[1] = ls[0];
buf[2] = ls[1];
buf[3] = ls[2];
buf[4] = ls[3];
I2CWrite(PCA9532_I2C_ADDR, buf, 5);
}
/******************************************************************************
* Public Functions
*****************************************************************************/
/******************************************************************************
*
* Description:
* Initialize the PCA9532 Device
*
*****************************************************************************/
void pca9532_init (void)
{
/* nothing to initialize */
}
/******************************************************************************
*
* Description:
* Get the LED states
*
* Params:
* [in] shadow - TRUE if the states should be retrieved from the shadow
* variables. The shadow variable are updated when any
* of setLeds, setBlink0Leds and/or setBlink1Leds are
* called.
*
* FALSE if the state should be retrieved from the PCA9532
* device. A blinkin LED may be reported as on or off
* depending on the state when calling the function.
*
* Returns:
* A mask where a 1 indicates that a LED is on (or blinking).
*
*****************************************************************************/
uint16_t pca9532_getLedState (uint32_t shadow)
{
uint8_t buf[2];
uint16_t ret = 0;
if (shadow) {
/* a blink LED is reported as on*/
ret = (ledStateShadow | blink0Shadow | blink1Shadow);
}
else {
/*
* A blinking LED may be reported as on or off depending on
* its state when reading the Input register.
*/
buf[0] = PCA9532_INPUT0;
I2CWrite(PCA9532_I2C_ADDR, buf, 1);
I2CRead(PCA9532_I2C_ADDR, buf, 1);
ret = buf[0];
buf[0] = PCA9532_INPUT1;
I2CWrite(PCA9532_I2C_ADDR, buf, 1);
I2CRead(PCA9532_I2C_ADDR, buf, 1);
ret |= (buf[0] << 8);
/* invert since LEDs are active low */
ret = ((~ret) & 0xFFFF);
}
return (ret & ~PCA9532_NOT_USED);
}
/******************************************************************************
*
* Description:
* Set LED states (on or off).
*
* Params:
* [in] ledOnMask - The LEDs that should be turned on. This mask has
* priority over ledOffMask
* [in] ledOffMask - The LEDs that should be turned off.
*
*****************************************************************************/
void pca9532_setLeds (uint16_t ledOnMask, uint16_t ledOffMask)
{
/* turn off leds */
ledStateShadow &= (~(ledOffMask) & 0xffff);
/* ledOnMask has priority over ledOffMask */
ledStateShadow |= ledOnMask;
/* turn off blinking */
blink0Shadow &= (~(ledOffMask) & 0xffff);
blink1Shadow &= (~(ledOffMask) & 0xffff);
setLeds();
}
/******************************************************************************
*
* Description:
* Set the blink period for PWM0. Valid values are 0 - 255 where 0
* means 152 Hz and 255 means 0.59 Hz. A value of 151 means 1 Hz.
*
* Params:
* [in] period - the period for pwm0
*
*****************************************************************************/
void pca9532_setBlink0Period(uint8_t period)
{
uint8_t buf[2];
buf[0] = PCA9532_PSC0;
buf[1] = period;
I2CWrite(PCA9532_I2C_ADDR, buf, 2);
}
/******************************************************************************
*
* Description:
* Set the duty cycle for PWM0. Valid values are 0 - 100. 25 means the LED
* is on 25% of the period.
*
* Params:
* [in] duty - duty cycle
*
*****************************************************************************/
void pca9532_setBlink0Duty(uint8_t duty)
{
uint8_t buf[2];
uint32_t tmp = duty;
if (tmp > 100) {
tmp = 100;
}
tmp = (256 * tmp)/100;
buf[0] = PCA9532_PWM0;
buf[1] = tmp;
I2CWrite(PCA9532_I2C_ADDR, buf, 2);
}
/******************************************************************************
*
* Description:
* Set the LEDs that should blink with rate and duty cycle from PWM0.
* Blinking is turned off with pca9532_setLeds.
*
* Params:
* [in] ledMask - LEDs that should blink.
*
*****************************************************************************/
void pca9532_setBlink0Leds(uint16_t ledMask)
{
blink0Shadow |= ledMask;
setLeds();
}
/******************************************************************************
*
* Description:
* Set the blink period for PWM1. Valid values are 0 - 255 where 0
* means 152 Hz and 255 means 0.59 Hz. A value of 151 means 1 Hz.
*
* Params:
* [in] period - The period for PWM1
*
*****************************************************************************/
void pca9532_setBlink1Period(uint8_t period)
{
uint8_t buf[2];
buf[0] = PCA9532_PSC1;
buf[1] = period;
I2CWrite(PCA9532_I2C_ADDR, buf, 2);
}
/******************************************************************************
*
* Description:
* Set the duty cycle for PWM1. Valid values are 0 - 100. 25 means the LED
* is on 25% of the period.
*
* Params:
* [in] duty - duty cycle.
*
*****************************************************************************/
void pca9532_setBlink1Duty(uint8_t duty)
{
uint8_t buf[2];
uint32_t tmp = duty;
if (tmp > 100) {
tmp = 100;
}
tmp = (256 * tmp)/100;
buf[0] = PCA9532_PWM1;
buf[1] = tmp;
I2CWrite(PCA9532_I2C_ADDR, buf, 2);
}
/******************************************************************************
*
* Description:
* Set the LEDs that should blink with rate and duty cycle from PWM1.
* Blinking is turned off with pca9532_setLeds.
*
* Params:
* [in] ledMask - LEDs that should blink.
*
*****************************************************************************/
void pca9532_setBlink1Leds(uint16_t ledMask)
{
blink1Shadow |= ledMask;
setLeds();
}

View file

@ -0,0 +1,94 @@
/*****************************************************************************
*
* Copyright(C) 2011, Embedded Artists AB
* All rights reserved.
*
******************************************************************************
* Software that is described herein is for illustrative purposes only
* which provides customers with programming information regarding the
* products. This software is supplied "AS IS" without any warranties.
* Embedded Artists AB assumes no responsibility or liability for the
* use of the software, conveys no license or title under any patent,
* copyright, or mask work right to the product. Embedded Artists AB
* reserves the right to make changes in the software without
* notification. Embedded Artists AB also make no representation or
* warranty that such application will be suitable for the specified
* use without further testing or modification.
*****************************************************************************/
#ifndef __PCA9532C_H
#define __PCA9532C_H
#define PCA9532_I2C_ADDR (0xC0>>1)
#define PCA9532_INPUT0 0x00
#define PCA9532_INPUT1 0x01
#define PCA9532_PSC0 0x02
#define PCA9532_PWM0 0x03
#define PCA9532_PSC1 0x04
#define PCA9532_PWM1 0x05
#define PCA9532_LS0 0x06
#define PCA9532_LS1 0x07
#define PCA9532_LS2 0x08
#define PCA9532_LS3 0x09
#define PCA9532_AUTO_INC 0x10
/*
* The Keys on the base board are mapped to LED0 -> LED3 on
* the PCA9532.
*/
#define KEY1 0x0001
#define KEY2 0x0002
#define KEY3 0x0004
#define KEY4 0x0008
#define KEY_MASK 0x000F
/*
* MMC Card Detect and MMC Write Protect are mapped to LED4
* and LED5 on the PCA9532. Please note that WP is active low.
*/
#define MMC_CD 0x0010
#define MMC_WP 0x0020
#define MMC_MASK 0x30
/* NOTE: LED6 and LED7 on PCA9532 are not connected to anything */
#define PCA9532_NOT_USED 0xC0
/*
* Below are the LED constants to use when enabling/disabling a LED.
* The LED names are the names printed on the base board and not
* the names from the PCA9532 device. base_LED1 -> LED8 on PCA9532,
* base_LED2 -> LED9, and so on.
*/
#define LED1 0x0100
#define LED2 0x0200
#define LED3 0x0400
#define LED4 0x0800
#define LED5 0x1000
#define LED6 0x2000
#define LED7 0x4000
#define LED8 0x8000
#define LED_MASK 0xFF00
void pca9532_init (void);
uint16_t pca9532_getLedState (uint32_t shadow);
void pca9532_setLeds (uint16_t ledOnMask, uint16_t ledOffMask);
void pca9532_setBlink0Period(uint8_t period);
void pca9532_setBlink0Duty(uint8_t duty);
void pca9532_setBlink0Leds(uint16_t ledMask);
void pca9532_setBlink1Period(uint8_t period);
void pca9532_setBlink1Duty(uint8_t duty);
void pca9532_setBlink1Leds(uint16_t ledMask);
#endif /* end __PCA9532C_H */
/****************************************************************************
** End Of File
*****************************************************************************/

View file

@ -0,0 +1,11 @@
set(MCU_VARIANT LPC43S67_M4)
set(JLINK_DEVICE LPC43S67_M4)
set(PYOCD_TARGET LPC43S67)
set(NXPLINK_DEVICE LPC43S67:LPCXPRESSO43S67)
set(LD_FILE_GNU ${CMAKE_CURRENT_LIST_DIR}/lpc4367.ld)
function(update_board TARGET)
# nothing to do
endfunction()

View file

@ -0,0 +1,73 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2021, 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_LPCXPRESSO43S67_H_
#define _BOARD_LPCXPRESSO43S67_H_
// Note: For USB Host demo, install JP4
// WARNING: don't install JP4 when running as device
#ifdef __cplusplus
extern "C" {
#endif
// LED Red
#define LED_PORT 3
#define LED_PIN 7
#define LED_STATE_ON 0
// ISP Button (SW2)
#define BUTTON_PORT 0
#define BUTTON_PIN 7
#define BUTTON_STATE_ACTIVE 0
#define UART_DEV LPC_USART0
static const PINMUX_GRP_T pinmuxing[] = {
// LEDs P6_11 as GPIO3[7]
{ 0x6, 11, SCU_MODE_INBUFF_EN | SCU_MODE_PULLUP | SCU_MODE_FUNC0 },
// Button P2_7 as GPIO0[7]
{ 0x2, 7, SCU_MODE_PULLUP | SCU_MODE_INBUFF_EN | SCU_MODE_ZIF_DIS | SCU_MODE_FUNC0 },
// UART
{ 0x06, 4, SCU_MODE_PULLDOWN | SCU_MODE_FUNC2 },
{ 0x02, 1, SCU_MODE_INACT | SCU_MODE_INBUFF_EN | SCU_MODE_ZIF_DIS | SCU_MODE_FUNC1 },
// USB0
//{ 0x6, 3, SCU_MODE_PULLUP | SCU_MODE_INBUFF_EN | SCU_MODE_FUNC1 }, // P6_3 USB0_PWR_EN, USB0 VBus function
// USB 1
//{ 0x9, 5, SCU_MODE_PULLUP | SCU_MODE_INBUFF_EN | SCU_MODE_FUNC2 }, // P9_5 USB1_VBUS_EN, USB1 VBus function
//{ 0x2, 5, SCU_MODE_INACT | SCU_MODE_INBUFF_EN | SCU_MODE_ZIF_DIS | SCU_MODE_FUNC2 }, // P2_5 USB1_VBUS, MUST CONFIGURE THIS SIGNAL FOR USB1 NORMAL OPERATION
{0x2, 5, SCU_MODE_INBUFF_EN | SCU_MODE_PULLUP | SCU_MODE_FUNC4 },
};
#ifdef __cplusplus
}
#endif
#endif

View file

@ -0,0 +1,6 @@
LD_FILE = $(BOARD_PATH)/lpc4367.ld
# For flash-jlink target
JLINK_DEVICE = LPC43S67_M4
flash: flash-jlink

View file

@ -0,0 +1,419 @@
/*
* GENERATED FILE - DO NOT EDIT
* Copyright (c) 2008-2013 Code Red Technologies Ltd,
* Copyright 2015, 2018-2019 NXP
* (c) NXP Semiconductors 2013-2023
* Generated linker script file for LPC4337
* Created from linkscript.ldt by FMCreateLinkLibraries
* Using Freemarker v2.3.30
* MCUXpresso IDE v11.7.1 [Build 9221] [2023-03-28] on Aug 14, 2023, 3:36:29 PM
*/
MEMORY
{
/* Define each memory region */
MFlashA512 (rx) : ORIGIN = 0x1a000000, LENGTH = 0x80000 /* 512K bytes (alias Flash) */
MFlashB512 (rx) : ORIGIN = 0x1b000000, LENGTH = 0x80000 /* 512K bytes (alias Flash2) */
RamLoc32 (rwx) : ORIGIN = 0x10000000, LENGTH = 0x8000 /* 32K bytes (alias RAM) */
RamLoc40 (rwx) : ORIGIN = 0x10080000, LENGTH = 0xa000 /* 40K bytes (alias RAM2) */
RamAHB32 (rwx) : ORIGIN = 0x20000000, LENGTH = 0x8000 /* 32K bytes (alias RAM3) */
RamAHB16 (rwx) : ORIGIN = 0x20008000, LENGTH = 0x4000 /* 16K bytes (alias RAM4) */
RamAHB_ETB16 (rwx) : ORIGIN = 0x2000c000, LENGTH = 0x4000 /* 16K bytes (alias RAM5) */
}
/* Define a symbol for the top of each memory region */
__base_MFlashA512 = 0x1a000000 ; /* MFlashA512 */
__base_Flash = 0x1a000000 ; /* Flash */
__top_MFlashA512 = 0x1a000000 + 0x80000 ; /* 512K bytes */
__top_Flash = 0x1a000000 + 0x80000 ; /* 512K bytes */
__base_MFlashB512 = 0x1b000000 ; /* MFlashB512 */
__base_Flash2 = 0x1b000000 ; /* Flash2 */
__top_MFlashB512 = 0x1b000000 + 0x80000 ; /* 512K bytes */
__top_Flash2 = 0x1b000000 + 0x80000 ; /* 512K bytes */
__base_RamLoc32 = 0x10000000 ; /* RamLoc32 */
__base_RAM = 0x10000000 ; /* RAM */
__top_RamLoc32 = 0x10000000 + 0x8000 ; /* 32K bytes */
__top_RAM = 0x10000000 + 0x8000 ; /* 32K bytes */
__base_RamLoc40 = 0x10080000 ; /* RamLoc40 */
__base_RAM2 = 0x10080000 ; /* RAM2 */
__top_RamLoc40 = 0x10080000 + 0xa000 ; /* 40K bytes */
__top_RAM2 = 0x10080000 + 0xa000 ; /* 40K bytes */
__base_RamAHB32 = 0x20000000 ; /* RamAHB32 */
__base_RAM3 = 0x20000000 ; /* RAM3 */
__top_RamAHB32 = 0x20000000 + 0x8000 ; /* 32K bytes */
__top_RAM3 = 0x20000000 + 0x8000 ; /* 32K bytes */
__base_RamAHB16 = 0x20008000 ; /* RamAHB16 */
__base_RAM4 = 0x20008000 ; /* RAM4 */
__top_RamAHB16 = 0x20008000 + 0x4000 ; /* 16K bytes */
__top_RAM4 = 0x20008000 + 0x4000 ; /* 16K bytes */
__base_RamAHB_ETB16 = 0x2000c000 ; /* RamAHB_ETB16 */
__base_RAM5 = 0x2000c000 ; /* RAM5 */
__top_RamAHB_ETB16 = 0x2000c000 + 0x4000 ; /* 16K bytes */
__top_RAM5 = 0x2000c000 + 0x4000 ; /* 16K bytes */
ENTRY(ResetISR)
SECTIONS
{
.text_Flash2 : ALIGN(4)
{
FILL(0xff)
*(.text_Flash2) /* for compatibility with previous releases */
*(.text_MFlashB512) /* for compatibility with previous releases */
*(.text.$Flash2)
*(.text.$MFlashB512)
*(.text_Flash2.*) /* for compatibility with previous releases */
*(.text_MFlashB512.*) /* for compatibility with previous releases */
*(.text.$Flash2.*)
*(.text.$MFlashB512.*)
*(.rodata.$Flash2)
*(.rodata.$MFlashB512)
*(.rodata.$Flash2.*)
*(.rodata.$MFlashB512.*) } > MFlashB512
/* MAIN TEXT SECTION */
.text : ALIGN(4)
{
FILL(0xff)
__vectors_start__ = ABSOLUTE(.) ;
KEEP(*(.isr_vector))
/* Global Section Table */
. = ALIGN(4) ;
__section_table_start = .;
__data_section_table = .;
LONG(LOADADDR(.data));
LONG( ADDR(.data));
LONG( SIZEOF(.data));
LONG(LOADADDR(.data_RAM2));
LONG( ADDR(.data_RAM2));
LONG( SIZEOF(.data_RAM2));
LONG(LOADADDR(.data_RAM3));
LONG( ADDR(.data_RAM3));
LONG( SIZEOF(.data_RAM3));
LONG(LOADADDR(.data_RAM4));
LONG( ADDR(.data_RAM4));
LONG( SIZEOF(.data_RAM4));
LONG(LOADADDR(.data_RAM5));
LONG( ADDR(.data_RAM5));
LONG( SIZEOF(.data_RAM5));
__data_section_table_end = .;
__bss_section_table = .;
LONG( ADDR(.bss));
LONG( SIZEOF(.bss));
LONG( ADDR(.bss_RAM2));
LONG( SIZEOF(.bss_RAM2));
LONG( ADDR(.bss_RAM3));
LONG( SIZEOF(.bss_RAM3));
LONG( ADDR(.bss_RAM4));
LONG( SIZEOF(.bss_RAM4));
LONG( ADDR(.bss_RAM5));
LONG( SIZEOF(.bss_RAM5));
__bss_section_table_end = .;
__section_table_end = . ;
/* End of Global Section Table */
*(.after_vectors*)
*(.text*)
*(.rodata .rodata.* .constdata .constdata.*)
. = ALIGN(4);
} > MFlashA512
/*
* for exception handling/unwind - some Newlib functions (in common
* with C++ and STDC++) use this.
*/
.ARM.extab : ALIGN(4)
{
*(.ARM.extab* .gnu.linkonce.armextab.*)
} > MFlashA512
.ARM.exidx : ALIGN(4)
{
__exidx_start = .;
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
__exidx_end = .;
} > MFlashA512
_etext = .;
/* DATA section for RamLoc40 */
.data_RAM2 : ALIGN(4)
{
FILL(0xff)
PROVIDE(__start_data_RAM2 = .) ;
PROVIDE(__start_data_RamLoc40 = .) ;
*(.ramfunc.$RAM2)
*(.ramfunc.$RamLoc40)
*(.data.$RAM2)
*(.data.$RamLoc40)
*(.data.$RAM2.*)
*(.data.$RamLoc40.*)
. = ALIGN(4) ;
PROVIDE(__end_data_RAM2 = .) ;
PROVIDE(__end_data_RamLoc40 = .) ;
} > RamLoc40 AT>MFlashA512
/* DATA section for RamAHB32 */
.data_RAM3 : ALIGN(4)
{
FILL(0xff)
PROVIDE(__start_data_RAM3 = .) ;
PROVIDE(__start_data_RamAHB32 = .) ;
*(.ramfunc.$RAM3)
*(.ramfunc.$RamAHB32)
*(.data.$RAM3)
*(.data.$RamAHB32)
*(.data.$RAM3.*)
*(.data.$RamAHB32.*)
. = ALIGN(4) ;
PROVIDE(__end_data_RAM3 = .) ;
PROVIDE(__end_data_RamAHB32 = .) ;
} > RamAHB32 AT>MFlashA512
/* DATA section for RamAHB16 */
.data_RAM4 : ALIGN(4)
{
FILL(0xff)
PROVIDE(__start_data_RAM4 = .) ;
PROVIDE(__start_data_RamAHB16 = .) ;
*(.ramfunc.$RAM4)
*(.ramfunc.$RamAHB16)
*(.data.$RAM4)
*(.data.$RamAHB16)
*(.data.$RAM4.*)
*(.data.$RamAHB16.*)
. = ALIGN(4) ;
PROVIDE(__end_data_RAM4 = .) ;
PROVIDE(__end_data_RamAHB16 = .) ;
} > RamAHB16 AT>MFlashA512
/* DATA section for RamAHB_ETB16 */
.data_RAM5 : ALIGN(4)
{
FILL(0xff)
PROVIDE(__start_data_RAM5 = .) ;
PROVIDE(__start_data_RamAHB_ETB16 = .) ;
*(.ramfunc.$RAM5)
*(.ramfunc.$RamAHB_ETB16)
*(.data.$RAM5)
*(.data.$RamAHB_ETB16)
*(.data.$RAM5.*)
*(.data.$RamAHB_ETB16.*)
. = ALIGN(4) ;
PROVIDE(__end_data_RAM5 = .) ;
PROVIDE(__end_data_RamAHB_ETB16 = .) ;
} > RamAHB_ETB16 AT>MFlashA512
/* MAIN DATA SECTION */
.uninit_RESERVED (NOLOAD) : ALIGN(4)
{
_start_uninit_RESERVED = .;
KEEP(*(.bss.$RESERVED*))
. = ALIGN(4) ;
_end_uninit_RESERVED = .;
} > RamLoc32 AT> RamLoc32
/* Main DATA section (RamLoc32) */
.data : ALIGN(4)
{
FILL(0xff)
_data = . ;
PROVIDE(__start_data_RAM = .) ;
PROVIDE(__start_data_RamLoc32 = .) ;
*(vtable)
*(.ramfunc*)
KEEP(*(CodeQuickAccess))
KEEP(*(DataQuickAccess))
*(RamFunction)
*(.data*)
. = ALIGN(4) ;
_edata = . ;
PROVIDE(__end_data_RAM = .) ;
PROVIDE(__end_data_RamLoc32 = .) ;
} > RamLoc32 AT>MFlashA512
/* BSS section for RamLoc40 */
.bss_RAM2 : ALIGN(4)
{
PROVIDE(__start_bss_RAM2 = .) ;
PROVIDE(__start_bss_RamLoc40 = .) ;
*(.bss.$RAM2)
*(.bss.$RamLoc40)
*(.bss.$RAM2.*)
*(.bss.$RamLoc40.*)
. = ALIGN (. != 0 ? 4 : 1) ; /* avoid empty segment */
PROVIDE(__end_bss_RAM2 = .) ;
PROVIDE(__end_bss_RamLoc40 = .) ;
} > RamLoc40 AT> RamLoc40
/* BSS section for RamAHB32 */
.bss_RAM3 : ALIGN(4)
{
PROVIDE(__start_bss_RAM3 = .) ;
PROVIDE(__start_bss_RamAHB32 = .) ;
*(.bss.$RAM3)
*(.bss.$RamAHB32)
*(.bss.$RAM3.*)
*(.bss.$RamAHB32.*)
. = ALIGN (. != 0 ? 4 : 1) ; /* avoid empty segment */
PROVIDE(__end_bss_RAM3 = .) ;
PROVIDE(__end_bss_RamAHB32 = .) ;
} > RamAHB32 AT> RamAHB32
/* BSS section for RamAHB16 */
.bss_RAM4 : ALIGN(4)
{
PROVIDE(__start_bss_RAM4 = .) ;
PROVIDE(__start_bss_RamAHB16 = .) ;
*(.bss.$RAM4)
*(.bss.$RamAHB16)
*(.bss.$RAM4.*)
*(.bss.$RamAHB16.*)
. = ALIGN (. != 0 ? 4 : 1) ; /* avoid empty segment */
PROVIDE(__end_bss_RAM4 = .) ;
PROVIDE(__end_bss_RamAHB16 = .) ;
} > RamAHB16 AT> RamAHB16
/* BSS section for RamAHB_ETB16 */
.bss_RAM5 : ALIGN(4)
{
PROVIDE(__start_bss_RAM5 = .) ;
PROVIDE(__start_bss_RamAHB_ETB16 = .) ;
*(.bss.$RAM5)
*(.bss.$RamAHB_ETB16)
*(.bss.$RAM5.*)
*(.bss.$RamAHB_ETB16.*)
. = ALIGN (. != 0 ? 4 : 1) ; /* avoid empty segment */
PROVIDE(__end_bss_RAM5 = .) ;
PROVIDE(__end_bss_RamAHB_ETB16 = .) ;
} > RamAHB_ETB16 AT> RamAHB_ETB16
/* MAIN BSS SECTION: EDIT change to RamLoc40 */
.bss : ALIGN(4)
{
_bss = .;
PROVIDE(__start_bss_RAM = .) ;
PROVIDE(__start_bss_RamLoc32 = .) ;
*(.bss*)
*(COMMON)
. = ALIGN(4) ;
_ebss = .;
PROVIDE(__end_bss_RAM = .) ;
PROVIDE(__end_bss_RamLoc32 = .) ;
/* PROVIDE(end = .);*/
} > RamLoc40 AT> RamLoc40 /* > RamLoc32 AT> RamLoc32 */
/* hathach add heap section for clang */
.heap (NOLOAD): {
__heap_start = .;
__HeapBase = .;
__heap_base = .;
__end = .;
PROVIDE(end = .);
PROVIDE(_end = .);
PROVIDE(__end__ = .);
KEEP(*(.heap*))
__HeapLimit = .;
__heap_limit = .;
__heap_end = .;
} > RamLoc40
/* NOINIT section for RamLoc40 */
.noinit_RAM2 (NOLOAD) : ALIGN(4)
{
PROVIDE(__start_noinit_RAM2 = .) ;
PROVIDE(__start_noinit_RamLoc40 = .) ;
*(.noinit.$RAM2)
*(.noinit.$RamLoc40)
*(.noinit.$RAM2.*)
*(.noinit.$RamLoc40.*)
. = ALIGN(4) ;
PROVIDE(__end_noinit_RAM2 = .) ;
PROVIDE(__end_noinit_RamLoc40 = .) ;
} > RamLoc40 AT> RamLoc40
/* NOINIT section for RamAHB32 */
.noinit_RAM3 (NOLOAD) : ALIGN(4)
{
PROVIDE(__start_noinit_RAM3 = .) ;
PROVIDE(__start_noinit_RamAHB32 = .) ;
*(.noinit.$RAM3)
*(.noinit.$RamAHB32)
*(.noinit.$RAM3.*)
*(.noinit.$RamAHB32.*)
. = ALIGN(4) ;
PROVIDE(__end_noinit_RAM3 = .) ;
PROVIDE(__end_noinit_RamAHB32 = .) ;
} > RamAHB32 AT> RamAHB32
/* NOINIT section for RamAHB16 */
.noinit_RAM4 (NOLOAD) : ALIGN(4)
{
PROVIDE(__start_noinit_RAM4 = .) ;
PROVIDE(__start_noinit_RamAHB16 = .) ;
*(.noinit.$RAM4)
*(.noinit.$RamAHB16)
*(.noinit.$RAM4.*)
*(.noinit.$RamAHB16.*)
. = ALIGN(4) ;
PROVIDE(__end_noinit_RAM4 = .) ;
PROVIDE(__end_noinit_RamAHB16 = .) ;
} > RamAHB16 AT> RamAHB16
/* NOINIT section for RamAHB_ETB16 */
.noinit_RAM5 (NOLOAD) : ALIGN(4)
{
PROVIDE(__start_noinit_RAM5 = .) ;
PROVIDE(__start_noinit_RamAHB_ETB16 = .) ;
*(.noinit.$RAM5)
*(.noinit.$RamAHB_ETB16)
*(.noinit.$RAM5.*)
*(.noinit.$RamAHB_ETB16.*)
. = ALIGN(4) ;
PROVIDE(__end_noinit_RAM5 = .) ;
PROVIDE(__end_noinit_RamAHB_ETB16 = .) ;
} > RamAHB_ETB16 AT> RamAHB_ETB16
/* DEFAULT NOINIT SECTION */
.noinit (NOLOAD): ALIGN(4)
{
_noinit = .;
PROVIDE(__start_noinit_RAM = .) ;
PROVIDE(__start_noinit_RamLoc32 = .) ;
*(.noinit*)
. = ALIGN(4) ;
_end_noinit = .;
PROVIDE(__end_noinit_RAM = .) ;
PROVIDE(__end_noinit_RamLoc32 = .) ;
} > RamLoc32 AT> RamLoc32
/* PROVIDE(_pvHeapStart = DEFINED(__user_heap_base) ? __user_heap_base : .);*/
PROVIDE(_vStackTop = DEFINED(__user_stack_top) ? __user_stack_top : __top_RamLoc32 - 0);
/* ## Create checksum value (used in startup) ## */
/* This cause issue with clang linker, so it is disabled */
/* MemManage_Handler, BusFault_Handler, UsageFault_Hander may not be defined */
/* PROVIDE(__valid_user_code_checksum = 0 -*/
/* (_vStackTop*/
/* + (ResetISR + 1)*/
/* + (NMI_Handler + 1)*/
/* + (HardFault_Handler + 1)*/
/* + (( DEFINED(MemManage_Handler) ? MemManage_Handler : 0 ) + 1)*/
/* + (( DEFINED(BusFault_Handler) ? BusFault_Handler : 0 ) + 1)*/
/* + (( DEFINED(UsageFault_Handler) ? UsageFault_Handler : 0 ) + 1)*/
/* ) );*/
/* Provide basic symbols giving location and size of main text
* block, including initial values of RW data sections. Note that
* these will need extending to give a complete picture with
* complex images (e.g multiple Flash banks).
*/
_image_start = LOADADDR(.text);
_image_end = LOADADDR(.data) + SIZEOF(.data);
_image_size = _image_end - _image_start;
}

View file

@ -0,0 +1,253 @@
/*
* 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.
*/
// Suppress warning caused by mcu driver
#ifdef __GNUC__
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-parameter"
#endif
#include "chip.h"
#ifdef __GNUC__
#pragma GCC diagnostic pop
#endif
#include "bsp/board_api.h"
#include "board.h"
/* System configuration variables used by chip driver */
const uint32_t OscRateIn = 12000000;
const uint32_t ExtRateIn = 0;
/*------------------------------------------------------------------*/
/* BOARD API
*------------------------------------------------------------------*/
// Invoked by startup code
void SystemInit(void)
{
#ifdef __USE_LPCOPEN
unsigned int *pSCB_VTOR = (unsigned int *) 0xE000ED08;
#ifdef __ICCARM__
extern void *__vector_table;
*pSCB_VTOR = (unsigned int) &__vector_table;
#elif defined(__ARMCC_VERSION)
extern void *__Vectors;
*pSCB_VTOR = (unsigned int) &__Vectors;
#else // other compoiler using cr_startup_lpc43xx.c
extern void (* const g_pfnVectors[])(void);
*pSCB_VTOR = (unsigned int) g_pfnVectors;
#endif
#if __FPU_USED == 1
fpuInit();
#endif
#endif
/* Setup system level pin muxing */
Chip_SCU_SetPinMuxing(pinmuxing, sizeof(pinmuxing) / sizeof(PINMUX_GRP_T));
// /* Clock pins only, group field not used */
// for ( int i = 0; i < (int) (sizeof(pinclockmuxing) / sizeof(pinclockmuxing[0])); i++ ) {
// Chip_SCU_ClockPinMuxSet(pinclockmuxing[i].pinnum, pinclockmuxing[i].modefunc);
// }
Chip_SetupXtalClocking();
}
void board_init(void)
{
SystemCoreClockUpdate();
#if CFG_TUSB_OS == OPT_OS_NONE
// 1ms tick timer
SysTick_Config(SystemCoreClock / 1000);
#elif CFG_TUSB_OS == OPT_OS_FREERTOS
// If freeRTOS is used, IRQ priority is limit by max syscall ( smaller is higher )
NVIC_SetPriority(USB0_IRQn, configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY);
#endif
Chip_GPIO_Init(LPC_GPIO_PORT);
#ifdef __PCA9532C_H
// LED via pca9532 I2C
Chip_SCU_I2C0PinConfig(I2C0_STANDARD_FAST_MODE);
Chip_I2C_Init(I2C0);
Chip_I2C_SetClockRate(I2C0, 100000);
Chip_I2C_SetMasterEventHandler(I2C0, Chip_I2C_EventHandlerPolling);
pca9532_init();
#else
Chip_GPIO_SetPinDIROutput(LPC_GPIO_PORT, LED_PORT, LED_PIN);
#endif
// Button
Chip_GPIO_SetPinDIRInput(LPC_GPIO_PORT, BUTTON_PORT, BUTTON_PIN);
//------------- UART -------------//
Chip_UART_Init(UART_DEV);
Chip_UART_SetBaud(UART_DEV, CFG_BOARD_UART_BAUDRATE);
Chip_UART_ConfigData(UART_DEV, UART_LCR_WLEN8 | UART_LCR_SBS_1BIT | UART_LCR_PARITY_DIS);
Chip_UART_TXEnable(UART_DEV);
//------------- USB -------------//
enum {
USBMODE_DEVICE = 2,
USBMODE_HOST = 3
};
enum {
USBMODE_VBUS_LOW = 0,
USBMODE_VBUS_HIGH = 1
};
/* From EA4357 user manual
*
* USB0 Device operation:
* - Insert jumpers in position 1-2 in JP17/JP18/JP19.
* - GPIO28 controls USB connect functionality
* - LED32 lights when the USB Device is connected. SJ4 has pads 1-2 shorted by default.
* - LED33 is controlled by GPIO27 and signals USB-up state. GPIO54 is used for VBUS
* sensing.
*
* USB0 Host operation:
* - insert jumpers in position 2-3 in JP17/JP18/JP19.
* - USB Host power is controlled via distribution switch U20 (found in schematic page 11).
* - Signal GPIO26 is active low and enables +5V on VBUS2.
* - LED35 light whenever +5V is present on VBUS2.
* - GPIO55 is connected to status feedback from the distribution switch.
* - GPIO54 is used for VBUS sensing. 15Kohm pull-down resistors are always active
*
* Note:
* - Insert jumpers in position 2-3 in JP17/JP18/JP19
* - Insert jumpers in JP31 (OTG)
*/
Chip_USB0_Init();
/* From EA4357 user manual
*
* For USB1 Device:
* - a 1.5Kohm pull-up resistor is needed on the USB DP data signal. There are two methods to create this.
* JP15 is inserted and the pull-up resistor is always enabled. Alternatively, the pull-up resistor is activated
* inside the USB OTG chip (U31), and this has to be done via the I2C interface of GPIO52/GPIO53. In the latter case,
* JP15 shall not be inserted.
* - J19 is the connector to use when USB Device is used. Normally it should be a USB-B connector for
* creating a USB Device interface, but the mini-AB connector can also be used in this case. The status
* of VBUS can be read via U31.
* - JP16 shall not be inserted.
*
* For USB1 Host:
* - 15Kohm pull-down resistors are needed on the USB data signals. These are activated inside the USB OTG chip (U31),
* and this has to be done via the I2C interface of GPIO52/GPIO53.
* - J20 is the connector to use when USB Host is used. In order to provide +5V to the external USB
* device connected to this connector (J20), channel A of U20 must be enabled. It is enabled by default
* since SJ5 is normally connected between pin 1-2.
* - LED34 lights green when +5V is available on J20.
* - JP15 shall not be inserted. JP16 has no effect
*/
Chip_USB1_Init();
// USB0 Vbus Power: P2_3 on EA4357 channel B U20 GPIO26 active low (base board)
Chip_SCU_PinMuxSet(2, 3, SCU_MODE_PULLUP | SCU_MODE_INBUFF_EN | SCU_MODE_FUNC7);
#if defined(BOARD_TUD_RHPORT) && BOARD_TUD_RHPORT == 0
// P9_5 (GPIO5[18]) (GPIO28 on oem base) as USB connect, active low.
Chip_SCU_PinMuxSet(9, 5, SCU_MODE_PULLDOWN | SCU_MODE_FUNC4);
Chip_GPIO_SetPinDIROutput(LPC_GPIO_PORT, 5, 18);
#endif
// USB1 Power: EA4357 channel A U20 is enabled by SJ5 connected to pad 1-2, no more action required
// TODO Remove R170, R171, solder a pair of 15K to USB1 D+/D- to test with USB1 Host
}
//--------------------------------------------------------------------+
// USB Interrupt Handler
//--------------------------------------------------------------------+
void USB0_IRQHandler(void) {
tusb_int_handler(0, true);
}
void USB1_IRQHandler(void) {
tusb_int_handler(1, true);
}
//--------------------------------------------------------------------+
// Board porting API
//--------------------------------------------------------------------+
void board_led_write(bool state) {
#ifdef __PCA9532C_H
if ( state ) {
pca9532_setLeds(LED1, 0);
} else {
pca9532_setLeds(0, LED1);
}
#else
Chip_GPIO_SetPinState(LPC_GPIO_PORT, LED_PORT, LED_PIN, state ? LED_STATE_ON : !LED_STATE_ON);
#endif
}
uint32_t board_button_read(void) {
return BUTTON_STATE_ACTIVE == Chip_GPIO_GetPinState(LPC_GPIO_PORT, BUTTON_PORT, BUTTON_PIN);
}
size_t board_get_unique_id(uint8_t id[], size_t max_len) {
if ( max_len < 16 ) return 0;
uint32_t* id32 = (uint32_t*) (uintptr_t) id;
Chip_IAP_ReadUID(id32);
return 16;
}
int board_uart_read(uint8_t *buf, int len) {
return Chip_UART_Read(UART_DEV, buf, len);
}
int board_uart_write(void const *buf, int len) {
uint8_t const *buf8 = (uint8_t const *) buf;
for ( int i = 0; i < len; i++ ) {
while ( (Chip_UART_ReadLineStatus(UART_DEV) & UART_LSR_THRE) == 0 ) {}
Chip_UART_SendByte(UART_DEV, buf8[i]);
}
return len;
}
#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

View file

@ -0,0 +1,109 @@
include_guard()
set(SDK_DIR ${TOP}/hw/mcu/nxp/lpcopen/lpc43xx/lpc_chip_43xx)
set(CMSIS_5 ${TOP}/lib/CMSIS_5)
# include board specific
include(${CMAKE_CURRENT_LIST_DIR}/boards/${BOARD}/board.cmake)
# toolchain set up
set(CMAKE_SYSTEM_PROCESSOR cortex-m4 CACHE INTERNAL "System Processor")
set(CMAKE_TOOLCHAIN_FILE ${TOP}/examples/build_system/cmake/toolchain/arm_${TOOLCHAIN}.cmake)
set(FAMILY_MCUS LPC43XX 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 ()
# Startup & Linker script
set(STARTUP_FILE_GNU ${SDK_DIR}/../gcc/cr_startup_lpc43xx.c)
set(STARTUP_FILE_Clang ${STARTUP_FILE_GNU})
set(STARTUP_FILE_IAR ${SDK_DIR}/../iar/iar_startup_lpc18xx43xx.s)
set(LD_FILE_IAR ${SDK_DIR}/../iar/linker/lpc18xx_43xx_ldscript_iflash.icf)
add_library(${BOARD_TARGET} STATIC
${STARTUP_FILE_${CMAKE_C_COMPILER_ID}}
${SDK_DIR}/src/chip_18xx_43xx.c
${SDK_DIR}/src/clock_18xx_43xx.c
${SDK_DIR}/src/fpu_init.c
${SDK_DIR}/src/gpio_18xx_43xx.c
${SDK_DIR}/src/iap_18xx_43xx.c
${SDK_DIR}/src/sysinit_18xx_43xx.c
${SDK_DIR}/src/uart_18xx_43xx.c
)
target_compile_definitions(${BOARD_TARGET} PUBLIC
__USE_LPCOPEN
CORE_M4
)
target_include_directories(${BOARD_TARGET} PUBLIC
${SDK_DIR}/inc
${SDK_DIR}/inc/config_43xx
${CMSIS_5}/CMSIS/Core/Include
)
update_board(${BOARD_TARGET})
if (CMAKE_C_COMPILER_ID STREQUAL "GNU")
target_compile_options(${BOARD_TARGET} PUBLIC -nostdlib)
target_link_options(${BOARD_TARGET} PUBLIC
"LINKER:--script=${LD_FILE_GNU}"
--specs=nosys.specs --specs=nano.specs
)
elseif (CMAKE_C_COMPILER_ID STREQUAL "Clang")
target_link_options(${BOARD_TARGET} PUBLIC
"LINKER:--script=${LD_FILE_GNU}"
)
elseif (CMAKE_C_COMPILER_ID STREQUAL "IAR")
target_link_options(${BOARD_TARGET} PUBLIC
"LINKER:--config=${LD_FILE_IAR}"
)
endif ()
endfunction()
#------------------------------------
# Functions
#------------------------------------
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_LPC43XX ${RTOS})
target_sources(${TARGET}-tinyusb PUBLIC
${TOP}/src/portable/chipidea/ci_hs/dcd_ci_hs.c
${TOP}/src/portable/chipidea/ci_hs/hcd_ci_hs.c
${TOP}/src/portable/ehci/ehci.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})
endfunction()

View file

@ -0,0 +1,40 @@
DEPS_SUBMODULES += hw/mcu/nxp/lpcopen
SDK_DIR = hw/mcu/nxp/lpcopen/lpc43xx/lpc_chip_43xx
include ${TOP}/${BOARD_PATH}/board.mk
CPU_CORE ?= cortex-m4
CFLAGS += \
-flto \
-nostdlib \
-DCORE_M4 \
-D__USE_LPCOPEN \
-DCFG_TUSB_MCU=OPT_MCU_LPC43XX
# mcu driver cause following warnings
CFLAGS += \
-Wno-error=unused-parameter \
-Wno-error=strict-prototypes \
-Wno-error=cast-qual \
-Wno-error=incompatible-pointer-types \
LDFLAGS_GCC += --specs=nosys.specs --specs=nano.specs
SRC_C += \
src/portable/chipidea/ci_hs/dcd_ci_hs.c \
src/portable/chipidea/ci_hs/hcd_ci_hs.c \
src/portable/ehci/ehci.c \
${SDK_DIR}/../gcc/cr_startup_lpc43xx.c \
${SDK_DIR}/src/chip_18xx_43xx.c \
${SDK_DIR}/src/clock_18xx_43xx.c \
${SDK_DIR}/src/fpu_init.c \
${SDK_DIR}/src/gpio_18xx_43xx.c \
${SDK_DIR}/src/iap_18xx_43xx.c \
${SDK_DIR}/src/sysinit_18xx_43xx.c \
${SDK_DIR}/src/uart_18xx_43xx.c \
INC += \
$(TOP)/$(BOARD_PATH) \
${TOP}/${SDK_DIR}/inc \
${TOP}/${SDK_DIR}/inc/config_43xx \
$(TOP)/lib/CMSIS_5/CMSIS/Core/Include \