diff --git a/arch/Makefile b/arch/Makefile
index d31f2e74..aca508ea 100644
--- a/arch/Makefile
+++ b/arch/Makefile
@@ -35,13 +35,14 @@ endif
include ${QTOP}/qmk/board-pack/bp.${BP}
-ifeq (,$(strip ${ARCH_LSCRS}))
+$(info ${ARCH_LSRCS})
+ifeq (,$(strip ${ARCH_LSRCS}))
$(error when compile arch/, must specify BP and ARCH_LSRCS obviously , see `make help`)
endif
endif
# arch src should be specify by bp
-LSRCS := $(subst $(QTOP)/$(LOCALDIR)/,, ${ARCH_LSCRS})
+LSRCS := $(subst $(QTOP)/arch/,, ${ARCH_LSRCS})
include ${QTOP}/qmk/generic/Make.tpl
diff --git a/board/TencentOS_tiny_EVB_MX_Plus/BSP/Hardware/QSPI_FLASH/hal_qspi_flash.c b/board/TencentOS_tiny_EVB_MX_Plus/BSP/Hardware/QSPI_FLASH/hal_qspi_flash.c
index d3f7a3a9..b8baa240 100644
--- a/board/TencentOS_tiny_EVB_MX_Plus/BSP/Hardware/QSPI_FLASH/hal_qspi_flash.c
+++ b/board/TencentOS_tiny_EVB_MX_Plus/BSP/Hardware/QSPI_FLASH/hal_qspi_flash.c
@@ -43,7 +43,7 @@
extern QSPI_HandleTypeDef hqspi;
/* This function is called by inner-HAL lib */
-static void HAL_QSPI_MspInit(QSPI_HandleTypeDef* qspiHandle)
+void HAL_QSPI_MspInit(QSPI_HandleTypeDef* qspiHandle)
{
GPIO_InitTypeDef GPIO_InitStruct;
@@ -75,7 +75,7 @@ static void HAL_QSPI_MspInit(QSPI_HandleTypeDef* qspiHandle)
}
/* This function is called by inner-HAL lib */
-static void HAL_QSPI_MspDeInit(QSPI_HandleTypeDef* qspiHandle)
+void HAL_QSPI_MspDeInit(QSPI_HandleTypeDef* qspiHandle)
{
if(qspiHandle->Instance==QUADSPI)
diff --git a/board/TencentOS_tiny_EVB_MX_Plus/BSP/Makefile b/board/TencentOS_tiny_EVB_MX_Plus/BSP/Makefile
new file mode 100644
index 00000000..3939796b
--- /dev/null
+++ b/board/TencentOS_tiny_EVB_MX_Plus/BSP/Makefile
@@ -0,0 +1,47 @@
+###################################################################
+#automatic detection QTOP and LOCALDIR
+CUR_DIR := $(patsubst %/,%,$(dir $(realpath $(firstword $(MAKEFILE_LIST)))))
+TRYQTOP := $(shell if [ -n "$$QTOP" ] ; then\
+ echo $$QTOP;\
+ else\
+ cd $(CUR_DIR); while /usr/bin/test ! -d qmk ; do \
+ dir=`cd ../;pwd`; \
+ if [ "$$dir" = "/" ] ; then \
+ echo Cannot find QTOP in $(firstword $(MAKEFILE_LIST)) 1>&2; \
+ exit 1; \
+ fi ; \
+ cd $$dir; \
+ done ; \
+ pwd; \
+ fi)
+QTOP ?= $(realpath ${TRYQTOP})
+
+ifeq ($(QTOP),)
+$(error Please run this in a tree)
+endif
+LOCALDIR = $(patsubst %/,%,$(subst $(realpath $(QTOP))/,,$(CUR_DIR)))
+
+####################################################################
+
+
+TREE_LIB_ENABLE=0
+lib=
+subdirs=
+ifneq (help,$(findstring help,$(MAKECMDGOALS)))
+
+ifeq (, $(strip ${BP}))
+$(error when compile arch/, must specify BP and BSP_LSRCS obviously , see `make help`)
+endif
+
+include ${QTOP}/qmk/board-pack/bp.${BP}
+
+ifeq (,$(strip ${BSP_LSRCS}))
+$(error when compile arch/, must specify BP and BSP_LSRCS obviously , see `make help`)
+endif
+endif
+
+# arch src should be specify by bp
+LSRCS := $(sort $(subst $(QTOP)/$(LOCALDIR)/,, ${BSP_LSRCS}))
+include ${QTOP}/qmk/generic/Make.tpl
+
+
diff --git a/board/TencentOS_tiny_EVB_MX_Plus/BSP/Src/stm32l4xx_it_evtdrv_module.c b/board/TencentOS_tiny_EVB_MX_Plus/BSP/Src/stm32l4xx_it_evtdrv_module.c
index 9ad57024..b6369783 100644
--- a/board/TencentOS_tiny_EVB_MX_Plus/BSP/Src/stm32l4xx_it_evtdrv_module.c
+++ b/board/TencentOS_tiny_EVB_MX_Plus/BSP/Src/stm32l4xx_it_evtdrv_module.c
@@ -16,6 +16,7 @@
*
******************************************************************************
*/
+#if TOS_CFG_EVENT_DRIVEN_EN > 0u
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
@@ -301,3 +302,5 @@ void HAL_UART_RxCpltCallback(UART_HandleTypeDef *huart)
}
/* USER CODE END 1 */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
+#endif
diff --git a/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/Makefile b/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/Makefile
new file mode 100644
index 00000000..04989722
--- /dev/null
+++ b/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/Makefile
@@ -0,0 +1,36 @@
+###################################################################
+#automatic detection QTOP and LOCALDIR
+CUR_DIR := $(patsubst %/,%,$(dir $(realpath $(firstword $(MAKEFILE_LIST)))))
+TRYQTOP := $(shell if [ -n "$$QTOP" ] ; then\
+ echo $$QTOP;\
+ else\
+ cd $(CUR_DIR); while /usr/bin/test ! -e qmk ; do \
+ dir=`cd ../;pwd`; \
+ if [ "$$dir" = "/" ] ; then \
+ echo Cannot find QTOP in $(firstword $(MAKEFILE_LIST)) 1>&2; \
+ exit 1; \
+ fi ; \
+ cd $$dir; \
+ done ; \
+ pwd; \
+ fi)
+QTOP ?= $(realpath ${TRYQTOP})
+
+ifeq ($(QTOP),)
+$(error Please run this in a tree)
+endif
+LOCALDIR = $(patsubst %/,%,$(subst $(realpath $(QTOP))/,,$(CUR_DIR)))
+####################################################################
+
+
+TREE_LIB_ENABLE=0
+lib=
+subdirs=
+
+export BP=TencentOS_tiny_EVB_MX_Plus
+
+include ${QTOP}/qmk/generic/Make.tpl
+
+
+include ${QTOP}/qmk/generic/Make.subdirs
+
diff --git a/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/app_farm_ai_demo/Makefile b/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/app_farm_ai_demo/Makefile
new file mode 100644
index 00000000..230b3d0b
--- /dev/null
+++ b/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/app_farm_ai_demo/Makefile
@@ -0,0 +1,64 @@
+###################################################################
+#automatic detection QTOP and LOCALDIR
+CUR_DIR := $(patsubst %/,%,$(dir $(realpath $(firstword $(MAKEFILE_LIST)))))
+TRYQTOP := $(shell if [ -n "$$QTOP" ] ; then\
+ echo $$QTOP;\
+ else\
+ cd $(CUR_DIR); while /usr/bin/test ! -e qmk ; do \
+ dir=`cd ../;pwd`; \
+ if [ "$$dir" = "/" ] ; then \
+ echo Cannot find QTOP in $(firstword $(MAKEFILE_LIST)) 1>&2; \
+ exit 1; \
+ fi ; \
+ cd $$dir; \
+ done ; \
+ pwd; \
+ fi)
+QTOP ?= $(realpath ${TRYQTOP})
+
+ifeq ($(QTOP),)
+$(error Please run this in a tree)
+endif
+LOCALDIR = $(patsubst %/,%,$(subst $(realpath $(QTOP))/,,$(CUR_DIR)))
+export QTOP
+
+####################################################################
+
+
+export BP=TencentOS_tiny_EVB_MX_Plus
+
+TREE_LIB_ENABLE=1
+lib=
+subdirs =
+
+LSRCS += $(QTOP)/examples/farm_ai_demo/farm_ai_demo.c
+LSRCS += $(wildcard *.s)
+
+all::
+ make -C ${QTOP}/arch BP=${BP}
+ make -C ${QTOP}/kernel BP=${BP}
+ make -C ${QTOP}/osal BP=${BP}
+ make -C ${QTOP}/platform BP=${BP}
+ make -C ${QTOP}/board/TencentOS_tiny_EVB_MX_Plus/BSP BP=${BP}
+ make -C ${QTOP}/components/utils BP=${BP}
+#exec =
+LD_A_FILES += $(LIBDIR)/libarch.a
+LD_A_FILES += $(LIBDIR)/libkernel.a
+#LD_A_FILES += $(LIBDIR)/lib$(notdir $(CUR_DIR)).a
+LD_A_FILES += $(LIBDIR)/libcmsis_os.a
+LD_A_FILES += $(LIBDIR)/libhal.a
+LD_A_FILES += $(LIBDIR)/libvendor_bsp.a
+LD_A_FILES += $(LIBDIR)/libJSON.a
+LD_A_FILES += $(LIBDIR)/libBSP.a
+LD_A_FILES += $(LIBDIR)/libEclipse-Paho-MQTT.a
+LD_A_FILES += $(LIBDIR)/libesp8266_tencent_firmware.a
+LD_A_FILES += $(LIBDIR)/libesp8266.a
+LD_A_FILES += $(LIBDIR)/libat.a
+LD_A_FILES += $(LIBDIR)/libtencent_firmware_module_wrapper.a
+LD_A_FILES += $(LIBDIR)/libsal_module_wrapper.a
+LD_A_FILES += $(LIBDIR)/libsocket_wrapper.a
+LD_A_LISTS += -lc -lm -lnosys
+LD_L_LISTS += -specs=nosys.specs -T$(CUR_DIR)/STM32L431RCTx_FLASH.ld -Wl,-Map=$(LIBDIR)/$(notdir $(CUR_DIR)).map,--cref -Wl,--gc-sections
+include ${QTOP}/qmk/generic/Make.exec
+
+
diff --git a/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/app_farm_ai_demo/STM32L431RCTx_FLASH.ld b/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/app_farm_ai_demo/STM32L431RCTx_FLASH.ld
new file mode 100644
index 00000000..3d07935e
--- /dev/null
+++ b/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/app_farm_ai_demo/STM32L431RCTx_FLASH.ld
@@ -0,0 +1,203 @@
+/*
+******************************************************************************
+**
+
+** File : LinkerScript.ld
+**
+** Author : Auto-generated by Ac6 System Workbench
+**
+** Abstract : Linker script for STM32L431RCTx series
+** 256Kbytes FLASH and 64Kbytes RAM
+**
+** Set heap size, stack size and stack location according
+** to application requirements.
+**
+** Set memory bank area and size if external memory is used.
+**
+** Target : STMicroelectronics STM32
+**
+** Distribution: The file is distributed “as is,” without any warranty
+** of any kind.
+**
+*****************************************************************************
+** @attention
+**
+**
© COPYRIGHT(c) 2014 Ac6
+**
+** 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 Ac6 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.
+**
+*****************************************************************************
+*/
+
+/* Entry Point */
+ENTRY(Reset_Handler)
+
+/* Highest address of the user mode stack */
+_estack = 0x20010000; /* end of RAM */
+/* Generate a link error if heap and stack don't fit into RAM */
+_Min_Heap_Size = 0x200; /* required amount of heap */
+_Min_Stack_Size = 0x400; /* required amount of stack */
+
+/* Specify the memory areas */
+MEMORY
+{
+RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 64K
+FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 256K
+}
+
+/* Define output sections */
+SECTIONS
+{
+ /* The startup code goes first into FLASH */
+ .isr_vector :
+ {
+ . = ALIGN(8);
+ KEEP(*(.isr_vector)) /* Startup code */
+ . = ALIGN(8);
+ } >FLASH
+
+ /* The program code and other data goes into FLASH */
+ .text :
+ {
+ . = ALIGN(8);
+ *(.text) /* .text sections (code) */
+ *(.text*) /* .text* sections (code) */
+ *(.glue_7) /* glue arm to thumb code */
+ *(.glue_7t) /* glue thumb to arm code */
+ *(.eh_frame)
+
+ KEEP (*(.init))
+ KEEP (*(.fini))
+
+ . = ALIGN(8);
+ _etext = .; /* define a global symbols at end of code */
+ } >FLASH
+
+ /* Constant data goes into FLASH */
+ .rodata :
+ {
+ . = ALIGN(8);
+ *(.rodata) /* .rodata sections (constants, strings, etc.) */
+ *(.rodata*) /* .rodata* sections (constants, strings, etc.) */
+ . = ALIGN(8);
+ } >FLASH
+
+ .ARM.extab :
+ {
+ . = ALIGN(8);
+ *(.ARM.extab* .gnu.linkonce.armextab.*)
+ . = ALIGN(8);
+ } >FLASH
+ .ARM : {
+ . = ALIGN(8);
+ __exidx_start = .;
+ *(.ARM.exidx*)
+ __exidx_end = .;
+ . = ALIGN(8);
+ } >FLASH
+
+ .preinit_array :
+ {
+ . = ALIGN(8);
+ PROVIDE_HIDDEN (__preinit_array_start = .);
+ KEEP (*(.preinit_array*))
+ PROVIDE_HIDDEN (__preinit_array_end = .);
+ . = ALIGN(8);
+ } >FLASH
+
+ .init_array :
+ {
+ . = ALIGN(8);
+ PROVIDE_HIDDEN (__init_array_start = .);
+ KEEP (*(SORT(.init_array.*)))
+ KEEP (*(.init_array*))
+ PROVIDE_HIDDEN (__init_array_end = .);
+ . = ALIGN(8);
+ } >FLASH
+ .fini_array :
+ {
+ . = ALIGN(8);
+ PROVIDE_HIDDEN (__fini_array_start = .);
+ KEEP (*(SORT(.fini_array.*)))
+ KEEP (*(.fini_array*))
+ PROVIDE_HIDDEN (__fini_array_end = .);
+ . = ALIGN(8);
+ } >FLASH
+
+ /* used by the startup to initialize data */
+ _sidata = LOADADDR(.data);
+
+ /* Initialized data sections goes into RAM, load LMA copy after code */
+ .data :
+ {
+ . = ALIGN(8);
+ _sdata = .; /* create a global symbol at data start */
+ *(.data) /* .data sections */
+ *(.data*) /* .data* sections */
+
+ . = ALIGN(8);
+ _edata = .; /* define a global symbol at data end */
+ } >RAM AT> FLASH
+
+
+ /* Uninitialized data section */
+ . = ALIGN(4);
+ .bss :
+ {
+ /* This is used by the startup in order to initialize the .bss secion */
+ _sbss = .; /* define a global symbol at bss start */
+ __bss_start__ = _sbss;
+ *(.bss)
+ *(.bss*)
+ *(COMMON)
+
+ . = ALIGN(4);
+ _ebss = .; /* define a global symbol at bss end */
+ __bss_end__ = _ebss;
+ } >RAM
+
+ /* User_heap_stack section, used to check that there is enough RAM left */
+ ._user_heap_stack :
+ {
+ . = ALIGN(8);
+ PROVIDE ( end = . );
+ PROVIDE ( _end = . );
+ . = . + _Min_Heap_Size;
+ . = . + _Min_Stack_Size;
+ . = ALIGN(8);
+ } >RAM
+
+
+
+ /* Remove information from the standard libraries */
+ /DISCARD/ :
+ {
+ libc.a ( * )
+ libm.a ( * )
+ libgcc.a ( * )
+ }
+
+ .ARM.attributes 0 : { *(.ARM.attributes) }
+}
+
+
diff --git a/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/app_farm_ai_demo/startup_stm32l431xx.s b/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/app_farm_ai_demo/startup_stm32l431xx.s
new file mode 100644
index 00000000..d8f45f45
--- /dev/null
+++ b/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/app_farm_ai_demo/startup_stm32l431xx.s
@@ -0,0 +1,474 @@
+/**
+ ******************************************************************************
+ * @file startup_stm32l431xx.s
+ * @author MCD Application Team
+ * @brief STM32L431xx devices vector table for GCC toolchain.
+ * This module performs:
+ * - Set the initial SP
+ * - Set the initial PC == Reset_Handler,
+ * - Set the vector table entries with the exceptions ISR address,
+ * - Configure the clock system
+ * - Branches to main in the C library (which eventually
+ * calls main()).
+ * After Reset the Cortex-M4 processor is in Thread mode,
+ * priority is Privileged, and the Stack is set to Main.
+ ******************************************************************************
+ * @attention
+ *
+ * © COPYRIGHT(c) 2017 STMicroelectronics
+ *
+ * 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 STMicroelectronics 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.
+ *
+ ******************************************************************************
+ */
+
+ .syntax unified
+ .cpu cortex-m4
+ .fpu softvfp
+ .thumb
+
+.global g_pfnVectors
+.global Default_Handler
+
+/* start address for the initialization values of the .data section.
+defined in linker script */
+.word _sidata
+/* start address for the .data section. defined in linker script */
+.word _sdata
+/* end address for the .data section. defined in linker script */
+.word _edata
+/* start address for the .bss section. defined in linker script */
+.word _sbss
+/* end address for the .bss section. defined in linker script */
+.word _ebss
+
+.equ BootRAM, 0xF1E0F85F
+/**
+ * @brief This is the code that gets called when the processor first
+ * starts execution following a reset event. Only the absolutely
+ * necessary set is performed, after which the application
+ * supplied main() routine is called.
+ * @param None
+ * @retval : None
+*/
+
+ .section .text.Reset_Handler
+ .weak Reset_Handler
+ .type Reset_Handler, %function
+Reset_Handler:
+ ldr sp, =_estack /* Atollic update: set stack pointer */
+
+/* Copy the data segment initializers from flash to SRAM */
+ movs r1, #0
+ b LoopCopyDataInit
+
+CopyDataInit:
+ ldr r3, =_sidata
+ ldr r3, [r3, r1]
+ str r3, [r0, r1]
+ adds r1, r1, #4
+
+LoopCopyDataInit:
+ ldr r0, =_sdata
+ ldr r3, =_edata
+ adds r2, r0, r1
+ cmp r2, r3
+ bcc CopyDataInit
+ ldr r2, =_sbss
+ b LoopFillZerobss
+/* Zero fill the bss segment. */
+FillZerobss:
+ movs r3, #0
+ str r3, [r2], #4
+
+LoopFillZerobss:
+ ldr r3, = _ebss
+ cmp r2, r3
+ bcc FillZerobss
+
+/* Call the clock system intitialization function.*/
+ bl SystemInit
+/* Call static constructors */
+ bl __libc_init_array
+/* Call the application's entry point.*/
+ bl main
+
+LoopForever:
+ b LoopForever
+
+.size Reset_Handler, .-Reset_Handler
+
+/**
+ * @brief This is the code that gets called when the processor receives an
+ * unexpected interrupt. This simply enters an infinite loop, preserving
+ * the system state for examination by a debugger.
+ *
+ * @param None
+ * @retval : None
+*/
+ .section .text.Default_Handler,"ax",%progbits
+Default_Handler:
+Infinite_Loop:
+ b Infinite_Loop
+ .size Default_Handler, .-Default_Handler
+/******************************************************************************
+*
+* The minimal vector table for a Cortex-M4. Note that the proper constructs
+* must be placed on this to ensure that it ends up at physical address
+* 0x0000.0000.
+*
+******************************************************************************/
+ .section .isr_vector,"a",%progbits
+ .type g_pfnVectors, %object
+ .size g_pfnVectors, .-g_pfnVectors
+
+
+g_pfnVectors:
+ .word _estack
+ .word Reset_Handler
+ .word NMI_Handler
+ .word HardFault_Handler
+ .word MemManage_Handler
+ .word BusFault_Handler
+ .word UsageFault_Handler
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word SVC_Handler
+ .word DebugMon_Handler
+ .word 0
+ .word PendSV_Handler
+ .word SysTick_Handler
+ .word WWDG_IRQHandler
+ .word PVD_PVM_IRQHandler
+ .word TAMP_STAMP_IRQHandler
+ .word RTC_WKUP_IRQHandler
+ .word FLASH_IRQHandler
+ .word RCC_IRQHandler
+ .word EXTI0_IRQHandler
+ .word EXTI1_IRQHandler
+ .word EXTI2_IRQHandler
+ .word EXTI3_IRQHandler
+ .word EXTI4_IRQHandler
+ .word DMA1_Channel1_IRQHandler
+ .word DMA1_Channel2_IRQHandler
+ .word DMA1_Channel3_IRQHandler
+ .word DMA1_Channel4_IRQHandler
+ .word DMA1_Channel5_IRQHandler
+ .word DMA1_Channel6_IRQHandler
+ .word DMA1_Channel7_IRQHandler
+ .word ADC1_IRQHandler
+ .word CAN1_TX_IRQHandler
+ .word CAN1_RX0_IRQHandler
+ .word CAN1_RX1_IRQHandler
+ .word CAN1_SCE_IRQHandler
+ .word EXTI9_5_IRQHandler
+ .word TIM1_BRK_TIM15_IRQHandler
+ .word TIM1_UP_TIM16_IRQHandler
+ .word TIM1_TRG_COM_IRQHandler
+ .word TIM1_CC_IRQHandler
+ .word TIM2_IRQHandler
+ .word 0
+ .word 0
+ .word I2C1_EV_IRQHandler
+ .word I2C1_ER_IRQHandler
+ .word I2C2_EV_IRQHandler
+ .word I2C2_ER_IRQHandler
+ .word SPI1_IRQHandler
+ .word SPI2_IRQHandler
+ .word USART1_IRQHandler
+ .word USART2_IRQHandler
+ .word USART3_IRQHandler
+ .word EXTI15_10_IRQHandler
+ .word RTC_Alarm_IRQHandler
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word SDMMC1_IRQHandler
+ .word 0
+ .word SPI3_IRQHandler
+ .word 0
+ .word 0
+ .word TIM6_DAC_IRQHandler
+ .word TIM7_IRQHandler
+ .word DMA2_Channel1_IRQHandler
+ .word DMA2_Channel2_IRQHandler
+ .word DMA2_Channel3_IRQHandler
+ .word DMA2_Channel4_IRQHandler
+ .word DMA2_Channel5_IRQHandler
+ .word 0
+ .word 0
+ .word 0
+ .word COMP_IRQHandler
+ .word LPTIM1_IRQHandler
+ .word LPTIM2_IRQHandler
+ .word 0
+ .word DMA2_Channel6_IRQHandler
+ .word DMA2_Channel7_IRQHandler
+ .word LPUART1_IRQHandler
+ .word QUADSPI_IRQHandler
+ .word I2C3_EV_IRQHandler
+ .word I2C3_ER_IRQHandler
+ .word SAI1_IRQHandler
+ .word 0
+ .word SWPMI1_IRQHandler
+ .word TSC_IRQHandler
+ .word 0
+ .word 0
+ .word RNG_IRQHandler
+ .word FPU_IRQHandler
+ .word CRS_IRQHandler
+
+
+/*******************************************************************************
+*
+* Provide weak aliases for each Exception handler to the Default_Handler.
+* As they are weak aliases, any function with the same name will override
+* this definition.
+*
+*******************************************************************************/
+
+ .weak NMI_Handler
+ .thumb_set NMI_Handler,Default_Handler
+
+ .weak HardFault_Handler
+ .thumb_set HardFault_Handler,Default_Handler
+
+ .weak MemManage_Handler
+ .thumb_set MemManage_Handler,Default_Handler
+
+ .weak BusFault_Handler
+ .thumb_set BusFault_Handler,Default_Handler
+
+ .weak UsageFault_Handler
+ .thumb_set UsageFault_Handler,Default_Handler
+
+ .weak SVC_Handler
+ .thumb_set SVC_Handler,Default_Handler
+
+ .weak DebugMon_Handler
+ .thumb_set DebugMon_Handler,Default_Handler
+
+ .weak PendSV_Handler
+ .thumb_set PendSV_Handler,Default_Handler
+
+ .weak SysTick_Handler
+ .thumb_set SysTick_Handler,Default_Handler
+
+ .weak WWDG_IRQHandler
+ .thumb_set WWDG_IRQHandler,Default_Handler
+
+ .weak PVD_PVM_IRQHandler
+ .thumb_set PVD_PVM_IRQHandler,Default_Handler
+
+ .weak TAMP_STAMP_IRQHandler
+ .thumb_set TAMP_STAMP_IRQHandler,Default_Handler
+
+ .weak RTC_WKUP_IRQHandler
+ .thumb_set RTC_WKUP_IRQHandler,Default_Handler
+
+ .weak FLASH_IRQHandler
+ .thumb_set FLASH_IRQHandler,Default_Handler
+
+ .weak RCC_IRQHandler
+ .thumb_set RCC_IRQHandler,Default_Handler
+
+ .weak EXTI0_IRQHandler
+ .thumb_set EXTI0_IRQHandler,Default_Handler
+
+ .weak EXTI1_IRQHandler
+ .thumb_set EXTI1_IRQHandler,Default_Handler
+
+ .weak EXTI2_IRQHandler
+ .thumb_set EXTI2_IRQHandler,Default_Handler
+
+ .weak EXTI3_IRQHandler
+ .thumb_set EXTI3_IRQHandler,Default_Handler
+
+ .weak EXTI4_IRQHandler
+ .thumb_set EXTI4_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel1_IRQHandler
+ .thumb_set DMA1_Channel1_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel2_IRQHandler
+ .thumb_set DMA1_Channel2_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel3_IRQHandler
+ .thumb_set DMA1_Channel3_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel4_IRQHandler
+ .thumb_set DMA1_Channel4_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel5_IRQHandler
+ .thumb_set DMA1_Channel5_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel6_IRQHandler
+ .thumb_set DMA1_Channel6_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel7_IRQHandler
+ .thumb_set DMA1_Channel7_IRQHandler,Default_Handler
+
+ .weak ADC1_IRQHandler
+ .thumb_set ADC1_IRQHandler,Default_Handler
+
+ .weak CAN1_TX_IRQHandler
+ .thumb_set CAN1_TX_IRQHandler,Default_Handler
+
+ .weak CAN1_RX0_IRQHandler
+ .thumb_set CAN1_RX0_IRQHandler,Default_Handler
+
+ .weak CAN1_RX1_IRQHandler
+ .thumb_set CAN1_RX1_IRQHandler,Default_Handler
+
+ .weak CAN1_SCE_IRQHandler
+ .thumb_set CAN1_SCE_IRQHandler,Default_Handler
+
+ .weak EXTI9_5_IRQHandler
+ .thumb_set EXTI9_5_IRQHandler,Default_Handler
+
+ .weak TIM1_BRK_TIM15_IRQHandler
+ .thumb_set TIM1_BRK_TIM15_IRQHandler,Default_Handler
+
+ .weak TIM1_UP_TIM16_IRQHandler
+ .thumb_set TIM1_UP_TIM16_IRQHandler,Default_Handler
+
+ .weak TIM1_TRG_COM_IRQHandler
+ .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler
+
+ .weak TIM1_CC_IRQHandler
+ .thumb_set TIM1_CC_IRQHandler,Default_Handler
+
+ .weak TIM2_IRQHandler
+ .thumb_set TIM2_IRQHandler,Default_Handler
+
+ .weak I2C1_EV_IRQHandler
+ .thumb_set I2C1_EV_IRQHandler,Default_Handler
+
+ .weak I2C1_ER_IRQHandler
+ .thumb_set I2C1_ER_IRQHandler,Default_Handler
+
+ .weak I2C2_EV_IRQHandler
+ .thumb_set I2C2_EV_IRQHandler,Default_Handler
+
+ .weak I2C2_ER_IRQHandler
+ .thumb_set I2C2_ER_IRQHandler,Default_Handler
+
+ .weak SPI1_IRQHandler
+ .thumb_set SPI1_IRQHandler,Default_Handler
+
+ .weak SPI2_IRQHandler
+ .thumb_set SPI2_IRQHandler,Default_Handler
+
+ .weak USART1_IRQHandler
+ .thumb_set USART1_IRQHandler,Default_Handler
+
+ .weak USART2_IRQHandler
+ .thumb_set USART2_IRQHandler,Default_Handler
+
+ .weak USART3_IRQHandler
+ .thumb_set USART3_IRQHandler,Default_Handler
+
+ .weak EXTI15_10_IRQHandler
+ .thumb_set EXTI15_10_IRQHandler,Default_Handler
+
+ .weak RTC_Alarm_IRQHandler
+ .thumb_set RTC_Alarm_IRQHandler,Default_Handler
+
+ .weak SDMMC1_IRQHandler
+ .thumb_set SDMMC1_IRQHandler,Default_Handler
+
+ .weak SPI3_IRQHandler
+ .thumb_set SPI3_IRQHandler,Default_Handler
+
+ .weak TIM6_DAC_IRQHandler
+ .thumb_set TIM6_DAC_IRQHandler,Default_Handler
+
+ .weak TIM7_IRQHandler
+ .thumb_set TIM7_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel1_IRQHandler
+ .thumb_set DMA2_Channel1_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel2_IRQHandler
+ .thumb_set DMA2_Channel2_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel3_IRQHandler
+ .thumb_set DMA2_Channel3_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel4_IRQHandler
+ .thumb_set DMA2_Channel4_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel5_IRQHandler
+ .thumb_set DMA2_Channel5_IRQHandler,Default_Handler
+
+ .weak COMP_IRQHandler
+ .thumb_set COMP_IRQHandler,Default_Handler
+
+ .weak LPTIM1_IRQHandler
+ .thumb_set LPTIM1_IRQHandler,Default_Handler
+
+ .weak LPTIM2_IRQHandler
+ .thumb_set LPTIM2_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel6_IRQHandler
+ .thumb_set DMA2_Channel6_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel7_IRQHandler
+ .thumb_set DMA2_Channel7_IRQHandler,Default_Handler
+
+ .weak LPUART1_IRQHandler
+ .thumb_set LPUART1_IRQHandler,Default_Handler
+
+ .weak QUADSPI_IRQHandler
+ .thumb_set QUADSPI_IRQHandler,Default_Handler
+
+ .weak I2C3_EV_IRQHandler
+ .thumb_set I2C3_EV_IRQHandler,Default_Handler
+
+ .weak I2C3_ER_IRQHandler
+ .thumb_set I2C3_ER_IRQHandler,Default_Handler
+
+ .weak SAI1_IRQHandler
+ .thumb_set SAI1_IRQHandler,Default_Handler
+
+ .weak SWPMI1_IRQHandler
+ .thumb_set SWPMI1_IRQHandler,Default_Handler
+
+ .weak TSC_IRQHandler
+ .thumb_set TSC_IRQHandler,Default_Handler
+
+ .weak RNG_IRQHandler
+ .thumb_set RNG_IRQHandler,Default_Handler
+
+ .weak FPU_IRQHandler
+ .thumb_set FPU_IRQHandler,Default_Handler
+
+ .weak CRS_IRQHandler
+ .thumb_set CRS_IRQHandler,Default_Handler
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/app_hello_world/Makefile b/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/app_hello_world/Makefile
new file mode 100644
index 00000000..9c4b682e
--- /dev/null
+++ b/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/app_hello_world/Makefile
@@ -0,0 +1,54 @@
+###################################################################
+#automatic detection QTOP and LOCALDIR
+CUR_DIR := $(patsubst %/,%,$(dir $(realpath $(firstword $(MAKEFILE_LIST)))))
+TRYQTOP := $(shell if [ -n "$$QTOP" ] ; then\
+ echo $$QTOP;\
+ else\
+ cd $(CUR_DIR); while /usr/bin/test ! -e qmk ; do \
+ dir=`cd ../;pwd`; \
+ if [ "$$dir" = "/" ] ; then \
+ echo Cannot find QTOP in $(firstword $(MAKEFILE_LIST)) 1>&2; \
+ exit 1; \
+ fi ; \
+ cd $$dir; \
+ done ; \
+ pwd; \
+ fi)
+QTOP ?= $(realpath ${TRYQTOP})
+
+ifeq ($(QTOP),)
+$(error Please run this in a tree)
+endif
+LOCALDIR = $(patsubst %/,%,$(subst $(realpath $(QTOP))/,,$(CUR_DIR)))
+export QTOP
+
+####################################################################
+
+
+export BP=TencentOS_tiny_EVB_MX_Plus
+
+TREE_LIB_ENABLE=1
+lib=
+subdirs =
+
+LSRCS += $(QTOP)/examples/hello_world/hello_world.c
+LSRCS += $(wildcard *.s)
+
+all::
+ make -C ${QTOP}/arch BP=${BP}
+ make -C ${QTOP}/kernel BP=${BP}
+ make -C ${QTOP}/osal BP=${BP}
+ make -C ${QTOP}/platform BP=${BP}
+ make -C ${QTOP}/board/TencentOS_tiny_EVB_MX_Plus/BSP BP=${BP}
+#exec =
+LD_A_FILES += $(LIBDIR)/libarch.a
+LD_A_FILES += $(LIBDIR)/libkernel.a
+#LD_A_FILES += $(LIBDIR)/lib$(notdir $(CUR_DIR)).a
+LD_A_FILES += $(LIBDIR)/libcmsis_os.a
+LD_A_FILES += $(LIBDIR)/libvendor_bsp.a
+LD_A_FILES += $(LIBDIR)/libBSP.a
+LD_A_LISTS += -lc -lm -lnosys
+LD_L_LISTS += -specs=nosys.specs -T$(CUR_DIR)/STM32L431RCTx_FLASH.ld -Wl,-Map=$(LIBDIR)/$(notdir $(CUR_DIR)).map,--cref -Wl,--gc-sections
+include ${QTOP}/qmk/generic/Make.exec
+
+
diff --git a/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/app_hello_world/STM32L431RCTx_FLASH.ld b/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/app_hello_world/STM32L431RCTx_FLASH.ld
new file mode 100644
index 00000000..3d07935e
--- /dev/null
+++ b/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/app_hello_world/STM32L431RCTx_FLASH.ld
@@ -0,0 +1,203 @@
+/*
+******************************************************************************
+**
+
+** File : LinkerScript.ld
+**
+** Author : Auto-generated by Ac6 System Workbench
+**
+** Abstract : Linker script for STM32L431RCTx series
+** 256Kbytes FLASH and 64Kbytes RAM
+**
+** Set heap size, stack size and stack location according
+** to application requirements.
+**
+** Set memory bank area and size if external memory is used.
+**
+** Target : STMicroelectronics STM32
+**
+** Distribution: The file is distributed “as is,” without any warranty
+** of any kind.
+**
+*****************************************************************************
+** @attention
+**
+** © COPYRIGHT(c) 2014 Ac6
+**
+** 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 Ac6 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.
+**
+*****************************************************************************
+*/
+
+/* Entry Point */
+ENTRY(Reset_Handler)
+
+/* Highest address of the user mode stack */
+_estack = 0x20010000; /* end of RAM */
+/* Generate a link error if heap and stack don't fit into RAM */
+_Min_Heap_Size = 0x200; /* required amount of heap */
+_Min_Stack_Size = 0x400; /* required amount of stack */
+
+/* Specify the memory areas */
+MEMORY
+{
+RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 64K
+FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 256K
+}
+
+/* Define output sections */
+SECTIONS
+{
+ /* The startup code goes first into FLASH */
+ .isr_vector :
+ {
+ . = ALIGN(8);
+ KEEP(*(.isr_vector)) /* Startup code */
+ . = ALIGN(8);
+ } >FLASH
+
+ /* The program code and other data goes into FLASH */
+ .text :
+ {
+ . = ALIGN(8);
+ *(.text) /* .text sections (code) */
+ *(.text*) /* .text* sections (code) */
+ *(.glue_7) /* glue arm to thumb code */
+ *(.glue_7t) /* glue thumb to arm code */
+ *(.eh_frame)
+
+ KEEP (*(.init))
+ KEEP (*(.fini))
+
+ . = ALIGN(8);
+ _etext = .; /* define a global symbols at end of code */
+ } >FLASH
+
+ /* Constant data goes into FLASH */
+ .rodata :
+ {
+ . = ALIGN(8);
+ *(.rodata) /* .rodata sections (constants, strings, etc.) */
+ *(.rodata*) /* .rodata* sections (constants, strings, etc.) */
+ . = ALIGN(8);
+ } >FLASH
+
+ .ARM.extab :
+ {
+ . = ALIGN(8);
+ *(.ARM.extab* .gnu.linkonce.armextab.*)
+ . = ALIGN(8);
+ } >FLASH
+ .ARM : {
+ . = ALIGN(8);
+ __exidx_start = .;
+ *(.ARM.exidx*)
+ __exidx_end = .;
+ . = ALIGN(8);
+ } >FLASH
+
+ .preinit_array :
+ {
+ . = ALIGN(8);
+ PROVIDE_HIDDEN (__preinit_array_start = .);
+ KEEP (*(.preinit_array*))
+ PROVIDE_HIDDEN (__preinit_array_end = .);
+ . = ALIGN(8);
+ } >FLASH
+
+ .init_array :
+ {
+ . = ALIGN(8);
+ PROVIDE_HIDDEN (__init_array_start = .);
+ KEEP (*(SORT(.init_array.*)))
+ KEEP (*(.init_array*))
+ PROVIDE_HIDDEN (__init_array_end = .);
+ . = ALIGN(8);
+ } >FLASH
+ .fini_array :
+ {
+ . = ALIGN(8);
+ PROVIDE_HIDDEN (__fini_array_start = .);
+ KEEP (*(SORT(.fini_array.*)))
+ KEEP (*(.fini_array*))
+ PROVIDE_HIDDEN (__fini_array_end = .);
+ . = ALIGN(8);
+ } >FLASH
+
+ /* used by the startup to initialize data */
+ _sidata = LOADADDR(.data);
+
+ /* Initialized data sections goes into RAM, load LMA copy after code */
+ .data :
+ {
+ . = ALIGN(8);
+ _sdata = .; /* create a global symbol at data start */
+ *(.data) /* .data sections */
+ *(.data*) /* .data* sections */
+
+ . = ALIGN(8);
+ _edata = .; /* define a global symbol at data end */
+ } >RAM AT> FLASH
+
+
+ /* Uninitialized data section */
+ . = ALIGN(4);
+ .bss :
+ {
+ /* This is used by the startup in order to initialize the .bss secion */
+ _sbss = .; /* define a global symbol at bss start */
+ __bss_start__ = _sbss;
+ *(.bss)
+ *(.bss*)
+ *(COMMON)
+
+ . = ALIGN(4);
+ _ebss = .; /* define a global symbol at bss end */
+ __bss_end__ = _ebss;
+ } >RAM
+
+ /* User_heap_stack section, used to check that there is enough RAM left */
+ ._user_heap_stack :
+ {
+ . = ALIGN(8);
+ PROVIDE ( end = . );
+ PROVIDE ( _end = . );
+ . = . + _Min_Heap_Size;
+ . = . + _Min_Stack_Size;
+ . = ALIGN(8);
+ } >RAM
+
+
+
+ /* Remove information from the standard libraries */
+ /DISCARD/ :
+ {
+ libc.a ( * )
+ libm.a ( * )
+ libgcc.a ( * )
+ }
+
+ .ARM.attributes 0 : { *(.ARM.attributes) }
+}
+
+
diff --git a/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/app_hello_world/startup_stm32l431xx.s b/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/app_hello_world/startup_stm32l431xx.s
new file mode 100644
index 00000000..d8f45f45
--- /dev/null
+++ b/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/app_hello_world/startup_stm32l431xx.s
@@ -0,0 +1,474 @@
+/**
+ ******************************************************************************
+ * @file startup_stm32l431xx.s
+ * @author MCD Application Team
+ * @brief STM32L431xx devices vector table for GCC toolchain.
+ * This module performs:
+ * - Set the initial SP
+ * - Set the initial PC == Reset_Handler,
+ * - Set the vector table entries with the exceptions ISR address,
+ * - Configure the clock system
+ * - Branches to main in the C library (which eventually
+ * calls main()).
+ * After Reset the Cortex-M4 processor is in Thread mode,
+ * priority is Privileged, and the Stack is set to Main.
+ ******************************************************************************
+ * @attention
+ *
+ * © COPYRIGHT(c) 2017 STMicroelectronics
+ *
+ * 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 STMicroelectronics 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.
+ *
+ ******************************************************************************
+ */
+
+ .syntax unified
+ .cpu cortex-m4
+ .fpu softvfp
+ .thumb
+
+.global g_pfnVectors
+.global Default_Handler
+
+/* start address for the initialization values of the .data section.
+defined in linker script */
+.word _sidata
+/* start address for the .data section. defined in linker script */
+.word _sdata
+/* end address for the .data section. defined in linker script */
+.word _edata
+/* start address for the .bss section. defined in linker script */
+.word _sbss
+/* end address for the .bss section. defined in linker script */
+.word _ebss
+
+.equ BootRAM, 0xF1E0F85F
+/**
+ * @brief This is the code that gets called when the processor first
+ * starts execution following a reset event. Only the absolutely
+ * necessary set is performed, after which the application
+ * supplied main() routine is called.
+ * @param None
+ * @retval : None
+*/
+
+ .section .text.Reset_Handler
+ .weak Reset_Handler
+ .type Reset_Handler, %function
+Reset_Handler:
+ ldr sp, =_estack /* Atollic update: set stack pointer */
+
+/* Copy the data segment initializers from flash to SRAM */
+ movs r1, #0
+ b LoopCopyDataInit
+
+CopyDataInit:
+ ldr r3, =_sidata
+ ldr r3, [r3, r1]
+ str r3, [r0, r1]
+ adds r1, r1, #4
+
+LoopCopyDataInit:
+ ldr r0, =_sdata
+ ldr r3, =_edata
+ adds r2, r0, r1
+ cmp r2, r3
+ bcc CopyDataInit
+ ldr r2, =_sbss
+ b LoopFillZerobss
+/* Zero fill the bss segment. */
+FillZerobss:
+ movs r3, #0
+ str r3, [r2], #4
+
+LoopFillZerobss:
+ ldr r3, = _ebss
+ cmp r2, r3
+ bcc FillZerobss
+
+/* Call the clock system intitialization function.*/
+ bl SystemInit
+/* Call static constructors */
+ bl __libc_init_array
+/* Call the application's entry point.*/
+ bl main
+
+LoopForever:
+ b LoopForever
+
+.size Reset_Handler, .-Reset_Handler
+
+/**
+ * @brief This is the code that gets called when the processor receives an
+ * unexpected interrupt. This simply enters an infinite loop, preserving
+ * the system state for examination by a debugger.
+ *
+ * @param None
+ * @retval : None
+*/
+ .section .text.Default_Handler,"ax",%progbits
+Default_Handler:
+Infinite_Loop:
+ b Infinite_Loop
+ .size Default_Handler, .-Default_Handler
+/******************************************************************************
+*
+* The minimal vector table for a Cortex-M4. Note that the proper constructs
+* must be placed on this to ensure that it ends up at physical address
+* 0x0000.0000.
+*
+******************************************************************************/
+ .section .isr_vector,"a",%progbits
+ .type g_pfnVectors, %object
+ .size g_pfnVectors, .-g_pfnVectors
+
+
+g_pfnVectors:
+ .word _estack
+ .word Reset_Handler
+ .word NMI_Handler
+ .word HardFault_Handler
+ .word MemManage_Handler
+ .word BusFault_Handler
+ .word UsageFault_Handler
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word SVC_Handler
+ .word DebugMon_Handler
+ .word 0
+ .word PendSV_Handler
+ .word SysTick_Handler
+ .word WWDG_IRQHandler
+ .word PVD_PVM_IRQHandler
+ .word TAMP_STAMP_IRQHandler
+ .word RTC_WKUP_IRQHandler
+ .word FLASH_IRQHandler
+ .word RCC_IRQHandler
+ .word EXTI0_IRQHandler
+ .word EXTI1_IRQHandler
+ .word EXTI2_IRQHandler
+ .word EXTI3_IRQHandler
+ .word EXTI4_IRQHandler
+ .word DMA1_Channel1_IRQHandler
+ .word DMA1_Channel2_IRQHandler
+ .word DMA1_Channel3_IRQHandler
+ .word DMA1_Channel4_IRQHandler
+ .word DMA1_Channel5_IRQHandler
+ .word DMA1_Channel6_IRQHandler
+ .word DMA1_Channel7_IRQHandler
+ .word ADC1_IRQHandler
+ .word CAN1_TX_IRQHandler
+ .word CAN1_RX0_IRQHandler
+ .word CAN1_RX1_IRQHandler
+ .word CAN1_SCE_IRQHandler
+ .word EXTI9_5_IRQHandler
+ .word TIM1_BRK_TIM15_IRQHandler
+ .word TIM1_UP_TIM16_IRQHandler
+ .word TIM1_TRG_COM_IRQHandler
+ .word TIM1_CC_IRQHandler
+ .word TIM2_IRQHandler
+ .word 0
+ .word 0
+ .word I2C1_EV_IRQHandler
+ .word I2C1_ER_IRQHandler
+ .word I2C2_EV_IRQHandler
+ .word I2C2_ER_IRQHandler
+ .word SPI1_IRQHandler
+ .word SPI2_IRQHandler
+ .word USART1_IRQHandler
+ .word USART2_IRQHandler
+ .word USART3_IRQHandler
+ .word EXTI15_10_IRQHandler
+ .word RTC_Alarm_IRQHandler
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word SDMMC1_IRQHandler
+ .word 0
+ .word SPI3_IRQHandler
+ .word 0
+ .word 0
+ .word TIM6_DAC_IRQHandler
+ .word TIM7_IRQHandler
+ .word DMA2_Channel1_IRQHandler
+ .word DMA2_Channel2_IRQHandler
+ .word DMA2_Channel3_IRQHandler
+ .word DMA2_Channel4_IRQHandler
+ .word DMA2_Channel5_IRQHandler
+ .word 0
+ .word 0
+ .word 0
+ .word COMP_IRQHandler
+ .word LPTIM1_IRQHandler
+ .word LPTIM2_IRQHandler
+ .word 0
+ .word DMA2_Channel6_IRQHandler
+ .word DMA2_Channel7_IRQHandler
+ .word LPUART1_IRQHandler
+ .word QUADSPI_IRQHandler
+ .word I2C3_EV_IRQHandler
+ .word I2C3_ER_IRQHandler
+ .word SAI1_IRQHandler
+ .word 0
+ .word SWPMI1_IRQHandler
+ .word TSC_IRQHandler
+ .word 0
+ .word 0
+ .word RNG_IRQHandler
+ .word FPU_IRQHandler
+ .word CRS_IRQHandler
+
+
+/*******************************************************************************
+*
+* Provide weak aliases for each Exception handler to the Default_Handler.
+* As they are weak aliases, any function with the same name will override
+* this definition.
+*
+*******************************************************************************/
+
+ .weak NMI_Handler
+ .thumb_set NMI_Handler,Default_Handler
+
+ .weak HardFault_Handler
+ .thumb_set HardFault_Handler,Default_Handler
+
+ .weak MemManage_Handler
+ .thumb_set MemManage_Handler,Default_Handler
+
+ .weak BusFault_Handler
+ .thumb_set BusFault_Handler,Default_Handler
+
+ .weak UsageFault_Handler
+ .thumb_set UsageFault_Handler,Default_Handler
+
+ .weak SVC_Handler
+ .thumb_set SVC_Handler,Default_Handler
+
+ .weak DebugMon_Handler
+ .thumb_set DebugMon_Handler,Default_Handler
+
+ .weak PendSV_Handler
+ .thumb_set PendSV_Handler,Default_Handler
+
+ .weak SysTick_Handler
+ .thumb_set SysTick_Handler,Default_Handler
+
+ .weak WWDG_IRQHandler
+ .thumb_set WWDG_IRQHandler,Default_Handler
+
+ .weak PVD_PVM_IRQHandler
+ .thumb_set PVD_PVM_IRQHandler,Default_Handler
+
+ .weak TAMP_STAMP_IRQHandler
+ .thumb_set TAMP_STAMP_IRQHandler,Default_Handler
+
+ .weak RTC_WKUP_IRQHandler
+ .thumb_set RTC_WKUP_IRQHandler,Default_Handler
+
+ .weak FLASH_IRQHandler
+ .thumb_set FLASH_IRQHandler,Default_Handler
+
+ .weak RCC_IRQHandler
+ .thumb_set RCC_IRQHandler,Default_Handler
+
+ .weak EXTI0_IRQHandler
+ .thumb_set EXTI0_IRQHandler,Default_Handler
+
+ .weak EXTI1_IRQHandler
+ .thumb_set EXTI1_IRQHandler,Default_Handler
+
+ .weak EXTI2_IRQHandler
+ .thumb_set EXTI2_IRQHandler,Default_Handler
+
+ .weak EXTI3_IRQHandler
+ .thumb_set EXTI3_IRQHandler,Default_Handler
+
+ .weak EXTI4_IRQHandler
+ .thumb_set EXTI4_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel1_IRQHandler
+ .thumb_set DMA1_Channel1_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel2_IRQHandler
+ .thumb_set DMA1_Channel2_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel3_IRQHandler
+ .thumb_set DMA1_Channel3_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel4_IRQHandler
+ .thumb_set DMA1_Channel4_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel5_IRQHandler
+ .thumb_set DMA1_Channel5_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel6_IRQHandler
+ .thumb_set DMA1_Channel6_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel7_IRQHandler
+ .thumb_set DMA1_Channel7_IRQHandler,Default_Handler
+
+ .weak ADC1_IRQHandler
+ .thumb_set ADC1_IRQHandler,Default_Handler
+
+ .weak CAN1_TX_IRQHandler
+ .thumb_set CAN1_TX_IRQHandler,Default_Handler
+
+ .weak CAN1_RX0_IRQHandler
+ .thumb_set CAN1_RX0_IRQHandler,Default_Handler
+
+ .weak CAN1_RX1_IRQHandler
+ .thumb_set CAN1_RX1_IRQHandler,Default_Handler
+
+ .weak CAN1_SCE_IRQHandler
+ .thumb_set CAN1_SCE_IRQHandler,Default_Handler
+
+ .weak EXTI9_5_IRQHandler
+ .thumb_set EXTI9_5_IRQHandler,Default_Handler
+
+ .weak TIM1_BRK_TIM15_IRQHandler
+ .thumb_set TIM1_BRK_TIM15_IRQHandler,Default_Handler
+
+ .weak TIM1_UP_TIM16_IRQHandler
+ .thumb_set TIM1_UP_TIM16_IRQHandler,Default_Handler
+
+ .weak TIM1_TRG_COM_IRQHandler
+ .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler
+
+ .weak TIM1_CC_IRQHandler
+ .thumb_set TIM1_CC_IRQHandler,Default_Handler
+
+ .weak TIM2_IRQHandler
+ .thumb_set TIM2_IRQHandler,Default_Handler
+
+ .weak I2C1_EV_IRQHandler
+ .thumb_set I2C1_EV_IRQHandler,Default_Handler
+
+ .weak I2C1_ER_IRQHandler
+ .thumb_set I2C1_ER_IRQHandler,Default_Handler
+
+ .weak I2C2_EV_IRQHandler
+ .thumb_set I2C2_EV_IRQHandler,Default_Handler
+
+ .weak I2C2_ER_IRQHandler
+ .thumb_set I2C2_ER_IRQHandler,Default_Handler
+
+ .weak SPI1_IRQHandler
+ .thumb_set SPI1_IRQHandler,Default_Handler
+
+ .weak SPI2_IRQHandler
+ .thumb_set SPI2_IRQHandler,Default_Handler
+
+ .weak USART1_IRQHandler
+ .thumb_set USART1_IRQHandler,Default_Handler
+
+ .weak USART2_IRQHandler
+ .thumb_set USART2_IRQHandler,Default_Handler
+
+ .weak USART3_IRQHandler
+ .thumb_set USART3_IRQHandler,Default_Handler
+
+ .weak EXTI15_10_IRQHandler
+ .thumb_set EXTI15_10_IRQHandler,Default_Handler
+
+ .weak RTC_Alarm_IRQHandler
+ .thumb_set RTC_Alarm_IRQHandler,Default_Handler
+
+ .weak SDMMC1_IRQHandler
+ .thumb_set SDMMC1_IRQHandler,Default_Handler
+
+ .weak SPI3_IRQHandler
+ .thumb_set SPI3_IRQHandler,Default_Handler
+
+ .weak TIM6_DAC_IRQHandler
+ .thumb_set TIM6_DAC_IRQHandler,Default_Handler
+
+ .weak TIM7_IRQHandler
+ .thumb_set TIM7_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel1_IRQHandler
+ .thumb_set DMA2_Channel1_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel2_IRQHandler
+ .thumb_set DMA2_Channel2_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel3_IRQHandler
+ .thumb_set DMA2_Channel3_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel4_IRQHandler
+ .thumb_set DMA2_Channel4_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel5_IRQHandler
+ .thumb_set DMA2_Channel5_IRQHandler,Default_Handler
+
+ .weak COMP_IRQHandler
+ .thumb_set COMP_IRQHandler,Default_Handler
+
+ .weak LPTIM1_IRQHandler
+ .thumb_set LPTIM1_IRQHandler,Default_Handler
+
+ .weak LPTIM2_IRQHandler
+ .thumb_set LPTIM2_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel6_IRQHandler
+ .thumb_set DMA2_Channel6_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel7_IRQHandler
+ .thumb_set DMA2_Channel7_IRQHandler,Default_Handler
+
+ .weak LPUART1_IRQHandler
+ .thumb_set LPUART1_IRQHandler,Default_Handler
+
+ .weak QUADSPI_IRQHandler
+ .thumb_set QUADSPI_IRQHandler,Default_Handler
+
+ .weak I2C3_EV_IRQHandler
+ .thumb_set I2C3_EV_IRQHandler,Default_Handler
+
+ .weak I2C3_ER_IRQHandler
+ .thumb_set I2C3_ER_IRQHandler,Default_Handler
+
+ .weak SAI1_IRQHandler
+ .thumb_set SAI1_IRQHandler,Default_Handler
+
+ .weak SWPMI1_IRQHandler
+ .thumb_set SWPMI1_IRQHandler,Default_Handler
+
+ .weak TSC_IRQHandler
+ .thumb_set TSC_IRQHandler,Default_Handler
+
+ .weak RNG_IRQHandler
+ .thumb_set RNG_IRQHandler,Default_Handler
+
+ .weak FPU_IRQHandler
+ .thumb_set FPU_IRQHandler,Default_Handler
+
+ .weak CRS_IRQHandler
+ .thumb_set CRS_IRQHandler,Default_Handler
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/app_tencent_os_mqtt/Makefile b/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/app_tencent_os_mqtt/Makefile
new file mode 100644
index 00000000..9e425936
--- /dev/null
+++ b/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/app_tencent_os_mqtt/Makefile
@@ -0,0 +1,68 @@
+###################################################################
+#automatic detection QTOP and LOCALDIR
+CUR_DIR := $(patsubst %/,%,$(dir $(realpath $(firstword $(MAKEFILE_LIST)))))
+TRYQTOP := $(shell if [ -n "$$QTOP" ] ; then\
+ echo $$QTOP;\
+ else\
+ cd $(CUR_DIR); while /usr/bin/test ! -e qmk ; do \
+ dir=`cd ../;pwd`; \
+ if [ "$$dir" = "/" ] ; then \
+ echo Cannot find QTOP in $(firstword $(MAKEFILE_LIST)) 1>&2; \
+ exit 1; \
+ fi ; \
+ cd $$dir; \
+ done ; \
+ pwd; \
+ fi)
+QTOP ?= $(realpath ${TRYQTOP})
+
+ifeq ($(QTOP),)
+$(error Please run this in a tree)
+endif
+LOCALDIR = $(patsubst %/,%,$(subst $(realpath $(QTOP))/,,$(CUR_DIR)))
+export QTOP
+
+####################################################################
+
+
+export BP=TencentOS_tiny_EVB_MX_Plus
+
+TREE_LIB_ENABLE=1
+lib=
+subdirs =
+
+LSRCS += $(QTOP)/examples/tencent_os_mqtt/mqtt_example.c
+LSRCS += $(wildcard *.s)
+
+all::
+ make -C ${QTOP}/arch BP=${BP}
+ make -C ${QTOP}/kernel BP=${BP}
+ make -C ${QTOP}/osal BP=${BP}
+ make -C ${QTOP}/platform BP=${BP}
+ make -C ${QTOP}/board/TencentOS_tiny_EVB_MX_Plus/BSP BP=${BP}
+ make -C ${QTOP}/components/connectivity/Eclipse-Paho-MQTT BP=${BP}
+ make -C ${QTOP}/devices BP=${BP}
+ make -C ${QTOP}/net/at BP=${BP}
+ make -C ${QTOP}/net/tencent_firmware_module_wrapper BP=${BP}
+ make -C ${QTOP}/net/sal_module_wrapper BP=${BP}
+ make -C ${QTOP}/net/socket_wrapper BP=${BP}
+#exec =
+LD_A_FILES += $(LIBDIR)/libarch.a
+LD_A_FILES += $(LIBDIR)/libkernel.a
+LD_A_FILES += $(LIBDIR)/lib$(notdir $(CUR_DIR)).a
+LD_A_FILES += $(LIBDIR)/libcmsis_os.a
+LD_A_FILES += $(LIBDIR)/libvendor_bsp.a
+LD_A_FILES += $(LIBDIR)/libhal.a
+LD_A_FILES += $(LIBDIR)/libBSP.a
+LD_A_FILES += $(LIBDIR)/libEclipse-Paho-MQTT.a
+LD_A_FILES += $(LIBDIR)/libesp8266_tencent_firmware.a
+LD_A_FILES += $(LIBDIR)/libesp8266.a
+LD_A_FILES += $(LIBDIR)/libat.a
+LD_A_FILES += $(LIBDIR)/libtencent_firmware_module_wrapper.a
+LD_A_FILES += $(LIBDIR)/libsal_module_wrapper.a
+LD_A_FILES += $(LIBDIR)/libsocket_wrapper.a
+LD_A_LISTS += -lc -lm -lnosys
+LD_L_LISTS += -specs=nosys.specs -T$(CUR_DIR)/STM32L431RCTx_FLASH.ld -Wl,-Map=$(LIBDIR)/$(notdir $(CUR_DIR)).map,--cref -Wl,--gc-sections
+include ${QTOP}/qmk/generic/Make.exec
+
+
diff --git a/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/app_tencent_os_mqtt/STM32L431RCTx_FLASH.ld b/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/app_tencent_os_mqtt/STM32L431RCTx_FLASH.ld
new file mode 100644
index 00000000..3d07935e
--- /dev/null
+++ b/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/app_tencent_os_mqtt/STM32L431RCTx_FLASH.ld
@@ -0,0 +1,203 @@
+/*
+******************************************************************************
+**
+
+** File : LinkerScript.ld
+**
+** Author : Auto-generated by Ac6 System Workbench
+**
+** Abstract : Linker script for STM32L431RCTx series
+** 256Kbytes FLASH and 64Kbytes RAM
+**
+** Set heap size, stack size and stack location according
+** to application requirements.
+**
+** Set memory bank area and size if external memory is used.
+**
+** Target : STMicroelectronics STM32
+**
+** Distribution: The file is distributed “as is,” without any warranty
+** of any kind.
+**
+*****************************************************************************
+** @attention
+**
+** © COPYRIGHT(c) 2014 Ac6
+**
+** 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 Ac6 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.
+**
+*****************************************************************************
+*/
+
+/* Entry Point */
+ENTRY(Reset_Handler)
+
+/* Highest address of the user mode stack */
+_estack = 0x20010000; /* end of RAM */
+/* Generate a link error if heap and stack don't fit into RAM */
+_Min_Heap_Size = 0x200; /* required amount of heap */
+_Min_Stack_Size = 0x400; /* required amount of stack */
+
+/* Specify the memory areas */
+MEMORY
+{
+RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 64K
+FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 256K
+}
+
+/* Define output sections */
+SECTIONS
+{
+ /* The startup code goes first into FLASH */
+ .isr_vector :
+ {
+ . = ALIGN(8);
+ KEEP(*(.isr_vector)) /* Startup code */
+ . = ALIGN(8);
+ } >FLASH
+
+ /* The program code and other data goes into FLASH */
+ .text :
+ {
+ . = ALIGN(8);
+ *(.text) /* .text sections (code) */
+ *(.text*) /* .text* sections (code) */
+ *(.glue_7) /* glue arm to thumb code */
+ *(.glue_7t) /* glue thumb to arm code */
+ *(.eh_frame)
+
+ KEEP (*(.init))
+ KEEP (*(.fini))
+
+ . = ALIGN(8);
+ _etext = .; /* define a global symbols at end of code */
+ } >FLASH
+
+ /* Constant data goes into FLASH */
+ .rodata :
+ {
+ . = ALIGN(8);
+ *(.rodata) /* .rodata sections (constants, strings, etc.) */
+ *(.rodata*) /* .rodata* sections (constants, strings, etc.) */
+ . = ALIGN(8);
+ } >FLASH
+
+ .ARM.extab :
+ {
+ . = ALIGN(8);
+ *(.ARM.extab* .gnu.linkonce.armextab.*)
+ . = ALIGN(8);
+ } >FLASH
+ .ARM : {
+ . = ALIGN(8);
+ __exidx_start = .;
+ *(.ARM.exidx*)
+ __exidx_end = .;
+ . = ALIGN(8);
+ } >FLASH
+
+ .preinit_array :
+ {
+ . = ALIGN(8);
+ PROVIDE_HIDDEN (__preinit_array_start = .);
+ KEEP (*(.preinit_array*))
+ PROVIDE_HIDDEN (__preinit_array_end = .);
+ . = ALIGN(8);
+ } >FLASH
+
+ .init_array :
+ {
+ . = ALIGN(8);
+ PROVIDE_HIDDEN (__init_array_start = .);
+ KEEP (*(SORT(.init_array.*)))
+ KEEP (*(.init_array*))
+ PROVIDE_HIDDEN (__init_array_end = .);
+ . = ALIGN(8);
+ } >FLASH
+ .fini_array :
+ {
+ . = ALIGN(8);
+ PROVIDE_HIDDEN (__fini_array_start = .);
+ KEEP (*(SORT(.fini_array.*)))
+ KEEP (*(.fini_array*))
+ PROVIDE_HIDDEN (__fini_array_end = .);
+ . = ALIGN(8);
+ } >FLASH
+
+ /* used by the startup to initialize data */
+ _sidata = LOADADDR(.data);
+
+ /* Initialized data sections goes into RAM, load LMA copy after code */
+ .data :
+ {
+ . = ALIGN(8);
+ _sdata = .; /* create a global symbol at data start */
+ *(.data) /* .data sections */
+ *(.data*) /* .data* sections */
+
+ . = ALIGN(8);
+ _edata = .; /* define a global symbol at data end */
+ } >RAM AT> FLASH
+
+
+ /* Uninitialized data section */
+ . = ALIGN(4);
+ .bss :
+ {
+ /* This is used by the startup in order to initialize the .bss secion */
+ _sbss = .; /* define a global symbol at bss start */
+ __bss_start__ = _sbss;
+ *(.bss)
+ *(.bss*)
+ *(COMMON)
+
+ . = ALIGN(4);
+ _ebss = .; /* define a global symbol at bss end */
+ __bss_end__ = _ebss;
+ } >RAM
+
+ /* User_heap_stack section, used to check that there is enough RAM left */
+ ._user_heap_stack :
+ {
+ . = ALIGN(8);
+ PROVIDE ( end = . );
+ PROVIDE ( _end = . );
+ . = . + _Min_Heap_Size;
+ . = . + _Min_Stack_Size;
+ . = ALIGN(8);
+ } >RAM
+
+
+
+ /* Remove information from the standard libraries */
+ /DISCARD/ :
+ {
+ libc.a ( * )
+ libm.a ( * )
+ libgcc.a ( * )
+ }
+
+ .ARM.attributes 0 : { *(.ARM.attributes) }
+}
+
+
diff --git a/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/app_tencent_os_mqtt/startup_stm32l431xx.s b/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/app_tencent_os_mqtt/startup_stm32l431xx.s
new file mode 100644
index 00000000..d8f45f45
--- /dev/null
+++ b/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/app_tencent_os_mqtt/startup_stm32l431xx.s
@@ -0,0 +1,474 @@
+/**
+ ******************************************************************************
+ * @file startup_stm32l431xx.s
+ * @author MCD Application Team
+ * @brief STM32L431xx devices vector table for GCC toolchain.
+ * This module performs:
+ * - Set the initial SP
+ * - Set the initial PC == Reset_Handler,
+ * - Set the vector table entries with the exceptions ISR address,
+ * - Configure the clock system
+ * - Branches to main in the C library (which eventually
+ * calls main()).
+ * After Reset the Cortex-M4 processor is in Thread mode,
+ * priority is Privileged, and the Stack is set to Main.
+ ******************************************************************************
+ * @attention
+ *
+ * © COPYRIGHT(c) 2017 STMicroelectronics
+ *
+ * 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 STMicroelectronics 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.
+ *
+ ******************************************************************************
+ */
+
+ .syntax unified
+ .cpu cortex-m4
+ .fpu softvfp
+ .thumb
+
+.global g_pfnVectors
+.global Default_Handler
+
+/* start address for the initialization values of the .data section.
+defined in linker script */
+.word _sidata
+/* start address for the .data section. defined in linker script */
+.word _sdata
+/* end address for the .data section. defined in linker script */
+.word _edata
+/* start address for the .bss section. defined in linker script */
+.word _sbss
+/* end address for the .bss section. defined in linker script */
+.word _ebss
+
+.equ BootRAM, 0xF1E0F85F
+/**
+ * @brief This is the code that gets called when the processor first
+ * starts execution following a reset event. Only the absolutely
+ * necessary set is performed, after which the application
+ * supplied main() routine is called.
+ * @param None
+ * @retval : None
+*/
+
+ .section .text.Reset_Handler
+ .weak Reset_Handler
+ .type Reset_Handler, %function
+Reset_Handler:
+ ldr sp, =_estack /* Atollic update: set stack pointer */
+
+/* Copy the data segment initializers from flash to SRAM */
+ movs r1, #0
+ b LoopCopyDataInit
+
+CopyDataInit:
+ ldr r3, =_sidata
+ ldr r3, [r3, r1]
+ str r3, [r0, r1]
+ adds r1, r1, #4
+
+LoopCopyDataInit:
+ ldr r0, =_sdata
+ ldr r3, =_edata
+ adds r2, r0, r1
+ cmp r2, r3
+ bcc CopyDataInit
+ ldr r2, =_sbss
+ b LoopFillZerobss
+/* Zero fill the bss segment. */
+FillZerobss:
+ movs r3, #0
+ str r3, [r2], #4
+
+LoopFillZerobss:
+ ldr r3, = _ebss
+ cmp r2, r3
+ bcc FillZerobss
+
+/* Call the clock system intitialization function.*/
+ bl SystemInit
+/* Call static constructors */
+ bl __libc_init_array
+/* Call the application's entry point.*/
+ bl main
+
+LoopForever:
+ b LoopForever
+
+.size Reset_Handler, .-Reset_Handler
+
+/**
+ * @brief This is the code that gets called when the processor receives an
+ * unexpected interrupt. This simply enters an infinite loop, preserving
+ * the system state for examination by a debugger.
+ *
+ * @param None
+ * @retval : None
+*/
+ .section .text.Default_Handler,"ax",%progbits
+Default_Handler:
+Infinite_Loop:
+ b Infinite_Loop
+ .size Default_Handler, .-Default_Handler
+/******************************************************************************
+*
+* The minimal vector table for a Cortex-M4. Note that the proper constructs
+* must be placed on this to ensure that it ends up at physical address
+* 0x0000.0000.
+*
+******************************************************************************/
+ .section .isr_vector,"a",%progbits
+ .type g_pfnVectors, %object
+ .size g_pfnVectors, .-g_pfnVectors
+
+
+g_pfnVectors:
+ .word _estack
+ .word Reset_Handler
+ .word NMI_Handler
+ .word HardFault_Handler
+ .word MemManage_Handler
+ .word BusFault_Handler
+ .word UsageFault_Handler
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word SVC_Handler
+ .word DebugMon_Handler
+ .word 0
+ .word PendSV_Handler
+ .word SysTick_Handler
+ .word WWDG_IRQHandler
+ .word PVD_PVM_IRQHandler
+ .word TAMP_STAMP_IRQHandler
+ .word RTC_WKUP_IRQHandler
+ .word FLASH_IRQHandler
+ .word RCC_IRQHandler
+ .word EXTI0_IRQHandler
+ .word EXTI1_IRQHandler
+ .word EXTI2_IRQHandler
+ .word EXTI3_IRQHandler
+ .word EXTI4_IRQHandler
+ .word DMA1_Channel1_IRQHandler
+ .word DMA1_Channel2_IRQHandler
+ .word DMA1_Channel3_IRQHandler
+ .word DMA1_Channel4_IRQHandler
+ .word DMA1_Channel5_IRQHandler
+ .word DMA1_Channel6_IRQHandler
+ .word DMA1_Channel7_IRQHandler
+ .word ADC1_IRQHandler
+ .word CAN1_TX_IRQHandler
+ .word CAN1_RX0_IRQHandler
+ .word CAN1_RX1_IRQHandler
+ .word CAN1_SCE_IRQHandler
+ .word EXTI9_5_IRQHandler
+ .word TIM1_BRK_TIM15_IRQHandler
+ .word TIM1_UP_TIM16_IRQHandler
+ .word TIM1_TRG_COM_IRQHandler
+ .word TIM1_CC_IRQHandler
+ .word TIM2_IRQHandler
+ .word 0
+ .word 0
+ .word I2C1_EV_IRQHandler
+ .word I2C1_ER_IRQHandler
+ .word I2C2_EV_IRQHandler
+ .word I2C2_ER_IRQHandler
+ .word SPI1_IRQHandler
+ .word SPI2_IRQHandler
+ .word USART1_IRQHandler
+ .word USART2_IRQHandler
+ .word USART3_IRQHandler
+ .word EXTI15_10_IRQHandler
+ .word RTC_Alarm_IRQHandler
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word SDMMC1_IRQHandler
+ .word 0
+ .word SPI3_IRQHandler
+ .word 0
+ .word 0
+ .word TIM6_DAC_IRQHandler
+ .word TIM7_IRQHandler
+ .word DMA2_Channel1_IRQHandler
+ .word DMA2_Channel2_IRQHandler
+ .word DMA2_Channel3_IRQHandler
+ .word DMA2_Channel4_IRQHandler
+ .word DMA2_Channel5_IRQHandler
+ .word 0
+ .word 0
+ .word 0
+ .word COMP_IRQHandler
+ .word LPTIM1_IRQHandler
+ .word LPTIM2_IRQHandler
+ .word 0
+ .word DMA2_Channel6_IRQHandler
+ .word DMA2_Channel7_IRQHandler
+ .word LPUART1_IRQHandler
+ .word QUADSPI_IRQHandler
+ .word I2C3_EV_IRQHandler
+ .word I2C3_ER_IRQHandler
+ .word SAI1_IRQHandler
+ .word 0
+ .word SWPMI1_IRQHandler
+ .word TSC_IRQHandler
+ .word 0
+ .word 0
+ .word RNG_IRQHandler
+ .word FPU_IRQHandler
+ .word CRS_IRQHandler
+
+
+/*******************************************************************************
+*
+* Provide weak aliases for each Exception handler to the Default_Handler.
+* As they are weak aliases, any function with the same name will override
+* this definition.
+*
+*******************************************************************************/
+
+ .weak NMI_Handler
+ .thumb_set NMI_Handler,Default_Handler
+
+ .weak HardFault_Handler
+ .thumb_set HardFault_Handler,Default_Handler
+
+ .weak MemManage_Handler
+ .thumb_set MemManage_Handler,Default_Handler
+
+ .weak BusFault_Handler
+ .thumb_set BusFault_Handler,Default_Handler
+
+ .weak UsageFault_Handler
+ .thumb_set UsageFault_Handler,Default_Handler
+
+ .weak SVC_Handler
+ .thumb_set SVC_Handler,Default_Handler
+
+ .weak DebugMon_Handler
+ .thumb_set DebugMon_Handler,Default_Handler
+
+ .weak PendSV_Handler
+ .thumb_set PendSV_Handler,Default_Handler
+
+ .weak SysTick_Handler
+ .thumb_set SysTick_Handler,Default_Handler
+
+ .weak WWDG_IRQHandler
+ .thumb_set WWDG_IRQHandler,Default_Handler
+
+ .weak PVD_PVM_IRQHandler
+ .thumb_set PVD_PVM_IRQHandler,Default_Handler
+
+ .weak TAMP_STAMP_IRQHandler
+ .thumb_set TAMP_STAMP_IRQHandler,Default_Handler
+
+ .weak RTC_WKUP_IRQHandler
+ .thumb_set RTC_WKUP_IRQHandler,Default_Handler
+
+ .weak FLASH_IRQHandler
+ .thumb_set FLASH_IRQHandler,Default_Handler
+
+ .weak RCC_IRQHandler
+ .thumb_set RCC_IRQHandler,Default_Handler
+
+ .weak EXTI0_IRQHandler
+ .thumb_set EXTI0_IRQHandler,Default_Handler
+
+ .weak EXTI1_IRQHandler
+ .thumb_set EXTI1_IRQHandler,Default_Handler
+
+ .weak EXTI2_IRQHandler
+ .thumb_set EXTI2_IRQHandler,Default_Handler
+
+ .weak EXTI3_IRQHandler
+ .thumb_set EXTI3_IRQHandler,Default_Handler
+
+ .weak EXTI4_IRQHandler
+ .thumb_set EXTI4_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel1_IRQHandler
+ .thumb_set DMA1_Channel1_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel2_IRQHandler
+ .thumb_set DMA1_Channel2_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel3_IRQHandler
+ .thumb_set DMA1_Channel3_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel4_IRQHandler
+ .thumb_set DMA1_Channel4_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel5_IRQHandler
+ .thumb_set DMA1_Channel5_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel6_IRQHandler
+ .thumb_set DMA1_Channel6_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel7_IRQHandler
+ .thumb_set DMA1_Channel7_IRQHandler,Default_Handler
+
+ .weak ADC1_IRQHandler
+ .thumb_set ADC1_IRQHandler,Default_Handler
+
+ .weak CAN1_TX_IRQHandler
+ .thumb_set CAN1_TX_IRQHandler,Default_Handler
+
+ .weak CAN1_RX0_IRQHandler
+ .thumb_set CAN1_RX0_IRQHandler,Default_Handler
+
+ .weak CAN1_RX1_IRQHandler
+ .thumb_set CAN1_RX1_IRQHandler,Default_Handler
+
+ .weak CAN1_SCE_IRQHandler
+ .thumb_set CAN1_SCE_IRQHandler,Default_Handler
+
+ .weak EXTI9_5_IRQHandler
+ .thumb_set EXTI9_5_IRQHandler,Default_Handler
+
+ .weak TIM1_BRK_TIM15_IRQHandler
+ .thumb_set TIM1_BRK_TIM15_IRQHandler,Default_Handler
+
+ .weak TIM1_UP_TIM16_IRQHandler
+ .thumb_set TIM1_UP_TIM16_IRQHandler,Default_Handler
+
+ .weak TIM1_TRG_COM_IRQHandler
+ .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler
+
+ .weak TIM1_CC_IRQHandler
+ .thumb_set TIM1_CC_IRQHandler,Default_Handler
+
+ .weak TIM2_IRQHandler
+ .thumb_set TIM2_IRQHandler,Default_Handler
+
+ .weak I2C1_EV_IRQHandler
+ .thumb_set I2C1_EV_IRQHandler,Default_Handler
+
+ .weak I2C1_ER_IRQHandler
+ .thumb_set I2C1_ER_IRQHandler,Default_Handler
+
+ .weak I2C2_EV_IRQHandler
+ .thumb_set I2C2_EV_IRQHandler,Default_Handler
+
+ .weak I2C2_ER_IRQHandler
+ .thumb_set I2C2_ER_IRQHandler,Default_Handler
+
+ .weak SPI1_IRQHandler
+ .thumb_set SPI1_IRQHandler,Default_Handler
+
+ .weak SPI2_IRQHandler
+ .thumb_set SPI2_IRQHandler,Default_Handler
+
+ .weak USART1_IRQHandler
+ .thumb_set USART1_IRQHandler,Default_Handler
+
+ .weak USART2_IRQHandler
+ .thumb_set USART2_IRQHandler,Default_Handler
+
+ .weak USART3_IRQHandler
+ .thumb_set USART3_IRQHandler,Default_Handler
+
+ .weak EXTI15_10_IRQHandler
+ .thumb_set EXTI15_10_IRQHandler,Default_Handler
+
+ .weak RTC_Alarm_IRQHandler
+ .thumb_set RTC_Alarm_IRQHandler,Default_Handler
+
+ .weak SDMMC1_IRQHandler
+ .thumb_set SDMMC1_IRQHandler,Default_Handler
+
+ .weak SPI3_IRQHandler
+ .thumb_set SPI3_IRQHandler,Default_Handler
+
+ .weak TIM6_DAC_IRQHandler
+ .thumb_set TIM6_DAC_IRQHandler,Default_Handler
+
+ .weak TIM7_IRQHandler
+ .thumb_set TIM7_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel1_IRQHandler
+ .thumb_set DMA2_Channel1_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel2_IRQHandler
+ .thumb_set DMA2_Channel2_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel3_IRQHandler
+ .thumb_set DMA2_Channel3_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel4_IRQHandler
+ .thumb_set DMA2_Channel4_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel5_IRQHandler
+ .thumb_set DMA2_Channel5_IRQHandler,Default_Handler
+
+ .weak COMP_IRQHandler
+ .thumb_set COMP_IRQHandler,Default_Handler
+
+ .weak LPTIM1_IRQHandler
+ .thumb_set LPTIM1_IRQHandler,Default_Handler
+
+ .weak LPTIM2_IRQHandler
+ .thumb_set LPTIM2_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel6_IRQHandler
+ .thumb_set DMA2_Channel6_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel7_IRQHandler
+ .thumb_set DMA2_Channel7_IRQHandler,Default_Handler
+
+ .weak LPUART1_IRQHandler
+ .thumb_set LPUART1_IRQHandler,Default_Handler
+
+ .weak QUADSPI_IRQHandler
+ .thumb_set QUADSPI_IRQHandler,Default_Handler
+
+ .weak I2C3_EV_IRQHandler
+ .thumb_set I2C3_EV_IRQHandler,Default_Handler
+
+ .weak I2C3_ER_IRQHandler
+ .thumb_set I2C3_ER_IRQHandler,Default_Handler
+
+ .weak SAI1_IRQHandler
+ .thumb_set SAI1_IRQHandler,Default_Handler
+
+ .weak SWPMI1_IRQHandler
+ .thumb_set SWPMI1_IRQHandler,Default_Handler
+
+ .weak TSC_IRQHandler
+ .thumb_set TSC_IRQHandler,Default_Handler
+
+ .weak RNG_IRQHandler
+ .thumb_set RNG_IRQHandler,Default_Handler
+
+ .weak FPU_IRQHandler
+ .thumb_set FPU_IRQHandler,Default_Handler
+
+ .weak CRS_IRQHandler
+ .thumb_set CRS_IRQHandler,Default_Handler
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/app_udp_through_module/Makefile b/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/app_udp_through_module/Makefile
new file mode 100644
index 00000000..dfd18e9d
--- /dev/null
+++ b/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/app_udp_through_module/Makefile
@@ -0,0 +1,68 @@
+###################################################################
+#automatic detection QTOP and LOCALDIR
+CUR_DIR := $(patsubst %/,%,$(dir $(realpath $(firstword $(MAKEFILE_LIST)))))
+TRYQTOP := $(shell if [ -n "$$QTOP" ] ; then\
+ echo $$QTOP;\
+ else\
+ cd $(CUR_DIR); while /usr/bin/test ! -e qmk ; do \
+ dir=`cd ../;pwd`; \
+ if [ "$$dir" = "/" ] ; then \
+ echo Cannot find QTOP in $(firstword $(MAKEFILE_LIST)) 1>&2; \
+ exit 1; \
+ fi ; \
+ cd $$dir; \
+ done ; \
+ pwd; \
+ fi)
+QTOP ?= $(realpath ${TRYQTOP})
+
+ifeq ($(QTOP),)
+$(error Please run this in a tree)
+endif
+LOCALDIR = $(patsubst %/,%,$(subst $(realpath $(QTOP))/,,$(CUR_DIR)))
+export QTOP
+
+####################################################################
+
+
+export BP=TencentOS_tiny_EVB_MX_Plus
+
+TREE_LIB_ENABLE=1
+lib=
+subdirs =
+
+LSRCS += $(QTOP)/examples/udp_through_module/udp_through_module.c
+LSRCS += $(wildcard *.s)
+
+all::
+ make -C ${QTOP}/arch BP=${BP}
+ make -C ${QTOP}/kernel BP=${BP}
+ make -C ${QTOP}/osal BP=${BP}
+ make -C ${QTOP}/platform BP=${BP}
+ make -C ${QTOP}/board/TencentOS_tiny_EVB_MX_Plus/BSP BP=${BP}
+ make -C ${QTOP}/components/connectivity/Eclipse-Paho-MQTT BP=${BP}
+ make -C ${QTOP}/devices BP=${BP}
+ make -C ${QTOP}/net/at BP=${BP}
+ make -C ${QTOP}/net/tencent_firmware_module_wrapper BP=${BP}
+ make -C ${QTOP}/net/sal_module_wrapper BP=${BP}
+ make -C ${QTOP}/net/socket_wrapper BP=${BP}
+#exec =
+LD_A_FILES += $(LIBDIR)/libarch.a
+LD_A_FILES += $(LIBDIR)/libkernel.a
+LD_A_FILES += $(LIBDIR)/lib$(notdir $(CUR_DIR)).a
+LD_A_FILES += $(LIBDIR)/libcmsis_os.a
+LD_A_FILES += $(LIBDIR)/libvendor_bsp.a
+LD_A_FILES += $(LIBDIR)/libhal.a
+LD_A_FILES += $(LIBDIR)/libBSP.a
+LD_A_FILES += $(LIBDIR)/libEclipse-Paho-MQTT.a
+LD_A_FILES += $(LIBDIR)/libesp8266_tencent_firmware.a
+LD_A_FILES += $(LIBDIR)/libesp8266.a
+LD_A_FILES += $(LIBDIR)/libat.a
+LD_A_FILES += $(LIBDIR)/libtencent_firmware_module_wrapper.a
+LD_A_FILES += $(LIBDIR)/libsal_module_wrapper.a
+LD_A_FILES += $(LIBDIR)/libsocket_wrapper.a
+LD_A_LISTS += -lc -lm -lnosys
+LD_L_LISTS += -specs=nosys.specs -T$(CUR_DIR)/STM32L431RCTx_FLASH.ld -Wl,-Map=$(LIBDIR)/$(notdir $(CUR_DIR)).map,--cref -Wl,--gc-sections
+include ${QTOP}/qmk/generic/Make.exec
+
+
diff --git a/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/app_udp_through_module/STM32L431RCTx_FLASH.ld b/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/app_udp_through_module/STM32L431RCTx_FLASH.ld
new file mode 100644
index 00000000..3d07935e
--- /dev/null
+++ b/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/app_udp_through_module/STM32L431RCTx_FLASH.ld
@@ -0,0 +1,203 @@
+/*
+******************************************************************************
+**
+
+** File : LinkerScript.ld
+**
+** Author : Auto-generated by Ac6 System Workbench
+**
+** Abstract : Linker script for STM32L431RCTx series
+** 256Kbytes FLASH and 64Kbytes RAM
+**
+** Set heap size, stack size and stack location according
+** to application requirements.
+**
+** Set memory bank area and size if external memory is used.
+**
+** Target : STMicroelectronics STM32
+**
+** Distribution: The file is distributed “as is,” without any warranty
+** of any kind.
+**
+*****************************************************************************
+** @attention
+**
+** © COPYRIGHT(c) 2014 Ac6
+**
+** 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 Ac6 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.
+**
+*****************************************************************************
+*/
+
+/* Entry Point */
+ENTRY(Reset_Handler)
+
+/* Highest address of the user mode stack */
+_estack = 0x20010000; /* end of RAM */
+/* Generate a link error if heap and stack don't fit into RAM */
+_Min_Heap_Size = 0x200; /* required amount of heap */
+_Min_Stack_Size = 0x400; /* required amount of stack */
+
+/* Specify the memory areas */
+MEMORY
+{
+RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 64K
+FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 256K
+}
+
+/* Define output sections */
+SECTIONS
+{
+ /* The startup code goes first into FLASH */
+ .isr_vector :
+ {
+ . = ALIGN(8);
+ KEEP(*(.isr_vector)) /* Startup code */
+ . = ALIGN(8);
+ } >FLASH
+
+ /* The program code and other data goes into FLASH */
+ .text :
+ {
+ . = ALIGN(8);
+ *(.text) /* .text sections (code) */
+ *(.text*) /* .text* sections (code) */
+ *(.glue_7) /* glue arm to thumb code */
+ *(.glue_7t) /* glue thumb to arm code */
+ *(.eh_frame)
+
+ KEEP (*(.init))
+ KEEP (*(.fini))
+
+ . = ALIGN(8);
+ _etext = .; /* define a global symbols at end of code */
+ } >FLASH
+
+ /* Constant data goes into FLASH */
+ .rodata :
+ {
+ . = ALIGN(8);
+ *(.rodata) /* .rodata sections (constants, strings, etc.) */
+ *(.rodata*) /* .rodata* sections (constants, strings, etc.) */
+ . = ALIGN(8);
+ } >FLASH
+
+ .ARM.extab :
+ {
+ . = ALIGN(8);
+ *(.ARM.extab* .gnu.linkonce.armextab.*)
+ . = ALIGN(8);
+ } >FLASH
+ .ARM : {
+ . = ALIGN(8);
+ __exidx_start = .;
+ *(.ARM.exidx*)
+ __exidx_end = .;
+ . = ALIGN(8);
+ } >FLASH
+
+ .preinit_array :
+ {
+ . = ALIGN(8);
+ PROVIDE_HIDDEN (__preinit_array_start = .);
+ KEEP (*(.preinit_array*))
+ PROVIDE_HIDDEN (__preinit_array_end = .);
+ . = ALIGN(8);
+ } >FLASH
+
+ .init_array :
+ {
+ . = ALIGN(8);
+ PROVIDE_HIDDEN (__init_array_start = .);
+ KEEP (*(SORT(.init_array.*)))
+ KEEP (*(.init_array*))
+ PROVIDE_HIDDEN (__init_array_end = .);
+ . = ALIGN(8);
+ } >FLASH
+ .fini_array :
+ {
+ . = ALIGN(8);
+ PROVIDE_HIDDEN (__fini_array_start = .);
+ KEEP (*(SORT(.fini_array.*)))
+ KEEP (*(.fini_array*))
+ PROVIDE_HIDDEN (__fini_array_end = .);
+ . = ALIGN(8);
+ } >FLASH
+
+ /* used by the startup to initialize data */
+ _sidata = LOADADDR(.data);
+
+ /* Initialized data sections goes into RAM, load LMA copy after code */
+ .data :
+ {
+ . = ALIGN(8);
+ _sdata = .; /* create a global symbol at data start */
+ *(.data) /* .data sections */
+ *(.data*) /* .data* sections */
+
+ . = ALIGN(8);
+ _edata = .; /* define a global symbol at data end */
+ } >RAM AT> FLASH
+
+
+ /* Uninitialized data section */
+ . = ALIGN(4);
+ .bss :
+ {
+ /* This is used by the startup in order to initialize the .bss secion */
+ _sbss = .; /* define a global symbol at bss start */
+ __bss_start__ = _sbss;
+ *(.bss)
+ *(.bss*)
+ *(COMMON)
+
+ . = ALIGN(4);
+ _ebss = .; /* define a global symbol at bss end */
+ __bss_end__ = _ebss;
+ } >RAM
+
+ /* User_heap_stack section, used to check that there is enough RAM left */
+ ._user_heap_stack :
+ {
+ . = ALIGN(8);
+ PROVIDE ( end = . );
+ PROVIDE ( _end = . );
+ . = . + _Min_Heap_Size;
+ . = . + _Min_Stack_Size;
+ . = ALIGN(8);
+ } >RAM
+
+
+
+ /* Remove information from the standard libraries */
+ /DISCARD/ :
+ {
+ libc.a ( * )
+ libm.a ( * )
+ libgcc.a ( * )
+ }
+
+ .ARM.attributes 0 : { *(.ARM.attributes) }
+}
+
+
diff --git a/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/app_udp_through_module/startup_stm32l431xx.s b/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/app_udp_through_module/startup_stm32l431xx.s
new file mode 100644
index 00000000..d8f45f45
--- /dev/null
+++ b/board/TencentOS_tiny_EVB_MX_Plus/GCC-QMK/app_udp_through_module/startup_stm32l431xx.s
@@ -0,0 +1,474 @@
+/**
+ ******************************************************************************
+ * @file startup_stm32l431xx.s
+ * @author MCD Application Team
+ * @brief STM32L431xx devices vector table for GCC toolchain.
+ * This module performs:
+ * - Set the initial SP
+ * - Set the initial PC == Reset_Handler,
+ * - Set the vector table entries with the exceptions ISR address,
+ * - Configure the clock system
+ * - Branches to main in the C library (which eventually
+ * calls main()).
+ * After Reset the Cortex-M4 processor is in Thread mode,
+ * priority is Privileged, and the Stack is set to Main.
+ ******************************************************************************
+ * @attention
+ *
+ * © COPYRIGHT(c) 2017 STMicroelectronics
+ *
+ * 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 STMicroelectronics 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.
+ *
+ ******************************************************************************
+ */
+
+ .syntax unified
+ .cpu cortex-m4
+ .fpu softvfp
+ .thumb
+
+.global g_pfnVectors
+.global Default_Handler
+
+/* start address for the initialization values of the .data section.
+defined in linker script */
+.word _sidata
+/* start address for the .data section. defined in linker script */
+.word _sdata
+/* end address for the .data section. defined in linker script */
+.word _edata
+/* start address for the .bss section. defined in linker script */
+.word _sbss
+/* end address for the .bss section. defined in linker script */
+.word _ebss
+
+.equ BootRAM, 0xF1E0F85F
+/**
+ * @brief This is the code that gets called when the processor first
+ * starts execution following a reset event. Only the absolutely
+ * necessary set is performed, after which the application
+ * supplied main() routine is called.
+ * @param None
+ * @retval : None
+*/
+
+ .section .text.Reset_Handler
+ .weak Reset_Handler
+ .type Reset_Handler, %function
+Reset_Handler:
+ ldr sp, =_estack /* Atollic update: set stack pointer */
+
+/* Copy the data segment initializers from flash to SRAM */
+ movs r1, #0
+ b LoopCopyDataInit
+
+CopyDataInit:
+ ldr r3, =_sidata
+ ldr r3, [r3, r1]
+ str r3, [r0, r1]
+ adds r1, r1, #4
+
+LoopCopyDataInit:
+ ldr r0, =_sdata
+ ldr r3, =_edata
+ adds r2, r0, r1
+ cmp r2, r3
+ bcc CopyDataInit
+ ldr r2, =_sbss
+ b LoopFillZerobss
+/* Zero fill the bss segment. */
+FillZerobss:
+ movs r3, #0
+ str r3, [r2], #4
+
+LoopFillZerobss:
+ ldr r3, = _ebss
+ cmp r2, r3
+ bcc FillZerobss
+
+/* Call the clock system intitialization function.*/
+ bl SystemInit
+/* Call static constructors */
+ bl __libc_init_array
+/* Call the application's entry point.*/
+ bl main
+
+LoopForever:
+ b LoopForever
+
+.size Reset_Handler, .-Reset_Handler
+
+/**
+ * @brief This is the code that gets called when the processor receives an
+ * unexpected interrupt. This simply enters an infinite loop, preserving
+ * the system state for examination by a debugger.
+ *
+ * @param None
+ * @retval : None
+*/
+ .section .text.Default_Handler,"ax",%progbits
+Default_Handler:
+Infinite_Loop:
+ b Infinite_Loop
+ .size Default_Handler, .-Default_Handler
+/******************************************************************************
+*
+* The minimal vector table for a Cortex-M4. Note that the proper constructs
+* must be placed on this to ensure that it ends up at physical address
+* 0x0000.0000.
+*
+******************************************************************************/
+ .section .isr_vector,"a",%progbits
+ .type g_pfnVectors, %object
+ .size g_pfnVectors, .-g_pfnVectors
+
+
+g_pfnVectors:
+ .word _estack
+ .word Reset_Handler
+ .word NMI_Handler
+ .word HardFault_Handler
+ .word MemManage_Handler
+ .word BusFault_Handler
+ .word UsageFault_Handler
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word SVC_Handler
+ .word DebugMon_Handler
+ .word 0
+ .word PendSV_Handler
+ .word SysTick_Handler
+ .word WWDG_IRQHandler
+ .word PVD_PVM_IRQHandler
+ .word TAMP_STAMP_IRQHandler
+ .word RTC_WKUP_IRQHandler
+ .word FLASH_IRQHandler
+ .word RCC_IRQHandler
+ .word EXTI0_IRQHandler
+ .word EXTI1_IRQHandler
+ .word EXTI2_IRQHandler
+ .word EXTI3_IRQHandler
+ .word EXTI4_IRQHandler
+ .word DMA1_Channel1_IRQHandler
+ .word DMA1_Channel2_IRQHandler
+ .word DMA1_Channel3_IRQHandler
+ .word DMA1_Channel4_IRQHandler
+ .word DMA1_Channel5_IRQHandler
+ .word DMA1_Channel6_IRQHandler
+ .word DMA1_Channel7_IRQHandler
+ .word ADC1_IRQHandler
+ .word CAN1_TX_IRQHandler
+ .word CAN1_RX0_IRQHandler
+ .word CAN1_RX1_IRQHandler
+ .word CAN1_SCE_IRQHandler
+ .word EXTI9_5_IRQHandler
+ .word TIM1_BRK_TIM15_IRQHandler
+ .word TIM1_UP_TIM16_IRQHandler
+ .word TIM1_TRG_COM_IRQHandler
+ .word TIM1_CC_IRQHandler
+ .word TIM2_IRQHandler
+ .word 0
+ .word 0
+ .word I2C1_EV_IRQHandler
+ .word I2C1_ER_IRQHandler
+ .word I2C2_EV_IRQHandler
+ .word I2C2_ER_IRQHandler
+ .word SPI1_IRQHandler
+ .word SPI2_IRQHandler
+ .word USART1_IRQHandler
+ .word USART2_IRQHandler
+ .word USART3_IRQHandler
+ .word EXTI15_10_IRQHandler
+ .word RTC_Alarm_IRQHandler
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word SDMMC1_IRQHandler
+ .word 0
+ .word SPI3_IRQHandler
+ .word 0
+ .word 0
+ .word TIM6_DAC_IRQHandler
+ .word TIM7_IRQHandler
+ .word DMA2_Channel1_IRQHandler
+ .word DMA2_Channel2_IRQHandler
+ .word DMA2_Channel3_IRQHandler
+ .word DMA2_Channel4_IRQHandler
+ .word DMA2_Channel5_IRQHandler
+ .word 0
+ .word 0
+ .word 0
+ .word COMP_IRQHandler
+ .word LPTIM1_IRQHandler
+ .word LPTIM2_IRQHandler
+ .word 0
+ .word DMA2_Channel6_IRQHandler
+ .word DMA2_Channel7_IRQHandler
+ .word LPUART1_IRQHandler
+ .word QUADSPI_IRQHandler
+ .word I2C3_EV_IRQHandler
+ .word I2C3_ER_IRQHandler
+ .word SAI1_IRQHandler
+ .word 0
+ .word SWPMI1_IRQHandler
+ .word TSC_IRQHandler
+ .word 0
+ .word 0
+ .word RNG_IRQHandler
+ .word FPU_IRQHandler
+ .word CRS_IRQHandler
+
+
+/*******************************************************************************
+*
+* Provide weak aliases for each Exception handler to the Default_Handler.
+* As they are weak aliases, any function with the same name will override
+* this definition.
+*
+*******************************************************************************/
+
+ .weak NMI_Handler
+ .thumb_set NMI_Handler,Default_Handler
+
+ .weak HardFault_Handler
+ .thumb_set HardFault_Handler,Default_Handler
+
+ .weak MemManage_Handler
+ .thumb_set MemManage_Handler,Default_Handler
+
+ .weak BusFault_Handler
+ .thumb_set BusFault_Handler,Default_Handler
+
+ .weak UsageFault_Handler
+ .thumb_set UsageFault_Handler,Default_Handler
+
+ .weak SVC_Handler
+ .thumb_set SVC_Handler,Default_Handler
+
+ .weak DebugMon_Handler
+ .thumb_set DebugMon_Handler,Default_Handler
+
+ .weak PendSV_Handler
+ .thumb_set PendSV_Handler,Default_Handler
+
+ .weak SysTick_Handler
+ .thumb_set SysTick_Handler,Default_Handler
+
+ .weak WWDG_IRQHandler
+ .thumb_set WWDG_IRQHandler,Default_Handler
+
+ .weak PVD_PVM_IRQHandler
+ .thumb_set PVD_PVM_IRQHandler,Default_Handler
+
+ .weak TAMP_STAMP_IRQHandler
+ .thumb_set TAMP_STAMP_IRQHandler,Default_Handler
+
+ .weak RTC_WKUP_IRQHandler
+ .thumb_set RTC_WKUP_IRQHandler,Default_Handler
+
+ .weak FLASH_IRQHandler
+ .thumb_set FLASH_IRQHandler,Default_Handler
+
+ .weak RCC_IRQHandler
+ .thumb_set RCC_IRQHandler,Default_Handler
+
+ .weak EXTI0_IRQHandler
+ .thumb_set EXTI0_IRQHandler,Default_Handler
+
+ .weak EXTI1_IRQHandler
+ .thumb_set EXTI1_IRQHandler,Default_Handler
+
+ .weak EXTI2_IRQHandler
+ .thumb_set EXTI2_IRQHandler,Default_Handler
+
+ .weak EXTI3_IRQHandler
+ .thumb_set EXTI3_IRQHandler,Default_Handler
+
+ .weak EXTI4_IRQHandler
+ .thumb_set EXTI4_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel1_IRQHandler
+ .thumb_set DMA1_Channel1_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel2_IRQHandler
+ .thumb_set DMA1_Channel2_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel3_IRQHandler
+ .thumb_set DMA1_Channel3_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel4_IRQHandler
+ .thumb_set DMA1_Channel4_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel5_IRQHandler
+ .thumb_set DMA1_Channel5_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel6_IRQHandler
+ .thumb_set DMA1_Channel6_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel7_IRQHandler
+ .thumb_set DMA1_Channel7_IRQHandler,Default_Handler
+
+ .weak ADC1_IRQHandler
+ .thumb_set ADC1_IRQHandler,Default_Handler
+
+ .weak CAN1_TX_IRQHandler
+ .thumb_set CAN1_TX_IRQHandler,Default_Handler
+
+ .weak CAN1_RX0_IRQHandler
+ .thumb_set CAN1_RX0_IRQHandler,Default_Handler
+
+ .weak CAN1_RX1_IRQHandler
+ .thumb_set CAN1_RX1_IRQHandler,Default_Handler
+
+ .weak CAN1_SCE_IRQHandler
+ .thumb_set CAN1_SCE_IRQHandler,Default_Handler
+
+ .weak EXTI9_5_IRQHandler
+ .thumb_set EXTI9_5_IRQHandler,Default_Handler
+
+ .weak TIM1_BRK_TIM15_IRQHandler
+ .thumb_set TIM1_BRK_TIM15_IRQHandler,Default_Handler
+
+ .weak TIM1_UP_TIM16_IRQHandler
+ .thumb_set TIM1_UP_TIM16_IRQHandler,Default_Handler
+
+ .weak TIM1_TRG_COM_IRQHandler
+ .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler
+
+ .weak TIM1_CC_IRQHandler
+ .thumb_set TIM1_CC_IRQHandler,Default_Handler
+
+ .weak TIM2_IRQHandler
+ .thumb_set TIM2_IRQHandler,Default_Handler
+
+ .weak I2C1_EV_IRQHandler
+ .thumb_set I2C1_EV_IRQHandler,Default_Handler
+
+ .weak I2C1_ER_IRQHandler
+ .thumb_set I2C1_ER_IRQHandler,Default_Handler
+
+ .weak I2C2_EV_IRQHandler
+ .thumb_set I2C2_EV_IRQHandler,Default_Handler
+
+ .weak I2C2_ER_IRQHandler
+ .thumb_set I2C2_ER_IRQHandler,Default_Handler
+
+ .weak SPI1_IRQHandler
+ .thumb_set SPI1_IRQHandler,Default_Handler
+
+ .weak SPI2_IRQHandler
+ .thumb_set SPI2_IRQHandler,Default_Handler
+
+ .weak USART1_IRQHandler
+ .thumb_set USART1_IRQHandler,Default_Handler
+
+ .weak USART2_IRQHandler
+ .thumb_set USART2_IRQHandler,Default_Handler
+
+ .weak USART3_IRQHandler
+ .thumb_set USART3_IRQHandler,Default_Handler
+
+ .weak EXTI15_10_IRQHandler
+ .thumb_set EXTI15_10_IRQHandler,Default_Handler
+
+ .weak RTC_Alarm_IRQHandler
+ .thumb_set RTC_Alarm_IRQHandler,Default_Handler
+
+ .weak SDMMC1_IRQHandler
+ .thumb_set SDMMC1_IRQHandler,Default_Handler
+
+ .weak SPI3_IRQHandler
+ .thumb_set SPI3_IRQHandler,Default_Handler
+
+ .weak TIM6_DAC_IRQHandler
+ .thumb_set TIM6_DAC_IRQHandler,Default_Handler
+
+ .weak TIM7_IRQHandler
+ .thumb_set TIM7_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel1_IRQHandler
+ .thumb_set DMA2_Channel1_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel2_IRQHandler
+ .thumb_set DMA2_Channel2_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel3_IRQHandler
+ .thumb_set DMA2_Channel3_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel4_IRQHandler
+ .thumb_set DMA2_Channel4_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel5_IRQHandler
+ .thumb_set DMA2_Channel5_IRQHandler,Default_Handler
+
+ .weak COMP_IRQHandler
+ .thumb_set COMP_IRQHandler,Default_Handler
+
+ .weak LPTIM1_IRQHandler
+ .thumb_set LPTIM1_IRQHandler,Default_Handler
+
+ .weak LPTIM2_IRQHandler
+ .thumb_set LPTIM2_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel6_IRQHandler
+ .thumb_set DMA2_Channel6_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel7_IRQHandler
+ .thumb_set DMA2_Channel7_IRQHandler,Default_Handler
+
+ .weak LPUART1_IRQHandler
+ .thumb_set LPUART1_IRQHandler,Default_Handler
+
+ .weak QUADSPI_IRQHandler
+ .thumb_set QUADSPI_IRQHandler,Default_Handler
+
+ .weak I2C3_EV_IRQHandler
+ .thumb_set I2C3_EV_IRQHandler,Default_Handler
+
+ .weak I2C3_ER_IRQHandler
+ .thumb_set I2C3_ER_IRQHandler,Default_Handler
+
+ .weak SAI1_IRQHandler
+ .thumb_set SAI1_IRQHandler,Default_Handler
+
+ .weak SWPMI1_IRQHandler
+ .thumb_set SWPMI1_IRQHandler,Default_Handler
+
+ .weak TSC_IRQHandler
+ .thumb_set TSC_IRQHandler,Default_Handler
+
+ .weak RNG_IRQHandler
+ .thumb_set RNG_IRQHandler,Default_Handler
+
+ .weak FPU_IRQHandler
+ .thumb_set FPU_IRQHandler,Default_Handler
+
+ .weak CRS_IRQHandler
+ .thumb_set CRS_IRQHandler,Default_Handler
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/net/at/Makefile b/net/at/Makefile
index c5126dc4..a82c0e54 100644
--- a/net/at/Makefile
+++ b/net/at/Makefile
@@ -24,7 +24,7 @@ LOCALDIR = $(patsubst %/,%,$(subst $(realpath $(QTOP))/,,$(CUR_DIR)))
####################################################################
-TREE_LIB_ENABLE=0
+TREE_LIB_ENABLE=1
lib=
subdirs=
diff --git a/platform/Makefile b/platform/Makefile
new file mode 100644
index 00000000..dab511e5
--- /dev/null
+++ b/platform/Makefile
@@ -0,0 +1,32 @@
+###################################################################
+#automatic detection QTOP and LOCALDIR
+CUR_DIR := $(patsubst %/,%,$(dir $(realpath $(firstword $(MAKEFILE_LIST)))))
+TRYQTOP := $(shell if [ -n "$$QTOP" ] ; then\
+ echo $$QTOP;\
+ else\
+ cd $(CUR_DIR); while /usr/bin/test ! -e qmk ; do \
+ dir=`cd ../;pwd`; \
+ if [ "$$dir" = "/" ] ; then \
+ echo Cannot find QTOP in $(firstword $(MAKEFILE_LIST)) 1>&2; \
+ exit 1; \
+ fi ; \
+ cd $$dir; \
+ done ; \
+ pwd; \
+ fi)
+QTOP ?= $(realpath ${TRYQTOP})
+
+ifeq ($(QTOP),)
+$(error Please run this in a tree)
+endif
+LOCALDIR = $(patsubst %/,%,$(subst $(realpath $(QTOP))/,,$(CUR_DIR)))
+####################################################################
+
+
+TREE_LIB_ENABLE=0
+lib=
+subdirs=
+
+
+include ${QTOP}/qmk/generic/Make.tpl
+
diff --git a/platform/hal/Makefile b/platform/hal/Makefile
new file mode 100644
index 00000000..77db6a0f
--- /dev/null
+++ b/platform/hal/Makefile
@@ -0,0 +1,47 @@
+###################################################################
+#automatic detection QTOP and LOCALDIR
+CUR_DIR := $(patsubst %/,%,$(dir $(realpath $(firstword $(MAKEFILE_LIST)))))
+TRYQTOP := $(shell if [ -n "$$QTOP" ] ; then\
+ echo $$QTOP;\
+ else\
+ cd $(CUR_DIR); while /usr/bin/test ! -d qmk ; do \
+ dir=`cd ../;pwd`; \
+ if [ "$$dir" = "/" ] ; then \
+ echo Cannot find QTOP in $(firstword $(MAKEFILE_LIST)) 1>&2; \
+ exit 1; \
+ fi ; \
+ cd $$dir; \
+ done ; \
+ pwd; \
+ fi)
+QTOP ?= $(realpath ${TRYQTOP})
+
+ifeq ($(QTOP),)
+$(error Please run this in a tree)
+endif
+LOCALDIR = $(patsubst %/,%,$(subst $(realpath $(QTOP))/,,$(CUR_DIR)))
+
+####################################################################
+
+
+TREE_LIB_ENABLE=0
+lib=
+subdirs=
+ifneq (help,$(findstring help,$(MAKECMDGOALS)))
+
+ifeq (, $(strip ${BP}))
+$(error when compile arch/, must specify BP and PLATFORM_HAL_LSRCS obviously , see `make help`)
+endif
+
+include ${QTOP}/qmk/board-pack/bp.${BP}
+
+ifeq (,$(strip ${PLATFORM_HAL_LSRCS}))
+$(error when compile arch/, must specify BP and PLATFORM_HAL_LSRCS obviously , see `make help`)
+endif
+endif
+
+# arch src should be specify by bp
+LSRCS := $(subst $(QTOP)/$(LOCALDIR)/,, ${PLATFORM_HAL_LSRCS})
+include ${QTOP}/qmk/generic/Make.tpl
+
+
diff --git a/platform/vendor_bsp/Makefile b/platform/vendor_bsp/Makefile
new file mode 100644
index 00000000..64aaf7eb
--- /dev/null
+++ b/platform/vendor_bsp/Makefile
@@ -0,0 +1,47 @@
+###################################################################
+#automatic detection QTOP and LOCALDIR
+CUR_DIR := $(patsubst %/,%,$(dir $(realpath $(firstword $(MAKEFILE_LIST)))))
+TRYQTOP := $(shell if [ -n "$$QTOP" ] ; then\
+ echo $$QTOP;\
+ else\
+ cd $(CUR_DIR); while /usr/bin/test ! -d qmk ; do \
+ dir=`cd ../;pwd`; \
+ if [ "$$dir" = "/" ] ; then \
+ echo Cannot find QTOP in $(firstword $(MAKEFILE_LIST)) 1>&2; \
+ exit 1; \
+ fi ; \
+ cd $$dir; \
+ done ; \
+ pwd; \
+ fi)
+QTOP ?= $(realpath ${TRYQTOP})
+
+ifeq ($(QTOP),)
+$(error Please run this in a tree)
+endif
+LOCALDIR = $(patsubst %/,%,$(subst $(realpath $(QTOP))/,,$(CUR_DIR)))
+
+####################################################################
+
+
+TREE_LIB_ENABLE=0
+lib=
+subdirs=
+ifneq (help,$(findstring help,$(MAKECMDGOALS)))
+
+ifeq (, $(strip ${BP}))
+$(error when compile arch/, must specify BP and PLATFORM_VENDOR_BSP_LSRCS obviously , see `make help`)
+endif
+
+include ${QTOP}/qmk/board-pack/bp.${BP}
+
+ifeq (,$(strip ${PLATFORM_VENDOR_BSP_LSRCS}))
+$(error when compile arch/, must specify BP and PLATFORM_VENDOR_BSP_LSRCS obviously , see `make help`)
+endif
+endif
+
+# arch src should be specify by bp
+LSRCS := $(subst $(QTOP)/$(LOCALDIR)/,, ${PLATFORM_VENDOR_BSP_LSRCS})
+include ${QTOP}/qmk/generic/Make.tpl
+
+
diff --git a/qmk/arch-pack/ap.linux.posix.gcc b/qmk/arch-pack/ap.linux.posix.gcc
deleted file mode 100644
index f189bc06..00000000
--- a/qmk/arch-pack/ap.linux.posix.gcc
+++ /dev/null
@@ -1,8 +0,0 @@
-
-CFGFLAGS += -I${QTOP}/arch/linux/common/include/
-CFGFLAGS += -I${QTOP}/arch/linux/posix/gcc
-
-
-
-ARCH_LSCRS := $(wildcard ${QTOP}/arch/linux/posix/gcc/*.c)
-ARCH_LSCRS += $(wildcard ${QTOP}/arch/linux/common/*.c)
diff --git a/qmk/arch-pack/apconfig b/qmk/arch-pack/apconfig
deleted file mode 100644
index e69de29b..00000000
diff --git a/qmk/board-pack/bp.Linux_Posix b/qmk/board-pack/bp.Linux_Posix
index f06697f6..eff58e0a 100644
--- a/qmk/board-pack/bp.Linux_Posix
+++ b/qmk/board-pack/bp.Linux_Posix
@@ -22,7 +22,14 @@ ifeq ($(filter-out Linux Darwin,$(uname)),)
endif
endif
-include ${QTOP}/qmk/arch-pack/ap.linux.posix.gcc
+
+CFGFLAGS += -I${QTOP}/arch/linux/common/include/
+CFGFLAGS += -I${QTOP}/arch/linux/posix/gcc
+
+
+
+ARCH_LSCRS := $(wildcard ${QTOP}/arch/linux/posix/gcc/*.c)
+ARCH_LSCRS += $(wildcard ${QTOP}/arch/linux/common/*.c)
CFGFLAGS += -O0 -Wall -g2 -ggdb
diff --git a/qmk/board-pack/bp.TencentOS_tiny_EVB_MX_Plus b/qmk/board-pack/bp.TencentOS_tiny_EVB_MX_Plus
new file mode 100644
index 00000000..f318fe98
--- /dev/null
+++ b/qmk/board-pack/bp.TencentOS_tiny_EVB_MX_Plus
@@ -0,0 +1,88 @@
+CROSS_COMPILE =arm-none-eabi-
+CC = $(CROSS_COMPILE)gcc
+CXX = $(CROSS_COMPILE)g++
+LD = $(CROSS_COMPILE)ld
+AR = $(CROSS_COMPILE)ar
+ARFLAGS = -rc
+STRIP = $(CROSS_COMPILE)strip
+RANLIB = $(CROSS_COMPILE)ranlib
+
+# cpu
+CFGFLAGS += -mcpu=cortex-m4
+
+# fpu
+CFGFLAGS += -mfpu=fpv4-sp-d16
+
+# float-abi
+CFGFLAGS += -mfloat-abi=hard -mthumb
+
+# Device
+CFGFLAGS += -DUSE_HAL_DRIVER -DSTM32L431xx
+
+CFGFLAGS += -Wall -fdata-sections -ffunction-sections
+
+CFGFLAGS += -g -gdwarf-2
+
+
+# C includes
+# Kernel
+CFGFLAGS += -I${QTOP}/kernel/core/include
+CFGFLAGS += -I${QTOP}/kernel/evtdrv/include
+CFGFLAGS += -I${QTOP}/kernel/hal/include
+CFGFLAGS += -I${QTOP}/kernel/pm/include
+
+# Arch
+CFGFLAGS += -I$(QTOP)/arch/arm/arm-v7m/common/include
+CFGFLAGS += -I$(QTOP)/arch/arm/arm-v7m/cortex-m4/gcc
+
+ARCH_LSRCS += $(wildcard ${QTOP}/arch/arm/arm-v7m/cortex-m4/gcc/*.c)
+ARCH_LSRCS += $(wildcard ${QTOP}/arch/arm/arm-v7m/cortex-m4/gcc/*.s)
+ARCH_LSRCS += $(wildcard ${QTOP}/arch/arm/arm-v7m/cortex-m4/gcc/*.S)
+ARCH_LSRCS += $(wildcard ${QTOP}/arch/arm/arm-v7m/common/*.c)
+ARCH_LSRCS += $(wildcard ${QTOP}/arch/arm/arm-v7m/common/*.s)
+ARCH_LSRCS += $(wildcard ${QTOP}/arch/arm/arm-v7m/common/*.S)
+
+# Board
+CFGFLAGS += -I$(QTOP)/board/TencentOS_tiny_EVB_MX_Plus/TOS-CONFIG
+
+# CMSIS
+CFGFLAGS += -I${QTOP}/osal/cmsis_os
+
+
+#board BSP
+CFGFLAGS += -I$(QTOP)/board/TencentOS_tiny_EVB_MX_Plus/BSP/Inc
+CFGFLAGS += -I$(QTOP)/platform/vendor_bsp/st/STM32L4xx_HAL_Driver/Inc
+CFGFLAGS += -I$(QTOP)/platform/vendor_bsp/st/STM32L4xx_HAL_Driver/Inc/Legacy
+CFGFLAGS += -I$(QTOP)/platform/vendor_bsp/st/CMSIS/Device/ST/STM32L4xx/Include
+CFGFLAGS += -I$(QTOP)/platform/vendor_bsp/st/CMSIS/Include
+CFGFLAGS += -I$(QTOP)/board/TencentOS_tiny_EVB_MX_Plus/BSP/Hardware/DHT11
+CFGFLAGS += -I$(QTOP)/board/TencentOS_tiny_EVB_MX_Plus/BSP/Hardware/BH1750
+CFGFLAGS += -I$(QTOP)/board/TencentOS_tiny_EVB_MX_Plus/BSP/Hardware/OLED
+CFGFLAGS += -I$(QTOP)/examples/event_driven_at_module/at_evtdrv/include
+
+
+#board BSP
+CFGFLAGS += -I$(QTOP)/net/at/include
+CFGFLAGS += -I$(QTOP)/net/sal_module_wrapper
+CFGFLAGS += -I$(QTOP)/board/TencentOS_tiny_EVB_MX_Plus/BSP/Hardware/PM25
+CFGFLAGS += -I$(QTOP)/board/TencentOS_tiny_EVB_MX_Plus/BSP/Hardware/Modbus_Port
+CFGFLAGS += -I$(QTOP)/board/TencentOS_tiny_EVB_MX_Plus/BSP/Hardware/E53_IA1
+CFGFLAGS += -I$(QTOP)/devices/esp8266
+CFGFLAGS += -I$(QTOP)/components/connectivity/Modbus/3rdparty/freemodbus-v1.6/modbus/include
+CFGFLAGS += -I$(QTOP)/components/shell/include
+CFGFLAGS += -I$(QTOP)/components/connectivity/mqttclient/mqttclient
+CFGFLAGS += -I$(QTOP)/components/connectivity/mqttclient/mqtt
+CFGFLAGS += -I$(QTOP)/components/connectivity/mqttclient/common
+CFGFLAGS += -I$(QTOP)/components/connectivity/mqttclient/platform/TencentOS-tiny
+CFGFLAGS += -I$(QTOP)/components/connectivity/mqttclient/network
+CFGFLAGS += -I$(QTOP)/components/fs/kv/include
+CFGFLAGS += -I$(QTOP)/components/ota/common/flash
+CFGFLAGS += -I$(QTOP)/components/connectivity/Eclipse-Paho-MQTT/wrapper/include
+CFGFLAGS += -I$(QTOP)/components/utils/JSON/include
+
+BSP_LSRCS += $(shell find $(QTOP)/board/TencentOS_tiny_EVB_MX_Plus/BSP/Src -name "*.c" -o -name "*.s")
+BSP_LSRCS += $(shell find $(QTOP)/board/TencentOS_tiny_EVB_MX_Plus/BSP/Hardware -name "*.c" -o -name "*.s")
+
+#platform/vendor_bsp
+PLATFORM_VENDOR_BSP_LSRCS += $(shell find $(QTOP)/platform/vendor_bsp/st/STM32L4xx_HAL_Driver/Src -name "*.c" -o -name "*.s")
+PLATFORM_HAL_LSRCS += $(shell find $(QTOP)/platform/hal/st/stm32l4xx -name "*.c" -o -name "*.s")
diff --git a/qmk/generic/Make.exec b/qmk/generic/Make.exec
index 4d6438f0..c12df6e6 100644
--- a/qmk/generic/Make.exec
+++ b/qmk/generic/Make.exec
@@ -42,10 +42,9 @@ $(targetexec): $(OUTDIR)/.tree ${LD_O_FILES}
@$(ECHO) "[$(BP)] LINK $@" # This is needed for error parsing
$(Q)/bin/ls $(LIBDIR)
$(Q)$(CC) \
- -o $@ \
- -L${LIBDIR} \
- $(_LD_START_GROUP) $(LD_O_FILES) $(LD_A_FILES) $(LD_L_LISTS) $(LDFLAGS) $(_LD_END_GROUP) \
- $(LD_INFO_OPTS)
+ $(patsubst -I%,,${CFLAGS} ${EXTRA_CFLAGS} ${LDFLAGS}) \
+ -o $@ -L${LIBDIR} \
+ $(_LD_START_GROUP) $(LD_O_FILES) $(LD_A_FILES) $(_LD_END_GROUP) $(LD_L_LISTS) $(LD_INFO_OPTS)
$(Q)$(STRIP) --strip-debug $@ -o $(OUTDIR)/$(basename $(notdir $@)).strip
$(Q)$(OBJCOPY) -O binary -S $@ $(OUTDIR)/$(basename $(notdir $@)).bin
$(Q)$(OBJCOPY) -O ihex $@ $(OUTDIR)/$(basename $(notdir $@)).hex
diff --git a/qmk/generic/Make.tpl b/qmk/generic/Make.tpl
index 430fc0ae..54eb80db 100644
--- a/qmk/generic/Make.tpl
+++ b/qmk/generic/Make.tpl
@@ -115,13 +115,13 @@ ifeq (,$(strip ${LSRCS})) # LSRCS
ifeq (,$(filter n no NO 0,$(TREE_LIB_ENABLE))) # TREE_LIB_ENABLE yes
ifeq (,$(strip ${LSRCS_DIRS})) # LSRCS_DIRS
-LSRCS_ALL = $(patsubst ./%,%, $(sort $(shell find . -name "*.c" -o -name "*.cpp" -o -name "*.s" -o -name "*.cc")))
+LSRCS_ALL = $(patsubst ./%,%, $(sort $(shell find . -name "*.c" -o -name "*.cpp" -o -name "*.s" -o -name "*.S" -o -name "*.cc")))
else
-LSRCS_ALL = $(patsubst ./%,%, $(sort $(shell find ${LSRCS_DIRS} -name "*.c" -o -name "*.cpp" -o -name "*.s" -o -name "*.cc")))
+LSRCS_ALL = $(patsubst ./%,%, $(sort $(shell find ${LSRCS_DIRS} -name "*.c" -o -name "*.cpp" -o -name "*.s" -o -name "*.S" -o -name "*.cc")))
endif # LSRCS_DIRS
else # TREE_LIB_ENABLE
-LSRCS_ALL = $(patsubst ./%,%,$(sort $(wildcard *.c *.cpp *.s *.cc *.C))) # only include src in this dir.
+LSRCS_ALL = $(patsubst ./%,%,$(sort $(wildcard *.c *.cpp *.s *.S *.cc *.C))) # only include src in this dir.
endif # TREE_LIB_ENABLE
endif # LSRCS
@@ -136,7 +136,7 @@ else
$(info $(shell echo -e "[$(BP)] INFO LSRCS is defined by users, LSRCS=$(LSRCS)"))
endif
-LOBJS = $(addsuffix .o, $(basename ${LSRCS}))
+LOBJS = $(patsubst $(QTOP)/%,%,$(addsuffix .o, $(basename ${LSRCS})))
BOBJS = $(addprefix ${BLDDIR}/,${LOBJS})
#
@@ -154,7 +154,7 @@ BOBJS = $(addprefix ${BLDDIR}/,${LOBJS})
# Rule allowing build through CPP only, creates .i file from .c file.
%.i: %.c
- @$Q$(ECHO) "EEEE ${LOCALDIR}/$<"
+ @$Q$(ECHO) "[$(BP)] EEEE ${LOCALDIR}/$<"
$Q$(CC) -E ${CFLAGS} $< | $(SED) -e '/^ *$$/d' -e p -e d > $@
# Rule allowing build through source only, creates .s file from .c file.
@@ -170,110 +170,13 @@ NO_QMK_DEPS = 1
# dependency makefiles
#
ifndef NO_QMK_DEPS
-# take the compiler generated .d file and reparse it
-# to generate a dependency graph rule for this object
-# file
-# the two steps generate:
-# file.o: file.c \
-# file.h ...
-#
-# file.h:
-# header.h:
-# some compilers will generate errors without the latter
-# part of the list
-
-.PHONY: .phony
-
-zDEPS_SED = \
- $(CP) $(BLDDIR)/$*.d $(BLDDIR)/$*.tmp;\
- $(ECHO) >> $(BLDDIR)/$*.tmp;\
- $(SED) -e 's/\#.*//' -e 's/^[^:]*: *//' \
- -e 's/ *\\$$//' -e '/^$$/ d' -e 's/$$/ :/' \
- -e '/^ .$$/d' \
- < $(BLDDIR)/$*.d >> $(BLDDIR)/$*.tmp; \
- $(SED) -e 's|^\([^\/ ].*\.o\):|'$(BLDDIR)/'\1:|g' \
- -e 's|.*?/\(.*\.o\):|'$(BLDDIR)/'\1:|g' \
- < $(BLDDIR)/$*.tmp > $(BLDDIR)/$*.P; \
- $(RM) -f $(BLDDIR)/$*.d $(BLDDIR)/$*.tmp
-zDEPS_CMD = $(zDEPS_SED)
+zDEPS_OPT = -MMD -MP -MF'$(@:%.o=%.d)'
+endif # ifndef NO_QMK_DEPS
-# newer gnu-based compilers allow -MD -MF
-zDEPS_OPT = -MD -MF $(BLDDIR)/$*.d
-zDEPS_CMD = $(zDEPS_SED)
-
-
-# From gmsl
-
-# Standard definitions for true and false. true is any non-empty
-# string, false is an empty string. These are intended for use with
-# $(if).
-
-true := T
-false :=
-
-# ----------------------------------------------------------------------------
-# Function: not
-# Arguments: 1: A boolean value
-# Returns: Returns the opposite of the arg. (true -> false, false -> true)
-# ----------------------------------------------------------------------------
-not = $(if $1,$(false),$(true))
-
-# ----------------------------------------------------------------------------
-# Function: map
-# Arguments: 1: Name of function to $(call) for each element of list
-# 2: List to iterate over calling the function in 1
-# Returns: The list after calling the function on each element
-# ----------------------------------------------------------------------------
-map = $(strip $(foreach a,$2,$(call $1,$a)))
-
-# ----------------------------------------------------------------------------
-# Function: seq
-# Arguments: 1: A string to compare against...
-# 2: ...this string
-# Returns: Returns $(true) if the two strings are identical
-# ----------------------------------------------------------------------------
-seq = $(if $(filter-out xx,x$(subst $1,,$2)$(subst $2,,$1)x),$(false),$(true))
-
-# ----------------------------------------------------------------------------
-# Function: sne
-# Arguments: 1: A string to compare against...
-# 2: ...this string
-# Returns: Returns $(true) if the two strings are not the same
-# ----------------------------------------------------------------------------
-sne = $(call not,$(call seq,$1,$2))
-
-# End from gmsl
-
-# Define comma symbol so we can repace it with a variable
-comma :=,
-
-# Signature
-last_target :=
-
-adump_var = $$(eval $1 := $($1))
-
-define new_rule
-@echo '$(call map,adump_var,@ < *)' > $S
-@$(if $(wildcard $F),,touch $F)
-@echo $@: $F >> $S
-endef
-
-define zdo
-$(eval S := $(BLDDIR)/$*.sig)$(eval F := $(BLDDIR)/$*.force)$(eval C := $1)
-$(if $(call sne,$@,$(last_target)),$(call new_rule),$(eval last_target := $@))
-@echo '$$(if $$(call sne,$$(sort $1),$(sort $(subst $(comma),$$(comma),$C))),$$(shell touch $F))' >> $S
-$Q$C
-endef
-
-# end of Signature
-
-
-else # ifndef NO_QMK_DEPS
# No dependency files, faster compile times
# no partial compile support
zDEPS_SED =
-zDEPS_OPT =
zDEPS_CPY =
zDEPS_CMD = /bin/true
@@ -282,38 +185,58 @@ $(eval C := $1)
$Q$C
endef
-endif # ifndef NO_QMK_DEPS
#
# Default Build rules for .c --> .o, leaving the binary in BLDDIR/X.o,
# even if file not built from directory of source.
#
-
-${BLDDIR}/%.o: %.c
-ifdef EEEE
- @$Q$(ECHO) "EEEE ${LOCALDIR}/$<"
- $Q$(CC) -E ${CFLAGS} $(EXTRA_CFLAGS) $< | $(SED) -e '/^ *$$/d' -e p -e d > $(@:.o=.i)
-endif
-# echo Compiling needed to properly process errors
- $Q$(MKDIR) $(BLDDIR)/
+${BLDDIR}/%.o: $(QTOP)/%.c
$Q$(MKDIR) $(dir $@)
$Q$(RM) -f $@
+ifdef E
+ @$Q$(ECHO) '[$(BP)] EEEE ${LOCALDIR}/$<'
+ $Q$(CC) -E ${CFLAGS} $(EXTRA_CFLAGS) $< | $(SED) -e '/^ *$$/d' -e p -e d > $(@:.o=.i)
+endif
+ifdef S
+ @$Q$(ECHO) "[$(BP)] SSSS ${LOCALDIR}/$<"
+ $Q$(CC) -S ${CFLAGS} $<
+endif
+ @$Q$(ECHO) "[$(BP)] CCCC $<"
+ $Q$(call zdo,$$(CC) $$(zDEPS_OPT) $$(CFLAGS) $$(EXTRA_CFLAGS) -o $$@ -c $$(realpath $$<)) && ($(zDEPS_CMD))
+
+${BLDDIR}/%.o: %.c
+ $Q$(MKDIR) $(dir $@)
+ $Q$(RM) -f $@
+ifdef E
+ @$Q$(ECHO) "[$(BP)] EEEE ${LOCALDIR}/$<"
+ $Q$(CC) -E ${CFLAGS} $(EXTRA_CFLAGS) $< | $(SED) -e '/^ *$$/d' -e p -e d > $(@:.o=.i)
+endif
@$Q$(ECHO) "[$(BP)] CCCC ${LOCALDIR}/$<"
$Q$(call zdo,$$(CC) $$(zDEPS_OPT) $$(CFLAGS) $$(EXTRA_CFLAGS) -o $$@ -c $$(realpath $$<)) && ($(zDEPS_CMD))
${BLDDIR}/%.o: %.s
-ifeq (@,$(Q))
- @$(ECHO) ASAS ${LOCALDIR}/$<
-endif
+ $Q$(MKDIR) $(dir $@)
+ $Q$(ECHO) "[$(BP)] ASAS ${LOCALDIR}/$<"
+# $Q$(MKDIR) $(BLDDIR)/
+# $Q$(MKDIR) $(dir $@)
+ $Q$(RM) -f $@
+ $Q$(CC) ${CFLAGS} ${EXTRA_CFLAGS} -o $@ -c $(realpath $<)
+
+${BLDDIR}/%.o: %.S
+ $Q$(MKDIR) $(dir $@)
+ $Q$(ECHO) "[$(BP)] ASAS ${LOCALDIR}/$<"
+ $Q$(RM) -f $@
$Q$(CC) ${CFLAGS} ${EXTRA_CFLAGS} -o $@ -c $(realpath $<)
${BLDDIR}/%.o: %.cpp
+ $Q$(MKDIR) $(dir $@)
ifeq (@,$(Q))
@$(ECHO) "[$(BP)] CCCC ${LOCALDIR}/$<"
endif
$Q$(CXX) ${CXXFLAGS} -o $@ -c $(realpath $<)
-${BLDDIR}/%.o: %.cc ${BLDDIR}/.tree
+${BLDDIR}/%.o: %.cc
+ $Q$(MKDIR) $(dir $@)
ifeq (@,$(Q))
@$(ECHO) "[$(BP)] CCCC ${LOCALDIR}/$<"
endif
@@ -342,7 +265,7 @@ help:
$Q$(ECHO) -e "\t make clean all"
$Q$(ECHO) -e "Debug build, verbose print, generate preprocess .i for .c"
$Q$(ECHO) -e "\t make V=1 "
- $Q$(ECHO) -e "\t make EEEE=1 "
+ $Q$(ECHO) -e "\t make E=1 "
$Q$(ECHO) -e "Debug Makefile"
$Q$(ECHO) -e "\t make dm"
endif