diff --git a/arch/risc-v/bumblebee/gcc/riscv_port_c.c b/arch/risc-v/bumblebee/gcc/riscv_port_c.c
index a5173726..a3fa4eb3 100644
--- a/arch/risc-v/bumblebee/gcc/riscv_port_c.c
+++ b/arch/risc-v/bumblebee/gcc/riscv_port_c.c
@@ -75,13 +75,13 @@ static void eclic_set_irq_level(uint32_t source, uint8_t level) {
return ;
}
- uint8_t intctrl_val = eclic_get_intctrl(CLIC_INT_TMR);
+ uint8_t intctrl_val = eclic_get_intctrl(source);
intctrl_val <<= nlbits;
intctrl_val >>= nlbits;
intctrl_val |= (level << (8- nlbits));
- eclic_set_intctrl(CLIC_INT_TMR, intctrl_val);
+ eclic_set_intctrl(source, intctrl_val);
}
static void eclic_set_irq_priority(uint32_t source, uint8_t priority) {
@@ -98,29 +98,32 @@ static void eclic_set_irq_priority(uint32_t source, uint8_t priority) {
pad >>= cicbits;
- uint8_t intctrl_val = eclic_get_intctrl(CLIC_INT_TMR);
+ uint8_t intctrl_val = eclic_get_intctrl(source);
intctrl_val >>= (8 - nlbits);
intctrl_val <<= (8 - nlbits);
intctrl_val |= (priority << (8 - cicbits));
intctrl_val |= pad;
- eclic_set_intctrl(CLIC_INT_TMR, intctrl_val);
+ eclic_set_intctrl(source, intctrl_val);
}
-void rv32_exception_entry();
__PORT__ void port_cpu_init() {
- __ASM__ __VOLATILE__("csrw mtvec, %0"::"r"(rv32_exception_entry));
+ void rv32_exception_entry();
+ uint32_t entry = (uint32_t) rv32_exception_entry;
+
+ // 0x03 means use eclic
+ __ASM__ __VOLATILE__("csrw mtvec, %0"::"r"(entry | 0x03));
// MTVT2: 0x7EC
+ // set mtvt2.MTVT2EN = 0 needs to clear bit 0
// use mtvec as entry of irq and other trap
__ASM__ __VOLATILE__("csrc 0x7EC, 0x1");
eclic_enable_interrupt(CLIC_INT_TMR);
eclic_set_irq_level(CLIC_INT_TMR, 0);
-
}
__PORT__ void port_systick_priority_set(uint32_t priority) {
diff --git a/arch/risc-v/bumblebee/gcc/riscv_port_s.S b/arch/risc-v/bumblebee/gcc/riscv_port_s.S
deleted file mode 100644
index e1747b09..00000000
--- a/arch/risc-v/bumblebee/gcc/riscv_port_s.S
+++ /dev/null
@@ -1,29 +0,0 @@
-/*----------------------------------------------------------------------------
- * Tencent is pleased to support the open source community by making TencentOS
- * available.
- *
- * Copyright (C) 2019 THL A29 Limited, a Tencent company. All rights reserved.
- * If you have downloaded a copy of the TencentOS binary from Tencent, please
- * note that the TencentOS binary is licensed under the BSD 3-Clause License.
- *
- * If you have downloaded a copy of the TencentOS source code from Tencent,
- * please note that TencentOS source code is licensed under the BSD 3-Clause
- * License, except for the third-party components listed below which are
- * subject to different license terms. Your integration of TencentOS into your
- * own projects may require compliance with the BSD 3-Clause License, as well
- * as the other licenses applicable to the third-party components included
- * within TencentOS.
- *---------------------------------------------------------------------------*/
-
-.global eclic_mtip_handler
-.global irq_entry
-.global trap_entry
-
-.align 2
-irq_entry:
- j irq_entry
-
-.align 2
-trap_entry:
- j trap_entry
-
diff --git a/arch/risc-v/common/tos_cpu.c b/arch/risc-v/common/tos_cpu.c
index 639b0338..25e9cd81 100644
--- a/arch/risc-v/common/tos_cpu.c
+++ b/arch/risc-v/common/tos_cpu.c
@@ -159,15 +159,21 @@ void cpu_trap_entry(cpu_data_t cause, cpu_context_t *regs)
}
}
+void eclic_mtip_handler();
void cpu_irq_entry(cpu_data_t irq)
{
- void (*irq_handler)();
+ typedef void (*irq_handler_t)();
- irq_handler = *((void (**)())(port_get_irq_vector_table() + irq*sizeof(cpu_addr_t)));
- if((*irq_handler) == 0) {
+
+ irq_handler_t *irq_handler_base = port_get_irq_vector_table();
+
+ irq_handler_t irq_handler = irq_handler_base[irq];
+
+ if(irq_handler == 0) {
return;
}
+
(*irq_handler)();
}
@@ -175,27 +181,27 @@ __API__ uint32_t tos_cpu_clz(uint32_t val)
{
uint32_t nbr_lead_zeros = 0;
- if (!(val & 0XFFFF0000)) {
+ if (!(val & 0xFFFF0000)) {
val <<= 16;
nbr_lead_zeros += 16;
}
- if (!(val & 0XFF000000)) {
+ if (!(val & 0xFF000000)) {
val <<= 8;
nbr_lead_zeros += 8;
}
- if (!(val & 0XF0000000)) {
+ if (!(val & 0xF0000000)) {
val <<= 4;
nbr_lead_zeros += 4;
}
- if (!(val & 0XC0000000)) {
+ if (!(val & 0xC0000000)) {
val <<= 2;
nbr_lead_zeros += 2;
}
- if (!(val & 0X80000000)) {
+ if (!(val & 0x80000000)) {
nbr_lead_zeros += 1;
}
diff --git a/arch/risc-v/rv32i/gcc/port_s.S b/arch/risc-v/rv32i/gcc/port_s.S
index 69868946..f085f874 100644
--- a/arch/risc-v/rv32i/gcc/port_s.S
+++ b/arch/risc-v/rv32i/gcc/port_s.S
@@ -267,7 +267,7 @@ restore_context:
mret
-.align 2
+.align 6
.global rv32_exception_entry
rv32_exception_entry:
addi sp, sp, -128
diff --git a/board/QEMU_Spike/GCC/demo/Makefile b/board/QEMU_Spike/GCC/demo/Makefile
index ef9e8ca6..523a045a 100644
--- a/board/QEMU_Spike/GCC/demo/Makefile
+++ b/board/QEMU_Spike/GCC/demo/Makefile
@@ -55,7 +55,6 @@ ASM_SOURCES =
ASM_SOURCES_S = \
$(TOP_DIR)/arch/risc-v/rv32i/gcc/port_s.S \
-$(TOP_DIR)/arch/risc-v/spike/gcc/riscv_port_s.S \
start.S
diff --git a/board/TencentOS_tiny_EVB_LX/BSP/Inc/EVB_LX_IoT_gd32vf103.h b/board/TencentOS_tiny_EVB_LX/BSP/Inc/EVB_LX_IoT_gd32vf103.h
index f02805f0..4e0e1860 100644
--- a/board/TencentOS_tiny_EVB_LX/BSP/Inc/EVB_LX_IoT_gd32vf103.h
+++ b/board/TencentOS_tiny_EVB_LX/BSP/Inc/EVB_LX_IoT_gd32vf103.h
@@ -104,10 +104,10 @@ typedef enum
#define COMn 2U
-#define EVAL_COM0 USART2
-#define EVAL_COM0_CLK RCU_USART2
-#define EVAL_COM0_TX_PIN GPIO_PIN_2
-#define EVAL_COM0_RX_PIN GPIO_PIN_3
+#define EVAL_COM0 USART0
+#define EVAL_COM0_CLK RCU_USART0
+#define EVAL_COM0_TX_PIN GPIO_PIN_9
+#define EVAL_COM0_RX_PIN GPIO_PIN_10
#define EVAL_COM0_GPIO_PORT GPIOA
#define EVAL_COM0_GPIO_CLK RCU_GPIOA
@@ -123,7 +123,7 @@ typedef enum
#define EVAL_COM3_TX_PIN GPIO_PIN_10
#define EVAL_COM3_RX_PIN GPIO_PIN_11
#define EVAL_COM3_GPIO_PORT GPIOC
-#define EVAL_COM3_GPIO_CLK RCU_GPIOC
+#define EVAL_COM3_GPIO_CLK RCU_GPIOB
#define KEYn 3U
diff --git a/board/TencentOS_tiny_EVB_LX/BSP/Inc/usart.h b/board/TencentOS_tiny_EVB_LX/BSP/Inc/usart.h
index 68631a13..8e2cf040 100644
--- a/board/TencentOS_tiny_EVB_LX/BSP/Inc/usart.h
+++ b/board/TencentOS_tiny_EVB_LX/BSP/Inc/usart.h
@@ -11,7 +11,7 @@
#define USART2_GPIO_TX_PIN GPIO_PIN_10
#define USART2_GPIO_RX_PIN GPIO_PIN_11
-#define USART2_GPIO_PORT GPIOC
+#define USART2_GPIO_PORT GPIOB
void usart0_init(int baud);
diff --git a/board/TencentOS_tiny_EVB_LX/BSP/Src/usart.c b/board/TencentOS_tiny_EVB_LX/BSP/Src/usart.c
index 284eb060..c36810e9 100644
--- a/board/TencentOS_tiny_EVB_LX/BSP/Src/usart.c
+++ b/board/TencentOS_tiny_EVB_LX/BSP/Src/usart.c
@@ -2,6 +2,10 @@
#include "usart.h"
void usart0_init(int baud)
{
+ eclic_priority_group_set(ECLIC_PRIGROUP_LEVEL3_PRIO1);
+ eclic_irq_enable(USART0_IRQn, 1, 0);
+
+
/* enable GPIO clock */
rcu_periph_clock_enable(RCU_GPIOA);
@@ -25,10 +29,14 @@ void usart0_init(int baud)
usart_receive_config(USART0, USART_RECEIVE_ENABLE);
usart_transmit_config(USART0, USART_TRANSMIT_ENABLE);
usart_enable(USART0);
+
+ usart_interrupt_enable(USART0, USART_INT_RBNE);
}
void usart1_init(int baud)
{
+ eclic_irq_enable(USART1_IRQn, 1, 0);
+
/* enable GPIO clock */
rcu_periph_clock_enable(RCU_GPIOA);
@@ -52,14 +60,19 @@ void usart1_init(int baud)
usart_receive_config(USART1, USART_RECEIVE_ENABLE);
usart_transmit_config(USART1, USART_TRANSMIT_ENABLE);
usart_enable(USART1);
+
+ usart_interrupt_enable(USART1, USART_INT_RBNE);
+
}
void usart2_init(int baud)
{
+ //eclic_irq_enable(USART2_IRQn, 1, 0);
+
/* enable GPIO clock */
- rcu_periph_clock_enable(RCU_GPIOC);
+ rcu_periph_clock_enable(RCU_GPIOB);
/* enable USART2 clock */
rcu_periph_clock_enable(RCU_USART2);
@@ -70,7 +83,7 @@ void usart2_init(int baud)
/* connect port to USART0_Rx */
gpio_init(USART2_GPIO_PORT, GPIO_MODE_IN_FLOATING, GPIO_OSPEED_50MHZ, USART2_GPIO_RX_PIN);
- gpio_pin_remap_config(GPIO_USART2_FULL_REMAP,ENABLE);
+ //gpio_pin_remap_config(GPIO_USART2_FULL_REMAP,ENABLE);
/* USART1 configure */
usart_deinit(USART2);
@@ -83,6 +96,9 @@ void usart2_init(int baud)
usart_receive_config(USART2, USART_RECEIVE_ENABLE);
usart_transmit_config(USART2, USART_TRANSMIT_ENABLE);
usart_enable(USART2);
+
+
+ //usart_interrupt_enable(USART2, USART_INT_RBNE);
}
diff --git a/board/TencentOS_tiny_EVB_LX/TOS_CONFIG/tos_config.h b/board/TencentOS_tiny_EVB_LX/TOS_CONFIG/tos_config.h
index e007b9ec..4bba2d58 100644
--- a/board/TencentOS_tiny_EVB_LX/TOS_CONFIG/tos_config.h
+++ b/board/TencentOS_tiny_EVB_LX/TOS_CONFIG/tos_config.h
@@ -20,7 +20,7 @@
#define TOS_CFG_MMHEAP_EN 1u
// 配置TencentOS tiny动态内存池大小
-#define TOS_CFG_MMHEAP_DEFAULT_POOL_SIZE 8192
+#define TOS_CFG_MMHEAP_DEFAULT_POOL_SIZE 16384
// 配置TencentOS tiny是否开启互斥锁模块
#define TOS_CFG_MUTEX_EN 1u
diff --git a/board/TencentOS_tiny_EVB_LX/eclipse/tencent_os_mqtt/.cproject b/board/TencentOS_tiny_EVB_LX/eclipse/tencent_os_mqtt/.cproject
new file mode 100644
index 00000000..565b7ba7
--- /dev/null
+++ b/board/TencentOS_tiny_EVB_LX/eclipse/tencent_os_mqtt/.cproject
@@ -0,0 +1,448 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/board/TencentOS_tiny_EVB_LX/eclipse/tencent_os_mqtt/.gitignore b/board/TencentOS_tiny_EVB_LX/eclipse/tencent_os_mqtt/.gitignore
new file mode 100644
index 00000000..3df573fe
--- /dev/null
+++ b/board/TencentOS_tiny_EVB_LX/eclipse/tencent_os_mqtt/.gitignore
@@ -0,0 +1 @@
+/Debug/
diff --git a/board/TencentOS_tiny_EVB_LX/eclipse/tencent_os_mqtt/.project b/board/TencentOS_tiny_EVB_LX/eclipse/tencent_os_mqtt/.project
new file mode 100644
index 00000000..a5400f89
--- /dev/null
+++ b/board/TencentOS_tiny_EVB_LX/eclipse/tencent_os_mqtt/.project
@@ -0,0 +1,154 @@
+
+
+ tencent_os_mqtt
+
+
+
+
+
+ org.eclipse.cdt.managedbuilder.core.genmakebuilder
+ clean,full,incremental,
+
+
+
+
+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder
+ full,incremental,
+
+
+
+
+
+ org.eclipse.cdt.core.cnature
+ org.eclipse.cdt.managedbuilder.core.managedBuildNature
+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature
+
+
+
+ Application
+ 2
+ virtual:/virtual
+
+
+ GD32VF103_Firmware_Library
+ 2
+ $%7BPARENT-4-PROJECT_LOC%7D/platform/vendor_bsp/gd/GD32VF103_Firmware_Library
+
+
+ TencentOS_tiny
+ 2
+ virtual:/virtual
+
+
+ Application/Inc
+ 2
+ $%7BPARENT-2-PROJECT_LOC%7D/BSP/Inc
+
+
+ Application/Src
+ 2
+ $%7BPARENT-2-PROJECT_LOC%7D/BSP/Src
+
+
+ Application/tencent_os_mqtt
+ 2
+ /Users/ace/workspace/TencentOS-tiny/examples/tencent_os_mqtt
+
+
+ Application/tos_config.h
+ 1
+ $%7BPARENT-2-PROJECT_LOC%7D/TOS_CONFIG/tos_config.h
+
+
+ TencentOS_tiny/arch
+ 2
+ virtual:/virtual
+
+
+ TencentOS_tiny/components
+ 2
+ virtual:/virtual
+
+
+ TencentOS_tiny/devices
+ 2
+ virtual:/virtual
+
+
+ TencentOS_tiny/kernel
+ 2
+ $%7BPARENT-4-PROJECT_LOC%7D/kernel
+
+
+ TencentOS_tiny/net
+ 2
+ virtual:/virtual
+
+
+ TencentOS_tiny/platform
+ 2
+ virtual:/virtual
+
+
+ TencentOS_tiny/arch/risc-v
+ 2
+ virtual:/virtual
+
+
+ TencentOS_tiny/components/connectivity
+ 2
+ virtual:/virtual
+
+
+ TencentOS_tiny/devices/esp8266
+ 2
+ TOP_DIR/devices/esp8266
+
+
+ TencentOS_tiny/net/at
+ 2
+ TOP_DIR/net/at
+
+
+ TencentOS_tiny/net/sal_module_wrapper
+ 2
+ TOP_DIR/net/sal_module_wrapper
+
+
+ TencentOS_tiny/platform/hal
+ 2
+ virtual:/virtual
+
+
+ TencentOS_tiny/arch/risc-v/bumblebee
+ 2
+ TOP_DIR/arch/risc-v/bumblebee/gcc
+
+
+ TencentOS_tiny/arch/risc-v/common
+ 2
+ $%7BPARENT-4-PROJECT_LOC%7D/arch/risc-v/common
+
+
+ TencentOS_tiny/arch/risc-v/rv32i
+ 2
+ TOP_DIR/arch/risc-v/rv32i/gcc
+
+
+ TencentOS_tiny/components/connectivity/Eclipse-Paho-MQTT
+ 2
+ TOP_DIR/components/connectivity/Eclipse-Paho-MQTT
+
+
+ TencentOS_tiny/platform/hal/gd
+ 2
+ TOP_DIR/platform/hal/gd
+
+
+
+
+ TOP_DIR
+ $%7BPARENT-4-PROJECT_LOC%7D
+
+
+
diff --git a/board/TencentOS_tiny_EVB_LX/eclipse/tencent_os_mqtt/gd32vf103_libopt.h b/board/TencentOS_tiny_EVB_LX/eclipse/tencent_os_mqtt/gd32vf103_libopt.h
new file mode 100644
index 00000000..875ff748
--- /dev/null
+++ b/board/TencentOS_tiny_EVB_LX/eclipse/tencent_os_mqtt/gd32vf103_libopt.h
@@ -0,0 +1,61 @@
+/*!
+ \file gd32vf103_libopt.h
+ \brief library optional for gd32vf103
+
+ \version 2019-6-5, V1.0.0, demo for GD32VF103
+*/
+
+/*
+ Copyright (c) 2019, GigaDevice Semiconductor Inc.
+
+ Redistribution and use in source and binary forms, with or without modification,
+are permitted provided that the following conditions are met:
+
+ 1. Redistributions of source code must retain the above copyright notice, this
+ list of conditions and the following disclaimer.
+ 2. Redistributions in binary form must reproduce the above copyright notice,
+ this list of conditions and the following disclaimer in the documentation
+ and/or other materials provided with the distribution.
+ 3. Neither the name of the copyright holder nor the names of its contributors
+ may be used to endorse or promote products derived from this software without
+ specific prior written permission.
+
+ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
+IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT,
+INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
+NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
+PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
+WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY
+OF SUCH DAMAGE.
+*/
+
+#ifndef GD32VF103_LIBOPT_H
+#define GD32VF103_LIBOPT_H
+
+#include "gd32vf103_adc.h"
+#include "gd32vf103_bkp.h"
+#include "gd32vf103_can.h"
+#include "gd32vf103_crc.h"
+#include "gd32vf103_dac.h"
+#include "gd32vf103_dma.h"
+#include "gd32vf103_eclic.h"
+#include "gd32vf103_exmc.h"
+#include "gd32vf103_exti.h"
+#include "gd32vf103_fmc.h"
+#include "gd32vf103_gpio.h"
+#include "gd32vf103_i2c.h"
+#include "gd32vf103_fwdgt.h"
+#include "gd32vf103_dbg.h"
+#include "gd32vf103_pmu.h"
+#include "gd32vf103_rcu.h"
+#include "gd32vf103_rtc.h"
+#include "gd32vf103_spi.h"
+#include "gd32vf103_timer.h"
+#include "gd32vf103_usart.h"
+#include "gd32vf103_wwdgt.h"
+#include "n200_func.h"
+
+#endif /* GD32VF103_LIBOPT_H */
diff --git a/board/TencentOS_tiny_EVB_LX/eclipse/tencent_os_mqtt/link.lds b/board/TencentOS_tiny_EVB_LX/eclipse/tencent_os_mqtt/link.lds
new file mode 100644
index 00000000..1c32e640
--- /dev/null
+++ b/board/TencentOS_tiny_EVB_LX/eclipse/tencent_os_mqtt/link.lds
@@ -0,0 +1,175 @@
+OUTPUT_ARCH( "riscv" )
+
+ENTRY( _start )
+
+MEMORY
+{
+ /* Run in FLASH */
+ flash (rxai!w) : ORIGIN = 0x08000000, LENGTH = 128k
+ ram (wxa!ri) : ORIGIN = 0x20000000, LENGTH = 32K
+
+ /* Run in RAM */
+/* flash (rxai!w) : ORIGIN = 0x20000000, LENGTH = 24k
+ ram (wxa!ri) : ORIGIN = 0x20006000, LENGTH = 8K
+*/
+}
+
+
+SECTIONS
+{
+ __stack_size = DEFINED(__stack_size) ? __stack_size : 2K;
+
+
+ .init :
+ {
+ KEEP (*(SORT_NONE(.init)))
+ } >flash AT>flash
+
+ .ilalign :
+ {
+ . = ALIGN(4);
+ PROVIDE( _ilm_lma = . );
+ } >flash AT>flash
+
+ .ialign :
+ {
+ PROVIDE( _ilm = . );
+ } >flash AT>flash
+
+ .text :
+ {
+ *(.rodata .rodata.*)
+ *(.text.unlikely .text.unlikely.*)
+ *(.text.startup .text.startup.*)
+ *(.text .text.*)
+ *(.gnu.linkonce.t.*)
+ } >flash AT>flash
+
+ .fini :
+ {
+ KEEP (*(SORT_NONE(.fini)))
+ } >flash AT>flash
+
+ . = ALIGN(4);
+
+ PROVIDE (__etext = .);
+ PROVIDE (_etext = .);/*0x80022c8*/
+ PROVIDE (etext = .);/*0x80022c8*/
+ PROVIDE( _eilm = . );
+
+ .preinit_array :
+ {
+ PROVIDE_HIDDEN (__preinit_array_start = .);
+ KEEP (*(.preinit_array))
+ PROVIDE_HIDDEN (__preinit_array_end = .);
+ } >flash AT>flash
+
+ .init_array :
+ {
+ PROVIDE_HIDDEN (__init_array_start = .);
+ KEEP (*(SORT_BY_INIT_PRIORITY(.init_array.*) SORT_BY_INIT_PRIORITY(.ctors.*)))
+ KEEP (*(.init_array EXCLUDE_FILE (*crtbegin.o *crtbegin?.o *crtend.o *crtend?.o ) .ctors))
+ PROVIDE_HIDDEN (__init_array_end = .);
+ } >flash AT>flash
+
+ .fini_array :
+ {
+ PROVIDE_HIDDEN (__fini_array_start = .);
+ KEEP (*(SORT_BY_INIT_PRIORITY(.fini_array.*) SORT_BY_INIT_PRIORITY(.dtors.*)))
+ KEEP (*(.fini_array EXCLUDE_FILE (*crtbegin.o *crtbegin?.o *crtend.o *crtend?.o ) .dtors))
+ PROVIDE_HIDDEN (__fini_array_end = .);
+ } >flash AT>flash
+
+ .ctors :
+ {
+ /* gcc uses crtbegin.o to find the start of
+ the constructors, so we make sure it is
+ first. Because this is a wildcard, it
+ doesn't matter if the user does not
+ actually link against crtbegin.o; the
+ linker won't look for a file to match a
+ wildcard. The wildcard also means that it
+ doesn't matter which directory crtbegin.o
+ is in. */
+ KEEP (*crtbegin.o(.ctors))
+ KEEP (*crtbegin?.o(.ctors))
+ /* We don't want to include the .ctor section from
+ the crtend.o file until after the sorted ctors.
+ The .ctor section from the crtend file contains the
+ end of ctors marker and it must be last */
+ KEEP (*(EXCLUDE_FILE (*crtend.o *crtend?.o ) .ctors))
+ KEEP (*(SORT(.ctors.*)))
+ KEEP (*(.ctors))
+ } >flash AT>flash
+
+ .dtors :
+ {
+ KEEP (*crtbegin.o(.dtors))
+ KEEP (*crtbegin?.o(.dtors))
+ KEEP (*(EXCLUDE_FILE (*crtend.o *crtend?.o ) .dtors))
+ KEEP (*(SORT(.dtors.*)))
+ KEEP (*(.dtors))
+ } >flash AT>flash
+
+ . = ALIGN(4);
+ PROVIDE( _eilm = . );
+
+ .lalign :
+ {
+ . = ALIGN(4);
+ PROVIDE( _data_lma = . );
+ } >flash AT>flash
+
+ .dalign :
+ {
+ . = ALIGN(4);
+ PROVIDE( _data = . );
+ } >ram AT>flash
+
+
+ .data :
+ {
+ *(.rdata)
+
+ *(.gnu.linkonce.r.*)
+ *(.data .data.*)
+ *(.gnu.linkonce.d.*)
+ . = ALIGN(8);
+ PROVIDE( __global_pointer$ = . + 0x800);
+ *(.sdata .sdata.*)
+ *(.gnu.linkonce.s.*)
+ . = ALIGN(8);
+ *(.srodata.cst16)
+ *(.srodata.cst8)
+ *(.srodata.cst4)
+ *(.srodata.cst2)
+ *(.srodata .srodata.*)
+ } >ram AT>flash
+
+ . = ALIGN(4);
+ PROVIDE( _edata = . );
+ PROVIDE( edata = . );
+
+ PROVIDE( _fbss = . ); /*0X200052A0 0X200002A0*/
+ PROVIDE( __bss_start = . );
+ .bss :
+ {
+ *(.sbss*)
+ *(.gnu.linkonce.sb.*)
+ *(.bss .bss.*)
+ *(.gnu.linkonce.b.*)
+ *(COMMON)
+ . = ALIGN(4);
+ } >ram AT>ram
+
+ . = ALIGN(8);
+ PROVIDE( _end = . ); /*0X2000,0340*/
+ PROVIDE( end = . );
+
+ .stack ORIGIN(ram) + LENGTH(ram) - __stack_size :
+ {
+ PROVIDE( _heap_end = . );
+ . = __stack_size;
+ PROVIDE( _sp = . );
+ } >ram AT>ram
+}
diff --git a/board/TencentOS_tiny_EVB_LX/eclipse/tencent_os_mqtt/main.c b/board/TencentOS_tiny_EVB_LX/eclipse/tencent_os_mqtt/main.c
new file mode 100644
index 00000000..daa53fe9
--- /dev/null
+++ b/board/TencentOS_tiny_EVB_LX/eclipse/tencent_os_mqtt/main.c
@@ -0,0 +1,71 @@
+#include "mcu_init.h"
+#include "tos_k.h"
+#include "tos_hal.h"
+
+#define BLED_TASK_SIZE 1024
+#define WIFI_TASK_SIZE 4096
+k_task_t k_task_bled;
+k_task_t k_task_wifi;
+uint8_t k_bled_stk[BLED_TASK_SIZE];
+uint8_t k_wifi_stk[WIFI_TASK_SIZE];
+
+
+void USART0_IRQHandler() {
+ tos_knl_irq_enter();
+ if(RESET != usart_interrupt_flag_get(USART0, USART_INT_FLAG_RBNE)){
+ uint8_t data = usart_data_receive(USART0);
+ printf("%c\n", data);
+ }
+ tos_knl_irq_leave();
+}
+
+void USART1_IRQHandler() {
+ tos_knl_irq_enter();
+ if(RESET != usart_interrupt_flag_get(USART1, USART_INT_FLAG_RBNE)){
+ uint8_t data = usart_data_receive(USART1);
+ tos_at_uart_input_byte(data);
+ }
+ tos_knl_irq_leave();
+}
+
+void USART2_IRQHandler() {
+ tos_knl_irq_enter();
+ if(RESET != usart_interrupt_flag_get(USART2, USART_INT_FLAG_RBNE)){
+ uint8_t data = usart_data_receive(USART2);
+ }
+ tos_knl_irq_leave();
+}
+
+void task_bled(void *pdata)
+{
+ int cnt = 0;
+ while (1) {
+ printf("blink led task cnt: %d\n", cnt++);
+ gpio_bit_write(LED_GPIO_PORT, LED_PIN,cnt % 2 ? SET : RESET);
+ tos_task_delay(1000);
+ }
+}
+
+extern void mqtt_demo();
+extern void mqtt_set_esp8266_port(hal_uart_port_t port);
+void task_wifi(void *pdata)
+{
+ while(1) {
+ mqtt_set_esp8266_port(HAL_UART_PORT_1);
+ mqtt_demo();
+ tos_task_delay(500);
+ }
+}
+
+
+void main(void) {
+ board_init();
+
+ tos_knl_init();
+
+ tos_task_create(&k_task_bled, "bled", task_bled, NULL, 5, k_bled_stk, BLED_TASK_SIZE, 0);
+ tos_task_create(&k_task_wifi, "wifi", task_wifi, NULL, 4, k_wifi_stk, WIFI_TASK_SIZE, 0);
+
+ tos_knl_start();
+
+}
diff --git a/board/TencentOS_tiny_EVB_LX/eclipse/tencent_os_mqtt/openocd_gdlink.cfg b/board/TencentOS_tiny_EVB_LX/eclipse/tencent_os_mqtt/openocd_gdlink.cfg
new file mode 100644
index 00000000..3ec85d42
--- /dev/null
+++ b/board/TencentOS_tiny_EVB_LX/eclipse/tencent_os_mqtt/openocd_gdlink.cfg
@@ -0,0 +1,45 @@
+adapter_khz 1000
+reset_config srst_only
+adapter_nsrst_assert_width 100
+
+
+
+interface cmsis-dap
+
+transport select jtag
+
+#autoexit true
+
+set _CHIPNAME riscv
+jtag newtap $_CHIPNAME cpu -irlen 5 -expected-id 0x1000563d
+
+set _TARGETNAME $_CHIPNAME.cpu
+target create $_TARGETNAME riscv -chain-position $_TARGETNAME
+$_TARGETNAME configure -work-area-phys 0x20000000 -work-area-size 20480 -work-area-backup 0
+
+
+# Work-area is a space in RAM used for flash programming
+if { [info exists WORKAREASIZE] } {
+ set _WORKAREASIZE $WORKAREASIZE
+} else {
+ set _WORKAREASIZE 0x5000
+}
+
+# Allow overriding the Flash bank size
+if { [info exists FLASH_SIZE] } {
+ set _FLASH_SIZE $FLASH_SIZE
+} else {
+ # autodetect size
+ set _FLASH_SIZE 0
+}
+
+# flash size will be probed
+set _FLASHNAME $_CHIPNAME.flash
+
+flash bank $_FLASHNAME gd32vf103 0x08000000 0 0 0 $_TARGETNAME
+riscv set_reset_timeout_sec 1
+init
+
+halt
+
+
diff --git a/examples/tencent_os_mqtt/mqtt_example.c b/examples/tencent_os_mqtt/mqtt_example.c
index 9f44de28..dba436a6 100644
--- a/examples/tencent_os_mqtt/mqtt_example.c
+++ b/examples/tencent_os_mqtt/mqtt_example.c
@@ -4,6 +4,13 @@
#define USE_ESP8266
+static hal_uart_port_t esp8266_port = HAL_UART_PORT_0;
+
+void mqtt_set_esp8266_port(hal_uart_port_t port) {
+ esp8266_port = port;
+}
+
+
void mqtt_demo(void)
{
int count = 1;
@@ -35,7 +42,7 @@ void mqtt_demo(void)
sub_opt.topic = MQTT_SUBSCRIBE_TOPIC;
#ifdef USE_ESP8266
- esp8266_sal_init(HAL_UART_PORT_0);
+ esp8266_sal_init(esp8266_port);
esp8266_join_ap("SheldonDai", "srnr6x9xbhmb0");
#endif
@@ -73,7 +80,7 @@ void mqtt_demo(void)
}
count++;
- osDelay(1000);
+ tos_task_delay(1000);
}
}
diff --git a/net/at/src/tos_at.c b/net/at/src/tos_at.c
index 95eca8a8..f632cbef 100644
--- a/net/at/src/tos_at.c
+++ b/net/at/src/tos_at.c
@@ -347,7 +347,7 @@ __STATIC_INLINE__ void at_echo_flush(at_echo_t *echo)
echo->__w_idx = 0;
}
-__STATIC_INLINE void at_echo_attach(at_echo_t *echo)
+__STATIC_INLINE__ void at_echo_attach(at_echo_t *echo)
{
at_echo_flush(echo);
AT_AGENT->echo = echo;
diff --git a/platform/hal/gd/gd32vf1xx/src/tos_hal_uart.c b/platform/hal/gd/gd32vf1xx/src/tos_hal_uart.c
new file mode 100644
index 00000000..d12ae682
--- /dev/null
+++ b/platform/hal/gd/gd32vf1xx/src/tos_hal_uart.c
@@ -0,0 +1,90 @@
+#include "tos_k.h"
+#include "tos_hal.h"
+#include "gd32vf103.h"
+#include "usart.h"
+
+typedef struct __UART_HandleTypeDef {
+ hal_uart_port_t port;
+} UART_HandleTypeDef;
+
+
+UART_HandleTypeDef huart0 = { USART0 };
+UART_HandleTypeDef huart1 = { USART1 };
+UART_HandleTypeDef huart2 = { USART2 };
+
+__API__ int tos_hal_uart_init(hal_uart_t *uart, hal_uart_port_t port)
+{
+ if (!uart) {
+ return -1;
+ }
+
+ if (port == HAL_UART_PORT_0) {
+ uart->private_uart = &huart0;
+ usart0_init(115200);
+ } else if (port == HAL_UART_PORT_1) {
+ uart->private_uart = &huart1;
+ usart1_init(115200);
+ } else if (port == HAL_UART_PORT_2) {
+ uart->private_uart = &huart2;
+ usart2_init(115200);
+ } else {
+ return -1;
+ }
+
+
+ uart->port = ((UART_HandleTypeDef*)(uart->private_uart))->port;
+
+
+
+ return 0;
+}
+
+__API__ int tos_hal_uart_write(hal_uart_t *uart, const uint8_t *buf, size_t size, uint32_t timeout)
+{
+ UART_HandleTypeDef *uart_handle;
+
+ if (!uart || !buf) {
+ return -1;
+ }
+
+ if (!uart->private_uart) {
+ return -1;
+ }
+
+ uart_handle = (UART_HandleTypeDef *)uart->private_uart;
+
+ for(size_t i=0; iport, buf[i]);
+ tos_task_delay(1);
+ }
+
+
+ return 0;
+}
+
+__API__ int tos_hal_uart_read(hal_uart_t *uart, const uint8_t *buf, size_t size, uint32_t timeout)
+{
+ return 0;
+}
+
+__API__ int tos_hal_uart_deinit(hal_uart_t *uart)
+{
+ UART_HandleTypeDef *uart_handle;
+
+ if (!uart) {
+ return -1;
+ }
+
+ if (!uart->private_uart) {
+ return -1;
+ }
+
+ uart_handle = (UART_HandleTypeDef *)uart->private_uart;
+
+
+ usart_deinit(uart_handle->port);
+
+
+ return 0;
+}
+