diff --git a/board/TencentOS_tiny_EVB_MX/GCC/tencent_os_mqtt/Makefile b/board/TencentOS_tiny_EVB_MX/GCC/tencent_os_mqtt/Makefile
new file mode 100644
index 00000000..d94790cd
--- /dev/null
+++ b/board/TencentOS_tiny_EVB_MX/GCC/tencent_os_mqtt/Makefile
@@ -0,0 +1,279 @@
+######################################
+# target
+######################################
+TARGET = TencentOS_tiny
+
+######################################
+# building variables
+######################################
+# debug build?
+DEBUG = 1
+# optimization
+OPT = -O0
+
+TOP_DIR = ../../../../
+#######################################
+# paths
+#######################################
+# Build path
+BUILD_DIR = build
+
+######################################
+# source
+######################################
+# C sources
+KERNEL_SRC = \
+ ${wildcard $(TOP_DIR)/kernel/core/*.c}
+ C_SOURCES += $(KERNEL_SRC)
+
+ARCH_SRC = \
+ ${wildcard $(TOP_DIR)/arch/arm/arm-v7m/cortex-m4/gcc/*.c} \
+ ${wildcard $(TOP_DIR)/arch/arm/arm-v7m/common/*.c}
+ C_SOURCES += $(ARCH_SRC)
+
+CMSIS_SRC = \
+ ${wildcard $(TOP_DIR)/osal/cmsis_os/*.c}
+ C_SOURCES += $(CMSIS_SRC)
+
+PLATFORM_SRC = \
+ $(TOP_DIR)/platform/vendor_bsp/st/STM32L4xx_HAL_Driver/Src/stm32l4xx_hal_tim.c \
+ $(TOP_DIR)/platform/vendor_bsp/st/STM32L4xx_HAL_Driver/Src/stm32l4xx_hal_tim_ex.c \
+ $(TOP_DIR)/platform/vendor_bsp/st/STM32L4xx_HAL_Driver/Src/stm32l4xx_hal_uart.c \
+ $(TOP_DIR)/platform/vendor_bsp/st/STM32L4xx_HAL_Driver/Src/stm32l4xx_hal_uart_ex.c \
+ $(TOP_DIR)/platform/vendor_bsp/st/STM32L4xx_HAL_Driver/Src/stm32l4xx_hal.c \
+ $(TOP_DIR)/platform/vendor_bsp/st/STM32L4xx_HAL_Driver/Src/stm32l4xx_hal_i2c.c \
+ $(TOP_DIR)/platform/vendor_bsp/st/STM32L4xx_HAL_Driver/Src/stm32l4xx_hal_i2c_ex.c \
+ $(TOP_DIR)/platform/vendor_bsp/st/STM32L4xx_HAL_Driver/Src/stm32l4xx_hal_rcc.c \
+ $(TOP_DIR)/platform/vendor_bsp/st/STM32L4xx_HAL_Driver/Src/stm32l4xx_hal_rcc_ex.c \
+ $(TOP_DIR)/platform/vendor_bsp/st/STM32L4xx_HAL_Driver/Src/stm32l4xx_hal_flash.c \
+ $(TOP_DIR)/platform/vendor_bsp/st/STM32L4xx_HAL_Driver/Src/stm32l4xx_hal_flash_ex.c \
+ $(TOP_DIR)/platform/vendor_bsp/st/STM32L4xx_HAL_Driver/Src/stm32l4xx_hal_flash_ramfunc.c \
+ $(TOP_DIR)/platform/vendor_bsp/st/STM32L4xx_HAL_Driver/Src/stm32l4xx_hal_gpio.c \
+ $(TOP_DIR)/platform/vendor_bsp/st/STM32L4xx_HAL_Driver/Src/stm32l4xx_hal_dma.c \
+ $(TOP_DIR)/platform/vendor_bsp/st/STM32L4xx_HAL_Driver/Src/stm32l4xx_hal_dma_ex.c \
+ $(TOP_DIR)/platform/vendor_bsp/st/STM32L4xx_HAL_Driver/Src/stm32l4xx_hal_pwr.c \
+ $(TOP_DIR)/platform/vendor_bsp/st/STM32L4xx_HAL_Driver/Src/stm32l4xx_hal_pwr_ex.c \
+ $(TOP_DIR)/platform/vendor_bsp/st/STM32L4xx_HAL_Driver/Src/stm32l4xx_hal_cortex.c \
+ $(TOP_DIR)/platform/vendor_bsp/st/STM32L4xx_HAL_Driver/Src/stm32l4xx_hal_adc_ex.c \
+ $(TOP_DIR)/platform/vendor_bsp/st/STM32L4xx_HAL_Driver/Src/stm32l4xx_hal_adc.c \
+ $(TOP_DIR)/platform/vendor_bsp/st/STM32L4xx_HAL_Driver/Src/stm32l4xx_hal_dac.c \
+ $(TOP_DIR)/platform/vendor_bsp/st/STM32L4xx_HAL_Driver/Src/stm32l4xx_hal_dac_ex.c \
+ $(TOP_DIR)/platform/vendor_bsp/st/STM32L4xx_HAL_Driver/Src/stm32l4xx_hal_spi.c \
+ $(TOP_DIR)/platform/vendor_bsp/st/STM32L4xx_HAL_Driver/Src/stm32l4xx_hal_spi_ex.c \
+ $(TOP_DIR)/platform/hal/st/stm32l4xx/src/tos_hal_uart.c
+ C_SOURCES += $(PLATFORM_SRC)
+
+NET_SRC = \
+ $(TOP_DIR)/net/at/src/tos_at.c \
+ $(TOP_DIR)/net/at/src/tos_at_utils.c \
+ $(TOP_DIR)/net/sal_module_wrapper/sal_module_wrapper.c \
+ $(TOP_DIR)/devices/esp8266/esp8266.c
+ C_SOURCES += $(NET_SRC)
+
+BSP_SRC = \
+ $(TOP_DIR)/board/TencentOS_tiny_EVB_MX/BSP/Src/gpio.c \
+ $(TOP_DIR)/board/TencentOS_tiny_EVB_MX/BSP/Src/main.c \
+ $(TOP_DIR)/board/TencentOS_tiny_EVB_MX/BSP/Src/mcu_init.c \
+ $(TOP_DIR)/board/TencentOS_tiny_EVB_MX/BSP/Src/stm32l4xx_hal_msp.c \
+ $(TOP_DIR)/board/TencentOS_tiny_EVB_MX/BSP/Src/stm32l4xx_it_module.c \
+ $(TOP_DIR)/board/TencentOS_tiny_EVB_MX/BSP/Src/usart.c \
+ $(TOP_DIR)/board/TencentOS_tiny_EVB_MX/BSP/Src/adc.c \
+ $(TOP_DIR)/board/TencentOS_tiny_EVB_MX/BSP/Src/dac.c \
+ $(TOP_DIR)/board/TencentOS_tiny_EVB_MX/BSP/Src/i2c.c \
+ $(TOP_DIR)/board/TencentOS_tiny_EVB_MX/BSP/Src/spi.c \
+ $(TOP_DIR)/board/TencentOS_tiny_EVB_MX/BSP/Src/system_stm32l4xx.c \
+ $(TOP_DIR)/board/TencentOS_tiny_EVB_MX/BSP/Hardware/DHT11/DHT11_BUS.c \
+ $(TOP_DIR)/board/TencentOS_tiny_EVB_MX/BSP/Hardware/OLED/oled.c \
+ $(TOP_DIR)/board/TencentOS_tiny_EVB_MX/BSP/Hardware/E53_IA1/E53_IA1.c
+ C_SOURCES += $(BSP_SRC)
+
+COMPONENTS_SRC = \
+ $(TOP_DIR)/components/connectivity/Eclipse-Paho-MQTT/wrapper/src/mqtt_wrapper.c \
+ $(TOP_DIR)/components/connectivity/Eclipse-Paho-MQTT/wrapper/src/transport_wrapper.c \
+ $(TOP_DIR)/components/connectivity/Eclipse-Paho-MQTT/3rdparty/src/MQTTConnectClient.c \
+ $(TOP_DIR)/components/connectivity/Eclipse-Paho-MQTT/3rdparty/src/MQTTConnectServer.c \
+ $(TOP_DIR)/components/connectivity/Eclipse-Paho-MQTT/3rdparty/src/MQTTDeserializePublish.c \
+ $(TOP_DIR)/components/connectivity/Eclipse-Paho-MQTT/3rdparty/src/MQTTFormat.c \
+ $(TOP_DIR)/components/connectivity/Eclipse-Paho-MQTT/3rdparty/src/MQTTPacket.c \
+ $(TOP_DIR)/components/connectivity/Eclipse-Paho-MQTT/3rdparty/src/MQTTSerializePublish.c \
+ $(TOP_DIR)/components/connectivity/Eclipse-Paho-MQTT/3rdparty/src/MQTTSubscribeClient.c \
+ $(TOP_DIR)/components/connectivity/Eclipse-Paho-MQTT/3rdparty/src/MQTTSubscribeServer.c \
+ $(TOP_DIR)/components/connectivity/Eclipse-Paho-MQTT/3rdparty/src/MQTTUnsubscribeClient.c \
+ $(TOP_DIR)/components/connectivity/Eclipse-Paho-MQTT/3rdparty/src/MQTTUnsubscribeServer.c
+ C_SOURCES += $(COMPONENTS_SRC)
+
+EXAMPLES_SRC = \
+ $(TOP_DIR)/examples/tencent_os_mqtt/mqtt_example.c
+ C_SOURCES += $(EXAMPLES_SRC)
+
+# ASM sources
+ASM_SOURCES = \
+startup_stm32l431xx.s \
+
+ASM_SOURCES_S = \
+$(TOP_DIR)/arch/arm/arm-v7m/cortex-m4/gcc/port_s.S
+
+#######################################
+# binaries
+#######################################
+PREFIX = arm-none-eabi-
+# The gcc compiler bin path can be either defined in make command via GCC_PATH variable (> make GCC_PATH=xxx)
+# either it can be added to the PATH environment variable.
+ifdef GCC_PATH
+CC = $(GCC_PATH)/$(PREFIX)gcc
+AS = $(GCC_PATH)/$(PREFIX)gcc -x assembler-with-cpp
+CP = $(GCC_PATH)/$(PREFIX)objcopy
+SZ = $(GCC_PATH)/$(PREFIX)size
+else
+CC = $(PREFIX)gcc
+AS = $(PREFIX)gcc -x assembler-with-cpp
+CP = $(PREFIX)objcopy
+SZ = $(PREFIX)size
+endif
+HEX = $(CP) -O ihex
+BIN = $(CP) -O binary -S
+
+#######################################
+# CFLAGS
+#######################################
+# cpu
+CPU = -mcpu=cortex-m4
+
+# fpu
+FPU = -mfpu=fpv4-sp-d16
+
+# float-abi
+FLOAT-ABI = -mfloat-abi=hard
+
+# mcu
+MCU = $(CPU) -mthumb $(FPU) $(FLOAT-ABI)
+
+# macros for gcc
+# AS defines
+AS_DEFS =
+
+# C defines
+C_DEFS = \
+-DUSE_HAL_DRIVER \
+-DSTM32L431xx \
+-DUSE_HAL_DRIVER \
+-DSTM32L431xx
+
+# AS includes
+AS_INCLUDES =
+
+# C includes
+KERNEL_INC = \
+ -I $(TOP_DIR)/kernel/core/include \
+ -I $(TOP_DIR)/kernel/pm/include \
+ -I $(TOP_DIR)/kernel/hal/include \
+ -I $(TOP_DIR)/arch/arm/arm-v7m/common/include \
+ -I $(TOP_DIR)/arch/arm/arm-v7m/cortex-m4/gcc
+ C_INCLUDES += $(KERNEL_INC)
+
+CMSIS_INC = \
+ -I $(TOP_DIR)/osal/cmsis_os
+ C_INCLUDES += $(CMSIS_INC)
+
+PLATFORM_INC = \
+ -I $(TOP_DIR)/platform/vendor_bsp/st/STM32L4xx_HAL_Driver/Inc \
+ -I $(TOP_DIR)/platform/vendor_bsp/st/STM32L4xx_HAL_Driver/Inc/Legacy \
+ -I $(TOP_DIR)/platform/vendor_bsp/st/CMSIS/Device/ST/STM32L4xx/Include \
+ -I $(TOP_DIR)/platform/vendor_bsp/st/CMSIS/Include
+ C_INCLUDES += $(PLATFORM_INC)
+
+BOARD_INC = \
+ -I $(TOP_DIR)/board/TencentOS_tiny_EVB_MX/TOS-CONFIG \
+ -I $(TOP_DIR)/board/TencentOS_tiny_EVB_MX/BSP/Inc \
+ -I $(TOP_DIR)/board/TencentOS_tiny_EVB_MX/BSP/Hardware/DHT11 \
+ -I $(TOP_DIR)/board/TencentOS_tiny_EVB_MX/BSP/Hardware/BH1750 \
+ -I $(TOP_DIR)/board/TencentOS_tiny_EVB_MX/BSP/Hardware/E53_IA1 \
+ -I $(TOP_DIR)/board/TencentOS_tiny_EVB_MX/BSP/Hardware/OLED
+ C_INCLUDES += $(BOARD_INC)
+
+NET_INC = \
+ -I $(TOP_DIR)/net/at/include \
+ -I $(TOP_DIR)/net/sal_module_wrapper \
+ -I $(TOP_DIR)/devices/esp8266
+ C_INCLUDES += $(NET_INC)
+
+COMPONENTS_INC = \
+ -I $(TOP_DIR)/components/connectivity/Eclipse-Paho-MQTT/wrapper/include \
+ -I $(TOP_DIR)/components/connectivity/Eclipse-Paho-MQTT/3rdparty/include
+ C_INCLUDES += $(COMPONENTS_INC)
+
+EXAMPLES_INC = \
+ -I $(TOP_DIR)/examples/tencent_os_mqtt
+ C_INCLUDES += $(EXAMPLES_INC)
+
+# compile gcc flags
+ASFLAGS = $(MCU) $(AS_DEFS) $(AS_INCLUDES) $(OPT) -Wall -fdata-sections -ffunction-sections
+
+CFLAGS = $(MCU) $(C_DEFS) $(C_INCLUDES) $(OPT) -Wall -fdata-sections -ffunction-sections
+
+ifeq ($(DEBUG), 1)
+CFLAGS += -g -gdwarf-2
+endif
+
+# Generate dependency information
+CFLAGS += -MMD -MP -MF"$(@:%.o=%.d)"
+
+#######################################
+# LDFLAGS
+#######################################
+# link script
+LDSCRIPT = STM32L431RCTx_FLASH.ld
+
+# libraries
+LIBS = -lc -lm -lnosys
+LIBDIR =
+LDFLAGS = $(MCU) -u _printf_float -specs=nano.specs -T$(LDSCRIPT) $(LIBDIR) $(LIBS) \
+ -Wl,-Map=$(BUILD_DIR)/$(TARGET).map,--cref -Wl,--gc-sections
+
+# default action: build all
+all: $(BUILD_DIR)/$(TARGET).elf $(BUILD_DIR)/$(TARGET).hex $(BUILD_DIR)/$(TARGET).bin
+
+#######################################
+# build the application
+#######################################
+# list of objects
+OBJECTS = $(addprefix $(BUILD_DIR)/,$(notdir $(C_SOURCES:.c=.o)))
+vpath %.c $(sort $(dir $(C_SOURCES)))
+# list of ASM program objects
+OBJECTS += $(addprefix $(BUILD_DIR)/,$(notdir $(ASM_SOURCES:.s=.o)))
+vpath %.s $(sort $(dir $(ASM_SOURCES)))
+OBJECTS += $(addprefix $(BUILD_DIR)/,$(notdir $(ASM_SOURCES_S:.S=.o)))
+vpath %.S $(sort $(dir $(ASM_SOURCES_S)))
+
+$(BUILD_DIR)/%.o: %.c Makefile | $(BUILD_DIR)
+ $(CC) -c $(CFLAGS) -Wa,-a,-ad,-alms=$(BUILD_DIR)/$(notdir $(<:.c=.lst)) $< -o $@
+
+$(BUILD_DIR)/%.o: %.s Makefile | $(BUILD_DIR)
+ $(AS) -c $(CFLAGS) $< -o $@
+
+$(BUILD_DIR)/%.o: %.S Makefile | $(BUILD_DIR)
+ $(AS) -c $(CFLAGS) $< -o $@
+
+$(BUILD_DIR)/$(TARGET).elf: $(OBJECTS) Makefile
+ $(CC) $(OBJECTS) $(LDFLAGS) -o $@
+ $(SZ) $@
+
+$(BUILD_DIR)/%.hex: $(BUILD_DIR)/%.elf | $(BUILD_DIR)
+ $(HEX) $< $@
+
+$(BUILD_DIR)/%.bin: $(BUILD_DIR)/%.elf | $(BUILD_DIR)
+ $(BIN) $< $@
+
+$(BUILD_DIR):
+ mkdir $@
+
+#######################################
+# clean up
+#######################################
+clean:
+ -rm -fR $(BUILD_DIR)
+
+#######################################
+# dependencies
+#######################################
+-include $(wildcard $(BUILD_DIR)/*.d)
diff --git a/board/TencentOS_tiny_EVB_MX/GCC/tencent_os_mqtt/STM32L431RCTx_FLASH.ld b/board/TencentOS_tiny_EVB_MX/GCC/tencent_os_mqtt/STM32L431RCTx_FLASH.ld
new file mode 100644
index 00000000..3d07935e
--- /dev/null
+++ b/board/TencentOS_tiny_EVB_MX/GCC/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/GCC/tencent_os_mqtt/startup_stm32l431xx.s b/board/TencentOS_tiny_EVB_MX/GCC/tencent_os_mqtt/startup_stm32l431xx.s
new file mode 100644
index 00000000..d8f45f45
--- /dev/null
+++ b/board/TencentOS_tiny_EVB_MX/GCC/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****/