diff --git a/board/BDW01-STM32L496VG/BSP/app/mqttclient_iot_explorer.c b/board/BDW01-STM32L496VG/BSP/app/mqttclient_iot_explorer.c
index 372b308a..5bb4d30e 100644
--- a/board/BDW01-STM32L496VG/BSP/app/mqttclient_iot_explorer.c
+++ b/board/BDW01-STM32L496VG/BSP/app/mqttclient_iot_explorer.c
@@ -2,7 +2,7 @@
#include "mcu_init.h"
#include "tos_k.h"
#include "mqttclient.h"
-#include "cjson.h"
+#include "cJSON.h"
#include "sal_module_wrapper.h"
diff --git a/board/BearPi_STM32L562RE/KEIL/mqttclient_iot_explorer/demo/mqttclient_iot_explorer.c b/board/BearPi_STM32L562RE/KEIL/mqttclient_iot_explorer/demo/mqttclient_iot_explorer.c
index 80a85644..aa9dc566 100644
--- a/board/BearPi_STM32L562RE/KEIL/mqttclient_iot_explorer/demo/mqttclient_iot_explorer.c
+++ b/board/BearPi_STM32L562RE/KEIL/mqttclient_iot_explorer/demo/mqttclient_iot_explorer.c
@@ -2,7 +2,7 @@
#include "mcu_init.h"
#include "tos_k.h"
#include "mqttclient.h"
-#include "cjson.h"
+#include "cJSON.h"
#include "sal_module_wrapper.h"
#define USE_ESP8266
diff --git a/board/GD32F310G_START/BSP/Inc/gd32f3x0_it.h b/board/GD32F310G_START/BSP/Inc/gd32f3x0_it.h
new file mode 100644
index 00000000..4eabb043
--- /dev/null
+++ b/board/GD32F310G_START/BSP/Inc/gd32f3x0_it.h
@@ -0,0 +1,60 @@
+/*!
+ \file gd32f3x0_it.h
+ \brief the header file of the ISR
+
+ \version 2022-03-06, V1.0.0, demo for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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 GD32F3X0_IT_H
+#define GD32F3X0_IT_H
+
+#include "gd32f3x0.h"
+
+/* function declarations */
+/* this function handles NMI exception */
+void NMI_Handler(void);
+/* this function handles HardFault exception */
+void HardFault_Handler(void);
+/* this function handles MemManage exception */
+void MemManage_Handler(void);
+/* this function handles BusFault exception */
+void BusFault_Handler(void);
+/* this function handles UsageFault exception */
+void UsageFault_Handler(void);
+/* this function handles SVC exception */
+void SVC_Handler(void);
+/* this function handles DebugMon exception */
+void DebugMon_Handler(void);
+/* this function handles PendSV exception */
+void PendSV_Handler(void);
+/* this function handles SysTick exception */
+void SysTick_Handler(void);
+
+#endif /* GD32F3X0_IT_H */
diff --git a/board/GD32F310G_START/BSP/Inc/gd32f3x0_libopt.h b/board/GD32F310G_START/BSP/Inc/gd32f3x0_libopt.h
new file mode 100644
index 00000000..5073be9c
--- /dev/null
+++ b/board/GD32F310G_START/BSP/Inc/gd32f3x0_libopt.h
@@ -0,0 +1,65 @@
+/*!
+ \file gd32f3x0_libopt.h
+ \brief library optional for gd32f3x0
+
+ \version 2022-03-06, V1.0.0, demo for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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 GD32F3X0_LIBOPT_H
+#define GD32F3X0_LIBOPT_H
+
+#include "gd32f3x0_adc.h"
+#include "gd32f3x0_crc.h"
+#include "gd32f3x0_ctc.h"
+#include "gd32f3x0_dbg.h"
+#include "gd32f3x0_dma.h"
+#include "gd32f3x0_exti.h"
+#include "gd32f3x0_fmc.h"
+#include "gd32f3x0_gpio.h"
+#include "gd32f3x0_syscfg.h"
+#include "gd32f3x0_i2c.h"
+#include "gd32f3x0_fwdgt.h"
+#include "gd32f3x0_pmu.h"
+#include "gd32f3x0_rcu.h"
+#include "gd32f3x0_rtc.h"
+#include "gd32f3x0_spi.h"
+#include "gd32f3x0_timer.h"
+#include "gd32f3x0_usart.h"
+#include "gd32f3x0_wwdgt.h"
+#include "gd32f3x0_misc.h"
+#include "gd32f3x0_tsi.h"
+
+#ifdef GD32F350
+#include "gd32f3x0_cec.h"
+#include "gd32f3x0_cmp.h"
+#include "gd32f3x0_dac.h"
+#endif /* GD32F350 */
+
+#endif /* GD32F3X0_LIBOPT_H */
diff --git a/board/GD32F310G_START/BSP/Inc/gpio.h b/board/GD32F310G_START/BSP/Inc/gpio.h
new file mode 100644
index 00000000..60ffe1e9
--- /dev/null
+++ b/board/GD32F310G_START/BSP/Inc/gpio.h
@@ -0,0 +1,30 @@
+/******************************************************************************
+* File: gpio.h
+*
+* Author: iysheng@163.com
+* Created: 04/14/22
+*****************************************************************************/
+
+#ifndef __GPIO_H__
+#define __GPIO_H__
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "gd32f3x0_libopt.h"
+
+#define LED_Pin GPIO_PIN_1
+#define LED_GPIO_Port GPIOA
+
+/**
+ * @brief GPIO inint
+ * @param void:
+ * retval N/A.
+ */
+void board_gpio_init(void);
+
+#ifdef __cplusplus
+}
+#endif
+#endif /*__PINOUT_H__ */
diff --git a/board/GD32F310G_START/BSP/Inc/main.h b/board/GD32F310G_START/BSP/Inc/main.h
new file mode 100644
index 00000000..bf6c2d3d
--- /dev/null
+++ b/board/GD32F310G_START/BSP/Inc/main.h
@@ -0,0 +1,36 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file : main.h
+ * @brief : Header for main.c file.
+ * This file contains the common defines of the application.
+ ******************************************************************************
+ * @attention
+ *
+ *
© Copyright (c) 2019 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under BSD 3-Clause license,
+ * the "License"; You may not use this file except in compliance with the
+ * License. You may obtain a copy of the License at:
+ * opensource.org/licenses/BSD-3-Clause
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __MAIN_H
+#define __MAIN_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __MAIN_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/board/GD32F310G_START/BSP/Inc/mcu_init.h b/board/GD32F310G_START/BSP/Inc/mcu_init.h
new file mode 100644
index 00000000..ec4a137b
--- /dev/null
+++ b/board/GD32F310G_START/BSP/Inc/mcu_init.h
@@ -0,0 +1,18 @@
+#ifndef __MCU_INIT_H
+#define __MCU_INIT_H
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+#include "main.h"
+#include "usart.h"
+#include "gpio.h"
+#include "tos_k.h"
+
+void board_init(void);
+void SystemClock_Config(void);
+
+#ifdef __cplusplus
+}
+#endif
+#endif /*__ __MCU_INIT_H */
diff --git a/board/GD32F310G_START/BSP/Inc/tickless/bsp_pm_device.h b/board/GD32F310G_START/BSP/Inc/tickless/bsp_pm_device.h
new file mode 100644
index 00000000..40efb2e1
--- /dev/null
+++ b/board/GD32F310G_START/BSP/Inc/tickless/bsp_pm_device.h
@@ -0,0 +1,11 @@
+#ifndef _PM_DEVICE_H_
+#define _PM_DEVICE_H_
+
+#if TOS_CFG_PWR_MGR_EN > 0u
+
+extern k_pm_device_t pm_device_uart;
+
+#endif
+
+#endif
+
diff --git a/board/GD32F310G_START/BSP/Inc/tickless/bsp_tickless_alarm.h b/board/GD32F310G_START/BSP/Inc/tickless/bsp_tickless_alarm.h
new file mode 100644
index 00000000..02cb3e8a
--- /dev/null
+++ b/board/GD32F310G_START/BSP/Inc/tickless/bsp_tickless_alarm.h
@@ -0,0 +1,17 @@
+#ifndef _TICKLESS_ALARM_H_
+#define _TICKLESS_ALARM_H_
+
+#if TOS_CFG_TICKLESS_EN > 0u
+
+extern k_tickless_wkup_alarm_t tickless_wkup_alarm_systick;
+
+extern k_tickless_wkup_alarm_t tickless_wkup_alarm_tim;
+
+extern k_tickless_wkup_alarm_t tickless_wkup_alarm_rtc_wkupirq;
+
+extern k_tickless_wkup_alarm_t tickless_wkup_alarm_rtc_alarmirq;
+
+#endif
+
+#endif
+
diff --git a/board/GD32F310G_START/BSP/Inc/usart.h b/board/GD32F310G_START/BSP/Inc/usart.h
new file mode 100644
index 00000000..dfe0b337
--- /dev/null
+++ b/board/GD32F310G_START/BSP/Inc/usart.h
@@ -0,0 +1,25 @@
+/******************************************************************************
+* File: usart.h
+*
+* Author: iysheng@163.com
+* Created: 04/14/22
+* Description:
+*****************************************************************************/
+#ifndef __USART_H__
+#define __USART_H__
+#ifdef __cplusplus
+extern "C" {
+#endif
+#include "gd32f3x0_libopt.h"
+
+/**
+ * @brief 板级 usart 硬件初始化
+ * @param void:
+ * retval N/A.
+ */
+int board_usart_init(void);
+
+#ifdef __cplusplus
+}
+#endif
+#endif /*__USART_H__ */
diff --git a/board/GD32F310G_START/BSP/Src/gd32f3x0_it.c b/board/GD32F310G_START/BSP/Src/gd32f3x0_it.c
new file mode 100644
index 00000000..fca2d443
--- /dev/null
+++ b/board/GD32F310G_START/BSP/Src/gd32f3x0_it.c
@@ -0,0 +1,151 @@
+/*!
+ \file gd32f3x0_it.c
+ \brief interrupt service routines
+
+ \version 2022-03-06, V1.0.0, demo for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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.
+*/
+
+#include "gd32f3x0_it.h"
+#include "tos_k.h"
+#include "tos_shell.h"
+
+/*!
+ \brief this function handles NMI exception
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void NMI_Handler(void)
+{
+}
+
+/*!
+ \brief this function handles HardFault exception
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void HardFault_Handler(void)
+{
+ /* if Hard Fault exception occurs, go to infinite loop */
+ while(1){
+ }
+}
+
+/*!
+ \brief this function handles MemManage exception
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void MemManage_Handler(void)
+{
+ /* if Memory Manage exception occurs, go to infinite loop */
+ while(1){
+ }
+}
+
+/*!
+ \brief this function handles BusFault exception
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void BusFault_Handler(void)
+{
+ /* if Bus Fault exception occurs, go to infinite loop */
+ while(1){
+ }
+}
+
+/*!
+ \brief this function handles UsageFault exception
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void UsageFault_Handler(void)
+{
+ /* if Usage Fault exception occurs, go to infinite loop */
+ while(1){
+ }
+}
+
+/*!
+ \brief this function handles SVC exception
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void SVC_Handler(void)
+{
+}
+
+/*!
+ \brief this function handles DebugMon exception
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void DebugMon_Handler(void)
+{
+}
+
+/*!
+ \brief this function handles SysTick exception
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void SysTick_Handler(void)
+{
+ if (tos_knl_is_running())
+ {
+ tos_knl_irq_enter();
+ tos_tick_handler();
+ tos_knl_irq_leave();
+ }
+}
+
+void USART0_IRQHandler(void)
+{
+ tos_knl_irq_enter();
+ if (SET == usart_interrupt_flag_get(USART0, USART_INT_FLAG_RBNE))
+ {
+ usart_flag_clear(USART0, USART_FLAG_ORERR);
+ tos_shell_input_byte((uint8_t)usart_data_receive(USART0));
+ }
+ if (SET == usart_interrupt_flag_get(USART0, USART_INT_FLAG_RBNE_ORERR))
+ {
+ usart_interrupt_flag_clear(USART0, USART_INT_FLAG_RBNE_ORERR);
+ }
+ tos_knl_irq_leave();
+}
+
diff --git a/board/GD32F310G_START/BSP/Src/gpio.c b/board/GD32F310G_START/BSP/Src/gpio.c
new file mode 100644
index 00000000..790b2a60
--- /dev/null
+++ b/board/GD32F310G_START/BSP/Src/gpio.c
@@ -0,0 +1,29 @@
+/******************************************************************************
+* File: gpio.c
+*
+* Author: iysheng@163.com
+* Created: 04/14/22
+* gpio hardware init
+*****************************************************************************/
+
+#include "gpio.h"
+
+/**
+ * @brief GPIO inint
+ * @param void:
+ * retval N/A.
+ */
+void board_gpio_init(void)
+{
+ rcu_periph_clock_enable(RCU_GPIOA);
+ rcu_periph_clock_enable(RCU_GPIOA);
+ gpio_mode_set(GPIOA, GPIO_MODE_AF, GPIO_PUPD_PULLUP, GPIO_PIN_9);
+ gpio_mode_set(GPIOA, GPIO_MODE_AF, GPIO_PUPD_PULLUP, GPIO_PIN_10);
+ gpio_output_options_set(GPIOA, GPIO_OTYPE_PP, GPIO_OSPEED_10MHZ, GPIO_PIN_10);
+ gpio_output_options_set(GPIOA, GPIO_OTYPE_PP, GPIO_OSPEED_10MHZ, GPIO_PIN_9);
+ gpio_af_set(GPIOA, GPIO_AF_1, GPIO_PIN_9);
+ gpio_af_set(GPIOA, GPIO_AF_1, GPIO_PIN_10);
+ gpio_mode_set(GPIOA, GPIO_MODE_OUTPUT, GPIO_PUPD_PULLUP, GPIO_PIN_1);
+ gpio_bit_set(GPIOA, GPIO_PIN_1);
+}
+
diff --git a/board/GD32F310G_START/BSP/Src/main.c b/board/GD32F310G_START/BSP/Src/main.c
new file mode 100644
index 00000000..4e05a837
--- /dev/null
+++ b/board/GD32F310G_START/BSP/Src/main.c
@@ -0,0 +1,37 @@
+#include "mcu_init.h"
+#include "tos_shell.h"
+
+#define APPLICATION_TASK_STK_SIZE 0x100
+k_task_t application_task;
+uint8_t application_task_stk[APPLICATION_TASK_STK_SIZE];
+static char gs_cmd_buffer[32];
+
+__attribute__ ((__weak__)) void application_entry(void *arg)
+{
+ while (1) {
+ gpio_bit_toggle(LED_GPIO_Port, LED_Pin);
+ tos_task_delay(1000);
+ }
+}
+
+static void board_shell_output_t(const char ch)
+{
+ if (ch == '\n')
+ {
+ while(RESET == usart_flag_get(USART0, USART_FLAG_TBE));
+ usart_data_transmit(USART0, '\r');
+ }
+ while(RESET == usart_flag_get(USART0, USART_FLAG_TBE));
+ usart_data_transmit(USART0, ch);
+}
+
+int main(void)
+{
+ board_init();
+ printf("Welcome to TencentOS tiny(%s)\r\n", TOS_VERSION);
+ tos_knl_init();
+ tos_task_create(&application_task, "application_task", application_entry, NULL, 4, application_task_stk, APPLICATION_TASK_STK_SIZE, 0);
+ tos_shell_init(gs_cmd_buffer, sizeof(gs_cmd_buffer), board_shell_output_t, NULL);
+ tos_knl_start();
+}
+
diff --git a/board/GD32F310G_START/BSP/Src/mcu_init.c b/board/GD32F310G_START/BSP/Src/mcu_init.c
new file mode 100644
index 00000000..381d805f
--- /dev/null
+++ b/board/GD32F310G_START/BSP/Src/mcu_init.c
@@ -0,0 +1,36 @@
+#include "mcu_init.h"
+
+#define USART_CONSOLE (USART0)
+int fputc(int ch, FILE *f)
+{
+ if (ch == '\n') {
+ while(RESET == usart_flag_get(USART_CONSOLE, USART_FLAG_TBE));
+ /* Auto complete return char */
+ usart_data_transmit(USART_CONSOLE, '\r');
+ }
+ while(RESET == usart_flag_get(USART_CONSOLE, USART_FLAG_TBE));
+ usart_data_transmit(USART_CONSOLE, ch);
+ return ch;
+}
+
+int _write(int fd, char *ptr, int len)
+{
+ int i = 0;
+ for (; i < len; i++)
+ {
+ if (*(ptr + i) == '\n') {
+ while(RESET == usart_flag_get(USART_CONSOLE, USART_FLAG_TBE));
+ /* Auto complete return char */
+ usart_data_transmit(USART_CONSOLE, '\r');
+ }
+ while(RESET == usart_flag_get(USART_CONSOLE, USART_FLAG_TBE));
+ usart_data_transmit(USART_CONSOLE, *(ptr + i));
+ }
+ return len;
+}
+
+void board_init(void)
+{
+ board_gpio_init();
+ board_usart_init();
+}
diff --git a/board/GD32F310G_START/BSP/Src/tickless/bsp_pm_device.c b/board/GD32F310G_START/BSP/Src/tickless/bsp_pm_device.c
new file mode 100644
index 00000000..bc95c813
--- /dev/null
+++ b/board/GD32F310G_START/BSP/Src/tickless/bsp_pm_device.c
@@ -0,0 +1,31 @@
+#include "tos_k.h"
+#include "mcu_init.h"
+
+#if TOS_CFG_PWR_MGR_EN > 0u
+
+static int pm_device_uart_init(void)
+{
+ return 0;
+}
+
+static int pm_device_uart_suspend(void)
+{
+ return 0;
+}
+
+static int pm_device_uart_resume(void)
+{
+ SystemClock_Config();
+
+ return 0;
+}
+
+k_pm_device_t pm_device_uart = {
+ .name = "uart",
+ .init = pm_device_uart_init,
+ .suspend = pm_device_uart_suspend,
+ .resume = pm_device_uart_resume,
+};
+
+#endif
+
diff --git a/board/GD32F310G_START/BSP/Src/tickless/bsp_pwr_mgr.c b/board/GD32F310G_START/BSP/Src/tickless/bsp_pwr_mgr.c
new file mode 100644
index 00000000..a8df35a8
--- /dev/null
+++ b/board/GD32F310G_START/BSP/Src/tickless/bsp_pwr_mgr.c
@@ -0,0 +1,26 @@
+#include "tos_k.h"
+#include "tickless/bsp_pm_device.h"
+#include "tickless/bsp_tickless_alarm.h"
+
+int tos_bsp_tickless_setup(void)
+{
+#if TOS_CFG_TICKLESS_EN > 0u
+ tos_pm_device_register(&pm_device_uart);
+
+ /* we set a default one shot timer here(systick) */
+ // tos_tickless_wkup_alarm_install(TOS_LOW_POWER_MODE_SLEEP, &tickless_wkup_alarm_systick);
+ tos_tickless_wkup_alarm_install(TOS_LOW_POWER_MODE_SLEEP, &tickless_wkup_alarm_tim);
+ tos_tickless_wkup_alarm_init(TOS_LOW_POWER_MODE_SLEEP);
+
+ tos_tickless_wkup_alarm_install(TOS_LOW_POWER_MODE_STOP, &tickless_wkup_alarm_rtc_wkupirq);
+ tos_tickless_wkup_alarm_init(TOS_LOW_POWER_MODE_STOP);
+
+ tos_tickless_wkup_alarm_install(TOS_LOW_POWER_MODE_STANDBY, &tickless_wkup_alarm_rtc_alarmirq);
+ tos_tickless_wkup_alarm_init(TOS_LOW_POWER_MODE_STANDBY);
+
+ tos_pm_cpu_lpwr_mode_set(TOS_LOW_POWER_MODE_SLEEP);
+#endif
+
+ return 0;
+}
+
diff --git a/board/GD32F310G_START/BSP/Src/tickless/bsp_tickless_alarm.c b/board/GD32F310G_START/BSP/Src/tickless/bsp_tickless_alarm.c
new file mode 100644
index 00000000..99c31edb
--- /dev/null
+++ b/board/GD32F310G_START/BSP/Src/tickless/bsp_tickless_alarm.c
@@ -0,0 +1,440 @@
+#include "tos_k.h"
+
+#include "stm32l4xx_hal.h"
+#include "stm32l4xx_hal_tim.h"
+#include "stm32l4xx_hal_rtc.h"
+
+#if TOS_CFG_TICKLESS_EN > 0u
+
+/*
+ systickҲʵΪticklessĻӣʵԭǣϵͳҪticklessģʽʱ
+ systickĴʱ
+ ˵һʱ6000msִУô6000mssystickûбҪһֱ
+ systickжϼΪ6000msʵsystickڲļʱĴֻ24λsystick
+ жϼʵСԲοtickless_systick_wkup_alarm_max_delayʵ֣ʹ
+ ȻڽidleʱʹcpusleepģʽҪͣΪsystickˣcpusleep
+ ģʽͣã
+
+ ʵϣtickless_systick_wkup_alarm_dismisstickless_wkup_alarm_dismissӿȱݵģ
+ ΪCPUticklessܲΪʱ䵽ˣпⲿжCPUѣһ
+ Ϊ걸ʵӦǣtickless_wkup_alarm_dismissӿڷʵ˯ߵʱ䣨ͨӵļʱĴ
+ ֵȱݺڻֽζӲвϤ
+
+ ע⣬systickֻΪsleepģʽµĻӡοtos_pm.h
+
+ Ŀǰһʵв걸кܶⷽѻӭͽ~
+ */
+static void tickless_systick_suspend(void)
+{
+ cpu_systick_suspend();
+ cpu_systick_pending_reset();
+}
+
+static void tickless_systick_resume(void)
+{
+ cpu_systick_resume();
+}
+
+static void tickless_systick_wkup_alarm_expires_set(k_time_t millisecond)
+{
+ cpu_systick_expires_set(millisecond);
+}
+
+static int tickless_systick_wkup_alarm_setup(k_time_t millisecond)
+{
+ tickless_systick_suspend();
+ tickless_systick_wkup_alarm_expires_set(millisecond);
+ tickless_systick_resume();
+ return 0;
+}
+
+static int tickless_systick_wkup_alarm_dismiss(void)
+{
+ // TODO:
+ // if not wakeup by systick(that's say another interrupt), need to identify this and fix
+ return 0;
+}
+
+static k_time_t tickless_systick_wkup_alarm_max_delay(void)
+{
+ return cpu_systick_max_delay_millisecond();
+}
+
+k_tickless_wkup_alarm_t tickless_wkup_alarm_systick = {
+ .init = K_NULL,
+ .setup = tickless_systick_wkup_alarm_setup,
+ .dismiss = tickless_systick_wkup_alarm_dismiss,
+ .max_delay = tickless_systick_wkup_alarm_max_delay,
+};
+
+
+/////////////////////////////////////////////////////////////////////////////////////////////
+/////////////////////////////////////////////////////////////////////////////////////////////
+/*
+ timer6ʵֵticklessӣΪSLEEPģʽµĻԴοtos_pm.h
+ Ŀǰһʵв걸кܶⷽѻӭͽ~
+ */
+static TIM_HandleTypeDef tim6;
+
+void HAL_TIM_Base_MspInit(TIM_HandleTypeDef *tim_handler)
+{
+ if (tim_handler->Instance == TIM6) {
+ __HAL_RCC_TIM6_CLK_ENABLE();
+
+ /* TIM6 interrupt Init */
+ HAL_NVIC_SetPriority(TIM6_DAC_IRQn, 0, 0);
+ HAL_NVIC_EnableIRQ(TIM6_DAC_IRQn);
+ }
+}
+
+void HAL_TIM_Base_MspDeInit(TIM_HandleTypeDef *tim_handler)
+{
+ if (tim_handler->Instance == TIM6) {
+ /* Peripheral clock disable */
+ __HAL_RCC_TIM6_CLK_DISABLE();
+
+ /* TIM6 interrupt Deinit */
+ HAL_NVIC_DisableIRQ(TIM6_DAC_IRQn);
+ }
+}
+
+static int tickless_tim6_wkup_alarm_init(void)
+{
+ tim6.Instance = TIM6;
+ tim6.Init.Prescaler = 0;
+ tim6.Init.CounterMode = TIM_COUNTERMODE_UP;
+ tim6.Init.Period = 0;
+ tim6.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
+ tim6.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
+ HAL_TIM_Base_Init(&tim6);
+ return 0;
+}
+
+static int tickless_tim6_wkup_alarm_setup(k_time_t millisecond)
+{
+ tim6.Init.Prescaler = 8000 - 1;
+ tim6.Init.Period = (millisecond * 10) - 1;
+
+ HAL_TIM_Base_Stop(&tim6);
+ __HAL_TIM_CLEAR_IT(&tim6, TIM_IT_UPDATE);
+
+ HAL_TIM_Base_Init(&tim6);
+ HAL_TIM_Base_Start_IT(&tim6);
+ return 0;
+}
+
+static int tickless_tim6_wkup_alarm_dismiss(void)
+{
+ TOS_CPU_CPSR_ALLOC();
+
+ TOS_CPU_INT_DISABLE();
+
+ HAL_TIM_Base_Stop(&tim6);
+ HAL_TIM_Base_Stop_IT(&tim6);
+
+ TOS_CPU_INT_ENABLE();
+ return 0;
+}
+
+static k_time_t tickless_tim6_wkup_alarm_max_delay(void)
+{
+ k_time_t millisecond;
+ uint32_t max_period;
+
+ max_period = ~((uint32_t)0u);
+ millisecond = (max_period - 1) / 10;
+ return millisecond;
+}
+
+void TIM6_DAC_IRQHandler(void)
+{
+ HAL_TIM_IRQHandler(&tim6);
+}
+
+k_tickless_wkup_alarm_t tickless_wkup_alarm_tim = {
+ .init = tickless_tim6_wkup_alarm_init,
+ .setup = tickless_tim6_wkup_alarm_setup,
+ .dismiss = tickless_tim6_wkup_alarm_dismiss,
+ .max_delay = tickless_tim6_wkup_alarm_max_delay,
+};
+
+
+/////////////////////////////////////////////////////////////////////////////////////////////
+/////////////////////////////////////////////////////////////////////////////////////////////
+/*
+ rtc wakeupжʵֵticklessӣΪSLEEPSTOPģʽµĻԴοtos_pm.h
+ Ŀǰһʵв걸кܶⷽѻӭͽ~
+ */
+static RTC_HandleTypeDef rtc_handler;
+
+static HAL_StatusTypeDef tickless_rtc_time_set(uint8_t hour, uint8_t minu, uint8_t sec, uint8_t format)
+{
+ RTC_TimeTypeDef rtc_time;
+
+ rtc_time.Hours = hour;
+ rtc_time.Minutes = minu;
+ rtc_time.Seconds = sec;
+ rtc_time.TimeFormat = format;
+ rtc_time.DayLightSaving = RTC_DAYLIGHTSAVING_NONE;
+ rtc_time.StoreOperation = RTC_STOREOPERATION_RESET;
+ return HAL_RTC_SetTime(&rtc_handler, &rtc_time, RTC_FORMAT_BIN);
+}
+
+static HAL_StatusTypeDef tickless_rtc_date_set(uint8_t year, uint8_t month, uint8_t date, uint8_t week)
+{
+ RTC_DateTypeDef rtc_date;
+
+ rtc_date.Date = date;
+ rtc_date.Month = month;
+ rtc_date.WeekDay = week;
+ rtc_date.Year = year;
+ return HAL_RTC_SetDate(&rtc_handler, &rtc_date, RTC_FORMAT_BIN);
+}
+
+static int tickless_rtc_wkup_alarm_init(void)
+{
+ rtc_handler.Instance = RTC;
+ rtc_handler.Init.HourFormat = RTC_HOURFORMAT_24;
+ rtc_handler.Init.AsynchPrediv = 0X7F;
+ rtc_handler.Init.SynchPrediv = 0XFF;
+ rtc_handler.Init.OutPut = RTC_OUTPUT_DISABLE;
+ rtc_handler.Init.OutPutPolarity = RTC_OUTPUT_POLARITY_HIGH;
+ rtc_handler.Init.OutPutType = RTC_OUTPUT_TYPE_OPENDRAIN;
+
+ if (HAL_RTC_Init(&rtc_handler) != HAL_OK) {
+ return -1;
+ }
+
+ if (HAL_RTCEx_BKUPRead(&rtc_handler, RTC_BKP_DR0) != 0X5050) {
+ tickless_rtc_time_set(23, 59, 56, RTC_HOURFORMAT12_PM);
+ tickless_rtc_date_set(15, 12, 27, 7);
+ HAL_RTCEx_BKUPWrite(&rtc_handler, RTC_BKP_DR0,0X5050);
+ }
+
+ return 0;
+}
+
+static int tickless_rtc_wkupirq_wkup_alarm_setup(k_time_t millisecond)
+{
+ uint32_t wkup_clock = RTC_WAKEUPCLOCK_CK_SPRE_16BITS;
+ if (millisecond < 1000) {
+ millisecond = 1000;
+ }
+ uint32_t wkup_count = (millisecond / 1000) - 1;
+
+ __HAL_RTC_WAKEUPTIMER_CLEAR_FLAG(&rtc_handler, RTC_FLAG_WUTF);
+
+ HAL_RTCEx_SetWakeUpTimer_IT(&rtc_handler, wkup_count, wkup_clock);
+
+ HAL_NVIC_SetPriority(RTC_WKUP_IRQn, 0x02, 0x02);
+ HAL_NVIC_EnableIRQ(RTC_WKUP_IRQn);
+ return 0;
+}
+
+static int tickless_rtc_wkupirq_wkup_alarm_dismiss(void)
+{
+#if defined(STM32F4) || defined(STM32L4)
+ __HAL_PWR_CLEAR_FLAG(PWR_FLAG_WU);
+#endif
+
+ __HAL_RTC_WAKEUPTIMER_CLEAR_FLAG(&rtc_handler, RTC_FLAG_WUTF);
+
+ if (HAL_RTCEx_DeactivateWakeUpTimer(&rtc_handler) != HAL_OK) {
+ return -1;
+ }
+
+ HAL_NVIC_DisableIRQ(RTC_WKUP_IRQn);
+ return 0;
+}
+
+static k_time_t tickless_rtc_wkupirq_wkup_alarm_max_delay(void)
+{
+ return 0xFFFF * K_TIME_MILLISEC_PER_SEC;
+}
+
+void HAL_RTC_MspInit(RTC_HandleTypeDef *rtc_handler)
+{
+ RCC_OscInitTypeDef rcc_osc;
+ RCC_PeriphCLKInitTypeDef periph_clock;
+
+ __HAL_RCC_PWR_CLK_ENABLE();
+ HAL_PWR_EnableBkUpAccess();
+
+ rcc_osc.OscillatorType = RCC_OSCILLATORTYPE_LSE;
+ rcc_osc.PLL.PLLState = RCC_PLL_NONE;
+ rcc_osc.LSEState = RCC_LSE_ON;
+ HAL_RCC_OscConfig(&rcc_osc);
+
+ periph_clock.PeriphClockSelection = RCC_PERIPHCLK_RTC;
+ periph_clock.RTCClockSelection = RCC_RTCCLKSOURCE_LSE;
+ HAL_RCCEx_PeriphCLKConfig(&periph_clock);
+
+ __HAL_RCC_RTC_ENABLE();
+}
+
+void RTC_WKUP_IRQHandler(void)
+{
+ HAL_RTCEx_WakeUpTimerIRQHandler(&rtc_handler);
+}
+
+void HAL_RTCEx_WakeUpTimerEventCallback(RTC_HandleTypeDef *rtc_handler)
+{
+}
+
+k_tickless_wkup_alarm_t tickless_wkup_alarm_rtc_wkupirq = {
+ .init = tickless_rtc_wkup_alarm_init,
+ .setup = tickless_rtc_wkupirq_wkup_alarm_setup,
+ .dismiss = tickless_rtc_wkupirq_wkup_alarm_dismiss,
+ .max_delay = tickless_rtc_wkupirq_wkup_alarm_max_delay,
+};
+
+
+
+/////////////////////////////////////////////////////////////////////////////////////////////
+/////////////////////////////////////////////////////////////////////////////////////////////
+/*
+ rtc alarmжʵֵticklessӣΪSLEEPSTOPSTANDBYģʽµĻԴοtos_pm.h
+ Ŀǰһʵв걸кܶⷽѻӭͽ~
+ */
+static int tickless_rtc_alarmirq_wkup_alarm_setup(k_time_t millisecond)
+{
+ uint8_t hour, minute, second, subsecond, date;
+
+ RTC_AlarmTypeDef rtc_alarm;
+ RTC_TimeTypeDef rtc_time;
+ RTC_DateTypeDef rtc_date;
+
+ HAL_RTC_GetTime(&rtc_handler, &rtc_time, RTC_FORMAT_BIN);
+ HAL_RTC_GetDate(&rtc_handler, &rtc_date, RTC_FORMAT_BIN);
+
+ hour = rtc_time.Hours;
+ minute = rtc_time.Minutes;
+ second = rtc_time.Seconds;
+#if 0
+ date = rtc_date.Date;
+#else
+ date = rtc_date.WeekDay;
+#endif
+
+ printf("before >>> %d %d %d %d\n", date, hour, minute, second);
+
+ /* I know it's ugly, I will find a elegant way. Welcome to tell me, 3ks~ */
+ second += millisecond / K_TIME_MILLISEC_PER_SEC;
+ if (second >= 60) {
+ minute += 1;
+ second -= 60;
+ }
+ if (minute >= 60) {
+ hour += 1;
+ minute -= 60;
+ }
+ if (hour >= 24) {
+ date += 1;
+ hour -= 24;
+ }
+
+ printf("after >>> %d %d %d %d\n", date, hour, minute, second);
+
+ rtc_alarm.AlarmTime.Hours = hour;
+ rtc_alarm.AlarmTime.Minutes = minute;
+ rtc_alarm.AlarmTime.Seconds = second;
+ rtc_alarm.AlarmTime.SubSeconds = 0;
+ rtc_alarm.AlarmTime.TimeFormat = RTC_HOURFORMAT12_AM;
+
+ rtc_alarm.AlarmMask = RTC_ALARMMASK_NONE;
+ rtc_alarm.AlarmSubSecondMask = RTC_ALARMSUBSECONDMASK_NONE;
+ rtc_alarm.AlarmDateWeekDaySel = RTC_ALARMDATEWEEKDAYSEL_WEEKDAY; // RTC_ALARMDATEWEEKDAYSEL_DATE; // RTC_ALARMDATEWEEKDAYSEL_WEEKDAY;
+ rtc_alarm.AlarmDateWeekDay = date;
+ rtc_alarm.Alarm = RTC_ALARM_A;
+ HAL_RTC_SetAlarm_IT(&rtc_handler, &rtc_alarm, RTC_FORMAT_BIN);
+
+ HAL_NVIC_SetPriority(RTC_Alarm_IRQn, 0x01, 0x02);
+ HAL_NVIC_EnableIRQ(RTC_Alarm_IRQn);
+
+
+ // __HAL_PWR_GET_FLAG(PWR_FLAG_WU)
+
+
+ __HAL_RCC_AHB1_FORCE_RESET(); //λIO
+ __HAL_RCC_PWR_CLK_ENABLE(); //ʹPWRʱ
+
+ // __HAL_RCC_BACKUPRESET_FORCE(); //λ
+ HAL_PWR_EnableBkUpAccess(); //ʹ
+
+ __HAL_PWR_CLEAR_FLAG(PWR_FLAG_SB);
+ __HAL_RTC_WRITEPROTECTION_DISABLE(&rtc_handler);//رRTCд
+
+ //رRTCж
+ __HAL_RTC_WAKEUPTIMER_DISABLE_IT(&rtc_handler,RTC_IT_WUT);
+#if 0
+ __HAL_RTC_TIMESTAMP_DISABLE_IT(&rtc_handler,RTC_IT_TS);
+ __HAL_RTC_ALARM_DISABLE_IT(&rtc_handler,RTC_IT_ALRA|RTC_IT_ALRB);
+#endif
+
+ //RTCжϱ־λ
+ __HAL_RTC_ALARM_CLEAR_FLAG(&rtc_handler,RTC_FLAG_ALRAF|RTC_FLAG_ALRBF);
+ __HAL_RTC_TIMESTAMP_CLEAR_FLAG(&rtc_handler,RTC_FLAG_TSF);
+ __HAL_RTC_WAKEUPTIMER_CLEAR_FLAG(&rtc_handler,RTC_FLAG_WUTF);
+
+ // __HAL_RCC_BACKUPRESET_RELEASE(); //λ
+ __HAL_RTC_WRITEPROTECTION_ENABLE(&rtc_handler); //ʹRTCд
+
+
+#ifdef STM32F4
+ __HAL_PWR_CLEAR_FLAG(PWR_FLAG_WU); //Wake_UP־
+#endif
+
+#ifdef STM32F7
+ // __HAL_PWR_CLEAR_WAKEUP_FLAG(PWR_WAKEUP_PIN_FLAG1); //Wake_UP־
+#endif
+
+ // HAL_PWR_EnableWakeUpPin(PWR_WAKEUP_PIN1); //WKUPڻ
+
+ return 0;
+}
+
+static int tickless_rtc_alarmirq_wkup_alarm_dismiss(void)
+{
+#if 1
+ // __HAL_PWR_GET_FLAG(PWR_FLAG_WU);
+
+ __HAL_PWR_CLEAR_FLAG(PWR_FLAG_WU);
+
+ // __HAL_RTC_WAKEUPTIMER_CLEAR_FLAG(&rtc_handler, RTC_FLAG_ALRAF);
+
+ __HAL_RTC_ALARM_CLEAR_FLAG(&rtc_handler, RTC_FLAG_ALRAF);
+
+#if 0
+ if (HAL_RTCEx_DeactivateWakeUpTimer(&rtc_handler) != HAL_OK) {
+ return -1;
+ }
+#endif
+
+ HAL_NVIC_DisableIRQ(RTC_Alarm_IRQn);
+ return 0;
+#endif
+}
+
+static k_time_t tickless_rtc_alarmirq_wkup_alarm_max_delay(void)
+{
+ return 0xFFFF; // just kidding, I will fix it out. Welcome to tell me, 3ks~ */
+}
+
+void RTC_Alarm_IRQHandler(void)
+{
+ HAL_RTC_AlarmIRQHandler(&rtc_handler);
+}
+
+void HAL_RTC_AlarmAEventCallback(RTC_HandleTypeDef *rtc_handler)
+{
+}
+
+k_tickless_wkup_alarm_t tickless_wkup_alarm_rtc_alarmirq = {
+ .init = tickless_rtc_wkup_alarm_init,
+ .setup = tickless_rtc_alarmirq_wkup_alarm_setup,
+ .dismiss = tickless_rtc_alarmirq_wkup_alarm_dismiss,
+ .max_delay = tickless_rtc_alarmirq_wkup_alarm_max_delay,
+};
+
+#endif
+
diff --git a/board/GD32F310G_START/BSP/Src/usart.c b/board/GD32F310G_START/BSP/Src/usart.c
new file mode 100644
index 00000000..e8660248
--- /dev/null
+++ b/board/GD32F310G_START/BSP/Src/usart.c
@@ -0,0 +1,43 @@
+/**
+ ******************************************************************************
+ * File Name : USART.c
+ * Description : This file provides code for the configuration
+ * of the USART instances.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2019 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under BSD 3-Clause license,
+ * the "License"; You may not use this file except in compliance with the
+ * License. You may obtain a copy of the License at:
+ * opensource.org/licenses/BSD-3-Clause
+ *
+ ******************************************************************************
+ */
+
+/* Includes ------------------------------------------------------------------*/
+#include "usart.h"
+
+/**
+ * @brief 板级 usart 硬件初始化
+ * @param void:
+ * retval N/A.
+ */
+int board_usart_init(void)
+{
+ rcu_periph_clock_enable(RCU_USART0);
+ usart_deinit(RCU_USART0);
+ usart_baudrate_set(USART0, 115200);
+ usart_stop_bit_set(USART0, USART_STB_1BIT);
+ usart_word_length_set(USART0, USART_WL_8BIT);
+ usart_parity_config(USART0, USART_PM_NONE);
+ usart_transmit_config(USART0, USART_TRANSMIT_ENABLE);
+ usart_receive_config(USART0, USART_RECEIVE_ENABLE);
+ usart_interrupt_enable(USART0, USART_INT_RBNE);
+ usart_enable(USART0);
+ nvic_irq_enable(USART0_IRQn, 0, 0);
+
+ return 0;
+}
diff --git a/board/GD32F310G_START/GCC/hello_world/Makefile b/board/GD32F310G_START/GCC/hello_world/Makefile
new file mode 100644
index 00000000..219a8fc9
--- /dev/null
+++ b/board/GD32F310G_START/GCC/hello_world/Makefile
@@ -0,0 +1,226 @@
+##########################################################################################################################
+# File automatically-generated by tool: [projectgenerator] version: [3.3.0] date: [Mon Aug 05 10:29:11 CST 2019]
+##########################################################################################################################
+
+# ------------------------------------------------
+# Generic Makefile (based on gcc)
+#
+# ChangeLog :
+# 2022-04-13 - Port to GD32F310-START
+# 2017-02-10 - Several enhancements + project update mode
+# 2015-07-22 - first version
+# ------------------------------------------------
+
+######################################
+# target
+######################################
+TARGET = TencentOS_tiny
+
+
+######################################
+# building variables
+######################################
+# debug build?
+DEBUG = 1
+# optimization
+OPT = -O2
+
+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)
+
+HAL_DRIVER_SRC = \
+ $(TOP_DIR)/board/GD32F310G_START/BSP/Src/main.c \
+ $(TOP_DIR)/board/GD32F310G_START/BSP/Src/mcu_init.c \
+ $(TOP_DIR)/board/GD32F310G_START/BSP/Src/gd32f3x0_it.c \
+ $(TOP_DIR)/board/GD32F310G_START/BSP/Src/gpio.c \
+ $(TOP_DIR)/board/GD32F310G_START/BSP/Src/usart.c \
+ $(TOP_DIR)/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/CMSIS/GD/GD32F3x0/Source/system_gd32f3x0.c \
+ $(TOP_DIR)/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_dbg.c \
+ $(TOP_DIR)/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_dma.c \
+ $(TOP_DIR)/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_exti.c \
+ $(TOP_DIR)/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_fmc.c \
+ $(TOP_DIR)/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_gpio.c \
+ $(TOP_DIR)/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_misc.c \
+ $(TOP_DIR)/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_pmu.c \
+ $(TOP_DIR)/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_rcu.c \
+ $(TOP_DIR)/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_syscfg.c \
+ $(TOP_DIR)/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_timer.c \
+ $(TOP_DIR)/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_usart.c
+ C_SOURCES += $(HAL_DRIVER_SRC)
+
+# ASM sources
+ASM_SOURCES = \
+$(TOP_DIR)/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/CMSIS/GD/GD32F3x0/Source/GCC/startup_gd32f3x0.s
+
+ASM_SOURCES_S = \
+$(TOP_DIR)/arch/arm/arm-v7m/cortex-m4/gcc/port_s.S
+
+COMPONENTS_SRC = \
+ $(TOP_DIR)/components/shell/tos_shell.c \
+ $(TOP_DIR)/components/shell/tos_shell_commands.c
+ C_SOURCES += $(COMPONENTS_SRC)
+
+#######################################
+# 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 = \
+-DGD32F310
+
+# 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 \
+ -I $(TOP_DIR)/board/GD32F310G_START/TOS-CONFIG
+C_INCLUDES += $(KERNEL_INC)
+
+CMSIS_INC = \
+ -I $(TOP_DIR)/osal/cmsis_os \
+ -I $(TOP_DIR)/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/CMSIS
+C_INCLUDES += $(CMSIS_INC)
+
+HAL_DRIVER_INC = \
+ -I $(TOP_DIR)/board/GD32F310G_START/BSP/Inc \
+ -I $(TOP_DIR)/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/CMSIS/GD/GD32F3x0/Include \
+ -I $(TOP_DIR)/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include
+C_INCLUDES += $(HAL_DRIVER_INC)
+
+COMPONENTS_INC = \
+ -I $(TOP_DIR)/components/shell/include
+C_INCLUDES += $(COMPONENTS_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 = gd32f310_flash.ld
+
+# libraries
+LIBS = -lc -lm -lnosys
+LIBDIR =
+LDFLAGS = $(MCU) -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) $< $@
+ @cp $@ ./$(notdir $@)
+
+$(BUILD_DIR):
+ mkdir $@
+
+#######################################
+# clean up
+#######################################
+clean:
+ -rm -fR $(BUILD_DIR)
+
+#######################################
+# dependencies
+#######################################
+-include $(wildcard $(BUILD_DIR)/*.d)
+
+# *** EOF ***
diff --git a/board/GD32F310G_START/GCC/hello_world/gd32f310_flash.ld b/board/GD32F310G_START/GCC/hello_world/gd32f310_flash.ld
new file mode 100644
index 00000000..a91c1e54
--- /dev/null
+++ b/board/GD32F310G_START/GCC/hello_world/gd32f310_flash.ld
@@ -0,0 +1,156 @@
+/*
+ * linker script for GD32F3x0 with GNU ld
+ * bernard.xiong 2009-10-14
+ * iysheng 2022-04-14
+ */
+
+/* Program Entry, set to mark it as "used" and avoid gc */
+ENTRY(Reset_Handler)
+FLASH_SIZE = 0x10000;
+SRAM_SIZE = 0x2000;
+HEAP_SIZE = 0x800;
+STACK_SIZE = 0x200;
+
+MEMORY
+{
+ CODE (rx) : ORIGIN = 0x08000000, LENGTH = FLASH_SIZE
+ DATA (rw) : ORIGIN = 0x20000000, LENGTH = SRAM_SIZE
+ HEAP (rw) : ORIGIN = 0x20000000 + SRAM_SIZE - HEAP_SIZE, LENGTH = HEAP_SIZE
+}
+
+SECTIONS
+{
+ .text :
+ {
+ . = ALIGN(4);
+ _stext = .;
+ KEEP(*(.isr_vector)) /* Startup code */
+ . = ALIGN(4);
+ *(.text) /* remaining code */
+ *(.text.*) /* remaining code */
+ *(.rodata) /* read-only data (constants) */
+ *(.rodata*)
+ *(.glue_7)
+ *(.glue_7t)
+ *(.gnu.linkonce.t*)
+
+ /* section information for finsh shell */
+ . = ALIGN(4);
+ __fsymtab_start = .;
+ KEEP(*(FSymTab))
+ __fsymtab_end = .;
+ . = ALIGN(4);
+ __vsymtab_start = .;
+ KEEP(*(VSymTab))
+ __vsymtab_end = .;
+ . = ALIGN(4);
+
+ /* section information for initial. */
+ . = ALIGN(4);
+ __rt_init_start = .;
+ KEEP(*(SORT(.rti_fn*)))
+ __rt_init_end = .;
+ . = ALIGN(4);
+
+ . = ALIGN(4);
+ _etext = .;
+ } > CODE = 0
+
+ /* .ARM.exidx is sorted, so has to go in its own output section. */
+ __exidx_start = .;
+ .ARM.exidx :
+ {
+ *(.ARM.exidx* .gnu.linkonce.armexidx.*)
+
+ /* This is used by the startup in order to initialize the .data secion */
+ _sidata = .;
+ } > CODE
+ __exidx_end = .;
+
+ /* .data section which is used for initialized data */
+
+ .data : AT (_sidata)
+ {
+ . = ALIGN(4);
+ /* This is used by the startup in order to initialize the .data secion */
+ _sdata = . ;
+
+ *(.data)
+ *(.data.*)
+ *(.gnu.linkonce.d*)
+
+ . = ALIGN(4);
+ /* This is used by the startup in order to initialize the .data secion */
+ _edata = . ;
+ } >DATA
+
+ .stack :
+ {
+ . = . + STACK_SIZE;
+ . = ALIGN(4);
+ _estack = .;
+ } >DATA
+
+ __bss_start = .;
+ .bss :
+ {
+ . = ALIGN(4);
+ /* This is used by the startup in order to initialize the .bss secion */
+ _sbss = .;
+
+ *(.bss)
+ *(.bss.*)
+ *(COMMON)
+
+ . = ALIGN(4);
+ /* This is used by the startup in order to initialize the .bss secion */
+ _ebss = . ;
+ *(.bss.init)
+ } > DATA
+ __bss_end = .;
+
+ .heap : {
+ __heap_start__ = .;
+ end = __heap_start__;
+ _end = end;
+ __end = end;
+ . = . + HEAP_SIZE;
+ /* . = . + Min_Heap_Size; */
+ __heap_end__ = .;
+ __HeapLimit = __heap_end__;
+ } > HEAP
+
+ /* Stabs debugging sections. */
+ .stab 0 : { *(.stab) }
+ .stabstr 0 : { *(.stabstr) }
+ .stab.excl 0 : { *(.stab.excl) }
+ .stab.exclstr 0 : { *(.stab.exclstr) }
+ .stab.index 0 : { *(.stab.index) }
+ .stab.indexstr 0 : { *(.stab.indexstr) }
+ .comment 0 : { *(.comment) }
+ /* DWARF debug sections.
+ * Symbols in the DWARF debugging sections are relative to the beginning
+ * of the section so we begin them at 0. */
+ /* DWARF 1 */
+ .debug 0 : { *(.debug) }
+ .line 0 : { *(.line) }
+ /* GNU DWARF 1 extensions */
+ .debug_srcinfo 0 : { *(.debug_srcinfo) }
+ .debug_sfnames 0 : { *(.debug_sfnames) }
+ /* DWARF 1.1 and DWARF 2 */
+ .debug_aranges 0 : { *(.debug_aranges) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ /* DWARF 2 */
+ .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) }
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+ .debug_line 0 : { *(.debug_line) }
+ .debug_frame 0 : { *(.debug_frame) }
+ .debug_str 0 : { *(.debug_str) }
+ .debug_loc 0 : { *(.debug_loc) }
+ .debug_macinfo 0 : { *(.debug_macinfo) }
+ /* SGI/MIPS DWARF 2 extensions */
+ .debug_weaknames 0 : { *(.debug_weaknames) }
+ .debug_funcnames 0 : { *(.debug_funcnames) }
+ .debug_typenames 0 : { *(.debug_typenames) }
+ .debug_varnames 0 : { *(.debug_varnames) }
+}
diff --git a/board/GD32F310G_START/TOS-CONFIG/tickless/tos_config.h b/board/GD32F310G_START/TOS-CONFIG/tickless/tos_config.h
new file mode 100644
index 00000000..e02e32a2
--- /dev/null
+++ b/board/GD32F310G_START/TOS-CONFIG/tickless/tos_config.h
@@ -0,0 +1,41 @@
+#ifndef _TOS_CONFIG_H_
+#define _TOS_CONFIG_H_
+
+#include "stm32l4xx.h"
+
+#define TOS_CFG_TASK_PRIO_MAX 10u
+
+#define TOS_CFG_ROUND_ROBIN_EN 1u
+
+#define TOS_CFG_OBJECT_VERIFY_EN 1u
+
+#define TOS_CFG_TASK_DYNAMIC_CREATE_EN 0u
+
+#define TOS_CFG_EVENT_EN 1u
+
+#define TOS_CFG_MMBLK_EN 1u
+
+#define TOS_CFG_MMHEAP_EN 1u
+
+#define TOS_CFG_MMHEAP_DEFAULT_POOL_SIZE 0x6000
+
+#define TOS_CFG_MUTEX_EN 1u
+
+#define TOS_CFG_TIMER_EN 1u
+
+#define TOS_CFG_PWR_MGR_EN 1u
+
+#define TOS_CFG_TICKLESS_EN 1u
+
+#define TOS_CFG_SEM_EN 1u
+
+#define TOS_CFG_IDLE_TASK_STK_SIZE 512u
+
+#define TOS_CFG_CPU_TICK_PER_SECOND 1000u
+
+#define TOS_CFG_CPU_CLOCK (SystemCoreClock)
+
+#define TOS_CFG_TIMER_AS_PROC 1u
+
+#endif
+
diff --git a/board/GD32F310G_START/TOS-CONFIG/tos_config.h b/board/GD32F310G_START/TOS-CONFIG/tos_config.h
new file mode 100644
index 00000000..7cf0dd30
--- /dev/null
+++ b/board/GD32F310G_START/TOS-CONFIG/tos_config.h
@@ -0,0 +1,47 @@
+#ifndef _TOS_CONFIG_H_
+#define _TOS_CONFIG_H_
+
+#include "gd32f3x0.h"
+
+#define TOS_CFG_TASK_PRIO_MAX 10u
+
+#define TOS_CFG_ROUND_ROBIN_EN 1u
+
+#define TOS_CFG_OBJECT_VERIFY_EN 1u
+
+#define TOS_CFG_TASK_DYNAMIC_CREATE_EN 0u
+
+#define TOS_CFG_EVENT_EN 1u
+
+#define TOS_CFG_MMBLK_EN 1u
+
+#define TOS_CFG_MMHEAP_EN 0u
+
+#define TOS_CFG_MMHEAP_DEFAULT_POOL_SIZE 0x400
+
+#define TOS_CFG_MUTEX_EN 1u
+
+#define TOS_CFG_TIMER_EN 1u
+
+#define TOS_CFG_PWR_MGR_EN 0u
+
+#define TOS_CFG_TICKLESS_EN 0u
+
+#define TOS_CFG_SEM_EN 1u
+
+#define TOS_CFG_TASK_STACK_DRAUGHT_DEPTH_DETACT_EN 1u
+
+#define TOS_CFG_FAULT_BACKTRACE_EN 0u
+
+#define TOS_CFG_IDLE_TASK_STK_SIZE 128u
+
+#define TOS_CFG_CPU_TICK_PER_SECOND 1000u
+
+#define TOS_CFG_CPU_CLOCK (SystemCoreClock)
+
+#define TOS_CFG_TIMER_AS_PROC 1u
+
+#define TOS_CFG_MAIL_QUEUE_EN 1u
+
+#endif
+
diff --git a/board/IoTClub_EVB_L2/KEIL/mqttclient_iot_explorer/demo/mqttclient_iot_explorer.c b/board/IoTClub_EVB_L2/KEIL/mqttclient_iot_explorer/demo/mqttclient_iot_explorer.c
index ff76d0ec..a87509e7 100644
--- a/board/IoTClub_EVB_L2/KEIL/mqttclient_iot_explorer/demo/mqttclient_iot_explorer.c
+++ b/board/IoTClub_EVB_L2/KEIL/mqttclient_iot_explorer/demo/mqttclient_iot_explorer.c
@@ -2,7 +2,7 @@
#include "mcu_init.h"
#include "tos_k.h"
#include "mqttclient.h"
-#include "cjson.h"
+#include "cJSON.h"
#include "sal_module_wrapper.h"
//#define USE_ESP8266
diff --git a/board/TencentOS_tiny_EVB_G0/KEIL/mqtt_iot_explorer_e53_light/demo/mqtt_iot_explorer_e53_light.c b/board/TencentOS_tiny_EVB_G0/KEIL/mqtt_iot_explorer_e53_light/demo/mqtt_iot_explorer_e53_light.c
index 8fc5b696..3b449f24 100644
--- a/board/TencentOS_tiny_EVB_G0/KEIL/mqtt_iot_explorer_e53_light/demo/mqtt_iot_explorer_e53_light.c
+++ b/board/TencentOS_tiny_EVB_G0/KEIL/mqtt_iot_explorer_e53_light/demo/mqtt_iot_explorer_e53_light.c
@@ -305,9 +305,6 @@ void application_entry(void *arg)
{
char *str = "TencentOS-tiny";
- // 初始化tencent-os tiny定时器模块
- timer_init();
-
// 初始化按键检测模块
stm32g0xx_key_init();
diff --git a/board/TencentOS_tiny_STM32H750/KEIL/mqtt_client_iot_exporer/demo/mqttclient_iot_explorer.c b/board/TencentOS_tiny_STM32H750/KEIL/mqtt_client_iot_exporer/demo/mqttclient_iot_explorer.c
index 30fbd63b..3b4bcc11 100644
--- a/board/TencentOS_tiny_STM32H750/KEIL/mqtt_client_iot_exporer/demo/mqttclient_iot_explorer.c
+++ b/board/TencentOS_tiny_STM32H750/KEIL/mqtt_client_iot_exporer/demo/mqttclient_iot_explorer.c
@@ -2,7 +2,7 @@
#include "mcu_init.h"
#include "tos_k.h"
#include "mqttclient.h"
-#include "cjson.h"
+#include "cJSON.h"
#include "sal_module_wrapper.h"
#define USE_ESP8266
diff --git a/components/shell/include/tos_shell.h b/components/shell/include/tos_shell.h
index 2d6c3893..77742e8e 100644
--- a/components/shell/include/tos_shell.h
+++ b/components/shell/include/tos_shell.h
@@ -26,7 +26,7 @@
#define SHELL_PARSER_TASK_STACK_SIZE 1024
#define SHELL_PARSER_TASK_PRIO 3
-typedef void (*shell_output_t)(const char *str);
+typedef void (*shell_output_t)(const char ch);
typedef struct shell_control_st {
k_task_t parser;
@@ -53,6 +53,8 @@ __API__ int tos_shell_cmd_set_unregiser(const shell_cmd_set_t *cmd_set);
__API__ void tos_shell_printf(const char *format, ...);
+__API__ void tos_shell_printfln(const char *format, ...);
+
__API__ void tos_shell_input_byte(uint8_t data);
#endif /* _TOS_SHELL_H_ */
diff --git a/components/shell/include/tos_shell_command.h b/components/shell/include/tos_shell_command.h
index 16e8019b..02089e3c 100644
--- a/components/shell/include/tos_shell_command.h
+++ b/components/shell/include/tos_shell_command.h
@@ -33,6 +33,8 @@ typedef struct shell_command_set_st {
const shell_cmd_t *const commands;
} shell_cmd_set_t;
+__KNL__ int cmd_help(int argc, char *argv[]);
+
__KNL__ int shell_cmd_set_regiser(const shell_cmd_set_t *cmd_set);
__KNL__ int shell_cmd_set_unregiser(const shell_cmd_set_t *cmd_set);
diff --git a/components/shell/tos_shell.c b/components/shell/tos_shell.c
index f940b33e..0646e731 100644
--- a/components/shell/tos_shell.c
+++ b/components/shell/tos_shell.c
@@ -35,10 +35,23 @@ __STATIC__ int shell_getchar(void)
return err == K_ERR_NONE ? chr : -1;
}
+__STATIC__ void shell_putchar(const char ch)
+{
+ SHELL_CTL->output(ch);
+}
+
+__STATIC__ void shell_puts(const char *s)
+{
+ while (*s) {
+ SHELL_CTL->output(*s++);
+ }
+}
+
__STATIC__ int shell_readline(void)
{
- int chr, last_chr = 0;
+ int chr;
char *buf = SHELL_CTL->cmd_buffer;
+ uint16_t line_length = 0;
while (K_TRUE) {
if (buf - SHELL_CTL->cmd_buffer >= (SHELL_CTL->cmd_buffer_size - 1)) {
@@ -50,23 +63,29 @@ __STATIC__ int shell_readline(void)
return -1;
}
- if (chr == '\n' && last_chr == '\r') {
- *--buf = '\0';
- return 0;
- } else if (chr == '\n') {
+ if (chr == '\n' || chr == '\r') {
*buf = '\0';
- return 0;
+ tos_shell_printf("\r\n");
+ break;
+ } else if (chr == '\t'){
+ *buf = '\0';
+ tos_shell_printf("\r\n");
+ cmd_help(0, NULL);
+ break;
}
-
- *buf++ = chr;
- last_chr = chr;
+
+ shell_putchar(chr);
+
+ *buf++ = chr;
+ line_length++;
}
+ return line_length;
}
__STATIC__ void shell_cmd_do_process(int argc, char *argv[])
{
const shell_cmd_t *cmd;
- static const char *cmd_not_found = "command not found\n";
+ static const char *cmd_not_found = "command not found\r\n";
cmd = shell_cmd_find(argv[0]);
if (!cmd) {
@@ -82,8 +101,6 @@ __STATIC__ void shell_cmd_process(void)
static char *argv[SHELL_CMD_ARGV_MAX];
char *pos = SHELL_CTL->cmd_buffer;
- tos_shell_printf("%s\n", SHELL_CTL->cmd_buffer);
-
// left strip
while (*pos == ' ' || *pos == '\t') {
++pos;
@@ -113,7 +130,7 @@ __STATIC__ void shell_cmd_process(void)
__STATIC__ void shell_prompt(void)
{
- tos_shell_printf("> ");
+ tos_shell_printf("tshell>");
}
__STATIC__ void shell_parser(void *arg)
@@ -125,7 +142,7 @@ __STATIC__ void shell_parser(void *arg)
while (K_TRUE) {
rc = shell_readline();
- if (!rc) {
+ if (rc > 0) {
shell_cmd_process();
}
@@ -208,7 +225,20 @@ __API__ void tos_shell_printf(const char *format, ...)
vsnprintf(buffer, sizeof(buffer), format, args);
va_end(args);
- (SHELL_CTL->output)(buffer);
+ shell_puts(buffer);
+}
+
+__API__ void tos_shell_printfln(const char *format, ...)
+{
+ va_list args;
+ static char buffer[SHELL_OUTPUT_MAX];
+
+ va_start(args, format);
+ vsnprintf(buffer, sizeof(buffer), format, args);
+ va_end(args);
+
+ shell_puts(buffer);
+ shell_puts("\r\n");
}
__API__ void tos_shell_input_byte(uint8_t data)
diff --git a/components/shell/tos_shell_commands.c b/components/shell/tos_shell_commands.c
index acfcb8b7..85ef186b 100644
--- a/components/shell/tos_shell_commands.c
+++ b/components/shell/tos_shell_commands.c
@@ -20,23 +20,72 @@
__STATIC__ TOS_SLIST_DEFINE(cmd_set_list);
-__STATIC__ int cmd_help(int argc, char *argv[])
+int cmd_help(int argc, char *argv[])
{
shell_cmd_set_t *cmd_set;
const shell_cmd_t *cmd;
TOS_SLIST_FOR_EACH_ENTRY(cmd_set, shell_cmd_set_t, list, &cmd_set_list) {
for (cmd = cmd_set->commands; cmd->name; ++cmd) {
- tos_shell_printf("%-8s: %s\n", cmd->name, cmd->help);
+ tos_shell_printf("%-8s: %s\r\n", cmd->name, cmd->help);
}
}
return 0;
}
+static void task_shell_walker(k_task_t *task)
+{
+ char *state_str = "ABNORMAL";
+
+ if (!task) {
+ return;
+ }
+
+ state_str = state_str;
+ tos_shell_printfln("task name: %s", task->name);
+
+ if (tos_task_curr_task_get() == task) {
+ state_str = "RUNNING";
+ } else if (task->state == K_TASK_STATE_PENDTIMEOUT_SUSPENDED) {
+ state_str = "PENDTIMEOUT_SUSPENDED";
+ } else if (task->state == K_TASK_STATE_PEND_SUSPENDED) {
+ state_str = "PEND_SUSPENDED";
+ } else if (task->state == K_TASK_STATE_SLEEP_SUSPENDED) {
+ state_str = "SLEEP_SUSPENDED";
+ } else if (task->state == K_TASK_STATE_PENDTIMEOUT) {
+ state_str = "PENDTIMEOUT";
+ } else if (task->state == K_TASK_STATE_SUSPENDED) {
+ state_str = "SUSPENDED";
+ } else if (task->state == K_TASK_STATE_PEND) {
+ state_str = "PEND";
+ } else if (task->state == K_TASK_STATE_SLEEP) {
+ state_str = "SLEEP";
+ } else if (task->state == K_TASK_STATE_READY) {
+ state_str = "READY";
+ }
+
+ tos_shell_printfln("task stat: %s", state_str);
+ tos_shell_printfln("stk size : %d", task->stk_size);
+ tos_shell_printfln("stk base : 0x%p", task->stk_base);
+ tos_shell_printfln("stk top : 0x%p", task->stk_base + task->stk_size);
+
+#if TOS_CFG_TASK_STACK_DRAUGHT_DEPTH_DETACT_EN > 0u
+ int depth;
+
+ if (tos_task_stack_draught_depth(task, &depth) != K_ERR_NONE) {
+ depth = -1;
+ }
+
+ tos_shell_printfln("stk depth: %d", depth);
+#endif /* TOS_CFG_TASK_STACK_DRAUGHT_DEPTH_DETACT_EN */
+
+ tos_shell_printf("\r\n");
+}
+
__STATIC__ int cmd_ps(int argc, char *argv[])
{
- tos_task_info_display();
+ tos_task_walkthru(task_shell_walker);
return 0;
}
diff --git a/examples/mqttclient_iot_explorer/mqttclient_iot_explorer.c b/examples/mqttclient_iot_explorer/mqttclient_iot_explorer.c
index 4827a837..4d1c3b17 100644
--- a/examples/mqttclient_iot_explorer/mqttclient_iot_explorer.c
+++ b/examples/mqttclient_iot_explorer/mqttclient_iot_explorer.c
@@ -1,7 +1,7 @@
#include "mcu_init.h"
#include "tos_k.h"
#include "mqttclient.h"
-#include "cjson.h"
+#include "cJSON.h"
#include "sal_module_wrapper.h"
#define USE_ESP8266
diff --git a/examples/shell/shell_sample.c b/examples/shell/shell_sample.c
index 919868be..5eb53b17 100644
--- a/examples/shell/shell_sample.c
+++ b/examples/shell/shell_sample.c
@@ -6,9 +6,9 @@ char cmd_buf[CMD_LEN_MAX];
hal_uart_t shell_uart;
-void uart_output(const char *str)
+void uart_output(const char ch)
{
- tos_hal_uart_write(&shell_uart, (const uint8_t *)str, strlen(str), 0xFF);
+ tos_hal_uart_write(&shell_uart, (const uint8_t *)&ch, 1, 0xFF);
#if 0
/* if using c lib printf through uart, a simpler one is: */
@@ -19,34 +19,34 @@ void uart_output(const char *str)
__STATIC__ int cmd_test00(int argc, char *argv[])
{
int i = 0;
- tos_shell_printf("test00:\n");
+ tos_shell_printf("test00:\r\n");
for (i = 0; i < argc; ++i) {
- tos_shell_printf("argv[%d]: %s\n", i, argv[i]);
+ tos_shell_printf("argv[%d]: %s\r\n", i, argv[i]);
}
return 0;
}
__STATIC__ int cmd_test01(int argc, char *argv[])
{
- tos_shell_printf("test01:\n");
+ tos_shell_printf("test01:\r\n");
return 0;
}
__STATIC__ int cmd_test10(int argc, char *argv[])
{
int i = 0;
- tos_shell_printf("test10:\n");
+ tos_shell_printf("test10:\r\n");
for (i = 0; i < argc; ++i) {
- tos_shell_printf("argv[%d]: %s\n", i, argv[i]);
+ tos_shell_printf("argv[%d]: %s\r\n", i, argv[i]);
}
return 0;
}
__STATIC__ int cmd_test11(int argc, char *argv[])
{
- tos_shell_printf("test11:\n");
+ tos_shell_printf("test11:\r\n");
return 0;
}
@@ -74,10 +74,16 @@ __STATIC__ shell_cmd_set_t custom_shell_cmd_set1 = {
void application_entry(void *arg)
{
+ int ret;
+
/* if test on ALIENTEK_STM32F429, switch HAL_UART_PORT_2 to HAL_UART_PORT_1 */
tos_hal_uart_init(&shell_uart, HAL_UART_PORT_2);
- tos_shell_init(cmd_buf, sizeof(cmd_buf), uart_output, &custom_shell_cmd_set0);
+ ret = tos_shell_init(cmd_buf, sizeof(cmd_buf), uart_output, &custom_shell_cmd_set0);
+ if (ret < 0) {
+ printf("tos shell init fail, ret is %d\r\n", ret);
+ }
+ printf("tos shell init success\r\n");
tos_shell_cmd_set_regiser(&custom_shell_cmd_set1);
diff --git a/kernel/core/include/tos_timer.h b/kernel/core/include/tos_timer.h
index 5ad3b3ae..bca901c5 100644
--- a/kernel/core/include/tos_timer.h
+++ b/kernel/core/include/tos_timer.h
@@ -177,13 +177,13 @@ __API__ k_err_t tos_timer_period_change(k_timer_t *tmr, k_tick_t period);
*
* @return None
*/
-__KNL__ void timer_update(void);
+__KNL__ void soft_timer_update(void);
#endif
-__KNL__ k_err_t timer_init(void);
+__KNL__ k_err_t soft_timer_init(void);
-__KNL__ k_tick_t timer_next_expires_get(void);
+__KNL__ k_tick_t soft_timer_next_expires_get(void);
#endif
diff --git a/kernel/core/tos_sys.c b/kernel/core/tos_sys.c
index 89bf904b..8dd8a0c4 100644
--- a/kernel/core/tos_sys.c
+++ b/kernel/core/tos_sys.c
@@ -42,7 +42,7 @@ __API__ k_err_t tos_knl_init(void)
}
#if TOS_CFG_TIMER_EN > 0
- err = timer_init();
+ err = soft_timer_init();
if (err != K_ERR_NONE) {
return err;
}
@@ -187,7 +187,7 @@ __KNL__ k_tick_t knl_next_expires_get(void)
tick_next_expires = tick_next_expires_get();
#if TOS_CFG_TIMER_EN > 0u
- timer_next_expires = timer_next_expires_get();
+ timer_next_expires = soft_timer_next_expires_get();
#endif
#if TOS_CFG_TIMER_EN > 0u
diff --git a/kernel/core/tos_tick.c b/kernel/core/tos_tick.c
index 8fb4bfc5..49feeb90 100644
--- a/kernel/core/tos_tick.c
+++ b/kernel/core/tos_tick.c
@@ -139,7 +139,7 @@ __API__ void tos_tick_handler(void)
tick_update((k_tick_t)1u);
#if TOS_CFG_TIMER_EN > 0u && TOS_CFG_TIMER_AS_PROC > 0u
- timer_update();
+ soft_timer_update();
#endif
#if TOS_CFG_ROUND_ROBIN_EN > 0u
diff --git a/kernel/core/tos_timer.c b/kernel/core/tos_timer.c
index 4e71f9ca..71d17442 100644
--- a/kernel/core/tos_timer.c
+++ b/kernel/core/tos_timer.c
@@ -253,7 +253,7 @@ __API__ k_err_t tos_timer_period_change(k_timer_t *tmr, k_tick_t period)
return timer_change(tmr, period, TIMER_CHANGE_TYPE_PERIOD);
}
-__KNL__ k_tick_t timer_next_expires_get(void)
+__KNL__ k_tick_t soft_timer_next_expires_get(void)
{
TOS_CPU_CPSR_ALLOC();
k_tick_t next_expires;
@@ -274,7 +274,7 @@ __KNL__ k_tick_t timer_next_expires_get(void)
#if TOS_CFG_TIMER_AS_PROC > 0u
-__KNL__ void timer_update(void)
+__KNL__ void soft_timer_update(void)
{
k_timer_t *tmr, *tmp;
@@ -314,7 +314,7 @@ __STATIC__ void timer_task_entry(void *arg)
arg = arg; // make compiler happy
while (K_TRUE) {
- next_expires = timer_next_expires_get();
+ next_expires = soft_timer_next_expires_get();
if (next_expires == TOS_TIME_FOREVER) {
tos_task_suspend(K_NULL);
} else if (next_expires > (k_tick_t)0u) {
@@ -347,13 +347,13 @@ __STATIC__ void timer_task_entry(void *arg)
#endif
-__KNL__ k_err_t timer_init(void)
+__KNL__ k_err_t soft_timer_init(void)
{
#if TOS_CFG_TIMER_AS_PROC > 0u
return K_ERR_NONE;
#else
return tos_task_create(&k_timer_task,
- "timer",
+ "soft_timer",
timer_task_entry,
K_NULL,
k_timer_task_prio,
diff --git a/kernel/pm/tos_tickless.c b/kernel/pm/tos_tickless.c
index 4446eacd..90d21d54 100644
--- a/kernel/pm/tos_tickless.c
+++ b/kernel/pm/tos_tickless.c
@@ -111,7 +111,7 @@ __STATIC__ void tickless_tick_fix(k_tick_t tick_sleep)
tick_update(tick_sleep);
#if TOS_CFG_TIMER_EN > 0u && TOS_CFG_TIMER_AS_PROC > 0u
- timer_update();
+ soft_timer_update();
#endif
tickless_tick_resume();
diff --git a/osal/cmsis_os/cmsis_os2.c b/osal/cmsis_os/cmsis_os2.c
index 3890fb72..a6ea5441 100644
--- a/osal/cmsis_os/cmsis_os2.c
+++ b/osal/cmsis_os/cmsis_os2.c
@@ -156,7 +156,7 @@ osThreadId_t osThreadNew(osThreadFunc_t func,
k_err_t err;
uint32_t stack_size = K_TASK_STK_SIZE_MIN;
k_task_t* taskId = NULL;
- k_prio_t prio;
+ k_prio_t prio = osPriorityNormal;
if (attr && func) {
if (attr->priority != osPriorityNone) {
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/CMSIS/GD/GD32F3x0/Include/gd32f3x0.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/CMSIS/GD/GD32F3x0/Include/gd32f3x0.h
new file mode 100644
index 00000000..97d12155
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/CMSIS/GD/GD32F3x0/Include/gd32f3x0.h
@@ -0,0 +1,243 @@
+/*!
+ \file gd32f3x0.h
+ \brief general definitions for gd32f3x0
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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 GD32F3X0_H
+#define GD32F3X0_H
+
+#ifdef cplusplus
+extern "C" {
+#endif
+
+ /* define GD32F3x0 */
+#if !defined (GD32F3x0)
+#define GD32F3x0
+#endif /* define GD32F3x0 */
+#if !defined (GD32F3x0)
+#error "Please select the target GD32F3x0 device used in your application (in gd32f3x0.h file)"
+#endif /* undefine GD32F3x0 tip */
+
+ /* define GD32F3x0 device category */
+#if (!defined (GD32F310))&&(!defined (GD32F330))&&(!defined (GD32F350))
+#error "Please select GD32F3x0 device category( GD32F310 or GD32F330 or GD32F350 )"
+#endif /* undefine GD32F330 or GD32F350 tip */
+#if (defined (GD32F310))&&(defined (GD32F330))&&(defined (GD32F350))
+#error "Please select one GD32F3x0 device category( GD32F310 or GD32F330 or GD32F350 )"
+#endif /* define GD32F330 and GD32F350 tip */
+
+ /* define value of high speed crystal oscillator (HXTAL) in Hz */
+#if !defined (HXTAL_VALUE)
+#define HXTAL_VALUE ((uint32_t)8000000)
+#endif /* high speed crystal oscillator value */
+
+ /* define startup timeout value of high speed crystal oscillator (HXTAL) */
+#if !defined (HXTAL_STARTUP_TIMEOUT)
+#define HXTAL_STARTUP_TIMEOUT ((uint16_t)0x0800)
+#endif /* high speed crystal oscillator startup timeout */
+
+ /* define value of internal 8MHz RC oscillator (IRC8M) in Hz */
+#if !defined (IRC8M_VALUE)
+#define IRC8M_VALUE ((uint32_t)8000000)
+#endif /* internal 8MHz RC oscillator value */
+
+ /* define startup timeout value of internal 8MHz RC oscillator (IRC8M) */
+#if !defined (IRC8M_STARTUP_TIMEOUT)
+#define IRC8M_STARTUP_TIMEOUT ((uint16_t)0x0500)
+#endif /* internal 8MHz RC oscillator startup timeout */
+
+ /* define value of internal RC oscillator for ADC in Hz */
+#if !defined (IRC28M_VALUE)
+#define IRC28M_VALUE ((uint32_t)28000000)
+#endif /* IRC28M_VALUE */
+
+#if !defined (IRC48M_VALUE)
+#define IRC48M_VALUE ((uint32_t)48000000)
+#endif /* IRC48M_VALUE */
+
+ /* define value of internal 40KHz RC oscillator(IRC40K) in Hz */
+#if !defined (IRC40K_VALUE)
+#define IRC40K_VALUE ((uint32_t)40000)
+#endif /* internal 40KHz RC oscillator value */
+
+ /* define value of low speed crystal oscillator (LXTAL)in Hz */
+#if !defined (LXTAL_VALUE)
+#define LXTAL_VALUE ((uint32_t)32768)
+#endif /* low speed crystal oscillator value */
+
+ /* GD32F3x0 firmware library version number V1.0 */
+#define __GD32F3x0_STDPERIPH_VERSION_MAIN (0x01) /*!< [31:24] main version */
+#define __GD32F3x0_STDPERIPH_VERSION_SUB1 (0x00) /*!< [23:16] sub1 version */
+#define __GD32F3x0_STDPERIPH_VERSION_SUB2 (0x00) /*!< [15:8] sub2 version */
+#define __GD32F3x0_STDPERIPH_VERSION_RC (0x00) /*!< [7:0] release candidate */
+#define __GD32F3x0_STDPERIPH_VERSION ((__GD32F3x0_STDPERIPH_VERSION_MAIN << 24)\
+ |(__GD32F3x0_STDPERIPH_VERSION_SUB1 << 16)\
+ |(__GD32F3x0_STDPERIPH_VERSION_SUB2 << 8)\
+ |(__GD32F3x0_STDPERIPH_VERSION_RC))
+
+ /* configuration of the Cortex-M4 processor and core peripherals */
+#define __CM4_REV 0x0001 /*!< Core revision r0p1 */
+#define __MPU_PRESENT 0U /*!< GD32F3x0 do not provide MPU */
+#define __NVIC_PRIO_BITS 4U /*!< GD32F3x0 uses 4 bits for the priority levels */
+#define __Vendor_SysTickConfig 0U /*!< set to 1 if different sysTick config is used */
+#define __FPU_PRESENT 1U /*!< FPU present */
+
+ /* define interrupt number */
+ typedef enum IRQn {
+ /* Cortex-M4 processor exceptions numbers */
+ NonMaskableInt_IRQn = -14, /*!< 2 non maskable interrupt */
+ MemoryManagement_IRQn = -12, /*!< 4 Cortex-M4 memory management interrupt */
+ BusFault_IRQn = -11, /*!< 5 Cortex-M4 bus fault interrupt */
+ UsageFault_IRQn = -10, /*!< 6 Cortex-M4 usage fault interrupt */
+ SVCall_IRQn = -5, /*!< 11 Cortex-M4 SV call interrupt */
+ DebugMonitor_IRQn = -4, /*!< 12 Cortex-M4 debug monitor interrupt */
+ PendSV_IRQn = -2, /*!< 14 Cortex-M4 pend SV interrupt */
+ SysTick_IRQn = -1, /*!< 15 Cortex-M4 system tick interrupt */
+ /* interruput numbers */
+ WWDGT_IRQn = 0, /*!< window watchdog timer interrupt */
+ LVD_IRQn = 1, /*!< LVD through EXTI line detect interrupt */
+ RTC_IRQn = 2, /*!< RTC interrupt */
+ FMC_IRQn = 3, /*!< FMC interrupt */
+ RCU_CTC_IRQn = 4, /*!< RCU and CTC interrupt */
+ EXTI0_1_IRQn = 5, /*!< EXTI line 0 and 1 interrupts */
+ EXTI2_3_IRQn = 6, /*!< EXTI line 2 and 3 interrupts */
+ EXTI4_15_IRQn = 7, /*!< EXTI line 4 to 15 interrupts */
+ TSI_IRQn = 8, /*!< TSI Interrupt */
+ DMA_Channel0_IRQn = 9, /*!< DMA channel 0 interrupt */
+ DMA_Channel1_2_IRQn = 10, /*!< DMA channel 1 and channel 2 interrupts */
+ DMA_Channel3_4_IRQn = 11, /*!< DMA channel 3 and channel 4 interrupts */
+ ADC_CMP_IRQn = 12, /*!< ADC, CMP0 and CMP1 interrupts */
+ TIMER0_BRK_UP_TRG_COM_IRQn = 13, /*!< TIMER0 break, update, trigger and commutation interrupts */
+ TIMER0_Channel_IRQn = 14, /*!< TIMER0 channel capture compare interrupts */
+ TIMER1_IRQn = 15, /*!< TIMER1 interrupt */
+ TIMER2_IRQn = 16, /*!< TIMER2 interrupt */
+#ifdef GD32F350
+ TIMER5_DAC_IRQn = 17, /*!< TIMER5 and DAC interrupts */
+#endif /* GD32F350 */
+ TIMER13_IRQn = 19, /*!< TIMER13 interrupt */
+ TIMER14_IRQn = 20, /*!< TIMER14 interrupt */
+ TIMER15_IRQn = 21, /*!< TIMER15 interrupt */
+ TIMER16_IRQn = 22, /*!< TIMER16 interrupt */
+ I2C0_EV_IRQn = 23, /*!< I2C0 event interrupt */
+ I2C1_EV_IRQn = 24, /*!< I2C1 event interrupt */
+ SPI0_IRQn = 25, /*!< SPI0 interrupt */
+ SPI1_IRQn = 26, /*!< SPI1 interrupt */
+ USART0_IRQn = 27, /*!< USART0 interrupt */
+ USART1_IRQn = 28, /*!< USART1 interrupt */
+#ifdef GD32F350
+ CEC_IRQn = 30, /*!< CEC interrupt */
+#endif /* GD32F350 */
+ I2C0_ER_IRQn = 32, /*!< I2C0 error interrupt */
+ I2C1_ER_IRQn = 34, /*!< I2C1 error interrupt */
+ DMA_Channel5_6_IRQn = 48, /*!< DMA channel 5 and channel 6 interrupts */
+#ifdef GD32F350
+ USBFS_WKUP_IRQn = 42, /*!< USBFS wakeup interrupt */
+ USBFS_IRQn = 67, /*!< USBFS global interrupt */
+#endif /* GD32F350 */
+ } IRQn_Type;
+
+ /* includes */
+#include "core_cm4.h"
+#include "system_gd32f3x0.h"
+#include
+
+ /* enum definitions */
+ typedef enum {DISABLE = 0, ENABLE = !DISABLE} EventStatus, ControlStatus;
+ typedef enum {FALSE = 0, TRUE = !FALSE} bool;
+ typedef enum {RESET = 0, SET = !RESET} FlagStatus;
+ typedef enum {ERROR = 0, SUCCESS = !ERROR} ErrStatus;
+
+ /* bit operations */
+#define REG32(addr) (*(volatile uint32_t *)(uint32_t)(addr))
+#define REG16(addr) (*(volatile uint16_t *)(uint32_t)(addr))
+#define REG8(addr) (*(volatile uint8_t *)(uint32_t)(addr))
+#define BIT(x) ((uint32_t)((uint32_t)0x01U<<(x)))
+#define BITS(start, end) ((0xFFFFFFFFUL << (start)) & (0xFFFFFFFFUL >> (31U - (uint32_t)(end))))
+#define GET_BITS(regval, start, end) (((regval) & BITS((start),(end))) >> (start))
+
+ /* main flash and SRAM memory map */
+#define FLASH_BASE ((uint32_t)0x08000000U) /*!< main FLASH base address */
+#define SRAM_BASE ((uint32_t)0x20000000U) /*!< SRAM base address */
+ /* SRAM and peripheral base bit-band region */
+#define SRAM_BB_BASE ((uint32_t)0x22000000U) /*!< SRAM bit-band base address */
+#define PERIPH_BB_BASE ((uint32_t)0x42000000U) /*!< peripheral bit-band base address */
+ /* peripheral memory map */
+#define APB1_BUS_BASE ((uint32_t)0x40000000U) /*!< apb1 base address */
+#define APB2_BUS_BASE ((uint32_t)0x40010000U) /*!< apb2 base address */
+#define AHB1_BUS_BASE ((uint32_t)0x40020000U) /*!< ahb1 base address */
+#define AHB2_BUS_BASE ((uint32_t)0x48000000U) /*!< ahb2 base address */
+ /* advanced peripheral bus 1 memory map */
+#define TIMER_BASE (APB1_BUS_BASE + 0x00000000U) /*!< TIMER base address */
+#define RTC_BASE (APB1_BUS_BASE + 0x00002800U) /*!< RTC base address */
+#define WWDGT_BASE (APB1_BUS_BASE + 0x00002C00U) /*!< WWDGT base address */
+#define FWDGT_BASE (APB1_BUS_BASE + 0x00003000U) /*!< FWDGT base address */
+#define SPI_BASE (APB1_BUS_BASE + 0x00003800U) /*!< SPI base address */
+#define USART_BASE (APB1_BUS_BASE + 0x00004400U) /*!< USART base address */
+#define I2C_BASE (APB1_BUS_BASE + 0x00005400U) /*!< I2C base address */
+#define PMU_BASE (APB1_BUS_BASE + 0x00007000U) /*!< PMU base address */
+#define DAC_BASE (APB1_BUS_BASE + 0x00007400U) /*!< DAC base address */
+#define CEC_BASE (APB1_BUS_BASE + 0x00007800U) /*!< CEC base address */
+#define CTC_BASE (APB1_BUS_BASE + 0x0000C800U) /*!< CTC base address */
+ /* advanced peripheral bus 2 memory map */
+#define SYSCFG_BASE (APB2_BUS_BASE + 0x00000000U) /*!< SYSCFG base address */
+#define CMP_BASE (APB2_BUS_BASE + 0x0000001CU) /*!< CMP base address */
+#define EXTI_BASE (APB2_BUS_BASE + 0x00000400U) /*!< EXTI base address */
+#define ADC_BASE (APB2_BUS_BASE + 0x00002400U) /*!< ADC base address */
+ /* advanced high performance bus 1 memory map */
+#define DMA_BASE (AHB1_BUS_BASE + 0x00000000U) /*!< DMA base address */
+#define DMA_CHANNEL_BASE (DMA_BASE + 0x00000008U) /*!< DMA channel base address */
+#define RCU_BASE (AHB1_BUS_BASE + 0x00001000U) /*!< RCU base address */
+#define FMC_BASE (AHB1_BUS_BASE + 0x00002000U) /*!< FMC base address */
+#define CRC_BASE (AHB1_BUS_BASE + 0x00003000U) /*!< CRC base address */
+#define TSI_BASE (AHB1_BUS_BASE + 0x00004000U) /*!< TSI base address */
+#define USBFS_BASE (AHB1_BUS_BASE + 0x0FFE0000U) /*!< USBFS base address */
+ /* advanced high performance bus 2 memory map */
+#define GPIO_BASE (AHB2_BUS_BASE + 0x00000000U) /*!< GPIO base address */
+ /* option byte and debug memory map */
+#define OB_BASE ((uint32_t)0x1FFFF800U) /*!< OB base address */
+#define DBG_BASE ((uint32_t)0xE0042000U) /*!< DBG base address */
+
+ /* define marco USE_STDPERIPH_DRIVER */
+#if !defined USE_STDPERIPH_DRIVER
+#define USE_STDPERIPH_DRIVER
+#endif
+#ifdef USE_STDPERIPH_DRIVER
+#include "gd32f3x0_libopt.h"
+#endif /* USE_STDPERIPH_DRIVER */
+
+#ifdef cplusplus
+}
+#endif
+#endif
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/CMSIS/GD/GD32F3x0/Include/system_gd32f3x0.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/CMSIS/GD/GD32F3x0/Include/system_gd32f3x0.h
new file mode 100644
index 00000000..73233055
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/CMSIS/GD/GD32F3x0/Include/system_gd32f3x0.h
@@ -0,0 +1,58 @@
+/*!
+ \file system_gd32f3x0.h
+ \brief CMSIS Cortex-M4 Device Peripheral Access Layer Header File for
+ GD32F3x0 Device Series
+*/
+
+/* Copyright (c) 2012 ARM LIMITED
+
+ All rights reserved.
+ Redistribution and use in source and binary forms, with or without
+ modification, are permitted provided that the following conditions are met:
+ - Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ - 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.
+ - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
+ ---------------------------------------------------------------------------*/
+
+/* This file refers the CMSIS standard, some adjustments are made according to GigaDevice chips */
+
+#ifndef SYSTEM_GD32F3X0_H
+#define SYSTEM_GD32F3X0_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#include
+
+/* system clock frequency (core clock) */
+extern uint32_t SystemCoreClock;
+
+/* function declarations */
+/* initialize the system and update the SystemCoreClock variable */
+extern void SystemInit(void);
+/* update the SystemCoreClock with current core clock retrieved from cpu registers */
+extern void SystemCoreClockUpdate(void);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* SYSTEM_GD32F3X0_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/CMSIS/GD/GD32F3x0/Source/ARM/startup_gd32f3x0.s b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/CMSIS/GD/GD32F3x0/Source/ARM/startup_gd32f3x0.s
new file mode 100644
index 00000000..712152c8
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/CMSIS/GD/GD32F3x0/Source/ARM/startup_gd32f3x0.s
@@ -0,0 +1,320 @@
+;/*!
+; \file startup_gd32f3x0.s
+; \brief start up file
+;
+; \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+; \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+; \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+; \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+;*/
+
+;/*
+ ;Copyright (c) 2022, 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.
+;*/
+
+; Stack Configuration
+; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8>
+;
+
+Stack_Size EQU 0x00000400
+
+ AREA STACK, NOINIT, READWRITE, ALIGN=3
+Stack_Mem SPACE Stack_Size
+__initial_sp
+
+
+; Heap Configuration
+; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8>
+;
+
+Heap_Size EQU 0x00000400
+
+ AREA HEAP, NOINIT, READWRITE, ALIGN=3
+__heap_base
+Heap_Mem SPACE Heap_Size
+__heap_limit
+
+ PRESERVE8
+ THUMB
+
+; /* reset Vector Mapped to at Address 0 */
+ AREA RESET, DATA, READONLY
+ EXPORT __Vectors
+ EXPORT __Vectors_End
+ EXPORT __Vectors_Size
+
+__Vectors DCD __initial_sp ; Top of Stack
+ DCD Reset_Handler ; Reset Handler
+ DCD NMI_Handler ; NMI Handler
+ DCD HardFault_Handler ; Hard Fault Handler
+ DCD MemManage_Handler ; MPU Fault Handler
+ DCD BusFault_Handler ; Bus Fault Handler
+ DCD UsageFault_Handler ; Usage Fault Handler
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD SVC_Handler ; SVCall Handler
+ DCD DebugMon_Handler ; Debug Monitor Handler
+ DCD 0 ; Reserved
+ DCD PendSV_Handler ; PendSV Handler
+ DCD SysTick_Handler ; SysTick Handler
+
+; /* external interrupts handler */
+ DCD WWDGT_IRQHandler ; 16:Window Watchdog Timer
+ DCD LVD_IRQHandler ; 17:LVD through EXTI Line detect
+ DCD RTC_IRQHandler ; 18:RTC through EXTI Line
+ DCD FMC_IRQHandler ; 19:FMC
+ DCD RCU_CTC_IRQHandler ; 20:RCU and CTC
+ DCD EXTI0_1_IRQHandler ; 21:EXTI Line 0 and EXTI Line 1
+ DCD EXTI2_3_IRQHandler ; 22:EXTI Line 2 and EXTI Line 3
+ DCD EXTI4_15_IRQHandler ; 23:EXTI Line 4 to EXTI Line 15
+ DCD TSI_IRQHandler ; 24:TSI
+ DCD DMA_Channel0_IRQHandler ; 25:DMA Channel 0
+ DCD DMA_Channel1_2_IRQHandler ; 26:DMA Channel 1 and DMA Channel 2
+ DCD DMA_Channel3_4_IRQHandler ; 27:DMA Channel 3 and DMA Channel 4
+ DCD ADC_CMP_IRQHandler ; 28:ADC and Comparator 0-1
+ DCD TIMER0_BRK_UP_TRG_COM_IRQHandler ; 29:TIMER0 Break,Update,Trigger and Commutation
+ DCD TIMER0_Channel_IRQHandler ; 30:TIMER0 Channel Capture Compare
+ DCD TIMER1_IRQHandler ; 31:TIMER1
+ DCD TIMER2_IRQHandler ; 32:TIMER2
+ DCD TIMER5_DAC_IRQHandler ; 33:TIMER5 and DAC
+ DCD 0 ; Reserved
+ DCD TIMER13_IRQHandler ; 35:TIMER13
+ DCD TIMER14_IRQHandler ; 36:TIMER14
+ DCD TIMER15_IRQHandler ; 37:TIMER15
+ DCD TIMER16_IRQHandler ; 38:TIMER16
+ DCD I2C0_EV_IRQHandler ; 39:I2C0 Event
+ DCD I2C1_EV_IRQHandler ; 40:I2C1 Event
+ DCD SPI0_IRQHandler ; 41:SPI0
+ DCD SPI1_IRQHandler ; 42:SPI1
+ DCD USART0_IRQHandler ; 43:USART0
+ DCD USART1_IRQHandler ; 44:USART1
+ DCD 0 ; Reserved
+ DCD CEC_IRQHandler ; 46:CEC
+ DCD 0 ; Reserved
+ DCD I2C0_ER_IRQHandler ; 48:I2C0 Error
+ DCD 0 ; Reserved
+ DCD I2C1_ER_IRQHandler ; 50:I2C1 Error
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD USBFS_WKUP_IRQHandler ; 58:USBFS Wakeup
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD DMA_Channel5_6_IRQHandler ; 64:DMA Channel5 and Channel6
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD USBFS_IRQHandler ; 83:USBFS
+__Vectors_End
+
+__Vectors_Size EQU __Vectors_End - __Vectors
+
+ AREA |.text|, CODE, READONLY
+
+;/* reset Handler */
+Reset_Handler PROC
+ EXPORT Reset_Handler [WEAK]
+ IMPORT SystemInit
+ IMPORT __main
+ LDR R0, =SystemInit
+ BLX R0
+ LDR R0, =__main
+ BX R0
+ ENDP
+
+;/* dummy Exception Handlers */
+NMI_Handler PROC
+ EXPORT NMI_Handler [WEAK]
+ B .
+ ENDP
+HardFault_Handler\
+ PROC
+ EXPORT HardFault_Handler [WEAK]
+ B .
+ ENDP
+MemManage_Handler\
+ PROC
+ EXPORT MemManage_Handler [WEAK]
+ B .
+ ENDP
+BusFault_Handler\
+ PROC
+ EXPORT BusFault_Handler [WEAK]
+ B .
+ ENDP
+UsageFault_Handler\
+ PROC
+ EXPORT UsageFault_Handler [WEAK]
+ B .
+ ENDP
+SVC_Handler PROC
+ EXPORT SVC_Handler [WEAK]
+ B .
+ ENDP
+DebugMon_Handler\
+ PROC
+ EXPORT DebugMon_Handler [WEAK]
+ B .
+ ENDP
+PendSV_Handler\
+ PROC
+ EXPORT PendSV_Handler [WEAK]
+ B .
+ ENDP
+SysTick_Handler\
+ PROC
+ EXPORT SysTick_Handler [WEAK]
+ B .
+ ENDP
+
+Default_Handler PROC
+; /* external interrupts handler */
+ EXPORT WWDGT_IRQHandler [WEAK]
+ EXPORT LVD_IRQHandler [WEAK]
+ EXPORT RTC_IRQHandler [WEAK]
+ EXPORT FMC_IRQHandler [WEAK]
+ EXPORT RCU_CTC_IRQHandler [WEAK]
+ EXPORT EXTI0_1_IRQHandler [WEAK]
+ EXPORT EXTI2_3_IRQHandler [WEAK]
+ EXPORT EXTI4_15_IRQHandler [WEAK]
+ EXPORT TSI_IRQHandler [WEAK]
+ EXPORT DMA_Channel0_IRQHandler [WEAK]
+ EXPORT DMA_Channel1_2_IRQHandler [WEAK]
+ EXPORT DMA_Channel3_4_IRQHandler [WEAK]
+ EXPORT ADC_CMP_IRQHandler [WEAK]
+ EXPORT TIMER0_BRK_UP_TRG_COM_IRQHandler [WEAK]
+ EXPORT TIMER0_Channel_IRQHandler [WEAK]
+ EXPORT TIMER1_IRQHandler [WEAK]
+ EXPORT TIMER2_IRQHandler [WEAK]
+ EXPORT TIMER5_DAC_IRQHandler [WEAK]
+ EXPORT TIMER13_IRQHandler [WEAK]
+ EXPORT TIMER14_IRQHandler [WEAK]
+ EXPORT TIMER15_IRQHandler [WEAK]
+ EXPORT TIMER16_IRQHandler [WEAK]
+ EXPORT I2C0_EV_IRQHandler [WEAK]
+ EXPORT I2C1_EV_IRQHandler [WEAK]
+ EXPORT SPI0_IRQHandler [WEAK]
+ EXPORT SPI1_IRQHandler [WEAK]
+ EXPORT USART0_IRQHandler [WEAK]
+ EXPORT USART1_IRQHandler [WEAK]
+ EXPORT CEC_IRQHandler [WEAK]
+ EXPORT I2C0_ER_IRQHandler [WEAK]
+ EXPORT I2C1_ER_IRQHandler [WEAK]
+ EXPORT USBFS_WKUP_IRQHandler [WEAK]
+ EXPORT DMA_Channel5_6_IRQHandler [WEAK]
+ EXPORT USBFS_IRQHandler [WEAK]
+
+;/* external interrupts handler */
+WWDGT_IRQHandler
+LVD_IRQHandler
+RTC_IRQHandler
+FMC_IRQHandler
+RCU_CTC_IRQHandler
+EXTI0_1_IRQHandler
+EXTI2_3_IRQHandler
+EXTI4_15_IRQHandler
+TSI_IRQHandler
+DMA_Channel0_IRQHandler
+DMA_Channel1_2_IRQHandler
+DMA_Channel3_4_IRQHandler
+ADC_CMP_IRQHandler
+TIMER0_BRK_UP_TRG_COM_IRQHandler
+TIMER0_Channel_IRQHandler
+TIMER1_IRQHandler
+TIMER2_IRQHandler
+TIMER5_DAC_IRQHandler
+TIMER13_IRQHandler
+TIMER14_IRQHandler
+TIMER15_IRQHandler
+TIMER16_IRQHandler
+I2C0_EV_IRQHandler
+I2C1_EV_IRQHandler
+SPI0_IRQHandler
+SPI1_IRQHandler
+USART0_IRQHandler
+USART1_IRQHandler
+CEC_IRQHandler
+I2C0_ER_IRQHandler
+I2C1_ER_IRQHandler
+USBFS_WKUP_IRQHandler
+DMA_Channel5_6_IRQHandler
+USBFS_IRQHandler
+
+ B .
+ ENDP
+
+ ALIGN
+
+; user Initial Stack & Heap
+
+ IF :DEF:__MICROLIB
+
+ EXPORT __initial_sp
+ EXPORT __heap_base
+ EXPORT __heap_limit
+
+ ELSE
+
+ IMPORT __use_two_region_memory
+ EXPORT __user_initial_stackheap
+
+__user_initial_stackheap PROC
+ LDR R0, = Heap_Mem
+ LDR R1, =(Stack_Mem + Stack_Size)
+ LDR R2, = (Heap_Mem + Heap_Size)
+ LDR R3, = Stack_Mem
+ BX LR
+ ENDP
+
+ ALIGN
+
+ ENDIF
+
+ END
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/CMSIS/GD/GD32F3x0/Source/GCC/startup_gd32f3x0.s b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/CMSIS/GD/GD32F3x0/Source/GCC/startup_gd32f3x0.s
new file mode 100644
index 00000000..78a23ac8
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/CMSIS/GD/GD32F3x0/Source/GCC/startup_gd32f3x0.s
@@ -0,0 +1,265 @@
+;/*!
+; \file startup_gd32f3x0.s
+; \brief start up file
+;
+; \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+; \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+; \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+; \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+;*/
+
+;/*
+ ;Copyright (c) 2022, 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.
+;*/
+
+.syntax unified
+.cpu cortex-m4
+.fpu fpv4-sp-d16
+.thumb
+
+.section .isr_vector,"a",%progbits
+.type g_pfnVectors, %object
+g_pfnVectors:
+ .word _estack // Top of Stack
+ .word Reset_Handler // Reset Handler
+ .word NMI_Handler // NMI Handler
+ .word HardFault_Handler // Hard Fault Handler
+ .word MemManage_Handler // MPU Fault Handler
+ .word BusFault_Handler // Bus Fault Handler
+ .word UsageFault_Handler // Usage Fault Handler
+ .word 0 // Reserved
+ .word 0 // Reserved
+ .word 0 // Reserved
+ .word 0 // Reserved
+ .word SVC_Handler // SVCall Handler
+ .word DebugMon_Handler // Debug Monitor Handler
+ .word 0 // Reserved
+ .word PendSV_Handler // PendSV Handler
+ .word SysTick_Handler // SysTick Handler
+
+ /* external interrupts handler */
+ .word WWDGT_IRQHandler // 16:Window Watchdog Timer
+ .word LVD_IRQHandler // 17:LVD through EXTI Line detect
+ .word RTC_IRQHandler // 18:RTC through EXTI Line
+ .word FMC_IRQHandler // 19:FMC
+ .word RCU_CTC_IRQHandler // 20:RCU and CTC
+ .word EXTI0_1_IRQHandler // 21:EXTI Line 0 and EXTI Line 1
+ .word EXTI2_3_IRQHandler // 22:EXTI Line 2 and EXTI Line 3
+ .word EXTI4_15_IRQHandler // 23:EXTI Line 4 to EXTI Line 15
+ .word TSI_IRQHandler // 24:TSI
+ .word DMA_Channel0_IRQHandler // 25:DMA Channel 0
+ .word DMA_Channel1_2_IRQHandler // 26:DMA Channel 1 and DMA Channel 2
+ .word DMA_Channel3_4_IRQHandler // 27:DMA Channel 3 and DMA Channel 4
+ .word ADC_CMP_IRQHandler // 28:ADC and Comparator 0-1
+ .word TIMER0_BRK_UP_TRG_COM_IRQHandler // 29:TIMER0 Break,Update,Trigger and Commutation
+ .word TIMER0_Channel_IRQHandler // 30:TIMER0 Channel Capture Compare
+ .word TIMER1_IRQHandler // 31:TIMER1
+ .word TIMER2_IRQHandler // 32:TIMER2
+ .word TIMER5_DAC_IRQHandler // 33:TIMER5 and DAC
+ .word 0 // Reserved
+ .word TIMER13_IRQHandler // 35:TIMER13
+ .word TIMER14_IRQHandler // 36:TIMER14
+ .word TIMER15_IRQHandler // 37:TIMER15
+ .word TIMER16_IRQHandler // 38:TIMER16
+ .word I2C0_EV_IRQHandler // 39:I2C0 Event
+ .word I2C1_EV_IRQHandler // 40:I2C1 Event
+ .word SPI0_IRQHandler // 41:SPI0
+ .word SPI1_IRQHandler // 42:SPI1
+ .word USART0_IRQHandler // 43:USART0
+ .word USART1_IRQHandler // 44:USART1
+ .word 0 // Reserved
+ .word CEC_IRQHandler // 46:CEC
+ .word 0 // Reserved
+ .word I2C0_ER_IRQHandler // 48:I2C0 Error
+ .word 0 // Reserved
+ .word I2C1_ER_IRQHandler // 50:I2C1 Error
+ .word 0 // Reserved
+ .word 0 // Reserved
+ .word 0 // Reserved
+ .word 0 // Reserved
+ .word 0 // Reserved
+ .word 0 // Reserved
+ .word 0 // Reserved
+ .word USBFS_WKUP_IRQHandler // 58:USBFS Wakeup
+ .word 0 // Reserved
+ .word 0 // Reserved
+ .word 0 // Reserved
+ .word 0 // Reserved
+ .word 0 // Reserved
+ .word DMA_Channel5_6_IRQHandler // 64:DMA Channel5 and Channel6
+ .word 0 // Reserved
+ .word 0 // Reserved
+ .word 0 // Reserved
+ .word 0 // Reserved
+ .word 0 // Reserved
+ .word 0 // Reserved
+ .word 0 // Reserved
+ .word 0 // Reserved
+ .word 0 // Reserved
+ .word 0 // Reserved
+ .word 0 // Reserved
+ .word 0 // Reserved
+ .word 0 // Reserved
+ .word 0 // Reserved
+ .word 0 // Reserved
+ .word 0 // Reserved
+ .word 0 // Reserved
+ .word 0 // Reserved
+ .word USBFS_IRQHandler // 83:USBFS
+ /* set size of g_pfnVectors */
+ .size g_pfnVectors, . - g_pfnVectors
+
+.weak Reset_Handler
+.type Reset_Handler, %function
+Reset_Handler:
+ ldr r1, =_sidata
+ ldr r2, =_sdata
+ ldr r3, =_edata
+
+ subs r3, r2
+ ble fill_bss_start
+
+loop_copy_data:
+ subs r3, #4
+ ldr r0, [r1,r3]
+ str r0, [r2,r3]
+ bgt loop_copy_data
+
+fill_bss_start:
+ ldr r1, =__bss_start
+ ldr r2, =__bss_end
+ movs r0, 0
+ subs r2, r1
+ ble startup_enter
+
+loop_fill_bss:
+ subs r2, #4
+ str r0, [r1, r2]
+ bgt loop_fill_bss
+
+startup_enter:
+ bl SystemInit
+ bl main
+
+ .weak NMI_Handler
+ .type NMI_Handler, %function
+NMI_Handler:
+ b .
+ .size NMI_Handler, . - NMI_Handler
+
+ .weak HardFault_Handler
+ .type HardFault_Handler, %function
+HardFault_Handler:
+ b .
+ .size HardFault_Handler, . - HardFault_Handler
+
+ .weak MemManage_Handler
+ .type MemManage_Handler, %function
+MemManage_Handler:
+ b .
+ .size MemManage_Handler, . - MemManage_Handler
+
+ .weak BusFault_Handler
+ .type BusFault_Handler, %function
+BusFault_Handler:
+ b .
+ .size BusFault_Handler, . - BusFault_Handler
+
+ .weak UsageFault_Handler
+ .type UsageFault_Handler, %function
+UsageFault_Handler:
+ b .
+ .size UsageFault_Handler, . - UsageFault_Handler
+
+ .weak SVC_Handler
+ .type SVC_Handler, %function
+SVC_Handler:
+ b .
+ .size SVC_Handler, . - SVC_Handler
+
+ .weak DebugMon_Handler
+ .type DebugMon_Handler, %function
+DebugMon_Handler:
+ b .
+ .size DebugMon_Handler, . - DebugMon_Handler
+
+ .weak PendSV_Handler
+ .type PendSV_Handler, %function
+PendSV_Handler:
+ b .
+ .size PendSV_Handler, . - PendSV_Handler
+
+ .weak SysTick_Handler
+ .type SysTick_Handler, %function
+SysTick_Handler:
+ b .
+ .size SysTick_Handler, . - SysTick_Handler
+
+ .section .text.Default_Handler,"ax",%progbits
+ .type Default_Handler, %function
+Default_Handler:
+ b .
+ .size Default_Handler, . - Default_Handler
+
+ .macro IRQ handler
+ .weak \handler
+ .set \handler, Default_Handler
+ .endm
+/* external interrupts handler */
+ IRQ WWDGT_IRQHandler
+ IRQ LVD_IRQHandler
+ IRQ RTC_IRQHandler
+ IRQ FMC_IRQHandler
+ IRQ RCU_CTC_IRQHandler
+ IRQ EXTI0_1_IRQHandler
+ IRQ EXTI2_3_IRQHandler
+ IRQ EXTI4_15_IRQHandler
+ IRQ TSI_IRQHandler
+ IRQ DMA_Channel0_IRQHandler
+ IRQ DMA_Channel1_2_IRQHandler
+ IRQ DMA_Channel3_4_IRQHandler
+ IRQ ADC_CMP_IRQHandler
+ IRQ TIMER0_BRK_UP_TRG_COM_IRQHandler
+ IRQ TIMER0_Channel_IRQHandler
+ IRQ TIMER1_IRQHandler
+ IRQ TIMER2_IRQHandler
+ IRQ TIMER5_DAC_IRQHandler
+ IRQ TIMER13_IRQHandler
+ IRQ TIMER14_IRQHandler
+ IRQ TIMER15_IRQHandler
+ IRQ TIMER16_IRQHandler
+ IRQ I2C0_EV_IRQHandler
+ IRQ I2C1_EV_IRQHandler
+ IRQ SPI0_IRQHandler
+ IRQ SPI1_IRQHandler
+ IRQ USART0_IRQHandler
+ IRQ USART1_IRQHandler
+ IRQ CEC_IRQHandler
+ IRQ I2C0_ER_IRQHandler
+ IRQ I2C1_ER_IRQHandler
+ IRQ USBFS_WKUP_IRQHandler
+ IRQ DMA_Channel5_6_IRQHandler
+ IRQ USBFS_IRQHandler
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/CMSIS/GD/GD32F3x0/Source/IAR/startup_gd32f3x0.s b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/CMSIS/GD/GD32F3x0/Source/IAR/startup_gd32f3x0.s
new file mode 100644
index 00000000..8c264c7b
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/CMSIS/GD/GD32F3x0/Source/IAR/startup_gd32f3x0.s
@@ -0,0 +1,368 @@
+;/*!
+; \file startup_gd32f3x0.s
+; \brief start up file
+;
+; \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+; \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+; \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+; \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+;*/
+
+;/*
+ ;Copyright (c) 2022, 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.
+;*/
+
+ MODULE ?cstartup
+
+ ;; Forward declaration of sections.
+ SECTION CSTACK:DATA:NOROOT(3)
+
+ SECTION .intvec:CODE:NOROOT(2)
+
+ EXTERN __iar_program_start
+ EXTERN SystemInit
+ PUBLIC __vector_table
+
+ DATA
+__vector_table
+ DCD sfe(CSTACK) ; top of stack
+ DCD Reset_Handler ; Vector Number 1,Reset Handler
+
+ DCD NMI_Handler ; Vector Number 2,NMI Handler
+ DCD HardFault_Handler ; Vector Number 3,Hard Fault Handler
+ DCD MemManage_Handler ; Vector Number 4,MPU Fault Handler
+ DCD BusFault_Handler ; Vector Number 5,Bus Fault Handler
+ DCD UsageFault_Handler ; Vector Number 6,Usage Fault Handler
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD SVC_Handler ; Vector Number 11,SVCall Handler
+ DCD DebugMon_Handler ; Vector Number 12,Debug Monitor Handler
+ DCD 0 ; Reserved
+ DCD PendSV_Handler ; Vector Number 14,PendSV Handler
+ DCD SysTick_Handler ; Vector Number 15,SysTick Handler
+
+ ; External Interrupts
+ DCD WWDGT_IRQHandler ; Vector Number 16,Window watchdog timer
+ DCD LVD_IRQHandler ; Vector Number 17,LVD through EXTI Line detect
+ DCD RTC_IRQHandler ; Vector Number 18,RTC through EXTI Line
+ DCD FMC_IRQHandler ; Vector Number 19,FMC
+ DCD RCU_CTC_IRQHandler ; Vector Number 20,RCU and CTC
+ DCD EXTI0_1_IRQHandler ; Vector Number 21,EXTI Line 0 and EXTI Line 1
+ DCD EXTI2_3_IRQHandler ; Vector Number 22,EXTI Line 2 and EXTI Line 3
+ DCD EXTI4_15_IRQHandler ; Vector Number 23,EXTI Line 4 to EXTI Line 15
+ DCD TSI_IRQHandler ; Vector Number 24,TSI
+ DCD DMA_Channel0_IRQHandler ; Vector Number 25,DMA Channel 0
+ DCD DMA_Channel1_2_IRQHandler ; Vector Number 26,DMA Channel 1 and DMA Channel 2
+ DCD DMA_Channel3_4_IRQHandler ; Vector Number 27,DMA Channel 3 and DMA Channel 4
+ DCD ADC_CMP_IRQHandler ; Vector Number 28,ADC and Comparator 1-2
+ DCD TIMER0_BRK_UP_TRG_COM_IRQHandler ; Vector Number 29,TIMER0 Break, Update, Trigger and Commutation
+ DCD TIMER0_Channel_IRQHandler ; Vector Number 30,TIMER0 Channel Capture Compare
+ DCD TIMER1_IRQHandler ; Vector Number 31,TIMER1
+ DCD TIMER2_IRQHandler ; Vector Number 32,TIMER2
+ DCD TIMER5_DAC_IRQHandler ; Vector Number 33,TIMER5 and DAC
+ DCD 0 ; Reserved
+ DCD TIMER13_IRQHandler ; Vector Number 35,TIMER13
+ DCD TIMER14_IRQHandler ; Vector Number 36,TIMER14
+ DCD TIMER15_IRQHandler ; Vector Number 37,TIMER15
+ DCD TIMER16_IRQHandler ; Vector Number 38,TIMER16
+ DCD I2C0_EV_IRQHandler ; Vector Number 39,I2C0 Event
+ DCD I2C1_EV_IRQHandler ; Vector Number 40,I2C1 Event
+ DCD SPI0_IRQHandler ; Vector Number 41,SPI0
+ DCD SPI1_IRQHandler ; Vector Number 42,SPI1
+ DCD USART0_IRQHandler ; Vector Number 43,USART0
+ DCD USART1_IRQHandler ; Vector Number 44,USART1
+ DCD 0 ; Reserved
+ DCD CEC_IRQHandler ; Vector Number 46,CEC
+ DCD 0 ; Reserved
+ DCD I2C0_ER_IRQHandler ; Vector Number 48,I2C0 Error
+ DCD 0 ; Reserved
+ DCD I2C1_ER_IRQHandler ; Vector Number 50,I2C1 Error
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD USBFS_WKUP_IRQHandler ; Vector Number 58,USBFS Wakeup
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD DMA_Channel5_6_IRQHandler ; Vector Number 64,DMA Channel5 and Channel6
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD USBFS_IRQHandler ; Vector Number 83,USBFS
+
+;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;
+;;
+;; Default interrupt handlers.
+;;
+ THUMB
+
+ PUBWEAK Reset_Handler
+ SECTION .text:CODE:NOROOT:REORDER(2)
+Reset_Handler
+ LDR R0, =SystemInit
+ BLX R0
+ LDR R0, =__iar_program_start
+ BX R0
+
+ PUBWEAK NMI_Handler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+NMI_Handler
+ B NMI_Handler
+
+ PUBWEAK HardFault_Handler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+HardFault_Handler
+ B HardFault_Handler
+
+ PUBWEAK MemManage_Handler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+MemManage_Handler
+ B MemManage_Handler
+
+ PUBWEAK BusFault_Handler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+BusFault_Handler
+ B BusFault_Handler
+
+ PUBWEAK UsageFault_Handler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+UsageFault_Handler
+ B UsageFault_Handler
+
+ PUBWEAK SVC_Handler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+SVC_Handler
+ B SVC_Handler
+
+ PUBWEAK DebugMon_Handler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+DebugMon_Handler
+ B DebugMon_Handler
+
+ PUBWEAK PendSV_Handler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+PendSV_Handler
+ B PendSV_Handler
+
+ PUBWEAK SysTick_Handler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+SysTick_Handler
+ B SysTick_Handler
+
+ PUBWEAK WWDGT_IRQHandler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+WWDGT_IRQHandler
+ B WWDGT_IRQHandler
+
+ PUBWEAK LVD_IRQHandler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+LVD_IRQHandler
+ B LVD_IRQHandler
+
+ PUBWEAK RTC_IRQHandler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+RTC_IRQHandler
+ B RTC_IRQHandler
+
+ PUBWEAK FMC_IRQHandler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+FMC_IRQHandler
+ B FMC_IRQHandler
+
+ PUBWEAK RCU_CTC_IRQHandler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+RCU_CTC_IRQHandler
+ B RCU_CTC_IRQHandler
+
+ PUBWEAK EXTI0_1_IRQHandler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+EXTI0_1_IRQHandler
+ B EXTI0_1_IRQHandler
+
+ PUBWEAK EXTI2_3_IRQHandler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+EXTI2_3_IRQHandler
+ B EXTI2_3_IRQHandler
+
+ PUBWEAK EXTI4_15_IRQHandler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+EXTI4_15_IRQHandler
+ B EXTI4_15_IRQHandler
+
+ PUBWEAK TSI_IRQHandler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+TSI_IRQHandler
+ B TSI_IRQHandler
+
+ PUBWEAK DMA_Channel0_IRQHandler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+DMA_Channel0_IRQHandler
+ B DMA_Channel0_IRQHandler
+
+ PUBWEAK DMA_Channel1_2_IRQHandler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+DMA_Channel1_2_IRQHandler
+ B DMA_Channel1_2_IRQHandler
+
+ PUBWEAK DMA_Channel3_4_IRQHandler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+DMA_Channel3_4_IRQHandler
+ B DMA_Channel3_4_IRQHandler
+
+ PUBWEAK ADC_CMP_IRQHandler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+ADC_CMP_IRQHandler
+ B ADC_CMP_IRQHandler
+
+ PUBWEAK TIMER0_BRK_UP_TRG_COM_IRQHandler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+TIMER0_BRK_UP_TRG_COM_IRQHandler
+ B TIMER0_BRK_UP_TRG_COM_IRQHandler
+
+ PUBWEAK TIMER0_Channel_IRQHandler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+TIMER0_Channel_IRQHandler
+ B TIMER0_Channel_IRQHandler
+
+ PUBWEAK TIMER1_IRQHandler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+TIMER1_IRQHandler
+ B TIMER1_IRQHandler
+
+ PUBWEAK TIMER2_IRQHandler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+TIMER2_IRQHandler
+ B TIMER2_IRQHandler
+
+ PUBWEAK TIMER5_DAC_IRQHandler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+TIMER5_DAC_IRQHandler
+ B TIMER5_DAC_IRQHandler
+
+ PUBWEAK TIMER13_IRQHandler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+TIMER13_IRQHandler
+ B TIMER13_IRQHandler
+
+ PUBWEAK TIMER14_IRQHandler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+TIMER14_IRQHandler
+ B TIMER14_IRQHandler
+
+ PUBWEAK TIMER15_IRQHandler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+TIMER15_IRQHandler
+ B TIMER15_IRQHandler
+
+ PUBWEAK TIMER16_IRQHandler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+TIMER16_IRQHandler
+ B TIMER16_IRQHandler
+
+ PUBWEAK I2C0_EV_IRQHandler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+I2C0_EV_IRQHandler
+ B I2C0_EV_IRQHandler
+
+ PUBWEAK I2C1_EV_IRQHandler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+I2C1_EV_IRQHandler
+ B I2C1_EV_IRQHandler
+
+ PUBWEAK SPI0_IRQHandler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+SPI0_IRQHandler
+ B SPI0_IRQHandler
+
+ PUBWEAK SPI1_IRQHandler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+SPI1_IRQHandler
+ B SPI1_IRQHandler
+
+ PUBWEAK USART0_IRQHandler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+USART0_IRQHandler
+ B USART0_IRQHandler
+
+ PUBWEAK USART1_IRQHandler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+USART1_IRQHandler
+ B USART1_IRQHandler
+
+ PUBWEAK CEC_IRQHandler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+CEC_IRQHandler
+ B CEC_IRQHandler
+
+ PUBWEAK I2C0_ER_IRQHandler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+I2C0_ER_IRQHandler
+ B I2C0_ER_IRQHandler
+
+ PUBWEAK I2C1_ER_IRQHandler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+I2C1_ER_IRQHandler
+ B I2C1_ER_IRQHandler
+
+ PUBWEAK USBFS_WKUP_IRQHandler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+USBFS_WKUP_IRQHandler
+ B USBFS_WKUP_IRQHandler
+
+ PUBWEAK DMA_Channel5_6_IRQHandler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+DMA_Channel5_6_IRQHandler
+ B DMA_Channel5_6_IRQHandler
+
+ PUBWEAK USBFS_IRQHandler
+ SECTION .text:CODE:NOROOT:REORDER(1)
+USBFS_IRQHandler
+ B USBFS_IRQHandler
+
+ END
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/CMSIS/GD/GD32F3x0/Source/system_gd32f3x0.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/CMSIS/GD/GD32F3x0/Source/system_gd32f3x0.c
new file mode 100644
index 00000000..3c1f25c7
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/CMSIS/GD/GD32F3x0/Source/system_gd32f3x0.c
@@ -0,0 +1,830 @@
+/*!
+ \file system_gd32f3x0.c
+ \brief CMSIS Cortex-M4 Device Peripheral Access Layer Source File for
+ GD32F3x0 Device Series
+*/
+
+/* Copyright (c) 2012 ARM LIMITED
+
+ All rights reserved.
+ Redistribution and use in source and binary forms, with or without
+ modification, are permitted provided that the following conditions are met:
+ - Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ - 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.
+ - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
+ ---------------------------------------------------------------------------*/
+
+/* This file refers the CMSIS standard, some adjustments are made according to GigaDevice chips */
+
+#include "gd32f3x0.h"
+
+/* system frequency define */
+#define __IRC8M (IRC8M_VALUE) /* internal 8 MHz RC oscillator frequency */
+#define __HXTAL (HXTAL_VALUE) /* high speed crystal oscillator frequency */
+#define __SYS_OSC_CLK (__IRC8M) /* main oscillator frequency */
+
+#define VECT_TAB_OFFSET (uint32_t)0x00 /* vector table base offset */
+
+/* select a system clock by uncommenting the following line */
+#if defined (GD32F310)
+//#define __SYSTEM_CLOCK_8M_HXTAL (__HXTAL)
+//#define __SYSTEM_CLOCK_8M_IRC8M (__IRC8M)
+#define __SYSTEM_CLOCK_72M_PLL_HXTAL (uint32_t)(72000000)
+//#define __SYSTEM_CLOCK_72M_PLL_IRC8M_DIV2 (uint32_t)(72000000)
+//#define __SYSTEM_CLOCK_72M_PLL_IRC48M_DIV2 (uint32_t)(72000000)
+#endif /* GD32F310 */
+
+#if defined (GD32F330)
+//#define __SYSTEM_CLOCK_8M_HXTAL (__HXTAL)
+//#define __SYSTEM_CLOCK_8M_IRC8M (__IRC8M)
+//#define __SYSTEM_CLOCK_72M_PLL_HXTAL (uint32_t)(72000000)
+//#define __SYSTEM_CLOCK_72M_PLL_IRC8M_DIV2 (uint32_t)(72000000)
+//#define __SYSTEM_CLOCK_72M_PLL_IRC48M_DIV2 (uint32_t)(72000000)
+#define __SYSTEM_CLOCK_84M_PLL_HXTAL (uint32_t)(84000000)
+//#define __SYSTEM_CLOCK_84M_PLL_IRC8M_DIV2 (uint32_t)(84000000)
+#endif /* GD32F330 */
+
+#if defined (GD32F350)
+//#define __SYSTEM_CLOCK_8M_HXTAL (__HXTAL)
+//#define __SYSTEM_CLOCK_8M_IRC8M (__IRC8M)
+//#define __SYSTEM_CLOCK_72M_PLL_HXTAL (uint32_t)(72000000)
+#define __SYSTEM_CLOCK_72M_PLL_IRC8M_DIV2 (uint32_t)(72000000)
+//#define __SYSTEM_CLOCK_84M_PLL_HXTAL (uint32_t)(84000000)
+//#define __SYSTEM_CLOCK_84M_PLL_IRC8M_DIV2 (uint32_t)(84000000)
+//#define __SYSTEM_CLOCK_96M_PLL_HXTAL (uint32_t)(96000000)
+//#define __SYSTEM_CLOCK_96M_PLL_IRC8M_DIV2 (uint32_t)(96000000)
+//#define __SYSTEM_CLOCK_97M_PLL_IRC48M_DIV2 (uint32_t)(96000000)
+//#define __SYSTEM_CLOCK_108M_PLL_HXTAL (uint32_t)(108000000)
+//#define __SYSTEM_CLOCK_108M_PLL_IRC8M_DIV2 (uint32_t)(108000000)
+#endif /* GD32F350 */
+
+#define SEL_IRC8M 0x00
+#define SEL_HXTAL 0x01
+#define SEL_PLL 0x02
+
+/* set the system clock frequency and declare the system clock configuration function */
+#ifdef __SYSTEM_CLOCK_8M_HXTAL
+uint32_t SystemCoreClock = __SYSTEM_CLOCK_8M_HXTAL;
+static void system_clock_8m_hxtal(void);
+
+#elif defined (__SYSTEM_CLOCK_72M_PLL_HXTAL)
+uint32_t SystemCoreClock = __SYSTEM_CLOCK_72M_PLL_HXTAL;
+static void system_clock_72m_hxtal(void);
+
+#elif defined (__SYSTEM_CLOCK_72M_PLL_IRC8M_DIV2)
+uint32_t SystemCoreClock = __SYSTEM_CLOCK_72M_PLL_IRC8M_DIV2;
+static void system_clock_72m_irc8m(void);
+
+#elif defined (__SYSTEM_CLOCK_72M_PLL_IRC48M_DIV2)
+uint32_t SystemCoreClock = __SYSTEM_CLOCK_72M_PLL_IRC48M_DIV2;
+static void system_clock_72m_irc48m(void);
+
+#elif defined (__SYSTEM_CLOCK_84M_PLL_HXTAL)
+uint32_t SystemCoreClock = __SYSTEM_CLOCK_84M_PLL_HXTAL;
+static void system_clock_84m_hxtal(void);
+
+#elif defined (__SYSTEM_CLOCK_84M_PLL_IRC8M_DIV2)
+uint32_t SystemCoreClock = __SYSTEM_CLOCK_84M_PLL_IRC8M_DIV2;
+static void system_clock_84m_irc8m(void);
+
+#elif defined (__SYSTEM_CLOCK_96M_PLL_HXTAL)
+uint32_t SystemCoreClock = __SYSTEM_CLOCK_96M_PLL_HXTAL;
+static void system_clock_96m_hxtal(void);
+
+#elif defined (__SYSTEM_CLOCK_96M_PLL_IRC8M_DIV2)
+uint32_t SystemCoreClock = __SYSTEM_CLOCK_96M_PLL_IRC8M_DIV2;
+static void system_clock_96m_irc8m(void);
+
+#elif defined (__SYSTEM_CLOCK_96M_PLL_IRC48M_DIV2)
+uint32_t SystemCoreClock = __SYSTEM_CLOCK_96M_PLL_IRC48M_DIV2;
+static void system_clock_96m_irc48m(void);
+
+#elif defined (__SYSTEM_CLOCK_108M_PLL_HXTAL)
+uint32_t SystemCoreClock = __SYSTEM_CLOCK_108M_PLL_HXTAL;
+static void system_clock_108m_hxtal(void);
+
+#elif defined (__SYSTEM_CLOCK_108M_PLL_IRC8M_DIV2)
+uint32_t SystemCoreClock = __SYSTEM_CLOCK_108M_PLL_IRC8M_DIV2;
+static void system_clock_108m_irc8m(void);
+
+#else
+uint32_t SystemCoreClock = __SYSTEM_CLOCK_8M_IRC8M;
+static void system_clock_8m_irc8m(void);
+#endif /* __SYSTEM_CLOCK_8M_HXTAL */
+
+/* configure the system clock */
+static void system_clock_config(void);
+
+/*!
+ \brief setup the microcontroller system, initialize the system
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void SystemInit(void)
+{
+#if (defined(GD32F350))
+ RCU_APB2EN |= BIT(0);
+ CMP_CS |= (CMP_CS_CMP1MSEL | CMP_CS_CMP0MSEL);
+#endif /* GD32F350 */
+ if(((FMC_OBSTAT & OB_OBSTAT_PLEVEL_HIGH) != OB_OBSTAT_PLEVEL_HIGH) &&
+ (((FMC_OBSTAT >> 13) & 0x1) == SET)) {
+ FMC_KEY = UNLOCK_KEY0;
+ FMC_KEY = UNLOCK_KEY1 ;
+ FMC_OBKEY = UNLOCK_KEY0;
+ FMC_OBKEY = UNLOCK_KEY1 ;
+ FMC_CTL |= FMC_CTL_OBER;
+ FMC_CTL |= FMC_CTL_START;
+ while((uint32_t)0x00U != (FMC_STAT & FMC_STAT_BUSY));
+ FMC_CTL &= ~FMC_CTL_OBER;
+ FMC_CTL |= FMC_CTL_OBPG;
+ if((FMC_OBSTAT & OB_OBSTAT_PLEVEL_HIGH) == OB_OBSTAT_PLEVEL_NO) {
+ OB_SPC = FMC_NSPC;
+ } else if((FMC_OBSTAT & OB_OBSTAT_PLEVEL_HIGH) == OB_OBSTAT_PLEVEL_LOW) {
+ OB_SPC = FMC_LSPC;
+ }
+ OB_USER = OB_USER_DEFAULT & ((uint8_t)(FMC_OBSTAT >> 8));
+ OB_DATA0 = ((uint8_t)(FMC_OBSTAT >> 16));
+ OB_DATA1 = ((uint8_t)(FMC_OBSTAT >> 24));
+ OB_WP0 = ((uint8_t)(FMC_WP));
+ OB_WP1 = ((uint8_t)(FMC_WP >> 8));
+ while((uint32_t)0x00U != (FMC_STAT & FMC_STAT_BUSY));
+ FMC_CTL &= ~FMC_CTL_OBPG;
+ FMC_CTL &= ~FMC_CTL_OBWEN;
+ FMC_CTL |= FMC_CTL_LK;
+ }
+ /* FPU settings */
+#if (__FPU_PRESENT == 1U) && (__FPU_USED == 1U)
+ SCB->CPACR |= ((3UL << 10 * 2) | (3UL << 11 * 2)); /* set CP10 and CP11 Full Access */
+#endif
+
+ /* enable IRC8M */
+ RCU_CTL0 |= RCU_CTL0_IRC8MEN;
+ while(0U == (RCU_CTL0 & RCU_CTL0_IRC8MSTB)) {
+ }
+ RCU_CFG0 &= ~(RCU_CFG0_SCS);
+ RCU_CTL0 &= ~(RCU_CTL0_HXTALEN | RCU_CTL0_CKMEN | RCU_CTL0_PLLEN | RCU_CTL0_HXTALBPS);
+
+ /* reset RCU */
+ RCU_CFG0 &= ~(RCU_CFG0_SCS | RCU_CFG0_AHBPSC | RCU_CFG0_APB1PSC | RCU_CFG0_APB2PSC | \
+ RCU_CFG0_ADCPSC | RCU_CFG0_CKOUTSEL | RCU_CFG0_CKOUTDIV | RCU_CFG0_PLLDV);
+ RCU_CFG0 &= ~(RCU_CFG0_PLLSEL | RCU_CFG0_PLLMF | RCU_CFG0_PLLMF4 | RCU_CFG0_PLLDV);
+#if (defined(GD32F350))
+ RCU_CFG0 &= ~(RCU_CFG0_USBFSPSC);
+ RCU_CFG2 &= ~(RCU_CFG2_CECSEL | RCU_CFG2_USBFSPSC2);
+#endif /* GD32F350 */
+
+ RCU_CFG1 &= ~(RCU_CFG1_PREDV | RCU_CFG1_PLLMF5 | RCU_CFG1_PLLPRESEL);
+ RCU_CFG2 &= ~(RCU_CFG2_USART0SEL | RCU_CFG2_ADCSEL);
+ RCU_CFG2 &= ~RCU_CFG2_IRC28MDIV;
+ RCU_CFG2 &= ~RCU_CFG2_ADCPSC2;
+ RCU_CTL1 &= ~RCU_CTL1_IRC28MEN;
+ RCU_ADDCTL &= ~RCU_ADDCTL_IRC48MEN;
+ RCU_INT = 0x00000000U;
+ RCU_ADDINT = 0x00000000U;
+
+ /* configure system clock */
+ system_clock_config();
+
+#ifdef VECT_TAB_SRAM
+ nvic_vector_table_set(NVIC_VECTTAB_RAM, VECT_TAB_OFFSET);
+#else
+ nvic_vector_table_set(NVIC_VECTTAB_FLASH, VECT_TAB_OFFSET);
+#endif
+}
+
+/*!
+ \brief configure the system clock
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+static void system_clock_config(void)
+{
+#ifdef __SYSTEM_CLOCK_8M_HXTAL
+ system_clock_8m_hxtal();
+#elif defined (__SYSTEM_CLOCK_72M_PLL_HXTAL)
+ system_clock_72m_hxtal();
+#elif defined (__SYSTEM_CLOCK_72M_PLL_IRC8M_DIV2)
+ system_clock_72m_irc8m();
+#elif defined (__SYSTEM_CLOCK_72M_PLL_IRC48M_DIV2)
+ system_clock_72m_irc48m();
+#elif defined (__SYSTEM_CLOCK_84M_PLL_HXTAL)
+ system_clock_84m_hxtal();
+#elif defined (__SYSTEM_CLOCK_84M_PLL_IRC8M_DIV2)
+ system_clock_84m_irc8m();
+#elif defined (__SYSTEM_CLOCK_96M_PLL_HXTAL)
+ system_clock_96m_hxtal();
+#elif defined (__SYSTEM_CLOCK_96M_PLL_IRC8M_DIV2)
+ system_clock_96m_irc8m();
+#elif defined (__SYSTEM_CLOCK_96M_PLL_IRC48M_DIV2)
+ system_clock_96m_irc48m();
+#elif defined (__SYSTEM_CLOCK_108M_PLL_HXTAL)
+ system_clock_108m_hxtal();
+#elif defined (__SYSTEM_CLOCK_108M_PLL_IRC8M_DIV2)
+ system_clock_108m_irc8m();
+#else
+ system_clock_8m_irc8m();
+#endif /* __SYSTEM_CLOCK_8M_HXTAL */
+}
+
+#ifdef __SYSTEM_CLOCK_8M_HXTAL
+/*!
+ \brief configure the system clock to 8M by HXTAL
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+static void system_clock_8m_hxtal(void)
+{
+ uint32_t timeout = 0U;
+ uint32_t stab_flag = 0U;
+
+ /* enable HXTAL */
+ RCU_CTL0 |= RCU_CTL0_HXTALEN;
+
+ /* wait until HXTAL is stable or the startup time is longer than HXTAL_STARTUP_TIMEOUT */
+ do {
+ timeout++;
+ stab_flag = (RCU_CTL0 & RCU_CTL0_HXTALSTB);
+ } while((0U == stab_flag) && (HXTAL_STARTUP_TIMEOUT != timeout));
+ /* if fail */
+ if(0U == (RCU_CTL0 & RCU_CTL0_HXTALSTB)) {
+ return;
+ }
+
+ /* HXTAL is stable */
+ /* AHB = SYSCLK */
+ RCU_CFG0 |= RCU_AHB_CKSYS_DIV1;
+ /* APB2 = AHB */
+ RCU_CFG0 |= RCU_APB2_CKAHB_DIV1;
+ /* APB1 = AHB */
+ RCU_CFG0 |= RCU_APB1_CKAHB_DIV1;
+
+ /* select HXTAL as system clock */
+ RCU_CFG0 &= ~RCU_CFG0_SCS;
+ RCU_CFG0 |= RCU_CKSYSSRC_HXTAL;
+
+ /* wait until HXTAL is selected as system clock */
+ while(0U == (RCU_CFG0 & RCU_SCSS_HXTAL)) {
+ }
+}
+
+#elif defined (__SYSTEM_CLOCK_72M_PLL_HXTAL)
+/*!
+ \brief configure the system clock to 72M by PLL which selects HXTAL as its clock source
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+static void system_clock_72m_hxtal(void)
+{
+ uint32_t timeout = 0U;
+ uint32_t stab_flag = 0U;
+
+ /* enable HXTAL */
+ RCU_CTL0 |= RCU_CTL0_HXTALEN;
+
+ /* wait until HXTAL is stable or the startup time is longer than HXTAL_STARTUP_TIMEOUT */
+ do {
+ timeout++;
+ stab_flag = (RCU_CTL0 & RCU_CTL0_HXTALSTB);
+ } while((0U == stab_flag) && (HXTAL_STARTUP_TIMEOUT != timeout));
+ /* if fail */
+ if(0U == (RCU_CTL0 & RCU_CTL0_HXTALSTB)) {
+ return;
+ }
+ /* HXTAL is stable */
+ /* AHB = SYSCLK */
+ RCU_CFG0 |= RCU_AHB_CKSYS_DIV1;
+ /* APB2 = AHB/2 */
+ RCU_CFG0 |= RCU_APB2_CKAHB_DIV2;
+ /* APB1 = AHB/2 */
+ RCU_CFG0 |= RCU_APB1_CKAHB_DIV2;
+
+ /* PLL = HXTAL * 9 = 72 MHz */
+ RCU_CFG0 &= ~(RCU_CFG0_PLLSEL | RCU_CFG0_PLLMF | RCU_CFG0_PLLMF4 | RCU_CFG0_PLLPREDV);
+ RCU_CFG1 &= ~(RCU_CFG1_PLLPRESEL | RCU_CFG1_PLLMF5 | RCU_CFG1_PREDV);
+ RCU_CFG0 |= (RCU_PLLSRC_HXTAL_IRC48M | (RCU_PLL_MUL9 & (~RCU_CFG1_PLLMF5)));
+ RCU_CFG1 |= (RCU_PLLPRESEL_HXTAL);
+ RCU_CFG1 |= (RCU_PLL_MUL9 & RCU_CFG1_PLLMF5);
+ /* enable PLL */
+ RCU_CTL0 |= RCU_CTL0_PLLEN;
+
+ /* wait until PLL is stable */
+ while(0U == (RCU_CTL0 & RCU_CTL0_PLLSTB)) {
+ }
+
+ /* select PLL as system clock */
+ RCU_CFG0 &= ~RCU_CFG0_SCS;
+ RCU_CFG0 |= RCU_CKSYSSRC_PLL;
+
+ /* wait until PLL is selected as system clock */
+ while(0U == (RCU_CFG0 & RCU_SCSS_PLL)) {
+ }
+}
+
+
+#elif defined (__SYSTEM_CLOCK_72M_PLL_IRC8M_DIV2)
+/*!
+ \brief configure the system clock to 72M by PLL which selects IRC8M/2 as its clock source
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+static void system_clock_72m_irc8m(void)
+{
+ /* AHB = SYSCLK */
+ RCU_CFG0 |= RCU_AHB_CKSYS_DIV1;
+ /* APB2 = AHB/2 */
+ RCU_CFG0 |= RCU_APB2_CKAHB_DIV2;
+ /* APB1 = AHB/2 */
+ RCU_CFG0 |= RCU_APB1_CKAHB_DIV2;
+ /* PLL = (IRC8M/2) * 18 = 72 MHz */
+ RCU_CFG0 &= ~(RCU_CFG0_PLLSEL | RCU_CFG0_PLLMF | RCU_CFG0_PLLMF4 | RCU_CFG0_PLLPREDV);
+ RCU_CFG1 &= ~(RCU_CFG1_PLLPRESEL | RCU_CFG1_PLLMF5 | RCU_CFG1_PREDV);
+ RCU_CFG0 |= (RCU_PLLSRC_IRC8M_DIV2 | (RCU_PLL_MUL18 & (~RCU_CFG1_PLLMF5)));
+ RCU_CFG1 |= (RCU_PLL_MUL18 & RCU_CFG1_PLLMF5);
+ /* enable PLL */
+ RCU_CTL0 |= RCU_CTL0_PLLEN;
+
+ /* wait until PLL is stable */
+ while(0U == (RCU_CTL0 & RCU_CTL0_PLLSTB)) {
+ }
+
+ /* select PLL as system clock */
+ RCU_CFG0 &= ~RCU_CFG0_SCS;
+ RCU_CFG0 |= RCU_CKSYSSRC_PLL;
+
+ /* wait until PLL is selected as system clock */
+ while(0U == (RCU_CFG0 & RCU_SCSS_PLL)) {
+ }
+}
+
+#elif defined (__SYSTEM_CLOCK_72M_PLL_IRC48M_DIV2)
+/*!
+ \brief configure the system clock to 72M by PLL which selects IRC48M/2 as its clock source
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+static void system_clock_72m_irc48m(void)
+{
+ /* enable IRC48M */
+ RCU_ADDCTL |= RCU_ADDCTL_IRC48MEN;
+
+ /* wait until IRC48M is stable*/
+ while(0U == (RCU_ADDCTL & RCU_ADDCTL_IRC48MSTB)) {
+ }
+ /* AHB = SYSCLK */
+ RCU_CFG0 |= RCU_AHB_CKSYS_DIV1;
+ /* APB2 = AHB/2 */
+ RCU_CFG0 |= RCU_APB2_CKAHB_DIV2;
+ /* APB1 = AHB/2 */
+ RCU_CFG0 |= RCU_APB1_CKAHB_DIV2;
+ /* PLL = (IRC48M/2) * 3 = 96 MHz */
+ RCU_CFG0 &= ~(RCU_CFG0_PLLSEL | RCU_CFG0_PLLMF | RCU_CFG0_PLLMF4 | RCU_CFG0_PLLPREDV);
+ RCU_CFG1 &= ~(RCU_CFG1_PLLPRESEL | RCU_CFG1_PLLMF5 | RCU_CFG1_PREDV);
+ RCU_CFG0 |= (RCU_PLLSRC_HXTAL_IRC48M | (RCU_PLL_MUL3 & (~RCU_CFG1_PLLMF5)));
+ RCU_CFG1 |= (RCU_PLLPRESEL_IRC48M | RCU_PLL_PREDV2);
+ RCU_CFG1 |= (RCU_PLL_MUL3 & RCU_CFG1_PLLMF5);
+ /* enable PLL */
+ RCU_CTL0 |= RCU_CTL0_PLLEN;
+
+ /* wait until PLL is stable */
+ while(0U == (RCU_CTL0 & RCU_CTL0_PLLSTB)) {
+ }
+
+ /* select PLL as system clock */
+ RCU_CFG0 &= ~RCU_CFG0_SCS;
+ RCU_CFG0 |= RCU_CKSYSSRC_PLL;
+
+ /* wait until PLL is selected as system clock */
+ while(0U == (RCU_CFG0 & RCU_SCSS_PLL)) {
+ }
+}
+
+#elif defined (__SYSTEM_CLOCK_84M_PLL_HXTAL)
+/*!
+ \brief configure the system clock to 84M by PLL which selects HXTAL as its clock source
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+static void system_clock_84m_hxtal(void)
+{
+ uint32_t timeout = 0U;
+ uint32_t stab_flag = 0U;
+ /* enable HXTAL */
+ RCU_CTL0 |= RCU_CTL0_HXTALEN;
+
+ /* wait until HXTAL is stable or the startup time is longer than HXTAL_STARTUP_TIMEOUT */
+ do {
+ timeout++;
+ stab_flag = (RCU_CTL0 & RCU_CTL0_HXTALSTB);
+ } while((0U == stab_flag) && (HXTAL_STARTUP_TIMEOUT != timeout));
+ /* if fail */
+ if(0U == (RCU_CTL0 & RCU_CTL0_HXTALSTB)) {
+ return;
+ }
+ /* HXTAL is stable */
+ /* AHB = SYSCLK */
+ RCU_CFG0 |= RCU_AHB_CKSYS_DIV1;
+ /* APB2 = AHB/2 */
+ RCU_CFG0 |= RCU_APB2_CKAHB_DIV2;
+ /* APB1 = AHB/2 */
+ RCU_CFG0 |= RCU_APB1_CKAHB_DIV2;
+
+ /* PLL = HXTAL /2 * 21 = 84 MHz */
+ RCU_CFG0 &= ~(RCU_CFG0_PLLSEL | RCU_CFG0_PLLMF | RCU_CFG0_PLLMF4 | RCU_CFG0_PLLPREDV);
+ RCU_CFG1 &= ~(RCU_CFG1_PLLPRESEL | RCU_CFG1_PLLMF5 | RCU_CFG1_PREDV);
+ RCU_CFG0 |= (RCU_PLLSRC_HXTAL_IRC48M | (RCU_PLL_MUL21 & (~RCU_CFG1_PLLMF5)));
+ RCU_CFG1 |= (RCU_PLLPRESEL_HXTAL | RCU_PLL_PREDV2);
+ RCU_CFG1 |= (RCU_PLL_MUL21 & RCU_CFG1_PLLMF5);
+ /* enable PLL */
+ RCU_CTL0 |= RCU_CTL0_PLLEN;
+
+ /* wait until PLL is stable */
+ while(0U == (RCU_CTL0 & RCU_CTL0_PLLSTB)) {
+ }
+
+ /* select PLL as system clock */
+ RCU_CFG0 &= ~RCU_CFG0_SCS;
+ RCU_CFG0 |= RCU_CKSYSSRC_PLL;
+
+ /* wait until PLL is selected as system clock */
+ while(0U == (RCU_CFG0 & RCU_SCSS_PLL)) {
+ }
+}
+
+#elif defined (__SYSTEM_CLOCK_84M_PLL_IRC8M_DIV2)
+/*!
+ \brief configure the system clock to 84M by PLL which selects IRC8M/2 as its clock source
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+static void system_clock_84m_irc8m(void)
+{
+ /* AHB = SYSCLK */
+ RCU_CFG0 |= RCU_AHB_CKSYS_DIV1;
+ /* APB2 = AHB/2 */
+ RCU_CFG0 |= RCU_APB2_CKAHB_DIV2;
+ /* APB1 = AHB/2 */
+ RCU_CFG0 |= RCU_APB1_CKAHB_DIV2;
+ /* PLL = (IRC8M/2) * 21 = 84 MHz */
+ RCU_CFG0 &= ~(RCU_CFG0_PLLSEL | RCU_CFG0_PLLMF | RCU_CFG0_PLLMF4 | RCU_CFG0_PLLPREDV);
+ RCU_CFG1 &= ~(RCU_CFG1_PLLPRESEL | RCU_CFG1_PLLMF5 | RCU_CFG1_PREDV);
+ RCU_CFG0 |= (RCU_PLLSRC_IRC8M_DIV2 | (RCU_PLL_MUL21 & (~RCU_CFG1_PLLMF5)));
+ RCU_CFG1 |= (RCU_PLL_MUL21 & RCU_CFG1_PLLMF5);
+ /* enable PLL */
+ RCU_CTL0 |= RCU_CTL0_PLLEN;
+
+ /* wait until PLL is stable */
+ while(0U == (RCU_CTL0 & RCU_CTL0_PLLSTB)) {
+ }
+
+ /* select PLL as system clock */
+ RCU_CFG0 &= ~RCU_CFG0_SCS;
+ RCU_CFG0 |= RCU_CKSYSSRC_PLL;
+
+ /* wait until PLL is selected as system clock */
+ while(0U == (RCU_CFG0 & RCU_SCSS_PLL)) {
+ }
+}
+
+#elif defined (__SYSTEM_CLOCK_96M_PLL_HXTAL)
+/*!
+ \brief configure the system clock to 96M by PLL which selects HXTAL as its clock source
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+static void system_clock_96m_hxtal(void)
+{
+ uint32_t timeout = 0U;
+ uint32_t stab_flag = 0U;
+ /* enable HXTAL */
+ RCU_CTL0 |= RCU_CTL0_HXTALEN;
+
+ /* wait until HXTAL is stable or the startup time is longer than HXTAL_STARTUP_TIMEOUT */
+ do {
+ timeout++;
+ stab_flag = (RCU_CTL0 & RCU_CTL0_HXTALSTB);
+ } while((0U == stab_flag) && (HXTAL_STARTUP_TIMEOUT != timeout));
+ /* if fail */
+ if(0U == (RCU_CTL0 & RCU_CTL0_HXTALSTB)) {
+ return;
+ }
+ /* HXTAL is stable */
+ /* AHB = SYSCLK */
+ RCU_CFG0 |= RCU_AHB_CKSYS_DIV1;
+ /* APB2 = AHB/2 */
+ RCU_CFG0 |= RCU_APB2_CKAHB_DIV2;
+ /* APB1 = AHB/2 */
+ RCU_CFG0 |= RCU_APB1_CKAHB_DIV2;
+
+ /* PLL = HXTAL /2 * 24 = 96 MHz */
+ RCU_CFG0 &= ~(RCU_CFG0_PLLSEL | RCU_CFG0_PLLMF | RCU_CFG0_PLLMF4 | RCU_CFG0_PLLPREDV);
+ RCU_CFG1 &= ~(RCU_CFG1_PLLPRESEL | RCU_CFG1_PLLMF5 | RCU_CFG1_PREDV);
+ RCU_CFG0 |= (RCU_PLLSRC_HXTAL_IRC48M | (RCU_PLL_MUL24 & (~RCU_CFG1_PLLMF5)));
+ RCU_CFG1 |= (RCU_PLLPRESEL_HXTAL | RCU_PLL_PREDV2);
+ RCU_CFG1 |= (RCU_PLL_MUL24 & RCU_CFG1_PLLMF5);
+
+ /* enable PLL */
+ RCU_CTL0 |= RCU_CTL0_PLLEN;
+
+ /* wait until PLL is stable */
+ while(0U == (RCU_CTL0 & RCU_CTL0_PLLSTB)) {
+ }
+
+ /* select PLL as system clock */
+ RCU_CFG0 &= ~RCU_CFG0_SCS;
+ RCU_CFG0 |= RCU_CKSYSSRC_PLL;
+
+ /* wait until PLL is selected as system clock */
+ while(0U == (RCU_CFG0 & RCU_SCSS_PLL)) {
+ }
+}
+
+#elif defined (__SYSTEM_CLOCK_96M_PLL_IRC8M_DIV2)
+/*!
+ \brief configure the system clock to 96M by PLL which selects IRC8M/2 as its clock source
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+static void system_clock_96m_irc8m(void)
+{
+ /* AHB = SYSCLK */
+ RCU_CFG0 |= RCU_AHB_CKSYS_DIV1;
+ /* APB2 = AHB/2 */
+ RCU_CFG0 |= RCU_APB2_CKAHB_DIV2;
+ /* APB1 = AHB/2 */
+ RCU_CFG0 |= RCU_APB1_CKAHB_DIV2;
+ /* PLL = (IRC8M/2) * 24 = 96 MHz */
+ RCU_CFG0 &= ~(RCU_CFG0_PLLSEL | RCU_CFG0_PLLMF | RCU_CFG0_PLLMF4 | RCU_CFG0_PLLPREDV);
+ RCU_CFG1 &= ~(RCU_CFG1_PLLPRESEL | RCU_CFG1_PLLMF5 | RCU_CFG1_PREDV);
+ RCU_CFG0 |= (RCU_PLLSRC_IRC8M_DIV2 | (RCU_PLL_MUL24 & (~RCU_CFG1_PLLMF5)));
+ RCU_CFG1 |= (RCU_PLL_MUL24 & RCU_CFG1_PLLMF5);
+
+ /* enable PLL */
+ RCU_CTL0 |= RCU_CTL0_PLLEN;
+
+ /* wait until PLL is stable */
+ while(0U == (RCU_CTL0 & RCU_CTL0_PLLSTB)) {
+ }
+
+ /* select PLL as system clock */
+ RCU_CFG0 &= ~RCU_CFG0_SCS;
+ RCU_CFG0 |= RCU_CKSYSSRC_PLL;
+
+ /* wait until PLL is selected as system clock */
+ while(0U == (RCU_CFG0 & RCU_SCSS_PLL)) {
+ }
+}
+
+#elif defined (__SYSTEM_CLOCK_96M_PLL_IRC48M_DIV2)
+/*!
+ \brief configure the system clock to 96M by PLL which selects IRC48M/2 as its clock source
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+static void system_clock_96m_irc48m(void)
+{
+ /* enable IRC48M */
+ RCU_ADDCTL |= RCU_ADDCTL_IRC48MEN;
+
+ /* wait until IRC48M is stable*/
+ while(0U == (RCU_ADDCTL & RCU_ADDCTL_IRC48MSTB)) {
+ }
+ /* AHB = SYSCLK */
+ RCU_CFG0 |= RCU_AHB_CKSYS_DIV1;
+ /* APB2 = AHB/2 */
+ RCU_CFG0 |= RCU_APB2_CKAHB_DIV2;
+ /* APB1 = AHB/2 */
+ RCU_CFG0 |= RCU_APB1_CKAHB_DIV2;
+ /* PLL = (IRC48M/2) * 4 = 96 MHz */
+ RCU_CFG0 &= ~(RCU_CFG0_PLLSEL | RCU_CFG0_PLLMF | RCU_CFG0_PLLMF4 | RCU_CFG0_PLLPREDV);
+ RCU_CFG1 &= ~(RCU_CFG1_PLLPRESEL | RCU_CFG1_PLLMF5 | RCU_CFG1_PREDV);
+ RCU_CFG0 |= (RCU_PLLSRC_HXTAL_IRC48M | (RCU_PLL_MUL4 & (~RCU_CFG1_PLLMF5)));
+ RCU_CFG1 |= (RCU_PLLPRESEL_IRC48M | RCU_PLL_PREDV2);
+ RCU_CFG1 |= (RCU_PLL_MUL4 & RCU_CFG1_PLLMF5);
+
+ /* enable PLL */
+ RCU_CTL0 |= RCU_CTL0_PLLEN;
+
+ /* wait until PLL is stable */
+ while(0U == (RCU_CTL0 & RCU_CTL0_PLLSTB)) {
+ }
+
+ /* select PLL as system clock */
+ RCU_CFG0 &= ~RCU_CFG0_SCS;
+ RCU_CFG0 |= RCU_CKSYSSRC_PLL;
+
+ /* wait until PLL is selected as system clock */
+ while(0U == (RCU_CFG0 & RCU_SCSS_PLL)) {
+ }
+}
+
+#elif defined (__SYSTEM_CLOCK_108M_PLL_HXTAL)
+/*!
+ \brief configure the system clock to 84M by PLL which selects HXTAL as its clock source
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+static void system_clock_108m_hxtal(void)
+{
+ uint32_t timeout = 0U;
+ uint32_t stab_flag = 0U;
+
+ /* enable HXTAL */
+ RCU_CTL0 |= RCU_CTL0_HXTALEN;
+
+ /* wait until HXTAL is stable or the startup time is longer than HXTAL_STARTUP_TIMEOUT */
+ do {
+ timeout++;
+ stab_flag = (RCU_CTL0 & RCU_CTL0_HXTALSTB);
+ } while((0U == stab_flag) && (HXTAL_STARTUP_TIMEOUT != timeout));
+ /* if fail */
+ if(0U == (RCU_CTL0 & RCU_CTL0_HXTALSTB)) {
+ return;
+ }
+ /* HXTAL is stable */
+ /* AHB = SYSCLK */
+ RCU_CFG0 |= RCU_AHB_CKSYS_DIV1;
+ /* APB2 = AHB/2 */
+ RCU_CFG0 |= RCU_APB2_CKAHB_DIV2;
+ /* APB1 = AHB/2 */
+ RCU_CFG0 |= RCU_APB1_CKAHB_DIV2;
+
+ /* PLL = HXTAL /2 * 27 = 108 MHz */
+ RCU_CFG0 &= ~(RCU_CFG0_PLLSEL | RCU_CFG0_PLLMF | RCU_CFG0_PLLMF4 | RCU_CFG0_PLLPREDV);
+ RCU_CFG1 &= ~(RCU_CFG1_PLLPRESEL | RCU_CFG1_PLLMF5 | RCU_CFG1_PREDV);
+ RCU_CFG0 |= (RCU_PLLSRC_HXTAL_IRC48M | (RCU_PLL_MUL27 & (~RCU_CFG1_PLLMF5)));
+ RCU_CFG1 |= (RCU_PLLPRESEL_HXTAL | RCU_PLL_PREDV2);
+ RCU_CFG1 |= (RCU_PLL_MUL27 & RCU_CFG1_PLLMF5);
+
+ /* enable PLL */
+ RCU_CTL0 |= RCU_CTL0_PLLEN;
+
+ /* wait until PLL is stable */
+ while(0U == (RCU_CTL0 & RCU_CTL0_PLLSTB)) {
+ }
+
+ /* select PLL as system clock */
+ RCU_CFG0 &= ~RCU_CFG0_SCS;
+ RCU_CFG0 |= RCU_CKSYSSRC_PLL;
+
+ /* wait until PLL is selected as system clock */
+ while(0U == (RCU_CFG0 & RCU_SCSS_PLL)) {
+ }
+}
+
+#elif defined (__SYSTEM_CLOCK_108M_PLL_IRC8M_DIV2)
+/*!
+ \brief configure the system clock to 108M by PLL which selects IRC8M/2 as its clock source
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+static void system_clock_108m_irc8m(void)
+{
+ /* AHB = SYSCLK */
+ RCU_CFG0 |= RCU_AHB_CKSYS_DIV1;
+ /* APB2 = AHB/2 */
+ RCU_CFG0 |= RCU_APB2_CKAHB_DIV2;
+ /* APB1 = AHB/2 */
+ RCU_CFG0 |= RCU_APB1_CKAHB_DIV2;
+ /* PLL = (IRC8M/2) * 27 = 108 MHz */
+ RCU_CFG0 &= ~(RCU_CFG0_PLLSEL | RCU_CFG0_PLLMF | RCU_CFG0_PLLMF4 | RCU_CFG0_PLLPREDV);
+ RCU_CFG1 &= ~(RCU_CFG1_PLLPRESEL | RCU_CFG1_PLLMF5 | RCU_CFG1_PREDV);
+ RCU_CFG0 |= (RCU_PLLSRC_IRC8M_DIV2 | (RCU_PLL_MUL27 & (~RCU_CFG1_PLLMF5)));
+ RCU_CFG1 |= (RCU_PLL_MUL27 & RCU_CFG1_PLLMF5);
+
+ /* enable PLL */
+ RCU_CTL0 |= RCU_CTL0_PLLEN;
+
+ /* wait until PLL is stable */
+ while(0U == (RCU_CTL0 & RCU_CTL0_PLLSTB)) {
+ }
+
+ /* select PLL as system clock */
+ RCU_CFG0 &= ~RCU_CFG0_SCS;
+ RCU_CFG0 |= RCU_CKSYSSRC_PLL;
+
+ /* wait until PLL is selected as system clock */
+ while(0U == (RCU_CFG0 & RCU_SCSS_PLL)) {
+ }
+}
+
+#else
+/*!
+ \brief configure the system clock to 8M by IRC8M
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+static void system_clock_8m_irc8m(void)
+{
+ /* AHB = SYSCLK */
+ RCU_CFG0 |= RCU_AHB_CKSYS_DIV1;
+ /* APB2 = AHB */
+ RCU_CFG0 |= RCU_APB2_CKAHB_DIV1;
+ /* APB1 = AHB */
+ RCU_CFG0 |= RCU_APB1_CKAHB_DIV1;
+
+ /* select IRC8M as system clock */
+ RCU_CFG0 &= ~RCU_CFG0_SCS;
+ RCU_CFG0 |= RCU_CKSYSSRC_IRC8M;
+
+ /* wait until IRC8M is selected as system clock */
+ while(0U != (RCU_CFG0 & RCU_SCSS_IRC8M)) {
+ }
+}
+#endif /* __SYSTEM_CLOCK_8M_HXTAL */
+
+/*!
+ \brief update the SystemCoreClock with current core clock retrieved from cpu registers
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void SystemCoreClockUpdate(void)
+{
+ uint32_t sws = 0U;
+ uint32_t pllmf = 0U, pllmf4 = 0U, pllmf5 = 0U, pllsel = 0U, pllpresel = 0U, prediv = 0U, idx = 0U, clk_exp = 0U;
+ /* exponent of AHB clock divider */
+ const uint8_t ahb_exp[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
+
+ sws = GET_BITS(RCU_CFG0, 2, 3);
+ switch(sws) {
+ /* IRC8M is selected as CK_SYS */
+ case SEL_IRC8M:
+ SystemCoreClock = IRC8M_VALUE;
+ break;
+ /* HXTAL is selected as CK_SYS */
+ case SEL_HXTAL:
+ SystemCoreClock = HXTAL_VALUE;
+ break;
+ /* PLL is selected as CK_SYS */
+ case SEL_PLL:
+ /* get the value of PLLMF[3:0] */
+ pllmf = GET_BITS(RCU_CFG0, 18, 21);
+ pllmf4 = GET_BITS(RCU_CFG0, 27, 27);
+ pllmf5 = GET_BITS(RCU_CFG1, 31, 31);
+ /* high 16 bits */
+ if((0U == pllmf4) && (0U == pllmf5)) {
+ pllmf += 2U;
+ }
+ if((1U == pllmf4) && (0U == pllmf5)) {
+ pllmf += 17U;
+ }
+ if((0U == pllmf4) && (1U == pllmf5)) {
+ pllmf += 33U;
+ }
+ if((1U == pllmf4) && (1U == pllmf5)) {
+ pllmf += 49U;
+ }
+ /* PLL clock source selection, HXTAL or IRC8M/2 */
+ pllsel = GET_BITS(RCU_CFG0, 16, 16);
+ if(0U != pllsel) {
+ prediv = (GET_BITS(RCU_CFG1, 0, 3) + 1U);
+ if(0U == pllpresel) {
+ SystemCoreClock = (HXTAL_VALUE / prediv) * pllmf;
+ } else {
+ SystemCoreClock = (IRC48M_VALUE / prediv) * pllmf;
+ }
+ } else {
+ SystemCoreClock = (IRC8M_VALUE >> 1) * pllmf;
+ }
+ break;
+ /* IRC8M is selected as CK_SYS */
+ default:
+ SystemCoreClock = IRC8M_VALUE;
+ break;
+ }
+ /* calculate AHB clock frequency */
+ idx = GET_BITS(RCU_CFG0, 4, 7);
+ clk_exp = ahb_exp[idx];
+ SystemCoreClock >>= clk_exp;
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/CMSIS/core_cm4.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/CMSIS/core_cm4.h
new file mode 100644
index 00000000..ad5789d4
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/CMSIS/core_cm4.h
@@ -0,0 +1,1778 @@
+/**************************************************************************//**
+ * @file core_cm4.h
+ * @brief CMSIS Cortex-M4 Core Peripheral Access Layer Header File
+ * @version V3.30
+ * @date 17. February 2014
+ *
+ * @note
+ *
+ ******************************************************************************/
+/* Copyright (c) 2009 - 2014 ARM LIMITED
+
+ All rights reserved.
+ Redistribution and use in source and binary forms, with or without
+ modification, are permitted provided that the following conditions are met:
+ - Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ - 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.
+ - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
+ ---------------------------------------------------------------------------*/
+
+
+#if defined ( __ICCARM__ )
+#pragma system_include /* treat file as system include file for MISRA check */
+#endif
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#ifndef __CORE_CM4_H_GENERIC
+#define __CORE_CM4_H_GENERIC
+
+/** \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions
+ CMSIS violates the following MISRA-C:2004 rules:
+
+ \li Required Rule 8.5, object/function definition in header file.
+ Function definitions in header files are used to allow 'inlining'.
+
+ \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
+ Unions are used for effective representation of core registers.
+
+ \li Advisory Rule 19.7, Function-like macro defined.
+ Function-like macros are used to allow more efficient code.
+ */
+
+
+/*******************************************************************************
+ * CMSIS definitions
+ ******************************************************************************/
+/** \ingroup Cortex_M4
+ @{
+ */
+
+/* CMSIS CM4 definitions */
+#define __CM4_CMSIS_VERSION_MAIN (0x03) /*!< [31:16] CMSIS HAL main version */
+#define __CM4_CMSIS_VERSION_SUB (0x20) /*!< [15:0] CMSIS HAL sub version */
+#define __CM4_CMSIS_VERSION ((__CM4_CMSIS_VERSION_MAIN << 16) | \
+ __CM4_CMSIS_VERSION_SUB ) /*!< CMSIS HAL version number */
+
+#define __CORTEX_M (0x04) /*!< Cortex-M Core */
+
+
+#if defined ( __CC_ARM )
+#define __ASM __asm /*!< asm keyword for ARM Compiler */
+#define __INLINE __inline /*!< inline keyword for ARM Compiler */
+#define __STATIC_INLINE static __inline
+
+#elif defined ( __GNUC__ )
+#define __ASM __asm /*!< asm keyword for GNU Compiler */
+#define __INLINE inline /*!< inline keyword for GNU Compiler */
+#define __STATIC_INLINE static inline
+
+#elif defined ( __ICCARM__ )
+#define __ASM __asm /*!< asm keyword for IAR Compiler */
+#define __INLINE inline /*!< inline keyword for IAR Compiler. Only available in High optimization mode! */
+#define __STATIC_INLINE static inline
+
+#elif defined ( __TMS470__ )
+#define __ASM __asm /*!< asm keyword for TI CCS Compiler */
+#define __STATIC_INLINE static inline
+
+#elif defined ( __TASKING__ )
+#define __ASM __asm /*!< asm keyword for TASKING Compiler */
+#define __INLINE inline /*!< inline keyword for TASKING Compiler */
+#define __STATIC_INLINE static inline
+
+#elif defined ( __CSMC__ ) /* Cosmic */
+#define __packed
+#define __ASM _asm /*!< asm keyword for COSMIC Compiler */
+#define __INLINE inline /*use -pc99 on compile line !< inline keyword for COSMIC Compiler */
+#define __STATIC_INLINE static inline
+
+#endif
+
+/** __FPU_USED indicates whether an FPU is used or not. For this, __FPU_PRESENT has to be checked prior to making use of FPU specific registers and functions.
+*/
+#if defined ( __CC_ARM )
+#if defined __TARGET_FPU_VFP
+#if (__FPU_PRESENT == 1)
+#define __FPU_USED 1
+#else
+#warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+#define __FPU_USED 0
+#endif
+#else
+#define __FPU_USED 0
+#endif
+
+#elif defined ( __GNUC__ )
+#if defined (__VFP_FP__) && !defined(__SOFTFP__)
+#if (__FPU_PRESENT == 1)
+#define __FPU_USED 1
+#else
+#warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+#define __FPU_USED 0
+#endif
+#else
+#define __FPU_USED 0
+#endif
+
+#elif defined ( __ICCARM__ )
+#if defined __ARMVFP__
+#if (__FPU_PRESENT == 1)
+#define __FPU_USED 1
+#else
+#warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+#define __FPU_USED 0
+#endif
+#else
+#define __FPU_USED 0
+#endif
+
+#elif defined ( __TMS470__ )
+#if defined __TI_VFP_SUPPORT__
+#if (__FPU_PRESENT == 1)
+#define __FPU_USED 1
+#else
+#warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+#define __FPU_USED 0
+#endif
+#else
+#define __FPU_USED 0
+#endif
+
+#elif defined ( __TASKING__ )
+#if defined __FPU_VFP__
+#if (__FPU_PRESENT == 1)
+#define __FPU_USED 1
+#else
+#error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+#define __FPU_USED 0
+#endif
+#else
+#define __FPU_USED 0
+#endif
+
+#elif defined ( __CSMC__ ) /* Cosmic */
+#if ( __CSMC__ & 0x400) // FPU present for parser
+#if (__FPU_PRESENT == 1)
+#define __FPU_USED 1
+#else
+#error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+#define __FPU_USED 0
+#endif
+#else
+#define __FPU_USED 0
+#endif
+#endif
+
+#include /* standard types definitions */
+#include /* Core Instruction Access */
+#include /* Core Function Access */
+#include /* Compiler specific SIMD Intrinsics */
+
+#endif /* __CORE_CM4_H_GENERIC */
+
+#ifndef __CMSIS_GENERIC
+
+#ifndef __CORE_CM4_H_DEPENDANT
+#define __CORE_CM4_H_DEPENDANT
+
+/* check device defines and use defaults */
+#if defined __CHECK_DEVICE_DEFINES
+#ifndef __CM4_REV
+#define __CM4_REV 0x0000
+#warning "__CM4_REV not defined in device header file; using default!"
+#endif
+
+#ifndef __FPU_PRESENT
+#define __FPU_PRESENT 0
+#warning "__FPU_PRESENT not defined in device header file; using default!"
+#endif
+
+#ifndef __MPU_PRESENT
+#define __MPU_PRESENT 0
+#warning "__MPU_PRESENT not defined in device header file; using default!"
+#endif
+
+#ifndef __NVIC_PRIO_BITS
+#define __NVIC_PRIO_BITS 4
+#warning "__NVIC_PRIO_BITS not defined in device header file; using default!"
+#endif
+
+#ifndef __Vendor_SysTickConfig
+#define __Vendor_SysTickConfig 0
+#warning "__Vendor_SysTickConfig not defined in device header file; using default!"
+#endif
+#endif
+
+/* IO definitions (access restrictions to peripheral registers) */
+/**
+ \defgroup CMSIS_glob_defs CMSIS Global Defines
+
+ IO Type Qualifiers are used
+ \li to specify the access to peripheral variables.
+ \li for automatic generation of peripheral register debug information.
+*/
+#ifdef __cplusplus
+#define __I volatile /*!< Defines 'read only' permissions */
+#else
+#define __I volatile const /*!< Defines 'read only' permissions */
+#endif
+#define __O volatile /*!< Defines 'write only' permissions */
+#define __IO volatile /*!< Defines 'read / write' permissions */
+
+/*@} end of group Cortex_M4 */
+
+
+
+/*******************************************************************************
+ * Register Abstraction
+ Core Register contain:
+ - Core Register
+ - Core NVIC Register
+ - Core SCB Register
+ - Core SysTick Register
+ - Core Debug Register
+ - Core MPU Register
+ - Core FPU Register
+ ******************************************************************************/
+/** \defgroup CMSIS_core_register Defines and Type Definitions
+ \brief Type definitions and defines for Cortex-M processor based devices.
+*/
+
+/** \ingroup CMSIS_core_register
+ \defgroup CMSIS_CORE Status and Control Registers
+ \brief Core Register type definitions.
+ @{
+ */
+
+/** \brief Union type to access the Application Program Status Register (APSR).
+ */
+typedef union {
+ struct {
+#if (__CORTEX_M != 0x04)
+ uint32_t _reserved0: 27; /*!< bit: 0..26 Reserved */
+#else
+ uint32_t _reserved0: 16; /*!< bit: 0..15 Reserved */
+ uint32_t GE: 4; /*!< bit: 16..19 Greater than or Equal flags */
+ uint32_t _reserved1: 7; /*!< bit: 20..26 Reserved */
+#endif
+ uint32_t Q: 1; /*!< bit: 27 Saturation condition flag */
+ uint32_t V: 1; /*!< bit: 28 Overflow condition code flag */
+ uint32_t C: 1; /*!< bit: 29 Carry condition code flag */
+ uint32_t Z: 1; /*!< bit: 30 Zero condition code flag */
+ uint32_t N: 1; /*!< bit: 31 Negative condition code flag */
+ } b; /*!< Structure used for bit access */
+ uint32_t w; /*!< Type used for word access */
+} APSR_Type;
+
+
+/** \brief Union type to access the Interrupt Program Status Register (IPSR).
+ */
+typedef union {
+ struct {
+ uint32_t ISR: 9; /*!< bit: 0.. 8 Exception number */
+ uint32_t _reserved0: 23; /*!< bit: 9..31 Reserved */
+ } b; /*!< Structure used for bit access */
+ uint32_t w; /*!< Type used for word access */
+} IPSR_Type;
+
+
+/** \brief Union type to access the Special-Purpose Program Status Registers (xPSR).
+ */
+typedef union {
+ struct {
+ uint32_t ISR: 9; /*!< bit: 0.. 8 Exception number */
+#if (__CORTEX_M != 0x04)
+ uint32_t _reserved0: 15; /*!< bit: 9..23 Reserved */
+#else
+ uint32_t _reserved0: 7; /*!< bit: 9..15 Reserved */
+ uint32_t GE: 4; /*!< bit: 16..19 Greater than or Equal flags */
+ uint32_t _reserved1: 4; /*!< bit: 20..23 Reserved */
+#endif
+ uint32_t T: 1; /*!< bit: 24 Thumb bit (read 0) */
+ uint32_t IT: 2; /*!< bit: 25..26 saved IT state (read 0) */
+ uint32_t Q: 1; /*!< bit: 27 Saturation condition flag */
+ uint32_t V: 1; /*!< bit: 28 Overflow condition code flag */
+ uint32_t C: 1; /*!< bit: 29 Carry condition code flag */
+ uint32_t Z: 1; /*!< bit: 30 Zero condition code flag */
+ uint32_t N: 1; /*!< bit: 31 Negative condition code flag */
+ } b; /*!< Structure used for bit access */
+ uint32_t w; /*!< Type used for word access */
+} xPSR_Type;
+
+
+/** \brief Union type to access the Control Registers (CONTROL).
+ */
+typedef union {
+ struct {
+ uint32_t nPRIV: 1; /*!< bit: 0 Execution privilege in Thread mode */
+ uint32_t SPSEL: 1; /*!< bit: 1 Stack to be used */
+ uint32_t FPCA: 1; /*!< bit: 2 FP extension active flag */
+ uint32_t _reserved0: 29; /*!< bit: 3..31 Reserved */
+ } b; /*!< Structure used for bit access */
+ uint32_t w; /*!< Type used for word access */
+} CONTROL_Type;
+
+/*@} end of group CMSIS_CORE */
+
+
+/** \ingroup CMSIS_core_register
+ \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC)
+ \brief Type definitions for the NVIC Registers
+ @{
+ */
+
+/** \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC).
+ */
+typedef struct {
+ __IO uint32_t ISER[8]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */
+ uint32_t RESERVED0[24];
+ __IO uint32_t ICER[8]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */
+ uint32_t RSERVED1[24];
+ __IO uint32_t ISPR[8]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */
+ uint32_t RESERVED2[24];
+ __IO uint32_t ICPR[8]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */
+ uint32_t RESERVED3[24];
+ __IO uint32_t IABR[8]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */
+ uint32_t RESERVED4[56];
+ __IO uint8_t IP[240]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */
+ uint32_t RESERVED5[644];
+ __O uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */
+} NVIC_Type;
+
+/* Software Triggered Interrupt Register Definitions */
+#define NVIC_STIR_INTID_Pos 0 /*!< STIR: INTLINESNUM Position */
+#define NVIC_STIR_INTID_Msk (0x1FFUL << NVIC_STIR_INTID_Pos) /*!< STIR: INTLINESNUM Mask */
+
+/*@} end of group CMSIS_NVIC */
+
+
+/** \ingroup CMSIS_core_register
+ \defgroup CMSIS_SCB System Control Block (SCB)
+ \brief Type definitions for the System Control Block Registers
+ @{
+ */
+
+/** \brief Structure type to access the System Control Block (SCB).
+ */
+typedef struct {
+ __I uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */
+ __IO uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */
+ __IO uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */
+ __IO uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */
+ __IO uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */
+ __IO uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */
+ __IO uint8_t SHP[12]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */
+ __IO uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */
+ __IO uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */
+ __IO uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */
+ __IO uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */
+ __IO uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */
+ __IO uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */
+ __IO uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */
+ __I uint32_t PFR[2]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */
+ __I uint32_t DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */
+ __I uint32_t ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */
+ __I uint32_t MMFR[4]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */
+ __I uint32_t ISAR[5]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */
+ uint32_t RESERVED0[5];
+ __IO uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */
+} SCB_Type;
+
+/* SCB CPUID Register Definitions */
+#define SCB_CPUID_IMPLEMENTER_Pos 24 /*!< SCB CPUID: IMPLEMENTER Position */
+#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */
+
+#define SCB_CPUID_VARIANT_Pos 20 /*!< SCB CPUID: VARIANT Position */
+#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */
+
+#define SCB_CPUID_ARCHITECTURE_Pos 16 /*!< SCB CPUID: ARCHITECTURE Position */
+#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */
+
+#define SCB_CPUID_PARTNO_Pos 4 /*!< SCB CPUID: PARTNO Position */
+#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */
+
+#define SCB_CPUID_REVISION_Pos 0 /*!< SCB CPUID: REVISION Position */
+#define SCB_CPUID_REVISION_Msk (0xFUL << SCB_CPUID_REVISION_Pos) /*!< SCB CPUID: REVISION Mask */
+
+/* SCB Interrupt Control State Register Definitions */
+#define SCB_ICSR_NMIPENDSET_Pos 31 /*!< SCB ICSR: NMIPENDSET Position */
+#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */
+
+#define SCB_ICSR_PENDSVSET_Pos 28 /*!< SCB ICSR: PENDSVSET Position */
+#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */
+
+#define SCB_ICSR_PENDSVCLR_Pos 27 /*!< SCB ICSR: PENDSVCLR Position */
+#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */
+
+#define SCB_ICSR_PENDSTSET_Pos 26 /*!< SCB ICSR: PENDSTSET Position */
+#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */
+
+#define SCB_ICSR_PENDSTCLR_Pos 25 /*!< SCB ICSR: PENDSTCLR Position */
+#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */
+
+#define SCB_ICSR_ISRPREEMPT_Pos 23 /*!< SCB ICSR: ISRPREEMPT Position */
+#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */
+
+#define SCB_ICSR_ISRPENDING_Pos 22 /*!< SCB ICSR: ISRPENDING Position */
+#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */
+
+#define SCB_ICSR_VECTPENDING_Pos 12 /*!< SCB ICSR: VECTPENDING Position */
+#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */
+
+#define SCB_ICSR_RETTOBASE_Pos 11 /*!< SCB ICSR: RETTOBASE Position */
+#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */
+
+#define SCB_ICSR_VECTACTIVE_Pos 0 /*!< SCB ICSR: VECTACTIVE Position */
+#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL << SCB_ICSR_VECTACTIVE_Pos) /*!< SCB ICSR: VECTACTIVE Mask */
+
+/* SCB Vector Table Offset Register Definitions */
+#define SCB_VTOR_TBLOFF_Pos 7 /*!< SCB VTOR: TBLOFF Position */
+#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */
+
+/* SCB Application Interrupt and Reset Control Register Definitions */
+#define SCB_AIRCR_VECTKEY_Pos 16 /*!< SCB AIRCR: VECTKEY Position */
+#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */
+
+#define SCB_AIRCR_VECTKEYSTAT_Pos 16 /*!< SCB AIRCR: VECTKEYSTAT Position */
+#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */
+
+#define SCB_AIRCR_ENDIANESS_Pos 15 /*!< SCB AIRCR: ENDIANESS Position */
+#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */
+
+#define SCB_AIRCR_PRIGROUP_Pos 8 /*!< SCB AIRCR: PRIGROUP Position */
+#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */
+
+#define SCB_AIRCR_SYSRESETREQ_Pos 2 /*!< SCB AIRCR: SYSRESETREQ Position */
+#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */
+
+#define SCB_AIRCR_VECTCLRACTIVE_Pos 1 /*!< SCB AIRCR: VECTCLRACTIVE Position */
+#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */
+
+#define SCB_AIRCR_VECTRESET_Pos 0 /*!< SCB AIRCR: VECTRESET Position */
+#define SCB_AIRCR_VECTRESET_Msk (1UL << SCB_AIRCR_VECTRESET_Pos) /*!< SCB AIRCR: VECTRESET Mask */
+
+/* SCB System Control Register Definitions */
+#define SCB_SCR_SEVONPEND_Pos 4 /*!< SCB SCR: SEVONPEND Position */
+#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */
+
+#define SCB_SCR_SLEEPDEEP_Pos 2 /*!< SCB SCR: SLEEPDEEP Position */
+#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */
+
+#define SCB_SCR_SLEEPONEXIT_Pos 1 /*!< SCB SCR: SLEEPONEXIT Position */
+#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */
+
+/* SCB Configuration Control Register Definitions */
+#define SCB_CCR_STKALIGN_Pos 9 /*!< SCB CCR: STKALIGN Position */
+#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */
+
+#define SCB_CCR_BFHFNMIGN_Pos 8 /*!< SCB CCR: BFHFNMIGN Position */
+#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */
+
+#define SCB_CCR_DIV_0_TRP_Pos 4 /*!< SCB CCR: DIV_0_TRP Position */
+#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */
+
+#define SCB_CCR_UNALIGN_TRP_Pos 3 /*!< SCB CCR: UNALIGN_TRP Position */
+#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */
+
+#define SCB_CCR_USERSETMPEND_Pos 1 /*!< SCB CCR: USERSETMPEND Position */
+#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */
+
+#define SCB_CCR_NONBASETHRDENA_Pos 0 /*!< SCB CCR: NONBASETHRDENA Position */
+#define SCB_CCR_NONBASETHRDENA_Msk (1UL << SCB_CCR_NONBASETHRDENA_Pos) /*!< SCB CCR: NONBASETHRDENA Mask */
+
+/* SCB System Handler Control and State Register Definitions */
+#define SCB_SHCSR_USGFAULTENA_Pos 18 /*!< SCB SHCSR: USGFAULTENA Position */
+#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */
+
+#define SCB_SHCSR_BUSFAULTENA_Pos 17 /*!< SCB SHCSR: BUSFAULTENA Position */
+#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */
+
+#define SCB_SHCSR_MEMFAULTENA_Pos 16 /*!< SCB SHCSR: MEMFAULTENA Position */
+#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */
+
+#define SCB_SHCSR_SVCALLPENDED_Pos 15 /*!< SCB SHCSR: SVCALLPENDED Position */
+#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */
+
+#define SCB_SHCSR_BUSFAULTPENDED_Pos 14 /*!< SCB SHCSR: BUSFAULTPENDED Position */
+#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */
+
+#define SCB_SHCSR_MEMFAULTPENDED_Pos 13 /*!< SCB SHCSR: MEMFAULTPENDED Position */
+#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */
+
+#define SCB_SHCSR_USGFAULTPENDED_Pos 12 /*!< SCB SHCSR: USGFAULTPENDED Position */
+#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */
+
+#define SCB_SHCSR_SYSTICKACT_Pos 11 /*!< SCB SHCSR: SYSTICKACT Position */
+#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */
+
+#define SCB_SHCSR_PENDSVACT_Pos 10 /*!< SCB SHCSR: PENDSVACT Position */
+#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */
+
+#define SCB_SHCSR_MONITORACT_Pos 8 /*!< SCB SHCSR: MONITORACT Position */
+#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */
+
+#define SCB_SHCSR_SVCALLACT_Pos 7 /*!< SCB SHCSR: SVCALLACT Position */
+#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */
+
+#define SCB_SHCSR_USGFAULTACT_Pos 3 /*!< SCB SHCSR: USGFAULTACT Position */
+#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */
+
+#define SCB_SHCSR_BUSFAULTACT_Pos 1 /*!< SCB SHCSR: BUSFAULTACT Position */
+#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */
+
+#define SCB_SHCSR_MEMFAULTACT_Pos 0 /*!< SCB SHCSR: MEMFAULTACT Position */
+#define SCB_SHCSR_MEMFAULTACT_Msk (1UL << SCB_SHCSR_MEMFAULTACT_Pos) /*!< SCB SHCSR: MEMFAULTACT Mask */
+
+/* SCB Configurable Fault Status Registers Definitions */
+#define SCB_CFSR_USGFAULTSR_Pos 16 /*!< SCB CFSR: Usage Fault Status Register Position */
+#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */
+
+#define SCB_CFSR_BUSFAULTSR_Pos 8 /*!< SCB CFSR: Bus Fault Status Register Position */
+#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */
+
+#define SCB_CFSR_MEMFAULTSR_Pos 0 /*!< SCB CFSR: Memory Manage Fault Status Register Position */
+#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL << SCB_CFSR_MEMFAULTSR_Pos) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */
+
+/* SCB Hard Fault Status Registers Definitions */
+#define SCB_HFSR_DEBUGEVT_Pos 31 /*!< SCB HFSR: DEBUGEVT Position */
+#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */
+
+#define SCB_HFSR_FORCED_Pos 30 /*!< SCB HFSR: FORCED Position */
+#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */
+
+#define SCB_HFSR_VECTTBL_Pos 1 /*!< SCB HFSR: VECTTBL Position */
+#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */
+
+/* SCB Debug Fault Status Register Definitions */
+#define SCB_DFSR_EXTERNAL_Pos 4 /*!< SCB DFSR: EXTERNAL Position */
+#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */
+
+#define SCB_DFSR_VCATCH_Pos 3 /*!< SCB DFSR: VCATCH Position */
+#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */
+
+#define SCB_DFSR_DWTTRAP_Pos 2 /*!< SCB DFSR: DWTTRAP Position */
+#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */
+
+#define SCB_DFSR_BKPT_Pos 1 /*!< SCB DFSR: BKPT Position */
+#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */
+
+#define SCB_DFSR_HALTED_Pos 0 /*!< SCB DFSR: HALTED Position */
+#define SCB_DFSR_HALTED_Msk (1UL << SCB_DFSR_HALTED_Pos) /*!< SCB DFSR: HALTED Mask */
+
+/*@} end of group CMSIS_SCB */
+
+
+/** \ingroup CMSIS_core_register
+ \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB)
+ \brief Type definitions for the System Control and ID Register not in the SCB
+ @{
+ */
+
+/** \brief Structure type to access the System Control and ID Register not in the SCB.
+ */
+typedef struct {
+ uint32_t RESERVED0[1];
+ __I uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */
+ __IO uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */
+} SCnSCB_Type;
+
+/* Interrupt Controller Type Register Definitions */
+#define SCnSCB_ICTR_INTLINESNUM_Pos 0 /*!< ICTR: INTLINESNUM Position */
+#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL << SCnSCB_ICTR_INTLINESNUM_Pos) /*!< ICTR: INTLINESNUM Mask */
+
+/* Auxiliary Control Register Definitions */
+#define SCnSCB_ACTLR_DISOOFP_Pos 9 /*!< ACTLR: DISOOFP Position */
+#define SCnSCB_ACTLR_DISOOFP_Msk (1UL << SCnSCB_ACTLR_DISOOFP_Pos) /*!< ACTLR: DISOOFP Mask */
+
+#define SCnSCB_ACTLR_DISFPCA_Pos 8 /*!< ACTLR: DISFPCA Position */
+#define SCnSCB_ACTLR_DISFPCA_Msk (1UL << SCnSCB_ACTLR_DISFPCA_Pos) /*!< ACTLR: DISFPCA Mask */
+
+#define SCnSCB_ACTLR_DISFOLD_Pos 2 /*!< ACTLR: DISFOLD Position */
+#define SCnSCB_ACTLR_DISFOLD_Msk (1UL << SCnSCB_ACTLR_DISFOLD_Pos) /*!< ACTLR: DISFOLD Mask */
+
+#define SCnSCB_ACTLR_DISDEFWBUF_Pos 1 /*!< ACTLR: DISDEFWBUF Position */
+#define SCnSCB_ACTLR_DISDEFWBUF_Msk (1UL << SCnSCB_ACTLR_DISDEFWBUF_Pos) /*!< ACTLR: DISDEFWBUF Mask */
+
+#define SCnSCB_ACTLR_DISMCYCINT_Pos 0 /*!< ACTLR: DISMCYCINT Position */
+#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL << SCnSCB_ACTLR_DISMCYCINT_Pos) /*!< ACTLR: DISMCYCINT Mask */
+
+/*@} end of group CMSIS_SCnotSCB */
+
+
+/** \ingroup CMSIS_core_register
+ \defgroup CMSIS_SysTick System Tick Timer (SysTick)
+ \brief Type definitions for the System Timer Registers.
+ @{
+ */
+
+/** \brief Structure type to access the System Timer (SysTick).
+ */
+typedef struct {
+ __IO uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */
+ __IO uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */
+ __IO uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */
+ __I uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */
+} SysTick_Type;
+
+/* SysTick Control / Status Register Definitions */
+#define SysTick_CTRL_COUNTFLAG_Pos 16 /*!< SysTick CTRL: COUNTFLAG Position */
+#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */
+
+#define SysTick_CTRL_CLKSOURCE_Pos 2 /*!< SysTick CTRL: CLKSOURCE Position */
+#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */
+
+#define SysTick_CTRL_TICKINT_Pos 1 /*!< SysTick CTRL: TICKINT Position */
+#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */
+
+#define SysTick_CTRL_ENABLE_Pos 0 /*!< SysTick CTRL: ENABLE Position */
+#define SysTick_CTRL_ENABLE_Msk (1UL << SysTick_CTRL_ENABLE_Pos) /*!< SysTick CTRL: ENABLE Mask */
+
+/* SysTick Reload Register Definitions */
+#define SysTick_LOAD_RELOAD_Pos 0 /*!< SysTick LOAD: RELOAD Position */
+#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL << SysTick_LOAD_RELOAD_Pos) /*!< SysTick LOAD: RELOAD Mask */
+
+/* SysTick Current Register Definitions */
+#define SysTick_VAL_CURRENT_Pos 0 /*!< SysTick VAL: CURRENT Position */
+#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL << SysTick_VAL_CURRENT_Pos) /*!< SysTick VAL: CURRENT Mask */
+
+/* SysTick Calibration Register Definitions */
+#define SysTick_CALIB_NOREF_Pos 31 /*!< SysTick CALIB: NOREF Position */
+#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */
+
+#define SysTick_CALIB_SKEW_Pos 30 /*!< SysTick CALIB: SKEW Position */
+#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */
+
+#define SysTick_CALIB_TENMS_Pos 0 /*!< SysTick CALIB: TENMS Position */
+#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL << SysTick_VAL_CURRENT_Pos) /*!< SysTick CALIB: TENMS Mask */
+
+/*@} end of group CMSIS_SysTick */
+
+
+/** \ingroup CMSIS_core_register
+ \defgroup CMSIS_ITM Instrumentation Trace Macrocell (ITM)
+ \brief Type definitions for the Instrumentation Trace Macrocell (ITM)
+ @{
+ */
+
+/** \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM).
+ */
+typedef struct {
+ __O union {
+ __O uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */
+ __O uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */
+ __O uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */
+ } PORT [32]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */
+ uint32_t RESERVED0[864];
+ __IO uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */
+ uint32_t RESERVED1[15];
+ __IO uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */
+ uint32_t RESERVED2[15];
+ __IO uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */
+ uint32_t RESERVED3[29];
+ __O uint32_t IWR; /*!< Offset: 0xEF8 ( /W) ITM Integration Write Register */
+ __I uint32_t IRR; /*!< Offset: 0xEFC (R/ ) ITM Integration Read Register */
+ __IO uint32_t IMCR; /*!< Offset: 0xF00 (R/W) ITM Integration Mode Control Register */
+ uint32_t RESERVED4[43];
+ __O uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */
+ __I uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */
+ uint32_t RESERVED5[6];
+ __I uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */
+ __I uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */
+ __I uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */
+ __I uint32_t PID7; /*!< Offset: 0xFDC (R/ ) ITM Peripheral Identification Register #7 */
+ __I uint32_t PID0; /*!< Offset: 0xFE0 (R/ ) ITM Peripheral Identification Register #0 */
+ __I uint32_t PID1; /*!< Offset: 0xFE4 (R/ ) ITM Peripheral Identification Register #1 */
+ __I uint32_t PID2; /*!< Offset: 0xFE8 (R/ ) ITM Peripheral Identification Register #2 */
+ __I uint32_t PID3; /*!< Offset: 0xFEC (R/ ) ITM Peripheral Identification Register #3 */
+ __I uint32_t CID0; /*!< Offset: 0xFF0 (R/ ) ITM Component Identification Register #0 */
+ __I uint32_t CID1; /*!< Offset: 0xFF4 (R/ ) ITM Component Identification Register #1 */
+ __I uint32_t CID2; /*!< Offset: 0xFF8 (R/ ) ITM Component Identification Register #2 */
+ __I uint32_t CID3; /*!< Offset: 0xFFC (R/ ) ITM Component Identification Register #3 */
+} ITM_Type;
+
+/* ITM Trace Privilege Register Definitions */
+#define ITM_TPR_PRIVMASK_Pos 0 /*!< ITM TPR: PRIVMASK Position */
+#define ITM_TPR_PRIVMASK_Msk (0xFUL << ITM_TPR_PRIVMASK_Pos) /*!< ITM TPR: PRIVMASK Mask */
+
+/* ITM Trace Control Register Definitions */
+#define ITM_TCR_BUSY_Pos 23 /*!< ITM TCR: BUSY Position */
+#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */
+
+#define ITM_TCR_TraceBusID_Pos 16 /*!< ITM TCR: ATBID Position */
+#define ITM_TCR_TraceBusID_Msk (0x7FUL << ITM_TCR_TraceBusID_Pos) /*!< ITM TCR: ATBID Mask */
+
+#define ITM_TCR_GTSFREQ_Pos 10 /*!< ITM TCR: Global timestamp frequency Position */
+#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */
+
+#define ITM_TCR_TSPrescale_Pos 8 /*!< ITM TCR: TSPrescale Position */
+#define ITM_TCR_TSPrescale_Msk (3UL << ITM_TCR_TSPrescale_Pos) /*!< ITM TCR: TSPrescale Mask */
+
+#define ITM_TCR_SWOENA_Pos 4 /*!< ITM TCR: SWOENA Position */
+#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */
+
+#define ITM_TCR_DWTENA_Pos 3 /*!< ITM TCR: DWTENA Position */
+#define ITM_TCR_DWTENA_Msk (1UL << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */
+
+#define ITM_TCR_SYNCENA_Pos 2 /*!< ITM TCR: SYNCENA Position */
+#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */
+
+#define ITM_TCR_TSENA_Pos 1 /*!< ITM TCR: TSENA Position */
+#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */
+
+#define ITM_TCR_ITMENA_Pos 0 /*!< ITM TCR: ITM Enable bit Position */
+#define ITM_TCR_ITMENA_Msk (1UL << ITM_TCR_ITMENA_Pos) /*!< ITM TCR: ITM Enable bit Mask */
+
+/* ITM Integration Write Register Definitions */
+#define ITM_IWR_ATVALIDM_Pos 0 /*!< ITM IWR: ATVALIDM Position */
+#define ITM_IWR_ATVALIDM_Msk (1UL << ITM_IWR_ATVALIDM_Pos) /*!< ITM IWR: ATVALIDM Mask */
+
+/* ITM Integration Read Register Definitions */
+#define ITM_IRR_ATREADYM_Pos 0 /*!< ITM IRR: ATREADYM Position */
+#define ITM_IRR_ATREADYM_Msk (1UL << ITM_IRR_ATREADYM_Pos) /*!< ITM IRR: ATREADYM Mask */
+
+/* ITM Integration Mode Control Register Definitions */
+#define ITM_IMCR_INTEGRATION_Pos 0 /*!< ITM IMCR: INTEGRATION Position */
+#define ITM_IMCR_INTEGRATION_Msk (1UL << ITM_IMCR_INTEGRATION_Pos) /*!< ITM IMCR: INTEGRATION Mask */
+
+/* ITM Lock Status Register Definitions */
+#define ITM_LSR_ByteAcc_Pos 2 /*!< ITM LSR: ByteAcc Position */
+#define ITM_LSR_ByteAcc_Msk (1UL << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */
+
+#define ITM_LSR_Access_Pos 1 /*!< ITM LSR: Access Position */
+#define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */
+
+#define ITM_LSR_Present_Pos 0 /*!< ITM LSR: Present Position */
+#define ITM_LSR_Present_Msk (1UL << ITM_LSR_Present_Pos) /*!< ITM LSR: Present Mask */
+
+/*@}*/ /* end of group CMSIS_ITM */
+
+
+/** \ingroup CMSIS_core_register
+ \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT)
+ \brief Type definitions for the Data Watchpoint and Trace (DWT)
+ @{
+ */
+
+/** \brief Structure type to access the Data Watchpoint and Trace Register (DWT).
+ */
+typedef struct {
+ __IO uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */
+ __IO uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */
+ __IO uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */
+ __IO uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */
+ __IO uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */
+ __IO uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */
+ __IO uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */
+ __I uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */
+ __IO uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */
+ __IO uint32_t MASK0; /*!< Offset: 0x024 (R/W) Mask Register 0 */
+ __IO uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */
+ uint32_t RESERVED0[1];
+ __IO uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */
+ __IO uint32_t MASK1; /*!< Offset: 0x034 (R/W) Mask Register 1 */
+ __IO uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */
+ uint32_t RESERVED1[1];
+ __IO uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */
+ __IO uint32_t MASK2; /*!< Offset: 0x044 (R/W) Mask Register 2 */
+ __IO uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */
+ uint32_t RESERVED2[1];
+ __IO uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */
+ __IO uint32_t MASK3; /*!< Offset: 0x054 (R/W) Mask Register 3 */
+ __IO uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */
+} DWT_Type;
+
+/* DWT Control Register Definitions */
+#define DWT_CTRL_NUMCOMP_Pos 28 /*!< DWT CTRL: NUMCOMP Position */
+#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */
+
+#define DWT_CTRL_NOTRCPKT_Pos 27 /*!< DWT CTRL: NOTRCPKT Position */
+#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */
+
+#define DWT_CTRL_NOEXTTRIG_Pos 26 /*!< DWT CTRL: NOEXTTRIG Position */
+#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */
+
+#define DWT_CTRL_NOCYCCNT_Pos 25 /*!< DWT CTRL: NOCYCCNT Position */
+#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */
+
+#define DWT_CTRL_NOPRFCNT_Pos 24 /*!< DWT CTRL: NOPRFCNT Position */
+#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */
+
+#define DWT_CTRL_CYCEVTENA_Pos 22 /*!< DWT CTRL: CYCEVTENA Position */
+#define DWT_CTRL_CYCEVTENA_Msk (0x1UL << DWT_CTRL_CYCEVTENA_Pos) /*!< DWT CTRL: CYCEVTENA Mask */
+
+#define DWT_CTRL_FOLDEVTENA_Pos 21 /*!< DWT CTRL: FOLDEVTENA Position */
+#define DWT_CTRL_FOLDEVTENA_Msk (0x1UL << DWT_CTRL_FOLDEVTENA_Pos) /*!< DWT CTRL: FOLDEVTENA Mask */
+
+#define DWT_CTRL_LSUEVTENA_Pos 20 /*!< DWT CTRL: LSUEVTENA Position */
+#define DWT_CTRL_LSUEVTENA_Msk (0x1UL << DWT_CTRL_LSUEVTENA_Pos) /*!< DWT CTRL: LSUEVTENA Mask */
+
+#define DWT_CTRL_SLEEPEVTENA_Pos 19 /*!< DWT CTRL: SLEEPEVTENA Position */
+#define DWT_CTRL_SLEEPEVTENA_Msk (0x1UL << DWT_CTRL_SLEEPEVTENA_Pos) /*!< DWT CTRL: SLEEPEVTENA Mask */
+
+#define DWT_CTRL_EXCEVTENA_Pos 18 /*!< DWT CTRL: EXCEVTENA Position */
+#define DWT_CTRL_EXCEVTENA_Msk (0x1UL << DWT_CTRL_EXCEVTENA_Pos) /*!< DWT CTRL: EXCEVTENA Mask */
+
+#define DWT_CTRL_CPIEVTENA_Pos 17 /*!< DWT CTRL: CPIEVTENA Position */
+#define DWT_CTRL_CPIEVTENA_Msk (0x1UL << DWT_CTRL_CPIEVTENA_Pos) /*!< DWT CTRL: CPIEVTENA Mask */
+
+#define DWT_CTRL_EXCTRCENA_Pos 16 /*!< DWT CTRL: EXCTRCENA Position */
+#define DWT_CTRL_EXCTRCENA_Msk (0x1UL << DWT_CTRL_EXCTRCENA_Pos) /*!< DWT CTRL: EXCTRCENA Mask */
+
+#define DWT_CTRL_PCSAMPLENA_Pos 12 /*!< DWT CTRL: PCSAMPLENA Position */
+#define DWT_CTRL_PCSAMPLENA_Msk (0x1UL << DWT_CTRL_PCSAMPLENA_Pos) /*!< DWT CTRL: PCSAMPLENA Mask */
+
+#define DWT_CTRL_SYNCTAP_Pos 10 /*!< DWT CTRL: SYNCTAP Position */
+#define DWT_CTRL_SYNCTAP_Msk (0x3UL << DWT_CTRL_SYNCTAP_Pos) /*!< DWT CTRL: SYNCTAP Mask */
+
+#define DWT_CTRL_CYCTAP_Pos 9 /*!< DWT CTRL: CYCTAP Position */
+#define DWT_CTRL_CYCTAP_Msk (0x1UL << DWT_CTRL_CYCTAP_Pos) /*!< DWT CTRL: CYCTAP Mask */
+
+#define DWT_CTRL_POSTINIT_Pos 5 /*!< DWT CTRL: POSTINIT Position */
+#define DWT_CTRL_POSTINIT_Msk (0xFUL << DWT_CTRL_POSTINIT_Pos) /*!< DWT CTRL: POSTINIT Mask */
+
+#define DWT_CTRL_POSTPRESET_Pos 1 /*!< DWT CTRL: POSTPRESET Position */
+#define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */
+
+#define DWT_CTRL_CYCCNTENA_Pos 0 /*!< DWT CTRL: CYCCNTENA Position */
+#define DWT_CTRL_CYCCNTENA_Msk (0x1UL << DWT_CTRL_CYCCNTENA_Pos) /*!< DWT CTRL: CYCCNTENA Mask */
+
+/* DWT CPI Count Register Definitions */
+#define DWT_CPICNT_CPICNT_Pos 0 /*!< DWT CPICNT: CPICNT Position */
+#define DWT_CPICNT_CPICNT_Msk (0xFFUL << DWT_CPICNT_CPICNT_Pos) /*!< DWT CPICNT: CPICNT Mask */
+
+/* DWT Exception Overhead Count Register Definitions */
+#define DWT_EXCCNT_EXCCNT_Pos 0 /*!< DWT EXCCNT: EXCCNT Position */
+#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL << DWT_EXCCNT_EXCCNT_Pos) /*!< DWT EXCCNT: EXCCNT Mask */
+
+/* DWT Sleep Count Register Definitions */
+#define DWT_SLEEPCNT_SLEEPCNT_Pos 0 /*!< DWT SLEEPCNT: SLEEPCNT Position */
+#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL << DWT_SLEEPCNT_SLEEPCNT_Pos) /*!< DWT SLEEPCNT: SLEEPCNT Mask */
+
+/* DWT LSU Count Register Definitions */
+#define DWT_LSUCNT_LSUCNT_Pos 0 /*!< DWT LSUCNT: LSUCNT Position */
+#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL << DWT_LSUCNT_LSUCNT_Pos) /*!< DWT LSUCNT: LSUCNT Mask */
+
+/* DWT Folded-instruction Count Register Definitions */
+#define DWT_FOLDCNT_FOLDCNT_Pos 0 /*!< DWT FOLDCNT: FOLDCNT Position */
+#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL << DWT_FOLDCNT_FOLDCNT_Pos) /*!< DWT FOLDCNT: FOLDCNT Mask */
+
+/* DWT Comparator Mask Register Definitions */
+#define DWT_MASK_MASK_Pos 0 /*!< DWT MASK: MASK Position */
+#define DWT_MASK_MASK_Msk (0x1FUL << DWT_MASK_MASK_Pos) /*!< DWT MASK: MASK Mask */
+
+/* DWT Comparator Function Register Definitions */
+#define DWT_FUNCTION_MATCHED_Pos 24 /*!< DWT FUNCTION: MATCHED Position */
+#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */
+
+#define DWT_FUNCTION_DATAVADDR1_Pos 16 /*!< DWT FUNCTION: DATAVADDR1 Position */
+#define DWT_FUNCTION_DATAVADDR1_Msk (0xFUL << DWT_FUNCTION_DATAVADDR1_Pos) /*!< DWT FUNCTION: DATAVADDR1 Mask */
+
+#define DWT_FUNCTION_DATAVADDR0_Pos 12 /*!< DWT FUNCTION: DATAVADDR0 Position */
+#define DWT_FUNCTION_DATAVADDR0_Msk (0xFUL << DWT_FUNCTION_DATAVADDR0_Pos) /*!< DWT FUNCTION: DATAVADDR0 Mask */
+
+#define DWT_FUNCTION_DATAVSIZE_Pos 10 /*!< DWT FUNCTION: DATAVSIZE Position */
+#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */
+
+#define DWT_FUNCTION_LNK1ENA_Pos 9 /*!< DWT FUNCTION: LNK1ENA Position */
+#define DWT_FUNCTION_LNK1ENA_Msk (0x1UL << DWT_FUNCTION_LNK1ENA_Pos) /*!< DWT FUNCTION: LNK1ENA Mask */
+
+#define DWT_FUNCTION_DATAVMATCH_Pos 8 /*!< DWT FUNCTION: DATAVMATCH Position */
+#define DWT_FUNCTION_DATAVMATCH_Msk (0x1UL << DWT_FUNCTION_DATAVMATCH_Pos) /*!< DWT FUNCTION: DATAVMATCH Mask */
+
+#define DWT_FUNCTION_CYCMATCH_Pos 7 /*!< DWT FUNCTION: CYCMATCH Position */
+#define DWT_FUNCTION_CYCMATCH_Msk (0x1UL << DWT_FUNCTION_CYCMATCH_Pos) /*!< DWT FUNCTION: CYCMATCH Mask */
+
+#define DWT_FUNCTION_EMITRANGE_Pos 5 /*!< DWT FUNCTION: EMITRANGE Position */
+#define DWT_FUNCTION_EMITRANGE_Msk (0x1UL << DWT_FUNCTION_EMITRANGE_Pos) /*!< DWT FUNCTION: EMITRANGE Mask */
+
+#define DWT_FUNCTION_FUNCTION_Pos 0 /*!< DWT FUNCTION: FUNCTION Position */
+#define DWT_FUNCTION_FUNCTION_Msk (0xFUL << DWT_FUNCTION_FUNCTION_Pos) /*!< DWT FUNCTION: FUNCTION Mask */
+
+/*@}*/ /* end of group CMSIS_DWT */
+
+
+/** \ingroup CMSIS_core_register
+ \defgroup CMSIS_TPI Trace Port Interface (TPI)
+ \brief Type definitions for the Trace Port Interface (TPI)
+ @{
+ */
+
+/** \brief Structure type to access the Trace Port Interface Register (TPI).
+ */
+typedef struct {
+ __IO uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Size Register */
+ __IO uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Size Register */
+ uint32_t RESERVED0[2];
+ __IO uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */
+ uint32_t RESERVED1[55];
+ __IO uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */
+ uint32_t RESERVED2[131];
+ __I uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */
+ __IO uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */
+ __I uint32_t FSCR; /*!< Offset: 0x308 (R/ ) Formatter Synchronization Counter Register */
+ uint32_t RESERVED3[759];
+ __I uint32_t TRIGGER; /*!< Offset: 0xEE8 (R/ ) TRIGGER */
+ __I uint32_t FIFO0; /*!< Offset: 0xEEC (R/ ) Integration ETM Data */
+ __I uint32_t ITATBCTR2; /*!< Offset: 0xEF0 (R/ ) ITATBCTR2 */
+ uint32_t RESERVED4[1];
+ __I uint32_t ITATBCTR0; /*!< Offset: 0xEF8 (R/ ) ITATBCTR0 */
+ __I uint32_t FIFO1; /*!< Offset: 0xEFC (R/ ) Integration ITM Data */
+ __IO uint32_t ITCTRL; /*!< Offset: 0xF00 (R/W) Integration Mode Control */
+ uint32_t RESERVED5[39];
+ __IO uint32_t CLAIMSET; /*!< Offset: 0xFA0 (R/W) Claim tag set */
+ __IO uint32_t CLAIMCLR; /*!< Offset: 0xFA4 (R/W) Claim tag clear */
+ uint32_t RESERVED7[8];
+ __I uint32_t DEVID; /*!< Offset: 0xFC8 (R/ ) TPIU_DEVID */
+ __I uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) TPIU_DEVTYPE */
+} TPI_Type;
+
+/* TPI Asynchronous Clock Prescaler Register Definitions */
+#define TPI_ACPR_PRESCALER_Pos 0 /*!< TPI ACPR: PRESCALER Position */
+#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL << TPI_ACPR_PRESCALER_Pos) /*!< TPI ACPR: PRESCALER Mask */
+
+/* TPI Selected Pin Protocol Register Definitions */
+#define TPI_SPPR_TXMODE_Pos 0 /*!< TPI SPPR: TXMODE Position */
+#define TPI_SPPR_TXMODE_Msk (0x3UL << TPI_SPPR_TXMODE_Pos) /*!< TPI SPPR: TXMODE Mask */
+
+/* TPI Formatter and Flush Status Register Definitions */
+#define TPI_FFSR_FtNonStop_Pos 3 /*!< TPI FFSR: FtNonStop Position */
+#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */
+
+#define TPI_FFSR_TCPresent_Pos 2 /*!< TPI FFSR: TCPresent Position */
+#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */
+
+#define TPI_FFSR_FtStopped_Pos 1 /*!< TPI FFSR: FtStopped Position */
+#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */
+
+#define TPI_FFSR_FlInProg_Pos 0 /*!< TPI FFSR: FlInProg Position */
+#define TPI_FFSR_FlInProg_Msk (0x1UL << TPI_FFSR_FlInProg_Pos) /*!< TPI FFSR: FlInProg Mask */
+
+/* TPI Formatter and Flush Control Register Definitions */
+#define TPI_FFCR_TrigIn_Pos 8 /*!< TPI FFCR: TrigIn Position */
+#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */
+
+#define TPI_FFCR_EnFCont_Pos 1 /*!< TPI FFCR: EnFCont Position */
+#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */
+
+/* TPI TRIGGER Register Definitions */
+#define TPI_TRIGGER_TRIGGER_Pos 0 /*!< TPI TRIGGER: TRIGGER Position */
+#define TPI_TRIGGER_TRIGGER_Msk (0x1UL << TPI_TRIGGER_TRIGGER_Pos) /*!< TPI TRIGGER: TRIGGER Mask */
+
+/* TPI Integration ETM Data Register Definitions (FIFO0) */
+#define TPI_FIFO0_ITM_ATVALID_Pos 29 /*!< TPI FIFO0: ITM_ATVALID Position */
+#define TPI_FIFO0_ITM_ATVALID_Msk (0x3UL << TPI_FIFO0_ITM_ATVALID_Pos) /*!< TPI FIFO0: ITM_ATVALID Mask */
+
+#define TPI_FIFO0_ITM_bytecount_Pos 27 /*!< TPI FIFO0: ITM_bytecount Position */
+#define TPI_FIFO0_ITM_bytecount_Msk (0x3UL << TPI_FIFO0_ITM_bytecount_Pos) /*!< TPI FIFO0: ITM_bytecount Mask */
+
+#define TPI_FIFO0_ETM_ATVALID_Pos 26 /*!< TPI FIFO0: ETM_ATVALID Position */
+#define TPI_FIFO0_ETM_ATVALID_Msk (0x3UL << TPI_FIFO0_ETM_ATVALID_Pos) /*!< TPI FIFO0: ETM_ATVALID Mask */
+
+#define TPI_FIFO0_ETM_bytecount_Pos 24 /*!< TPI FIFO0: ETM_bytecount Position */
+#define TPI_FIFO0_ETM_bytecount_Msk (0x3UL << TPI_FIFO0_ETM_bytecount_Pos) /*!< TPI FIFO0: ETM_bytecount Mask */
+
+#define TPI_FIFO0_ETM2_Pos 16 /*!< TPI FIFO0: ETM2 Position */
+#define TPI_FIFO0_ETM2_Msk (0xFFUL << TPI_FIFO0_ETM2_Pos) /*!< TPI FIFO0: ETM2 Mask */
+
+#define TPI_FIFO0_ETM1_Pos 8 /*!< TPI FIFO0: ETM1 Position */
+#define TPI_FIFO0_ETM1_Msk (0xFFUL << TPI_FIFO0_ETM1_Pos) /*!< TPI FIFO0: ETM1 Mask */
+
+#define TPI_FIFO0_ETM0_Pos 0 /*!< TPI FIFO0: ETM0 Position */
+#define TPI_FIFO0_ETM0_Msk (0xFFUL << TPI_FIFO0_ETM0_Pos) /*!< TPI FIFO0: ETM0 Mask */
+
+/* TPI ITATBCTR2 Register Definitions */
+#define TPI_ITATBCTR2_ATREADY_Pos 0 /*!< TPI ITATBCTR2: ATREADY Position */
+#define TPI_ITATBCTR2_ATREADY_Msk (0x1UL << TPI_ITATBCTR2_ATREADY_Pos) /*!< TPI ITATBCTR2: ATREADY Mask */
+
+/* TPI Integration ITM Data Register Definitions (FIFO1) */
+#define TPI_FIFO1_ITM_ATVALID_Pos 29 /*!< TPI FIFO1: ITM_ATVALID Position */
+#define TPI_FIFO1_ITM_ATVALID_Msk (0x3UL << TPI_FIFO1_ITM_ATVALID_Pos) /*!< TPI FIFO1: ITM_ATVALID Mask */
+
+#define TPI_FIFO1_ITM_bytecount_Pos 27 /*!< TPI FIFO1: ITM_bytecount Position */
+#define TPI_FIFO1_ITM_bytecount_Msk (0x3UL << TPI_FIFO1_ITM_bytecount_Pos) /*!< TPI FIFO1: ITM_bytecount Mask */
+
+#define TPI_FIFO1_ETM_ATVALID_Pos 26 /*!< TPI FIFO1: ETM_ATVALID Position */
+#define TPI_FIFO1_ETM_ATVALID_Msk (0x3UL << TPI_FIFO1_ETM_ATVALID_Pos) /*!< TPI FIFO1: ETM_ATVALID Mask */
+
+#define TPI_FIFO1_ETM_bytecount_Pos 24 /*!< TPI FIFO1: ETM_bytecount Position */
+#define TPI_FIFO1_ETM_bytecount_Msk (0x3UL << TPI_FIFO1_ETM_bytecount_Pos) /*!< TPI FIFO1: ETM_bytecount Mask */
+
+#define TPI_FIFO1_ITM2_Pos 16 /*!< TPI FIFO1: ITM2 Position */
+#define TPI_FIFO1_ITM2_Msk (0xFFUL << TPI_FIFO1_ITM2_Pos) /*!< TPI FIFO1: ITM2 Mask */
+
+#define TPI_FIFO1_ITM1_Pos 8 /*!< TPI FIFO1: ITM1 Position */
+#define TPI_FIFO1_ITM1_Msk (0xFFUL << TPI_FIFO1_ITM1_Pos) /*!< TPI FIFO1: ITM1 Mask */
+
+#define TPI_FIFO1_ITM0_Pos 0 /*!< TPI FIFO1: ITM0 Position */
+#define TPI_FIFO1_ITM0_Msk (0xFFUL << TPI_FIFO1_ITM0_Pos) /*!< TPI FIFO1: ITM0 Mask */
+
+/* TPI ITATBCTR0 Register Definitions */
+#define TPI_ITATBCTR0_ATREADY_Pos 0 /*!< TPI ITATBCTR0: ATREADY Position */
+#define TPI_ITATBCTR0_ATREADY_Msk (0x1UL << TPI_ITATBCTR0_ATREADY_Pos) /*!< TPI ITATBCTR0: ATREADY Mask */
+
+/* TPI Integration Mode Control Register Definitions */
+#define TPI_ITCTRL_Mode_Pos 0 /*!< TPI ITCTRL: Mode Position */
+#define TPI_ITCTRL_Mode_Msk (0x1UL << TPI_ITCTRL_Mode_Pos) /*!< TPI ITCTRL: Mode Mask */
+
+/* TPI DEVID Register Definitions */
+#define TPI_DEVID_NRZVALID_Pos 11 /*!< TPI DEVID: NRZVALID Position */
+#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */
+
+#define TPI_DEVID_MANCVALID_Pos 10 /*!< TPI DEVID: MANCVALID Position */
+#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */
+
+#define TPI_DEVID_PTINVALID_Pos 9 /*!< TPI DEVID: PTINVALID Position */
+#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */
+
+#define TPI_DEVID_MinBufSz_Pos 6 /*!< TPI DEVID: MinBufSz Position */
+#define TPI_DEVID_MinBufSz_Msk (0x7UL << TPI_DEVID_MinBufSz_Pos) /*!< TPI DEVID: MinBufSz Mask */
+
+#define TPI_DEVID_AsynClkIn_Pos 5 /*!< TPI DEVID: AsynClkIn Position */
+#define TPI_DEVID_AsynClkIn_Msk (0x1UL << TPI_DEVID_AsynClkIn_Pos) /*!< TPI DEVID: AsynClkIn Mask */
+
+#define TPI_DEVID_NrTraceInput_Pos 0 /*!< TPI DEVID: NrTraceInput Position */
+#define TPI_DEVID_NrTraceInput_Msk (0x1FUL << TPI_DEVID_NrTraceInput_Pos) /*!< TPI DEVID: NrTraceInput Mask */
+
+/* TPI DEVTYPE Register Definitions */
+#define TPI_DEVTYPE_SubType_Pos 0 /*!< TPI DEVTYPE: SubType Position */
+#define TPI_DEVTYPE_SubType_Msk (0xFUL << TPI_DEVTYPE_SubType_Pos) /*!< TPI DEVTYPE: SubType Mask */
+
+#define TPI_DEVTYPE_MajorType_Pos 4 /*!< TPI DEVTYPE: MajorType Position */
+#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */
+
+/*@}*/ /* end of group CMSIS_TPI */
+
+
+#if (__MPU_PRESENT == 1)
+/** \ingroup CMSIS_core_register
+ \defgroup CMSIS_MPU Memory Protection Unit (MPU)
+ \brief Type definitions for the Memory Protection Unit (MPU)
+ @{
+ */
+
+/** \brief Structure type to access the Memory Protection Unit (MPU).
+ */
+typedef struct {
+ __I uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */
+ __IO uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */
+ __IO uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */
+ __IO uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */
+ __IO uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */
+ __IO uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Alias 1 Region Base Address Register */
+ __IO uint32_t RASR_A1; /*!< Offset: 0x018 (R/W) MPU Alias 1 Region Attribute and Size Register */
+ __IO uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Alias 2 Region Base Address Register */
+ __IO uint32_t RASR_A2; /*!< Offset: 0x020 (R/W) MPU Alias 2 Region Attribute and Size Register */
+ __IO uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Alias 3 Region Base Address Register */
+ __IO uint32_t RASR_A3; /*!< Offset: 0x028 (R/W) MPU Alias 3 Region Attribute and Size Register */
+} MPU_Type;
+
+/* MPU Type Register */
+#define MPU_TYPE_IREGION_Pos 16 /*!< MPU TYPE: IREGION Position */
+#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */
+
+#define MPU_TYPE_DREGION_Pos 8 /*!< MPU TYPE: DREGION Position */
+#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */
+
+#define MPU_TYPE_SEPARATE_Pos 0 /*!< MPU TYPE: SEPARATE Position */
+#define MPU_TYPE_SEPARATE_Msk (1UL << MPU_TYPE_SEPARATE_Pos) /*!< MPU TYPE: SEPARATE Mask */
+
+/* MPU Control Register */
+#define MPU_CTRL_PRIVDEFENA_Pos 2 /*!< MPU CTRL: PRIVDEFENA Position */
+#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */
+
+#define MPU_CTRL_HFNMIENA_Pos 1 /*!< MPU CTRL: HFNMIENA Position */
+#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */
+
+#define MPU_CTRL_ENABLE_Pos 0 /*!< MPU CTRL: ENABLE Position */
+#define MPU_CTRL_ENABLE_Msk (1UL << MPU_CTRL_ENABLE_Pos) /*!< MPU CTRL: ENABLE Mask */
+
+/* MPU Region Number Register */
+#define MPU_RNR_REGION_Pos 0 /*!< MPU RNR: REGION Position */
+#define MPU_RNR_REGION_Msk (0xFFUL << MPU_RNR_REGION_Pos) /*!< MPU RNR: REGION Mask */
+
+/* MPU Region Base Address Register */
+#define MPU_RBAR_ADDR_Pos 5 /*!< MPU RBAR: ADDR Position */
+#define MPU_RBAR_ADDR_Msk (0x7FFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */
+
+#define MPU_RBAR_VALID_Pos 4 /*!< MPU RBAR: VALID Position */
+#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */
+
+#define MPU_RBAR_REGION_Pos 0 /*!< MPU RBAR: REGION Position */
+#define MPU_RBAR_REGION_Msk (0xFUL << MPU_RBAR_REGION_Pos) /*!< MPU RBAR: REGION Mask */
+
+/* MPU Region Attribute and Size Register */
+#define MPU_RASR_ATTRS_Pos 16 /*!< MPU RASR: MPU Region Attribute field Position */
+#define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */
+
+#define MPU_RASR_XN_Pos 28 /*!< MPU RASR: ATTRS.XN Position */
+#define MPU_RASR_XN_Msk (1UL << MPU_RASR_XN_Pos) /*!< MPU RASR: ATTRS.XN Mask */
+
+#define MPU_RASR_AP_Pos 24 /*!< MPU RASR: ATTRS.AP Position */
+#define MPU_RASR_AP_Msk (0x7UL << MPU_RASR_AP_Pos) /*!< MPU RASR: ATTRS.AP Mask */
+
+#define MPU_RASR_TEX_Pos 19 /*!< MPU RASR: ATTRS.TEX Position */
+#define MPU_RASR_TEX_Msk (0x7UL << MPU_RASR_TEX_Pos) /*!< MPU RASR: ATTRS.TEX Mask */
+
+#define MPU_RASR_S_Pos 18 /*!< MPU RASR: ATTRS.S Position */
+#define MPU_RASR_S_Msk (1UL << MPU_RASR_S_Pos) /*!< MPU RASR: ATTRS.S Mask */
+
+#define MPU_RASR_C_Pos 17 /*!< MPU RASR: ATTRS.C Position */
+#define MPU_RASR_C_Msk (1UL << MPU_RASR_C_Pos) /*!< MPU RASR: ATTRS.C Mask */
+
+#define MPU_RASR_B_Pos 16 /*!< MPU RASR: ATTRS.B Position */
+#define MPU_RASR_B_Msk (1UL << MPU_RASR_B_Pos) /*!< MPU RASR: ATTRS.B Mask */
+
+#define MPU_RASR_SRD_Pos 8 /*!< MPU RASR: Sub-Region Disable Position */
+#define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */
+
+#define MPU_RASR_SIZE_Pos 1 /*!< MPU RASR: Region Size Field Position */
+#define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */
+
+#define MPU_RASR_ENABLE_Pos 0 /*!< MPU RASR: Region enable bit Position */
+#define MPU_RASR_ENABLE_Msk (1UL << MPU_RASR_ENABLE_Pos) /*!< MPU RASR: Region enable bit Disable Mask */
+
+/*@} end of group CMSIS_MPU */
+#endif
+
+
+#if (__FPU_PRESENT == 1)
+/** \ingroup CMSIS_core_register
+ \defgroup CMSIS_FPU Floating Point Unit (FPU)
+ \brief Type definitions for the Floating Point Unit (FPU)
+ @{
+ */
+
+/** \brief Structure type to access the Floating Point Unit (FPU).
+ */
+typedef struct {
+ uint32_t RESERVED0[1];
+ __IO uint32_t FPCCR; /*!< Offset: 0x004 (R/W) Floating-Point Context Control Register */
+ __IO uint32_t FPCAR; /*!< Offset: 0x008 (R/W) Floating-Point Context Address Register */
+ __IO uint32_t FPDSCR; /*!< Offset: 0x00C (R/W) Floating-Point Default Status Control Register */
+ __I uint32_t MVFR0; /*!< Offset: 0x010 (R/ ) Media and FP Feature Register 0 */
+ __I uint32_t MVFR1; /*!< Offset: 0x014 (R/ ) Media and FP Feature Register 1 */
+} FPU_Type;
+
+/* Floating-Point Context Control Register */
+#define FPU_FPCCR_ASPEN_Pos 31 /*!< FPCCR: ASPEN bit Position */
+#define FPU_FPCCR_ASPEN_Msk (1UL << FPU_FPCCR_ASPEN_Pos) /*!< FPCCR: ASPEN bit Mask */
+
+#define FPU_FPCCR_LSPEN_Pos 30 /*!< FPCCR: LSPEN Position */
+#define FPU_FPCCR_LSPEN_Msk (1UL << FPU_FPCCR_LSPEN_Pos) /*!< FPCCR: LSPEN bit Mask */
+
+#define FPU_FPCCR_MONRDY_Pos 8 /*!< FPCCR: MONRDY Position */
+#define FPU_FPCCR_MONRDY_Msk (1UL << FPU_FPCCR_MONRDY_Pos) /*!< FPCCR: MONRDY bit Mask */
+
+#define FPU_FPCCR_BFRDY_Pos 6 /*!< FPCCR: BFRDY Position */
+#define FPU_FPCCR_BFRDY_Msk (1UL << FPU_FPCCR_BFRDY_Pos) /*!< FPCCR: BFRDY bit Mask */
+
+#define FPU_FPCCR_MMRDY_Pos 5 /*!< FPCCR: MMRDY Position */
+#define FPU_FPCCR_MMRDY_Msk (1UL << FPU_FPCCR_MMRDY_Pos) /*!< FPCCR: MMRDY bit Mask */
+
+#define FPU_FPCCR_HFRDY_Pos 4 /*!< FPCCR: HFRDY Position */
+#define FPU_FPCCR_HFRDY_Msk (1UL << FPU_FPCCR_HFRDY_Pos) /*!< FPCCR: HFRDY bit Mask */
+
+#define FPU_FPCCR_THREAD_Pos 3 /*!< FPCCR: processor mode bit Position */
+#define FPU_FPCCR_THREAD_Msk (1UL << FPU_FPCCR_THREAD_Pos) /*!< FPCCR: processor mode active bit Mask */
+
+#define FPU_FPCCR_USER_Pos 1 /*!< FPCCR: privilege level bit Position */
+#define FPU_FPCCR_USER_Msk (1UL << FPU_FPCCR_USER_Pos) /*!< FPCCR: privilege level bit Mask */
+
+#define FPU_FPCCR_LSPACT_Pos 0 /*!< FPCCR: Lazy state preservation active bit Position */
+#define FPU_FPCCR_LSPACT_Msk (1UL << FPU_FPCCR_LSPACT_Pos) /*!< FPCCR: Lazy state preservation active bit Mask */
+
+/* Floating-Point Context Address Register */
+#define FPU_FPCAR_ADDRESS_Pos 3 /*!< FPCAR: ADDRESS bit Position */
+#define FPU_FPCAR_ADDRESS_Msk (0x1FFFFFFFUL << FPU_FPCAR_ADDRESS_Pos) /*!< FPCAR: ADDRESS bit Mask */
+
+/* Floating-Point Default Status Control Register */
+#define FPU_FPDSCR_AHP_Pos 26 /*!< FPDSCR: AHP bit Position */
+#define FPU_FPDSCR_AHP_Msk (1UL << FPU_FPDSCR_AHP_Pos) /*!< FPDSCR: AHP bit Mask */
+
+#define FPU_FPDSCR_DN_Pos 25 /*!< FPDSCR: DN bit Position */
+#define FPU_FPDSCR_DN_Msk (1UL << FPU_FPDSCR_DN_Pos) /*!< FPDSCR: DN bit Mask */
+
+#define FPU_FPDSCR_FZ_Pos 24 /*!< FPDSCR: FZ bit Position */
+#define FPU_FPDSCR_FZ_Msk (1UL << FPU_FPDSCR_FZ_Pos) /*!< FPDSCR: FZ bit Mask */
+
+#define FPU_FPDSCR_RMode_Pos 22 /*!< FPDSCR: RMode bit Position */
+#define FPU_FPDSCR_RMode_Msk (3UL << FPU_FPDSCR_RMode_Pos) /*!< FPDSCR: RMode bit Mask */
+
+/* Media and FP Feature Register 0 */
+#define FPU_MVFR0_FP_rounding_modes_Pos 28 /*!< MVFR0: FP rounding modes bits Position */
+#define FPU_MVFR0_FP_rounding_modes_Msk (0xFUL << FPU_MVFR0_FP_rounding_modes_Pos) /*!< MVFR0: FP rounding modes bits Mask */
+
+#define FPU_MVFR0_Short_vectors_Pos 24 /*!< MVFR0: Short vectors bits Position */
+#define FPU_MVFR0_Short_vectors_Msk (0xFUL << FPU_MVFR0_Short_vectors_Pos) /*!< MVFR0: Short vectors bits Mask */
+
+#define FPU_MVFR0_Square_root_Pos 20 /*!< MVFR0: Square root bits Position */
+#define FPU_MVFR0_Square_root_Msk (0xFUL << FPU_MVFR0_Square_root_Pos) /*!< MVFR0: Square root bits Mask */
+
+#define FPU_MVFR0_Divide_Pos 16 /*!< MVFR0: Divide bits Position */
+#define FPU_MVFR0_Divide_Msk (0xFUL << FPU_MVFR0_Divide_Pos) /*!< MVFR0: Divide bits Mask */
+
+#define FPU_MVFR0_FP_excep_trapping_Pos 12 /*!< MVFR0: FP exception trapping bits Position */
+#define FPU_MVFR0_FP_excep_trapping_Msk (0xFUL << FPU_MVFR0_FP_excep_trapping_Pos) /*!< MVFR0: FP exception trapping bits Mask */
+
+#define FPU_MVFR0_Double_precision_Pos 8 /*!< MVFR0: Double-precision bits Position */
+#define FPU_MVFR0_Double_precision_Msk (0xFUL << FPU_MVFR0_Double_precision_Pos) /*!< MVFR0: Double-precision bits Mask */
+
+#define FPU_MVFR0_Single_precision_Pos 4 /*!< MVFR0: Single-precision bits Position */
+#define FPU_MVFR0_Single_precision_Msk (0xFUL << FPU_MVFR0_Single_precision_Pos) /*!< MVFR0: Single-precision bits Mask */
+
+#define FPU_MVFR0_A_SIMD_registers_Pos 0 /*!< MVFR0: A_SIMD registers bits Position */
+#define FPU_MVFR0_A_SIMD_registers_Msk (0xFUL << FPU_MVFR0_A_SIMD_registers_Pos) /*!< MVFR0: A_SIMD registers bits Mask */
+
+/* Media and FP Feature Register 1 */
+#define FPU_MVFR1_FP_fused_MAC_Pos 28 /*!< MVFR1: FP fused MAC bits Position */
+#define FPU_MVFR1_FP_fused_MAC_Msk (0xFUL << FPU_MVFR1_FP_fused_MAC_Pos) /*!< MVFR1: FP fused MAC bits Mask */
+
+#define FPU_MVFR1_FP_HPFP_Pos 24 /*!< MVFR1: FP HPFP bits Position */
+#define FPU_MVFR1_FP_HPFP_Msk (0xFUL << FPU_MVFR1_FP_HPFP_Pos) /*!< MVFR1: FP HPFP bits Mask */
+
+#define FPU_MVFR1_D_NaN_mode_Pos 4 /*!< MVFR1: D_NaN mode bits Position */
+#define FPU_MVFR1_D_NaN_mode_Msk (0xFUL << FPU_MVFR1_D_NaN_mode_Pos) /*!< MVFR1: D_NaN mode bits Mask */
+
+#define FPU_MVFR1_FtZ_mode_Pos 0 /*!< MVFR1: FtZ mode bits Position */
+#define FPU_MVFR1_FtZ_mode_Msk (0xFUL << FPU_MVFR1_FtZ_mode_Pos) /*!< MVFR1: FtZ mode bits Mask */
+
+/*@} end of group CMSIS_FPU */
+#endif
+
+
+/** \ingroup CMSIS_core_register
+ \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug)
+ \brief Type definitions for the Core Debug Registers
+ @{
+ */
+
+/** \brief Structure type to access the Core Debug Register (CoreDebug).
+ */
+typedef struct {
+ __IO uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */
+ __O uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */
+ __IO uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */
+ __IO uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */
+} CoreDebug_Type;
+
+/* Debug Halting Control and Status Register */
+#define CoreDebug_DHCSR_DBGKEY_Pos 16 /*!< CoreDebug DHCSR: DBGKEY Position */
+#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */
+
+#define CoreDebug_DHCSR_S_RESET_ST_Pos 25 /*!< CoreDebug DHCSR: S_RESET_ST Position */
+#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */
+
+#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24 /*!< CoreDebug DHCSR: S_RETIRE_ST Position */
+#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */
+
+#define CoreDebug_DHCSR_S_LOCKUP_Pos 19 /*!< CoreDebug DHCSR: S_LOCKUP Position */
+#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */
+
+#define CoreDebug_DHCSR_S_SLEEP_Pos 18 /*!< CoreDebug DHCSR: S_SLEEP Position */
+#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */
+
+#define CoreDebug_DHCSR_S_HALT_Pos 17 /*!< CoreDebug DHCSR: S_HALT Position */
+#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */
+
+#define CoreDebug_DHCSR_S_REGRDY_Pos 16 /*!< CoreDebug DHCSR: S_REGRDY Position */
+#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */
+
+#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5 /*!< CoreDebug DHCSR: C_SNAPSTALL Position */
+#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */
+
+#define CoreDebug_DHCSR_C_MASKINTS_Pos 3 /*!< CoreDebug DHCSR: C_MASKINTS Position */
+#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */
+
+#define CoreDebug_DHCSR_C_STEP_Pos 2 /*!< CoreDebug DHCSR: C_STEP Position */
+#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */
+
+#define CoreDebug_DHCSR_C_HALT_Pos 1 /*!< CoreDebug DHCSR: C_HALT Position */
+#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */
+
+#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0 /*!< CoreDebug DHCSR: C_DEBUGEN Position */
+#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL << CoreDebug_DHCSR_C_DEBUGEN_Pos) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */
+
+/* Debug Core Register Selector Register */
+#define CoreDebug_DCRSR_REGWnR_Pos 16 /*!< CoreDebug DCRSR: REGWnR Position */
+#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */
+
+#define CoreDebug_DCRSR_REGSEL_Pos 0 /*!< CoreDebug DCRSR: REGSEL Position */
+#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL << CoreDebug_DCRSR_REGSEL_Pos) /*!< CoreDebug DCRSR: REGSEL Mask */
+
+/* Debug Exception and Monitor Control Register */
+#define CoreDebug_DEMCR_TRCENA_Pos 24 /*!< CoreDebug DEMCR: TRCENA Position */
+#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */
+
+#define CoreDebug_DEMCR_MON_REQ_Pos 19 /*!< CoreDebug DEMCR: MON_REQ Position */
+#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */
+
+#define CoreDebug_DEMCR_MON_STEP_Pos 18 /*!< CoreDebug DEMCR: MON_STEP Position */
+#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */
+
+#define CoreDebug_DEMCR_MON_PEND_Pos 17 /*!< CoreDebug DEMCR: MON_PEND Position */
+#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */
+
+#define CoreDebug_DEMCR_MON_EN_Pos 16 /*!< CoreDebug DEMCR: MON_EN Position */
+#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */
+
+#define CoreDebug_DEMCR_VC_HARDERR_Pos 10 /*!< CoreDebug DEMCR: VC_HARDERR Position */
+#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */
+
+#define CoreDebug_DEMCR_VC_INTERR_Pos 9 /*!< CoreDebug DEMCR: VC_INTERR Position */
+#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */
+
+#define CoreDebug_DEMCR_VC_BUSERR_Pos 8 /*!< CoreDebug DEMCR: VC_BUSERR Position */
+#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */
+
+#define CoreDebug_DEMCR_VC_STATERR_Pos 7 /*!< CoreDebug DEMCR: VC_STATERR Position */
+#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */
+
+#define CoreDebug_DEMCR_VC_CHKERR_Pos 6 /*!< CoreDebug DEMCR: VC_CHKERR Position */
+#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */
+
+#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5 /*!< CoreDebug DEMCR: VC_NOCPERR Position */
+#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */
+
+#define CoreDebug_DEMCR_VC_MMERR_Pos 4 /*!< CoreDebug DEMCR: VC_MMERR Position */
+#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */
+
+#define CoreDebug_DEMCR_VC_CORERESET_Pos 0 /*!< CoreDebug DEMCR: VC_CORERESET Position */
+#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL << CoreDebug_DEMCR_VC_CORERESET_Pos) /*!< CoreDebug DEMCR: VC_CORERESET Mask */
+
+/*@} end of group CMSIS_CoreDebug */
+
+
+/** \ingroup CMSIS_core_register
+ \defgroup CMSIS_core_base Core Definitions
+ \brief Definitions for base addresses, unions, and structures.
+ @{
+ */
+
+/* Memory mapping of Cortex-M4 Hardware */
+#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */
+#define ITM_BASE (0xE0000000UL) /*!< ITM Base Address */
+#define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */
+#define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */
+#define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */
+#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */
+#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */
+#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */
+
+#define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */
+#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */
+#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */
+#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */
+#define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */
+#define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */
+#define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */
+#define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE) /*!< Core Debug configuration struct */
+
+#if (__MPU_PRESENT == 1)
+#define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */
+#define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */
+#endif
+
+#if (__FPU_PRESENT == 1)
+#define FPU_BASE (SCS_BASE + 0x0F30UL) /*!< Floating Point Unit */
+#define FPU ((FPU_Type *) FPU_BASE ) /*!< Floating Point Unit */
+#endif
+
+/*@} */
+
+
+
+/*******************************************************************************
+ * Hardware Abstraction Layer
+ Core Function Interface contains:
+ - Core NVIC Functions
+ - Core SysTick Functions
+ - Core Debug Functions
+ - Core Register Access Functions
+ ******************************************************************************/
+/** \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference
+*/
+
+
+
+/* ########################## NVIC functions #################################### */
+/** \ingroup CMSIS_Core_FunctionInterface
+ \defgroup CMSIS_Core_NVICFunctions NVIC Functions
+ \brief Functions that manage interrupts and exceptions via the NVIC.
+ @{
+ */
+
+/** \brief Set Priority Grouping
+
+ The function sets the priority grouping field using the required unlock sequence.
+ The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field.
+ Only values from 0..7 are used.
+ In case of a conflict between priority grouping and available
+ priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set.
+
+ \param [in] PriorityGroup Priority grouping field.
+ */
+__STATIC_INLINE void NVIC_SetPriorityGrouping(uint32_t PriorityGroup)
+{
+ uint32_t reg_value;
+ uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07); /* only values 0..7 are used */
+
+ reg_value = SCB->AIRCR; /* read old register configuration */
+ reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk); /* clear bits to change */
+ reg_value = (reg_value |
+ ((uint32_t)0x5FA << SCB_AIRCR_VECTKEY_Pos) |
+ (PriorityGroupTmp << 8)); /* Insert write key and priorty group */
+ SCB->AIRCR = reg_value;
+}
+
+
+/** \brief Get Priority Grouping
+
+ The function reads the priority grouping field from the NVIC Interrupt Controller.
+
+ \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field).
+ */
+__STATIC_INLINE uint32_t NVIC_GetPriorityGrouping(void)
+{
+ return ((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos); /* read priority grouping field */
+}
+
+
+/** \brief Enable External Interrupt
+
+ The function enables a device-specific interrupt in the NVIC interrupt controller.
+
+ \param [in] IRQn External interrupt number. Value cannot be negative.
+ */
+__STATIC_INLINE void NVIC_EnableIRQ(IRQn_Type IRQn)
+{
+ /* NVIC->ISER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); enable interrupt */
+ NVIC->ISER[(uint32_t)((int32_t)IRQn) >> 5] = (uint32_t)(1 << ((uint32_t)((int32_t)IRQn) & (uint32_t)0x1F)); /* enable interrupt */
+}
+
+
+/** \brief Disable External Interrupt
+
+ The function disables a device-specific interrupt in the NVIC interrupt controller.
+
+ \param [in] IRQn External interrupt number. Value cannot be negative.
+ */
+__STATIC_INLINE void NVIC_DisableIRQ(IRQn_Type IRQn)
+{
+ NVIC->ICER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* disable interrupt */
+}
+
+
+/** \brief Get Pending Interrupt
+
+ The function reads the pending register in the NVIC and returns the pending bit
+ for the specified interrupt.
+
+ \param [in] IRQn Interrupt number.
+
+ \return 0 Interrupt status is not pending.
+ \return 1 Interrupt status is pending.
+ */
+__STATIC_INLINE uint32_t NVIC_GetPendingIRQ(IRQn_Type IRQn)
+{
+ return((uint32_t)((NVIC->ISPR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F))) ? 1 : 0)); /* Return 1 if pending else 0 */
+}
+
+
+/** \brief Set Pending Interrupt
+
+ The function sets the pending bit of an external interrupt.
+
+ \param [in] IRQn Interrupt number. Value cannot be negative.
+ */
+__STATIC_INLINE void NVIC_SetPendingIRQ(IRQn_Type IRQn)
+{
+ NVIC->ISPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* set interrupt pending */
+}
+
+
+/** \brief Clear Pending Interrupt
+
+ The function clears the pending bit of an external interrupt.
+
+ \param [in] IRQn External interrupt number. Value cannot be negative.
+ */
+__STATIC_INLINE void NVIC_ClearPendingIRQ(IRQn_Type IRQn)
+{
+ NVIC->ICPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* Clear pending interrupt */
+}
+
+
+/** \brief Get Active Interrupt
+
+ The function reads the active register in NVIC and returns the active bit.
+
+ \param [in] IRQn Interrupt number.
+
+ \return 0 Interrupt status is not active.
+ \return 1 Interrupt status is active.
+ */
+__STATIC_INLINE uint32_t NVIC_GetActive(IRQn_Type IRQn)
+{
+ return((uint32_t)((NVIC->IABR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F))) ? 1 : 0)); /* Return 1 if active else 0 */
+}
+
+
+/** \brief Set Interrupt Priority
+
+ The function sets the priority of an interrupt.
+
+ \note The priority cannot be set for every core interrupt.
+
+ \param [in] IRQn Interrupt number.
+ \param [in] priority Priority to set.
+ */
+__STATIC_INLINE void NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority)
+{
+ if(IRQn < 0) {
+ SCB->SHP[((uint32_t)(IRQn) & 0xF) - 4] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff);
+ } /* set Priority for Cortex-M System Interrupts */
+ else {
+ NVIC->IP[(uint32_t)(IRQn)] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff);
+ } /* set Priority for device specific Interrupts */
+}
+
+
+/** \brief Get Interrupt Priority
+
+ The function reads the priority of an interrupt. The interrupt
+ number can be positive to specify an external (device specific)
+ interrupt, or negative to specify an internal (core) interrupt.
+
+
+ \param [in] IRQn Interrupt number.
+ \return Interrupt Priority. Value is aligned automatically to the implemented
+ priority bits of the microcontroller.
+ */
+__STATIC_INLINE uint32_t NVIC_GetPriority(IRQn_Type IRQn)
+{
+
+ if(IRQn < 0) {
+ return((uint32_t)(SCB->SHP[((uint32_t)(IRQn) & 0xF) - 4] >> (8 - __NVIC_PRIO_BITS)));
+ } /* get priority for Cortex-M system interrupts */
+ else {
+ return((uint32_t)(NVIC->IP[(uint32_t)(IRQn)] >> (8 - __NVIC_PRIO_BITS)));
+ } /* get priority for device specific interrupts */
+}
+
+
+/** \brief Encode Priority
+
+ The function encodes the priority for an interrupt with the given priority group,
+ preemptive priority value, and subpriority value.
+ In case of a conflict between priority grouping and available
+ priority bits (__NVIC_PRIO_BITS), the samllest possible priority group is set.
+
+ \param [in] PriorityGroup Used priority group.
+ \param [in] PreemptPriority Preemptive priority value (starting from 0).
+ \param [in] SubPriority Subpriority value (starting from 0).
+ \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority().
+ */
+__STATIC_INLINE uint32_t NVIC_EncodePriority(uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority)
+{
+ uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */
+ uint32_t PreemptPriorityBits;
+ uint32_t SubPriorityBits;
+
+ PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp;
+ SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS;
+
+ return (
+ ((PreemptPriority & ((1 << (PreemptPriorityBits)) - 1)) << SubPriorityBits) |
+ ((SubPriority & ((1 << (SubPriorityBits)) - 1)))
+ );
+}
+
+
+/** \brief Decode Priority
+
+ The function decodes an interrupt priority value with a given priority group to
+ preemptive priority value and subpriority value.
+ In case of a conflict between priority grouping and available
+ priority bits (__NVIC_PRIO_BITS) the samllest possible priority group is set.
+
+ \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority().
+ \param [in] PriorityGroup Used priority group.
+ \param [out] pPreemptPriority Preemptive priority value (starting from 0).
+ \param [out] pSubPriority Subpriority value (starting from 0).
+ */
+__STATIC_INLINE void NVIC_DecodePriority(uint32_t Priority, uint32_t PriorityGroup, uint32_t *pPreemptPriority, uint32_t *pSubPriority)
+{
+ uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */
+ uint32_t PreemptPriorityBits;
+ uint32_t SubPriorityBits;
+
+ PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp;
+ SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS;
+
+ *pPreemptPriority = (Priority >> SubPriorityBits) & ((1 << (PreemptPriorityBits)) - 1);
+ *pSubPriority = (Priority) & ((1 << (SubPriorityBits)) - 1);
+}
+
+
+/** \brief System Reset
+
+ The function initiates a system reset request to reset the MCU.
+ */
+__STATIC_INLINE void NVIC_SystemReset(void)
+{
+ __DSB(); /* Ensure all outstanding memory accesses included
+ buffered write are completed before reset */
+ SCB->AIRCR = ((0x5FA << SCB_AIRCR_VECTKEY_Pos) |
+ (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) |
+ SCB_AIRCR_SYSRESETREQ_Msk); /* Keep priority group unchanged */
+ __DSB(); /* Ensure completion of memory access */
+ while(1); /* wait until reset */
+}
+
+/*@} end of CMSIS_Core_NVICFunctions */
+
+
+
+/* ################################## SysTick function ############################################ */
+/** \ingroup CMSIS_Core_FunctionInterface
+ \defgroup CMSIS_Core_SysTickFunctions SysTick Functions
+ \brief Functions that configure the System.
+ @{
+ */
+
+#if (__Vendor_SysTickConfig == 0)
+
+/** \brief System Tick Configuration
+
+ The function initializes the System Timer and its interrupt, and starts the System Tick Timer.
+ Counter is in free running mode to generate periodic interrupts.
+
+ \param [in] ticks Number of ticks between two interrupts.
+
+ \return 0 Function succeeded.
+ \return 1 Function failed.
+
+ \note When the variable __Vendor_SysTickConfig is set to 1, then the
+ function SysTick_Config is not included. In this case, the file device.h
+ must contain a vendor-specific implementation of this function.
+
+ */
+__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks)
+{
+ if((ticks - 1) > SysTick_LOAD_RELOAD_Msk) {
+ return (1); /* Reload value impossible */
+ }
+
+ SysTick->LOAD = ticks - 1; /* set reload register */
+ NVIC_SetPriority(SysTick_IRQn, (1 << __NVIC_PRIO_BITS) - 1); /* set Priority for Systick Interrupt */
+ SysTick->VAL = 0; /* Load the SysTick Counter Value */
+ SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk |
+ SysTick_CTRL_TICKINT_Msk |
+ SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */
+ return (0); /* Function successful */
+}
+
+#endif
+
+/*@} end of CMSIS_Core_SysTickFunctions */
+
+
+
+/* ##################################### Debug In/Output function ########################################### */
+/** \ingroup CMSIS_Core_FunctionInterface
+ \defgroup CMSIS_core_DebugFunctions ITM Functions
+ \brief Functions that access the ITM debug interface.
+ @{
+ */
+
+extern volatile int32_t ITM_RxBuffer; /*!< External variable to receive characters. */
+#define ITM_RXBUFFER_EMPTY 0x5AA55AA5 /*!< Value identifying \ref ITM_RxBuffer is ready for next character. */
+
+
+/** \brief ITM Send Character
+
+ The function transmits a character via the ITM channel 0, and
+ \li Just returns when no debugger is connected that has booked the output.
+ \li Is blocking when a debugger is connected, but the previous character sent has not been transmitted.
+
+ \param [in] ch Character to transmit.
+
+ \returns Character to transmit.
+ */
+__STATIC_INLINE uint32_t ITM_SendChar(uint32_t ch)
+{
+ if((ITM->TCR & ITM_TCR_ITMENA_Msk) && /* ITM enabled */
+ (ITM->TER & (1UL << 0))) { /* ITM Port #0 enabled */
+ while(ITM->PORT[0].u32 == 0);
+ ITM->PORT[0].u8 = (uint8_t) ch;
+ }
+ return (ch);
+}
+
+
+/** \brief ITM Receive Character
+
+ The function inputs a character via the external variable \ref ITM_RxBuffer.
+
+ \return Received character.
+ \return -1 No character pending.
+ */
+__STATIC_INLINE int32_t ITM_ReceiveChar(void)
+{
+ int32_t ch = -1; /* no character available */
+
+ if(ITM_RxBuffer != ITM_RXBUFFER_EMPTY) {
+ ch = ITM_RxBuffer;
+ ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */
+ }
+
+ return (ch);
+}
+
+
+/** \brief ITM Check Character
+
+ The function checks whether a character is pending for reading in the variable \ref ITM_RxBuffer.
+
+ \return 0 No character available.
+ \return 1 Character available.
+ */
+__STATIC_INLINE int32_t ITM_CheckChar(void)
+{
+
+ if(ITM_RxBuffer == ITM_RXBUFFER_EMPTY) {
+ return (0); /* no character available */
+ } else {
+ return (1); /* character available */
+ }
+}
+
+/*@} end of CMSIS_core_DebugFunctions */
+
+#endif /* __CORE_CM4_H_DEPENDANT */
+
+#endif /* __CMSIS_GENERIC */
+
+#ifdef __cplusplus
+}
+#endif
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/CMSIS/core_cm4_simd.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/CMSIS/core_cm4_simd.h
new file mode 100644
index 00000000..c7e14407
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/CMSIS/core_cm4_simd.h
@@ -0,0 +1,697 @@
+/**************************************************************************//**
+ * @file core_cm4_simd.h
+ * @brief CMSIS Cortex-M4 SIMD Header File
+ * @version V3.30
+ * @date 17. February 2014
+ *
+ * @note
+ *
+ ******************************************************************************/
+/* Copyright (c) 2009 - 2014 ARM LIMITED
+
+ All rights reserved.
+ Redistribution and use in source and binary forms, with or without
+ modification, are permitted provided that the following conditions are met:
+ - Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ - 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.
+ - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
+ ---------------------------------------------------------------------------*/
+
+
+#if defined ( __ICCARM__ )
+#pragma system_include /* treat file as system include file for MISRA check */
+#endif
+
+#ifndef __CORE_CM4_SIMD_H
+#define __CORE_CM4_SIMD_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+
+/*******************************************************************************
+ * Hardware Abstraction Layer
+ ******************************************************************************/
+
+
+/* ################### Compiler specific Intrinsics ########################### */
+/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics
+ Access to dedicated SIMD instructions
+ @{
+*/
+
+#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/
+/* ARM armcc specific functions */
+#define __SADD8 __sadd8
+#define __QADD8 __qadd8
+#define __SHADD8 __shadd8
+#define __UADD8 __uadd8
+#define __UQADD8 __uqadd8
+#define __UHADD8 __uhadd8
+#define __SSUB8 __ssub8
+#define __QSUB8 __qsub8
+#define __SHSUB8 __shsub8
+#define __USUB8 __usub8
+#define __UQSUB8 __uqsub8
+#define __UHSUB8 __uhsub8
+#define __SADD16 __sadd16
+#define __QADD16 __qadd16
+#define __SHADD16 __shadd16
+#define __UADD16 __uadd16
+#define __UQADD16 __uqadd16
+#define __UHADD16 __uhadd16
+#define __SSUB16 __ssub16
+#define __QSUB16 __qsub16
+#define __SHSUB16 __shsub16
+#define __USUB16 __usub16
+#define __UQSUB16 __uqsub16
+#define __UHSUB16 __uhsub16
+#define __SASX __sasx
+#define __QASX __qasx
+#define __SHASX __shasx
+#define __UASX __uasx
+#define __UQASX __uqasx
+#define __UHASX __uhasx
+#define __SSAX __ssax
+#define __QSAX __qsax
+#define __SHSAX __shsax
+#define __USAX __usax
+#define __UQSAX __uqsax
+#define __UHSAX __uhsax
+#define __USAD8 __usad8
+#define __USADA8 __usada8
+#define __SSAT16 __ssat16
+#define __USAT16 __usat16
+#define __UXTB16 __uxtb16
+#define __UXTAB16 __uxtab16
+#define __SXTB16 __sxtb16
+#define __SXTAB16 __sxtab16
+#define __SMUAD __smuad
+#define __SMUADX __smuadx
+#define __SMLAD __smlad
+#define __SMLADX __smladx
+#define __SMLALD __smlald
+#define __SMLALDX __smlaldx
+#define __SMUSD __smusd
+#define __SMUSDX __smusdx
+#define __SMLSD __smlsd
+#define __SMLSDX __smlsdx
+#define __SMLSLD __smlsld
+#define __SMLSLDX __smlsldx
+#define __SEL __sel
+#define __QADD __qadd
+#define __QSUB __qsub
+
+#define __PKHBT(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0x0000FFFFUL) | \
+ ((((uint32_t)(ARG2)) << (ARG3)) & 0xFFFF0000UL) )
+
+#define __PKHTB(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0xFFFF0000UL) | \
+ ((((uint32_t)(ARG2)) >> (ARG3)) & 0x0000FFFFUL) )
+
+#define __SMMLA(ARG1,ARG2,ARG3) ( (int32_t)((((int64_t)(ARG1) * (ARG2)) + \
+ ((int64_t)(ARG3) << 32) ) >> 32))
+
+
+#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/
+/* GNU gcc specific functions */
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __SADD8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("sadd8 %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __QADD8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("qadd8 %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __SHADD8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("shadd8 %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __UADD8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("uadd8 %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __UQADD8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("uqadd8 %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __UHADD8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("uhadd8 %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __SSUB8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("ssub8 %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __QSUB8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("qsub8 %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __SHSUB8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("shsub8 %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __USUB8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("usub8 %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __UQSUB8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("uqsub8 %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __UHSUB8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("uhsub8 %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __SADD16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("sadd16 %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __QADD16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("qadd16 %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __SHADD16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("shadd16 %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __UADD16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("uadd16 %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __UQADD16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("uqadd16 %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __UHADD16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("uhadd16 %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __SSUB16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("ssub16 %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __QSUB16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("qsub16 %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __SHSUB16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("shsub16 %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __USUB16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("usub16 %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __UQSUB16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("uqsub16 %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __UHSUB16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("uhsub16 %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __SASX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("sasx %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __QASX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("qasx %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __SHASX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("shasx %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __UASX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("uasx %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __UQASX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("uqasx %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __UHASX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("uhasx %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __SSAX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("ssax %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __QSAX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("qsax %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __SHSAX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("shsax %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __USAX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("usax %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __UQSAX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("uqsax %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __UHSAX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("uhsax %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __USAD8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("usad8 %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __USADA8(uint32_t op1, uint32_t op2, uint32_t op3)
+{
+ uint32_t result;
+
+ __ASM volatile("usada8 %0, %1, %2, %3" : "=r"(result) : "r"(op1), "r"(op2), "r"(op3));
+ return(result);
+}
+
+#define __SSAT16(ARG1,ARG2) \
+({ \
+ uint32_t __RES, __ARG1 = (ARG1); \
+ __ASM ("ssat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \
+ __RES; \
+ })
+
+#define __USAT16(ARG1,ARG2) \
+({ \
+ uint32_t __RES, __ARG1 = (ARG1); \
+ __ASM ("usat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \
+ __RES; \
+ })
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __UXTB16(uint32_t op1)
+{
+ uint32_t result;
+
+ __ASM volatile("uxtb16 %0, %1" : "=r"(result) : "r"(op1));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __UXTAB16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("uxtab16 %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __SXTB16(uint32_t op1)
+{
+ uint32_t result;
+
+ __ASM volatile("sxtb16 %0, %1" : "=r"(result) : "r"(op1));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __SXTAB16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("sxtab16 %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __SMUAD(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("smuad %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __SMUADX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("smuadx %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __SMLAD(uint32_t op1, uint32_t op2, uint32_t op3)
+{
+ uint32_t result;
+
+ __ASM volatile("smlad %0, %1, %2, %3" : "=r"(result) : "r"(op1), "r"(op2), "r"(op3));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __SMLADX(uint32_t op1, uint32_t op2, uint32_t op3)
+{
+ uint32_t result;
+
+ __ASM volatile("smladx %0, %1, %2, %3" : "=r"(result) : "r"(op1), "r"(op2), "r"(op3));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint64_t __SMLALD(uint32_t op1, uint32_t op2, uint64_t acc)
+{
+ union llreg_u {
+ uint32_t w32[2];
+ uint64_t w64;
+ } llr;
+ llr.w64 = acc;
+
+#ifndef __ARMEB__ // Little endian
+ __ASM volatile("smlald %0, %1, %2, %3" : "=r"(llr.w32[0]), "=r"(llr.w32[1]): "r"(op1), "r"(op2), "0"(llr.w32[0]), "1"(llr.w32[1]));
+#else // Big endian
+ __ASM volatile("smlald %0, %1, %2, %3" : "=r"(llr.w32[1]), "=r"(llr.w32[0]): "r"(op1), "r"(op2), "0"(llr.w32[1]), "1"(llr.w32[0]));
+#endif
+
+ return(llr.w64);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint64_t __SMLALDX(uint32_t op1, uint32_t op2, uint64_t acc)
+{
+ union llreg_u {
+ uint32_t w32[2];
+ uint64_t w64;
+ } llr;
+ llr.w64 = acc;
+
+#ifndef __ARMEB__ // Little endian
+ __ASM volatile("smlaldx %0, %1, %2, %3" : "=r"(llr.w32[0]), "=r"(llr.w32[1]): "r"(op1), "r"(op2), "0"(llr.w32[0]), "1"(llr.w32[1]));
+#else // Big endian
+ __ASM volatile("smlaldx %0, %1, %2, %3" : "=r"(llr.w32[1]), "=r"(llr.w32[0]): "r"(op1), "r"(op2), "0"(llr.w32[1]), "1"(llr.w32[0]));
+#endif
+
+ return(llr.w64);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __SMUSD(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("smusd %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __SMUSDX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("smusdx %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __SMLSD(uint32_t op1, uint32_t op2, uint32_t op3)
+{
+ uint32_t result;
+
+ __ASM volatile("smlsd %0, %1, %2, %3" : "=r"(result) : "r"(op1), "r"(op2), "r"(op3));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __SMLSDX(uint32_t op1, uint32_t op2, uint32_t op3)
+{
+ uint32_t result;
+
+ __ASM volatile("smlsdx %0, %1, %2, %3" : "=r"(result) : "r"(op1), "r"(op2), "r"(op3));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint64_t __SMLSLD(uint32_t op1, uint32_t op2, uint64_t acc)
+{
+ union llreg_u {
+ uint32_t w32[2];
+ uint64_t w64;
+ } llr;
+ llr.w64 = acc;
+
+#ifndef __ARMEB__ // Little endian
+ __ASM volatile("smlsld %0, %1, %2, %3" : "=r"(llr.w32[0]), "=r"(llr.w32[1]): "r"(op1), "r"(op2), "0"(llr.w32[0]), "1"(llr.w32[1]));
+#else // Big endian
+ __ASM volatile("smlsld %0, %1, %2, %3" : "=r"(llr.w32[1]), "=r"(llr.w32[0]): "r"(op1), "r"(op2), "0"(llr.w32[1]), "1"(llr.w32[0]));
+#endif
+
+ return(llr.w64);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint64_t __SMLSLDX(uint32_t op1, uint32_t op2, uint64_t acc)
+{
+ union llreg_u {
+ uint32_t w32[2];
+ uint64_t w64;
+ } llr;
+ llr.w64 = acc;
+
+#ifndef __ARMEB__ // Little endian
+ __ASM volatile("smlsldx %0, %1, %2, %3" : "=r"(llr.w32[0]), "=r"(llr.w32[1]): "r"(op1), "r"(op2), "0"(llr.w32[0]), "1"(llr.w32[1]));
+#else // Big endian
+ __ASM volatile("smlsldx %0, %1, %2, %3" : "=r"(llr.w32[1]), "=r"(llr.w32[0]): "r"(op1), "r"(op2), "0"(llr.w32[1]), "1"(llr.w32[0]));
+#endif
+
+ return(llr.w64);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __SEL(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("sel %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __QADD(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("qadd %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __QSUB(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile("qsub %0, %1, %2" : "=r"(result) : "r"(op1), "r"(op2));
+ return(result);
+}
+
+#define __PKHBT(ARG1,ARG2,ARG3) \
+({ \
+ uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \
+ __ASM ("pkhbt %0, %1, %2, lsl %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \
+ __RES; \
+ })
+
+#define __PKHTB(ARG1,ARG2,ARG3) \
+({ \
+ uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \
+ if (ARG3 == 0) \
+ __ASM ("pkhtb %0, %1, %2" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2) ); \
+ else \
+ __ASM ("pkhtb %0, %1, %2, asr %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \
+ __RES; \
+ })
+
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __SMMLA(int32_t op1, int32_t op2, int32_t op3)
+{
+ int32_t result;
+
+ __ASM volatile("smmla %0, %1, %2, %3" : "=r"(result): "r"(op1), "r"(op2), "r"(op3));
+ return(result);
+}
+
+
+#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/
+/* IAR iccarm specific functions */
+#include
+
+
+#elif defined ( __TMS470__ ) /*---------------- TI CCS Compiler ------------------*/
+/* TI CCS specific functions */
+#include
+
+
+#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/
+/* TASKING carm specific functions */
+/* not yet supported */
+
+
+#elif defined ( __CSMC__ ) /*------------------ COSMIC Compiler -------------------*/
+/* Cosmic specific functions */
+#include
+
+#endif
+
+/*@} end of group CMSIS_SIMD_intrinsics */
+
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __CORE_CM4_SIMD_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/CMSIS/core_cmFunc.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/CMSIS/core_cmFunc.h
new file mode 100644
index 00000000..30c0036c
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/CMSIS/core_cmFunc.h
@@ -0,0 +1,616 @@
+/**************************************************************************//**
+ * @file core_cmFunc.h
+ * @brief CMSIS Cortex-M Core Function Access Header File
+ * @version V3.01
+ * @date 06. March 2012
+ *
+ * @note
+ * Copyright (C) 2009-2012 ARM Limited. All rights reserved.
+ *
+ * @par
+ * ARM Limited (ARM) is supplying this software for use with Cortex-M
+ * processor based microcontrollers. This file can be freely distributed
+ * within development tools that are supporting such ARM based processors.
+ *
+ * @par
+ * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED
+ * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF
+ * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE.
+ * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR
+ * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER.
+ *
+ ******************************************************************************/
+
+#ifndef __CORE_CMFUNC_H
+#define __CORE_CMFUNC_H
+
+
+/* ########################### Core Function Access ########################### */
+/** \ingroup CMSIS_Core_FunctionInterface
+ \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions
+ @{
+ */
+
+#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/
+/* ARM armcc specific functions */
+
+#if (__ARMCC_VERSION < 400677)
+#error "Please use ARM Compiler Toolchain V4.0.677 or later!"
+#endif
+
+/* intrinsic void __enable_irq(); */
+/* intrinsic void __disable_irq(); */
+
+/** \brief Get Control Register
+
+ This function returns the content of the Control Register.
+
+ \return Control Register value
+ */
+__STATIC_INLINE uint32_t __get_CONTROL(void)
+{
+ register uint32_t __regControl __ASM("control");
+ return(__regControl);
+}
+
+
+/** \brief Set Control Register
+
+ This function writes the given value to the Control Register.
+
+ \param [in] control Control Register value to set
+ */
+__STATIC_INLINE void __set_CONTROL(uint32_t control)
+{
+ register uint32_t __regControl __ASM("control");
+ __regControl = control;
+}
+
+
+/** \brief Get IPSR Register
+
+ This function returns the content of the IPSR Register.
+
+ \return IPSR Register value
+ */
+__STATIC_INLINE uint32_t __get_IPSR(void)
+{
+ register uint32_t __regIPSR __ASM("ipsr");
+ return(__regIPSR);
+}
+
+
+/** \brief Get APSR Register
+
+ This function returns the content of the APSR Register.
+
+ \return APSR Register value
+ */
+__STATIC_INLINE uint32_t __get_APSR(void)
+{
+ register uint32_t __regAPSR __ASM("apsr");
+ return(__regAPSR);
+}
+
+
+/** \brief Get xPSR Register
+
+ This function returns the content of the xPSR Register.
+
+ \return xPSR Register value
+ */
+__STATIC_INLINE uint32_t __get_xPSR(void)
+{
+ register uint32_t __regXPSR __ASM("xpsr");
+ return(__regXPSR);
+}
+
+
+/** \brief Get Process Stack Pointer
+
+ This function returns the current value of the Process Stack Pointer (PSP).
+
+ \return PSP Register value
+ */
+__STATIC_INLINE uint32_t __get_PSP(void)
+{
+ register uint32_t __regProcessStackPointer __ASM("psp");
+ return(__regProcessStackPointer);
+}
+
+
+/** \brief Set Process Stack Pointer
+
+ This function assigns the given value to the Process Stack Pointer (PSP).
+
+ \param [in] topOfProcStack Process Stack Pointer value to set
+ */
+__STATIC_INLINE void __set_PSP(uint32_t topOfProcStack)
+{
+ register uint32_t __regProcessStackPointer __ASM("psp");
+ __regProcessStackPointer = topOfProcStack;
+}
+
+
+/** \brief Get Main Stack Pointer
+
+ This function returns the current value of the Main Stack Pointer (MSP).
+
+ \return MSP Register value
+ */
+__STATIC_INLINE uint32_t __get_MSP(void)
+{
+ register uint32_t __regMainStackPointer __ASM("msp");
+ return(__regMainStackPointer);
+}
+
+
+/** \brief Set Main Stack Pointer
+
+ This function assigns the given value to the Main Stack Pointer (MSP).
+
+ \param [in] topOfMainStack Main Stack Pointer value to set
+ */
+__STATIC_INLINE void __set_MSP(uint32_t topOfMainStack)
+{
+ register uint32_t __regMainStackPointer __ASM("msp");
+ __regMainStackPointer = topOfMainStack;
+}
+
+
+/** \brief Get Priority Mask
+
+ This function returns the current state of the priority mask bit from the Priority Mask Register.
+
+ \return Priority Mask value
+ */
+__STATIC_INLINE uint32_t __get_PRIMASK(void)
+{
+ register uint32_t __regPriMask __ASM("primask");
+ return(__regPriMask);
+}
+
+
+/** \brief Set Priority Mask
+
+ This function assigns the given value to the Priority Mask Register.
+
+ \param [in] priMask Priority Mask
+ */
+__STATIC_INLINE void __set_PRIMASK(uint32_t priMask)
+{
+ register uint32_t __regPriMask __ASM("primask");
+ __regPriMask = (priMask);
+}
+
+
+#if (__CORTEX_M >= 0x03)
+
+/** \brief Enable FIQ
+
+ This function enables FIQ interrupts by clearing the F-bit in the CPSR.
+ Can only be executed in Privileged modes.
+ */
+#define __enable_fault_irq __enable_fiq
+
+
+/** \brief Disable FIQ
+
+ This function disables FIQ interrupts by setting the F-bit in the CPSR.
+ Can only be executed in Privileged modes.
+ */
+#define __disable_fault_irq __disable_fiq
+
+
+/** \brief Get Base Priority
+
+ This function returns the current value of the Base Priority register.
+
+ \return Base Priority register value
+ */
+__STATIC_INLINE uint32_t __get_BASEPRI(void)
+{
+ register uint32_t __regBasePri __ASM("basepri");
+ return(__regBasePri);
+}
+
+
+/** \brief Set Base Priority
+
+ This function assigns the given value to the Base Priority register.
+
+ \param [in] basePri Base Priority value to set
+ */
+__STATIC_INLINE void __set_BASEPRI(uint32_t basePri)
+{
+ register uint32_t __regBasePri __ASM("basepri");
+ __regBasePri = (basePri & 0xff);
+}
+
+
+/** \brief Get Fault Mask
+
+ This function returns the current value of the Fault Mask register.
+
+ \return Fault Mask register value
+ */
+__STATIC_INLINE uint32_t __get_FAULTMASK(void)
+{
+ register uint32_t __regFaultMask __ASM("faultmask");
+ return(__regFaultMask);
+}
+
+
+/** \brief Set Fault Mask
+
+ This function assigns the given value to the Fault Mask register.
+
+ \param [in] faultMask Fault Mask value to set
+ */
+__STATIC_INLINE void __set_FAULTMASK(uint32_t faultMask)
+{
+ register uint32_t __regFaultMask __ASM("faultmask");
+ __regFaultMask = (faultMask & (uint32_t)1);
+}
+
+#endif /* (__CORTEX_M >= 0x03) */
+
+
+#if (__CORTEX_M == 0x04)
+
+/** \brief Get FPSCR
+
+ This function returns the current value of the Floating Point Status/Control register.
+
+ \return Floating Point Status/Control register value
+ */
+__STATIC_INLINE uint32_t __get_FPSCR(void)
+{
+#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
+ register uint32_t __regfpscr __ASM("fpscr");
+ return(__regfpscr);
+#else
+ return(0);
+#endif
+}
+
+
+/** \brief Set FPSCR
+
+ This function assigns the given value to the Floating Point Status/Control register.
+
+ \param [in] fpscr Floating Point Status/Control value to set
+ */
+__STATIC_INLINE void __set_FPSCR(uint32_t fpscr)
+{
+#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
+ register uint32_t __regfpscr __ASM("fpscr");
+ __regfpscr = (fpscr);
+#endif
+}
+
+#endif /* (__CORTEX_M == 0x04) */
+
+
+#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/
+/* IAR iccarm specific functions */
+
+#include
+
+
+#elif defined ( __TMS470__ ) /*---------------- TI CCS Compiler ------------------*/
+/* TI CCS specific functions */
+
+#include
+
+
+#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/
+/* GNU gcc specific functions */
+
+/** \brief Enable IRQ Interrupts
+
+ This function enables IRQ interrupts by clearing the I-bit in the CPSR.
+ Can only be executed in Privileged modes.
+ */
+__attribute__((always_inline)) __STATIC_INLINE void __enable_irq(void)
+{
+ __ASM volatile("cpsie i");
+}
+
+
+/** \brief Disable IRQ Interrupts
+
+ This function disables IRQ interrupts by setting the I-bit in the CPSR.
+ Can only be executed in Privileged modes.
+ */
+__attribute__((always_inline)) __STATIC_INLINE void __disable_irq(void)
+{
+ __ASM volatile("cpsid i");
+}
+
+
+/** \brief Get Control Register
+
+ This function returns the content of the Control Register.
+
+ \return Control Register value
+ */
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_CONTROL(void)
+{
+ uint32_t result;
+
+ __ASM volatile("MRS %0, control" : "=r"(result));
+ return(result);
+}
+
+
+/** \brief Set Control Register
+
+ This function writes the given value to the Control Register.
+
+ \param [in] control Control Register value to set
+ */
+__attribute__((always_inline)) __STATIC_INLINE void __set_CONTROL(uint32_t control)
+{
+ __ASM volatile("MSR control, %0" : : "r"(control));
+}
+
+
+/** \brief Get IPSR Register
+
+ This function returns the content of the IPSR Register.
+
+ \return IPSR Register value
+ */
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_IPSR(void)
+{
+ uint32_t result;
+
+ __ASM volatile("MRS %0, ipsr" : "=r"(result));
+ return(result);
+}
+
+
+/** \brief Get APSR Register
+
+ This function returns the content of the APSR Register.
+
+ \return APSR Register value
+ */
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_APSR(void)
+{
+ uint32_t result;
+
+ __ASM volatile("MRS %0, apsr" : "=r"(result));
+ return(result);
+}
+
+
+/** \brief Get xPSR Register
+
+ This function returns the content of the xPSR Register.
+
+ \return xPSR Register value
+ */
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_xPSR(void)
+{
+ uint32_t result;
+
+ __ASM volatile("MRS %0, xpsr" : "=r"(result));
+ return(result);
+}
+
+
+/** \brief Get Process Stack Pointer
+
+ This function returns the current value of the Process Stack Pointer (PSP).
+
+ \return PSP Register value
+ */
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_PSP(void)
+{
+ register uint32_t result;
+
+ __ASM volatile("MRS %0, psp\n" : "=r"(result));
+ return(result);
+}
+
+
+/** \brief Set Process Stack Pointer
+
+ This function assigns the given value to the Process Stack Pointer (PSP).
+
+ \param [in] topOfProcStack Process Stack Pointer value to set
+ */
+__attribute__((always_inline)) __STATIC_INLINE void __set_PSP(uint32_t topOfProcStack)
+{
+ __ASM volatile("MSR psp, %0\n" : : "r"(topOfProcStack));
+}
+
+
+/** \brief Get Main Stack Pointer
+
+ This function returns the current value of the Main Stack Pointer (MSP).
+
+ \return MSP Register value
+ */
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_MSP(void)
+{
+ register uint32_t result;
+
+ __ASM volatile("MRS %0, msp\n" : "=r"(result));
+ return(result);
+}
+
+
+/** \brief Set Main Stack Pointer
+
+ This function assigns the given value to the Main Stack Pointer (MSP).
+
+ \param [in] topOfMainStack Main Stack Pointer value to set
+ */
+__attribute__((always_inline)) __STATIC_INLINE void __set_MSP(uint32_t topOfMainStack)
+{
+ __ASM volatile("MSR msp, %0\n" : : "r"(topOfMainStack));
+}
+
+
+/** \brief Get Priority Mask
+
+ This function returns the current state of the priority mask bit from the Priority Mask Register.
+
+ \return Priority Mask value
+ */
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_PRIMASK(void)
+{
+ uint32_t result;
+
+ __ASM volatile("MRS %0, primask" : "=r"(result));
+ return(result);
+}
+
+
+/** \brief Set Priority Mask
+
+ This function assigns the given value to the Priority Mask Register.
+
+ \param [in] priMask Priority Mask
+ */
+__attribute__((always_inline)) __STATIC_INLINE void __set_PRIMASK(uint32_t priMask)
+{
+ __ASM volatile("MSR primask, %0" : : "r"(priMask));
+}
+
+
+#if (__CORTEX_M >= 0x03)
+
+/** \brief Enable FIQ
+
+ This function enables FIQ interrupts by clearing the F-bit in the CPSR.
+ Can only be executed in Privileged modes.
+ */
+__attribute__((always_inline)) __STATIC_INLINE void __enable_fault_irq(void)
+{
+ __ASM volatile("cpsie f");
+}
+
+
+/** \brief Disable FIQ
+
+ This function disables FIQ interrupts by setting the F-bit in the CPSR.
+ Can only be executed in Privileged modes.
+ */
+__attribute__((always_inline)) __STATIC_INLINE void __disable_fault_irq(void)
+{
+ __ASM volatile("cpsid f");
+}
+
+
+/** \brief Get Base Priority
+
+ This function returns the current value of the Base Priority register.
+
+ \return Base Priority register value
+ */
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_BASEPRI(void)
+{
+ uint32_t result;
+
+ __ASM volatile("MRS %0, basepri_max" : "=r"(result));
+ return(result);
+}
+
+
+/** \brief Set Base Priority
+
+ This function assigns the given value to the Base Priority register.
+
+ \param [in] basePri Base Priority value to set
+ */
+__attribute__((always_inline)) __STATIC_INLINE void __set_BASEPRI(uint32_t value)
+{
+ __ASM volatile("MSR basepri, %0" : : "r"(value));
+}
+
+
+/** \brief Get Fault Mask
+
+ This function returns the current value of the Fault Mask register.
+
+ \return Fault Mask register value
+ */
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_FAULTMASK(void)
+{
+ uint32_t result;
+
+ __ASM volatile("MRS %0, faultmask" : "=r"(result));
+ return(result);
+}
+
+
+/** \brief Set Fault Mask
+
+ This function assigns the given value to the Fault Mask register.
+
+ \param [in] faultMask Fault Mask value to set
+ */
+__attribute__((always_inline)) __STATIC_INLINE void __set_FAULTMASK(uint32_t faultMask)
+{
+ __ASM volatile("MSR faultmask, %0" : : "r"(faultMask));
+}
+
+#endif /* (__CORTEX_M >= 0x03) */
+
+
+#if (__CORTEX_M == 0x04)
+
+/** \brief Get FPSCR
+
+ This function returns the current value of the Floating Point Status/Control register.
+
+ \return Floating Point Status/Control register value
+ */
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_FPSCR(void)
+{
+#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
+ uint32_t result;
+
+ __ASM volatile("VMRS %0, fpscr" : "=r"(result));
+ return(result);
+#else
+ return(0);
+#endif
+}
+
+
+/** \brief Set FPSCR
+
+ This function assigns the given value to the Floating Point Status/Control register.
+
+ \param [in] fpscr Floating Point Status/Control value to set
+ */
+__attribute__((always_inline)) __STATIC_INLINE void __set_FPSCR(uint32_t fpscr)
+{
+#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
+ __ASM volatile("VMSR fpscr, %0" : : "r"(fpscr));
+#endif
+}
+
+#endif /* (__CORTEX_M == 0x04) */
+
+
+#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/
+/* TASKING carm specific functions */
+
+/*
+ * The CMSIS functions have been implemented as intrinsics in the compiler.
+ * Please use "carm -?i" to get an up to date list of all instrinsics,
+ * Including the CMSIS ones.
+ */
+
+#endif
+
+/*@} end of CMSIS_Core_RegAccFunctions */
+
+
+#endif /* __CORE_CMFUNC_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/CMSIS/core_cmInstr.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/CMSIS/core_cmInstr.h
new file mode 100644
index 00000000..b177d6a5
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/CMSIS/core_cmInstr.h
@@ -0,0 +1,618 @@
+/**************************************************************************//**
+ * @file core_cmInstr.h
+ * @brief CMSIS Cortex-M Core Instruction Access Header File
+ * @version V3.01
+ * @date 06. March 2012
+ *
+ * @note
+ * Copyright (C) 2009-2012 ARM Limited. All rights reserved.
+ *
+ * @par
+ * ARM Limited (ARM) is supplying this software for use with Cortex-M
+ * processor based microcontrollers. This file can be freely distributed
+ * within development tools that are supporting such ARM based processors.
+ *
+ * @par
+ * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED
+ * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF
+ * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE.
+ * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR
+ * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER.
+ *
+ ******************************************************************************/
+
+#ifndef __CORE_CMINSTR_H
+#define __CORE_CMINSTR_H
+
+
+/* ########################## Core Instruction Access ######################### */
+/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface
+ Access to dedicated instructions
+ @{
+*/
+
+#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/
+/* ARM armcc specific functions */
+
+#if (__ARMCC_VERSION < 400677)
+#error "Please use ARM Compiler Toolchain V4.0.677 or later!"
+#endif
+
+
+/** \brief No Operation
+
+ No Operation does nothing. This instruction can be used for code alignment purposes.
+ */
+#define __NOP __nop
+
+
+/** \brief Wait For Interrupt
+
+ Wait For Interrupt is a hint instruction that suspends execution
+ until one of a number of events occurs.
+ */
+#define __WFI __wfi
+
+
+/** \brief Wait For Event
+
+ Wait For Event is a hint instruction that permits the processor to enter
+ a low-power state until one of a number of events occurs.
+ */
+#define __WFE __wfe
+
+
+/** \brief Send Event
+
+ Send Event is a hint instruction. It causes an event to be signaled to the CPU.
+ */
+#define __SEV __sev
+
+
+/** \brief Instruction Synchronization Barrier
+
+ Instruction Synchronization Barrier flushes the pipeline in the processor,
+ so that all instructions following the ISB are fetched from cache or
+ memory, after the instruction has been completed.
+ */
+#define __ISB() __isb(0xF)
+
+
+/** \brief Data Synchronization Barrier
+
+ This function acts as a special kind of Data Memory Barrier.
+ It completes when all explicit memory accesses before this instruction complete.
+ */
+#define __DSB() __dsb(0xF)
+
+
+/** \brief Data Memory Barrier
+
+ This function ensures the apparent order of the explicit memory operations before
+ and after the instruction, without ensuring their completion.
+ */
+#define __DMB() __dmb(0xF)
+
+
+/** \brief Reverse byte order (32 bit)
+
+ This function reverses the byte order in integer value.
+
+ \param [in] value Value to reverse
+ \return Reversed value
+ */
+#define __REV __rev
+
+
+/** \brief Reverse byte order (16 bit)
+
+ This function reverses the byte order in two unsigned short values.
+
+ \param [in] value Value to reverse
+ \return Reversed value
+ */
+__attribute__((section(".rev16_text"))) __STATIC_INLINE __ASM uint32_t __REV16(uint32_t value)
+{
+ rev16 r0, r0
+ bx lr
+}
+
+
+/** \brief Reverse byte order in signed short value
+
+ This function reverses the byte order in a signed short value with sign extension to integer.
+
+ \param [in] value Value to reverse
+ \return Reversed value
+ */
+__attribute__((section(".revsh_text"))) __STATIC_INLINE __ASM int32_t __REVSH(int32_t value)
+{
+ revsh r0, r0
+ bx lr
+}
+
+
+/** \brief Rotate Right in unsigned value (32 bit)
+
+ This function Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits.
+
+ \param [in] value Value to rotate
+ \param [in] value Number of Bits to rotate
+ \return Rotated value
+ */
+#define __ROR __ror
+
+
+#if (__CORTEX_M >= 0x03)
+
+/** \brief Reverse bit order of value
+
+ This function reverses the bit order of the given value.
+
+ \param [in] value Value to reverse
+ \return Reversed value
+ */
+#define __RBIT __rbit
+
+
+/** \brief LDR Exclusive (8 bit)
+
+ This function performs a exclusive LDR command for 8 bit value.
+
+ \param [in] ptr Pointer to data
+ \return value of type uint8_t at (*ptr)
+ */
+#define __LDREXB(ptr) ((uint8_t ) __ldrex(ptr))
+
+
+/** \brief LDR Exclusive (16 bit)
+
+ This function performs a exclusive LDR command for 16 bit values.
+
+ \param [in] ptr Pointer to data
+ \return value of type uint16_t at (*ptr)
+ */
+#define __LDREXH(ptr) ((uint16_t) __ldrex(ptr))
+
+
+/** \brief LDR Exclusive (32 bit)
+
+ This function performs a exclusive LDR command for 32 bit values.
+
+ \param [in] ptr Pointer to data
+ \return value of type uint32_t at (*ptr)
+ */
+#define __LDREXW(ptr) ((uint32_t ) __ldrex(ptr))
+
+
+/** \brief STR Exclusive (8 bit)
+
+ This function performs a exclusive STR command for 8 bit values.
+
+ \param [in] value Value to store
+ \param [in] ptr Pointer to location
+ \return 0 Function succeeded
+ \return 1 Function failed
+ */
+#define __STREXB(value, ptr) __strex(value, ptr)
+
+
+/** \brief STR Exclusive (16 bit)
+
+ This function performs a exclusive STR command for 16 bit values.
+
+ \param [in] value Value to store
+ \param [in] ptr Pointer to location
+ \return 0 Function succeeded
+ \return 1 Function failed
+ */
+#define __STREXH(value, ptr) __strex(value, ptr)
+
+
+/** \brief STR Exclusive (32 bit)
+
+ This function performs a exclusive STR command for 32 bit values.
+
+ \param [in] value Value to store
+ \param [in] ptr Pointer to location
+ \return 0 Function succeeded
+ \return 1 Function failed
+ */
+#define __STREXW(value, ptr) __strex(value, ptr)
+
+
+/** \brief Remove the exclusive lock
+
+ This function removes the exclusive lock which is created by LDREX.
+
+ */
+#define __CLREX __clrex
+
+
+/** \brief Signed Saturate
+
+ This function saturates a signed value.
+
+ \param [in] value Value to be saturated
+ \param [in] sat Bit position to saturate to (1..32)
+ \return Saturated value
+ */
+#define __SSAT __ssat
+
+
+/** \brief Unsigned Saturate
+
+ This function saturates an unsigned value.
+
+ \param [in] value Value to be saturated
+ \param [in] sat Bit position to saturate to (0..31)
+ \return Saturated value
+ */
+#define __USAT __usat
+
+
+/** \brief Count leading zeros
+
+ This function counts the number of leading zeros of a data value.
+
+ \param [in] value Value to count the leading zeros
+ \return number of leading zeros in value
+ */
+#define __CLZ __clz
+
+#endif /* (__CORTEX_M >= 0x03) */
+
+
+
+#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/
+/* IAR iccarm specific functions */
+
+#include
+
+
+#elif defined ( __TMS470__ ) /*---------------- TI CCS Compiler ------------------*/
+/* TI CCS specific functions */
+
+#include
+
+
+#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/
+/* GNU gcc specific functions */
+
+/** \brief No Operation
+
+ No Operation does nothing. This instruction can be used for code alignment purposes.
+ */
+__attribute__((always_inline)) __STATIC_INLINE void __NOP(void)
+{
+ __ASM volatile("nop");
+}
+
+
+/** \brief Wait For Interrupt
+
+ Wait For Interrupt is a hint instruction that suspends execution
+ until one of a number of events occurs.
+ */
+__attribute__((always_inline)) __STATIC_INLINE void __WFI(void)
+{
+ __ASM volatile("wfi");
+}
+
+
+/** \brief Wait For Event
+
+ Wait For Event is a hint instruction that permits the processor to enter
+ a low-power state until one of a number of events occurs.
+ */
+__attribute__((always_inline)) __STATIC_INLINE void __WFE(void)
+{
+ __ASM volatile("wfe");
+}
+
+
+/** \brief Send Event
+
+ Send Event is a hint instruction. It causes an event to be signaled to the CPU.
+ */
+__attribute__((always_inline)) __STATIC_INLINE void __SEV(void)
+{
+ __ASM volatile("sev");
+}
+
+
+/** \brief Instruction Synchronization Barrier
+
+ Instruction Synchronization Barrier flushes the pipeline in the processor,
+ so that all instructions following the ISB are fetched from cache or
+ memory, after the instruction has been completed.
+ */
+__attribute__((always_inline)) __STATIC_INLINE void __ISB(void)
+{
+ __ASM volatile("isb");
+}
+
+
+/** \brief Data Synchronization Barrier
+
+ This function acts as a special kind of Data Memory Barrier.
+ It completes when all explicit memory accesses before this instruction complete.
+ */
+__attribute__((always_inline)) __STATIC_INLINE void __DSB(void)
+{
+ __ASM volatile("dsb");
+}
+
+
+/** \brief Data Memory Barrier
+
+ This function ensures the apparent order of the explicit memory operations before
+ and after the instruction, without ensuring their completion.
+ */
+__attribute__((always_inline)) __STATIC_INLINE void __DMB(void)
+{
+ __ASM volatile("dmb");
+}
+
+
+/** \brief Reverse byte order (32 bit)
+
+ This function reverses the byte order in integer value.
+
+ \param [in] value Value to reverse
+ \return Reversed value
+ */
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __REV(uint32_t value)
+{
+ uint32_t result;
+
+ __ASM volatile("rev %0, %1" : "=r"(result) : "r"(value));
+ return(result);
+}
+
+
+/** \brief Reverse byte order (16 bit)
+
+ This function reverses the byte order in two unsigned short values.
+
+ \param [in] value Value to reverse
+ \return Reversed value
+ */
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __REV16(uint32_t value)
+{
+ uint32_t result;
+
+ __ASM volatile("rev16 %0, %1" : "=r"(result) : "r"(value));
+ return(result);
+}
+
+
+/** \brief Reverse byte order in signed short value
+
+ This function reverses the byte order in a signed short value with sign extension to integer.
+
+ \param [in] value Value to reverse
+ \return Reversed value
+ */
+__attribute__((always_inline)) __STATIC_INLINE int32_t __REVSH(int32_t value)
+{
+ uint32_t result;
+
+ __ASM volatile("revsh %0, %1" : "=r"(result) : "r"(value));
+ return(result);
+}
+
+
+/** \brief Rotate Right in unsigned value (32 bit)
+
+ This function Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits.
+
+ \param [in] value Value to rotate
+ \param [in] value Number of Bits to rotate
+ \return Rotated value
+ */
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __ROR(uint32_t op1, uint32_t op2)
+{
+
+ __ASM volatile("ror %0, %0, %1" : "+r"(op1) : "r"(op2));
+ return(op1);
+}
+
+
+#if (__CORTEX_M >= 0x03)
+
+/** \brief Reverse bit order of value
+
+ This function reverses the bit order of the given value.
+
+ \param [in] value Value to reverse
+ \return Reversed value
+ */
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __RBIT(uint32_t value)
+{
+ uint32_t result;
+
+ __ASM volatile("rbit %0, %1" : "=r"(result) : "r"(value));
+ return(result);
+}
+
+
+/** \brief LDR Exclusive (8 bit)
+
+ This function performs a exclusive LDR command for 8 bit value.
+
+ \param [in] ptr Pointer to data
+ \return value of type uint8_t at (*ptr)
+ */
+__attribute__((always_inline)) __STATIC_INLINE uint8_t __LDREXB(volatile uint8_t *addr)
+{
+ uint8_t result;
+
+ __ASM volatile("ldrexb %0, [%1]" : "=r"(result) : "r"(addr));
+ return(result);
+}
+
+
+/** \brief LDR Exclusive (16 bit)
+
+ This function performs a exclusive LDR command for 16 bit values.
+
+ \param [in] ptr Pointer to data
+ \return value of type uint16_t at (*ptr)
+ */
+__attribute__((always_inline)) __STATIC_INLINE uint16_t __LDREXH(volatile uint16_t *addr)
+{
+ uint16_t result;
+
+ __ASM volatile("ldrexh %0, [%1]" : "=r"(result) : "r"(addr));
+ return(result);
+}
+
+
+/** \brief LDR Exclusive (32 bit)
+
+ This function performs a exclusive LDR command for 32 bit values.
+
+ \param [in] ptr Pointer to data
+ \return value of type uint32_t at (*ptr)
+ */
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __LDREXW(volatile uint32_t *addr)
+{
+ uint32_t result;
+
+ __ASM volatile("ldrex %0, [%1]" : "=r"(result) : "r"(addr));
+ return(result);
+}
+
+
+/** \brief STR Exclusive (8 bit)
+
+ This function performs a exclusive STR command for 8 bit values.
+
+ \param [in] value Value to store
+ \param [in] ptr Pointer to location
+ \return 0 Function succeeded
+ \return 1 Function failed
+ */
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __STREXB(uint8_t value, volatile uint8_t *addr)
+{
+ uint32_t result;
+
+ __ASM volatile("strexb %0, %2, [%1]" : "=&r"(result) : "r"(addr), "r"(value));
+ return(result);
+}
+
+
+/** \brief STR Exclusive (16 bit)
+
+ This function performs a exclusive STR command for 16 bit values.
+
+ \param [in] value Value to store
+ \param [in] ptr Pointer to location
+ \return 0 Function succeeded
+ \return 1 Function failed
+ */
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __STREXH(uint16_t value, volatile uint16_t *addr)
+{
+ uint32_t result;
+
+ __ASM volatile("strexh %0, %2, [%1]" : "=&r"(result) : "r"(addr), "r"(value));
+ return(result);
+}
+
+
+/** \brief STR Exclusive (32 bit)
+
+ This function performs a exclusive STR command for 32 bit values.
+
+ \param [in] value Value to store
+ \param [in] ptr Pointer to location
+ \return 0 Function succeeded
+ \return 1 Function failed
+ */
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __STREXW(uint32_t value, volatile uint32_t *addr)
+{
+ uint32_t result;
+
+ __ASM volatile("strex %0, %2, [%1]" : "=&r"(result) : "r"(addr), "r"(value));
+ return(result);
+}
+
+
+/** \brief Remove the exclusive lock
+
+ This function removes the exclusive lock which is created by LDREX.
+
+ */
+__attribute__((always_inline)) __STATIC_INLINE void __CLREX(void)
+{
+ __ASM volatile("clrex");
+}
+
+
+/** \brief Signed Saturate
+
+ This function saturates a signed value.
+
+ \param [in] value Value to be saturated
+ \param [in] sat Bit position to saturate to (1..32)
+ \return Saturated value
+ */
+#define __SSAT(ARG1,ARG2) \
+({ \
+ uint32_t __RES, __ARG1 = (ARG1); \
+ __ASM ("ssat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \
+ __RES; \
+ })
+
+
+/** \brief Unsigned Saturate
+
+ This function saturates an unsigned value.
+
+ \param [in] value Value to be saturated
+ \param [in] sat Bit position to saturate to (0..31)
+ \return Saturated value
+ */
+#define __USAT(ARG1,ARG2) \
+({ \
+ uint32_t __RES, __ARG1 = (ARG1); \
+ __ASM ("usat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \
+ __RES; \
+ })
+
+
+/** \brief Count leading zeros
+
+ This function counts the number of leading zeros of a data value.
+
+ \param [in] value Value to count the leading zeros
+ \return number of leading zeros in value
+ */
+__attribute__((always_inline)) __STATIC_INLINE uint8_t __CLZ(uint32_t value)
+{
+ uint8_t result;
+
+ __ASM volatile("clz %0, %1" : "=r"(result) : "r"(value));
+ return(result);
+}
+
+#endif /* (__CORTEX_M >= 0x03) */
+
+
+
+
+#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/
+/* TASKING carm specific functions */
+
+/*
+ * The CMSIS functions have been implemented as intrinsics in the compiler.
+ * Please use "carm -?i" to get an up to date list of all intrinsics,
+ * Including the CMSIS ones.
+ */
+
+#endif
+
+/*@}*/ /* end of group CMSIS_Core_InstructionInterface */
+
+#endif /* __CORE_CMINSTR_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_adc.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_adc.h
new file mode 100644
index 00000000..fb7df424
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_adc.h
@@ -0,0 +1,367 @@
+/*!
+ \file gd32f3x0_adc.h
+ \brief definitions for the ADC
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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 GD32F3X0_ADC_H
+#define GD32F3X0_ADC_H
+
+#include "gd32f3x0.h"
+
+/* ADC definitions */
+#define ADC ADC_BASE /*!< ADC base address */
+
+/* registers definitions */
+#define ADC_STAT REG32(ADC + 0x00000000U) /*!< ADC status register */
+#define ADC_CTL0 REG32(ADC + 0x00000004U) /*!< ADC control register 0 */
+#define ADC_CTL1 REG32(ADC + 0x00000008U) /*!< ADC control register 1 */
+#define ADC_SAMPT0 REG32(ADC + 0x0000000CU) /*!< ADC sample time register 0 */
+#define ADC_SAMPT1 REG32(ADC + 0x00000010U) /*!< ADC sample time register 1 */
+#define ADC_IOFF0 REG32(ADC + 0x00000014U) /*!< ADC inserted channel data offset register 0 */
+#define ADC_IOFF1 REG32(ADC + 0x00000018U) /*!< ADC inserted channel data offset register 1 */
+#define ADC_IOFF2 REG32(ADC + 0x0000001CU) /*!< ADC inserted channel data offset register 2 */
+#define ADC_IOFF3 REG32(ADC + 0x00000020U) /*!< ADC inserted channel data offset register 3 */
+#define ADC_WDHT REG32(ADC + 0x00000024U) /*!< ADC watchdog high threshold register */
+#define ADC_WDLT REG32(ADC + 0x00000028U) /*!< ADC watchdog low threshold register */
+#define ADC_RSQ0 REG32(ADC + 0x0000002CU) /*!< ADC regular sequence register 0 */
+#define ADC_RSQ1 REG32(ADC + 0x00000030U) /*!< ADC regular sequence register 1 */
+#define ADC_RSQ2 REG32(ADC + 0x00000034U) /*!< ADC regular sequence register 2 */
+#define ADC_ISQ REG32(ADC + 0x00000038U) /*!< ADC inserted sequence register */
+#define ADC_IDATA0 REG32(ADC + 0x0000003CU) /*!< ADC inserted data register 0 */
+#define ADC_IDATA1 REG32(ADC + 0x00000040U) /*!< ADC inserted data register 1 */
+#define ADC_IDATA2 REG32(ADC + 0x00000044U) /*!< ADC inserted data register 2 */
+#define ADC_IDATA3 REG32(ADC + 0x00000048U) /*!< ADC inserted data register 3 */
+#define ADC_RDATA REG32(ADC + 0x0000004CU) /*!< ADC regular data register */
+#define ADC_OVSAMPCTL REG32(ADC + 0x00000080U) /*!< ADC oversampling control register */
+
+/* bits definitions */
+/* ADC_STAT */
+#define ADC_STAT_WDE BIT(0) /*!< analog watchdog event flag */
+#define ADC_STAT_EOC BIT(1) /*!< end of conversion flag */
+#define ADC_STAT_EOIC BIT(2) /*!< inserted channel end of conversion flag */
+#define ADC_STAT_STIC BIT(3) /*!< inserted channel start flag */
+#define ADC_STAT_STRC BIT(4) /*!< regular channel start flag */
+
+/* ADC_CTL0 */
+#define ADC_CTL0_WDCHSEL BITS(0,4) /*!< analog watchdog channel select bits */
+#define ADC_CTL0_EOCIE BIT(5) /*!< interrupt enable for EOC */
+#define ADC_CTL0_WDEIE BIT(6) /*!< analog watchdog interrupt enable */
+#define ADC_CTL0_EOICIE BIT(7) /*!< interrupt enable for inserted channels */
+#define ADC_CTL0_SM BIT(8) /*!< scan mode */
+#define ADC_CTL0_WDSC BIT(9) /*!< when in scan mode, analog watchdog is effective on a single channel */
+#define ADC_CTL0_ICA BIT(10) /*!< automatic inserted group conversion */
+#define ADC_CTL0_DISRC BIT(11) /*!< discontinuous mode on regular channels */
+#define ADC_CTL0_DISIC BIT(12) /*!< discontinuous mode on inserted channels */
+#define ADC_CTL0_DISNUM BITS(13,15) /*!< discontinuous mode channel count */
+#define ADC_CTL0_IWDEN BIT(22) /*!< analog watchdog enable on inserted channels */
+#define ADC_CTL0_RWDEN BIT(23) /*!< analog watchdog enable on regular channels */
+#define ADC_CTL0_DRES BITS(24,25) /*!< ADC data resolution */
+
+/* ADC_CTL1 */
+#define ADC_CTL1_ADCON BIT(0) /*!< ADC converter on */
+#define ADC_CTL1_CTN BIT(1) /*!< continuous conversion */
+#define ADC_CTL1_CLB BIT(2) /*!< ADC calibration */
+#define ADC_CTL1_RSTCLB BIT(3) /*!< reset calibration */
+#define ADC_CTL1_DMA BIT(8) /*!< direct memory access mode */
+#define ADC_CTL1_DAL BIT(11) /*!< data alignment */
+#define ADC_CTL1_ETSIC BITS(12,14) /*!< external trigger select for inserted channel */
+#define ADC_CTL1_ETEIC BIT(15) /*!< external trigger enable for inserted channel */
+#define ADC_CTL1_ETSRC BITS(17,19) /*!< external trigger select for regular channel */
+#define ADC_CTL1_ETERC BIT(20) /*!< external trigger enable for regular channel */
+#define ADC_CTL1_SWICST BIT(21) /*!< start on inserted channel */
+#define ADC_CTL1_SWRCST BIT(22) /*!< start on regular channel */
+#define ADC_CTL1_TSVREN BIT(23) /*!< enable channel 16 and 17 */
+#define ADC_CTL1_VBETEN BIT(24) /*!< VBAT enable */
+
+/* ADC_SAMPTx x=0,1 */
+#define ADC_SAMPTX_SPTN BITS(0,2) /*!< channel n(n=0..18) sample time selection */
+
+/* ADC_IOFFx x=0..3 */
+#define ADC_IOFFX_IOFF BITS(0,11) /*!< data offset for inserted channel x */
+
+/* ADC_WDHT */
+#define ADC_WDHT_WDHT BITS(0,11) /*!< analog watchdog high threshold */
+
+/* ADC_WDLT */
+#define ADC_WDLT_WDLT BITS(0,11) /*!< analog watchdog low threshold */
+
+/* ADC_RSQx x=0..2 */
+#define ADC_RSQX_RSQN BITS(0,4) /*!< n conversion in regular sequence */
+#define ADC_RSQ0_RL BITS(20,23) /*!< regular channel sequence length */
+
+/* ADC_ISQ */
+#define ADC_ISQ_ISQN BITS(0,4) /*!< n conversion in regular sequence */
+#define ADC_ISQ_IL BITS(20,21) /*!< inserted sequence length */
+
+/* ADC_IDATAx x=0..3 */
+#define ADC_IDATAX_IDATAN BITS(0,15) /*!< inserted channel x conversion data */
+
+/* ADC_RDATA */
+#define ADC_RDATA_RDATA BITS(0,15) /*!< regular channel data */
+
+/* ADC_OVSAMPCTL */
+#define ADC_OVSAMPCTL_OVSEN BIT(0) /*!< oversampling enable */
+#define ADC_OVSAMPCTL_OVSR BITS(2,4) /*!< oversampling ratio */
+#define ADC_OVSAMPCTL_OVSS BITS(5,8) /*!< oversampling shift */
+#define ADC_OVSAMPCTL_TOVS BIT(9) /*!< triggered oversampling */
+
+/* constants definitions */
+/* ADC flag definitions */
+#define ADC_FLAG_WDE ADC_STAT_WDE /*!< analog watchdog event flag */
+#define ADC_FLAG_EOC ADC_STAT_EOC /*!< end of group conversion flag */
+#define ADC_FLAG_EOIC ADC_STAT_EOIC /*!< end of inserted channel group conversion flag */
+#define ADC_FLAG_STIC ADC_STAT_STIC /*!< start flag of inserted channel group */
+#define ADC_FLAG_STRC ADC_STAT_STRC /*!< start flag of regular channel group */
+
+/* adc_ctl0 register value */
+#define CTL0_DISNUM(regval) (BITS(13,15) & ((uint32_t)(regval) << 13)) /*!< number of conversions in discontinuous mode */
+
+/* ADC special function */
+#define ADC_SCAN_MODE ADC_CTL0_SM /*!< scan mode */
+#define ADC_INSERTED_CHANNEL_AUTO ADC_CTL0_ICA /*!< inserted channel group convert automatically */
+#define ADC_CONTINUOUS_MODE ADC_CTL1_CTN /*!< continuous mode */
+
+/* ADC data alignment */
+#define ADC_DATAALIGN_RIGHT ((uint32_t)0x00000000U) /*!< right alignment */
+#define ADC_DATAALIGN_LEFT ADC_CTL1_DAL /*!< left alignment */
+
+/* external trigger select for regular channel */
+#define CTL1_ETSRC(regval) (BITS(17,19) & ((uint32_t)(regval) << 17))
+#define ADC_EXTTRIG_REGULAR_T0_CH0 CTL1_ETSRC(0) /*!< TIMER0 CH0 event select */
+#define ADC_EXTTRIG_REGULAR_T0_CH1 CTL1_ETSRC(1) /*!< TIMER0 CH1 event select */
+#define ADC_EXTTRIG_REGULAR_T0_CH2 CTL1_ETSRC(2) /*!< TIMER0 CH2 event select */
+#define ADC_EXTTRIG_REGULAR_T1_CH1 CTL1_ETSRC(3) /*!< TIMER1 CH1 event select */
+#define ADC_EXTTRIG_REGULAR_T2_TRGO CTL1_ETSRC(4) /*!< TIMER2 TRGO event select */
+#define ADC_EXTTRIG_REGULAR_T14_CH0 CTL1_ETSRC(5) /*!< TIMER14 CH0 event select */
+#define ADC_EXTTRIG_REGULAR_EXTI_11 CTL1_ETSRC(6) /*!< external interrupt line 11 */
+#define ADC_EXTTRIG_REGULAR_NONE CTL1_ETSRC(7) /*!< software trigger */
+
+/* external trigger select for inserted channel */
+#define CTL1_ETSIC(regval) (BITS(12,14) & ((uint32_t)(regval) << 12))
+#define ADC_EXTTRIG_INSERTED_T0_TRGO CTL1_ETSIC(0) /*!< TIMER0 TRGO event select */
+#define ADC_EXTTRIG_INSERTED_T0_CH3 CTL1_ETSIC(1) /*!< TIMER0 CH3 event select */
+#define ADC_EXTTRIG_INSERTED_T1_TRGO CTL1_ETSIC(2) /*!< TIMER1 TRGO event select */
+#define ADC_EXTTRIG_INSERTED_T1_CH0 CTL1_ETSIC(3) /*!< TIMER1 CH0 event select */
+#define ADC_EXTTRIG_INSERTED_T2_CH3 CTL1_ETSIC(4) /*!< TIMER2 CH3 event select */
+#define ADC_EXTTRIG_INSERTED_T14_TRGO CTL1_ETSIC(5) /*!< TIMER14 TRGO event select */
+#define ADC_EXTTRIG_INSERTED_EXTI_15 CTL1_ETSIC(6) /*!< external interrupt line 15 */
+#define ADC_EXTTRIG_INSERTED_NONE CTL1_ETSIC(7) /*!< software trigger */
+
+/* adc_samptx register value */
+#define SAMPTX_SPT(regval) (BITS(0,2) & ((uint32_t)(regval) << 0))
+#define ADC_SAMPLETIME_1POINT5 SAMPTX_SPT(0) /*!< 1.5 sampling cycles */
+#define ADC_SAMPLETIME_7POINT5 SAMPTX_SPT(1) /*!< 7.5 sampling cycles */
+#define ADC_SAMPLETIME_13POINT5 SAMPTX_SPT(2) /*!< 13.5 sampling cycles */
+#define ADC_SAMPLETIME_28POINT5 SAMPTX_SPT(3) /*!< 28.5 sampling cycles */
+#define ADC_SAMPLETIME_41POINT5 SAMPTX_SPT(4) /*!< 41.5 sampling cycles */
+#define ADC_SAMPLETIME_55POINT5 SAMPTX_SPT(5) /*!< 55.5 sampling cycles */
+#define ADC_SAMPLETIME_71POINT5 SAMPTX_SPT(6) /*!< 71.5 sampling cycles */
+#define ADC_SAMPLETIME_239POINT5 SAMPTX_SPT(7) /*!< 239.5 sampling cycles */
+
+/* ADC data offset for inserted channel x */
+#define IOFFX_IOFF(regval) (BITS(0,11) & ((uint32_t)(regval) << 0))
+
+/* ADC analog watchdog high threshold */
+#define WDHT_WDHT(regval) (BITS(0,11) & ((uint32_t)(regval) << 0))
+
+/* ADC analog watchdog low threshold */
+#define WDLT_WDLT(regval) (BITS(0,11) & ((uint32_t)(regval) << 0))
+
+/* ADC regular channel group length */
+#define RSQ0_RL(regval) (BITS(20,23) & ((uint32_t)(regval) << 20))
+
+/* ADC inserted channel group length */
+#define ISQ_IL(regval) (BITS(20,21) & ((uint32_t)(regval) << 20))
+
+/* ADC resolution definitions */
+#define CTL0_DRES(regval) (BITS(24,25) & ((uint32_t)(regval) << 24)) /*!< ADC resolution */
+#define ADC_RESOLUTION_12B CTL0_DRES(0) /*!< 12-bit ADC resolution */
+#define ADC_RESOLUTION_10B CTL0_DRES(1) /*!< 10-bit ADC resolution */
+#define ADC_RESOLUTION_8B CTL0_DRES(2) /*!< 8-bit ADC resolution */
+#define ADC_RESOLUTION_6B CTL0_DRES(3) /*!< 6-bit ADC resolution */
+
+/* ADC oversampling shift */
+#define OVSAMPCTL_OVSS(regval) (BITS(5,8) & ((uint32_t)(regval) << 5))
+#define ADC_OVERSAMPLING_SHIFT_NONE OVSAMPCTL_OVSS(0) /*!< no oversampling shift */
+#define ADC_OVERSAMPLING_SHIFT_1B OVSAMPCTL_OVSS(1) /*!< 1-bit oversampling shift */
+#define ADC_OVERSAMPLING_SHIFT_2B OVSAMPCTL_OVSS(2) /*!< 2-bit oversampling shift */
+#define ADC_OVERSAMPLING_SHIFT_3B OVSAMPCTL_OVSS(3) /*!< 3-bit oversampling shift */
+#define ADC_OVERSAMPLING_SHIFT_4B OVSAMPCTL_OVSS(4) /*!< 4-bit oversampling shift */
+#define ADC_OVERSAMPLING_SHIFT_5B OVSAMPCTL_OVSS(5) /*!< 5-bit oversampling shift */
+#define ADC_OVERSAMPLING_SHIFT_6B OVSAMPCTL_OVSS(6) /*!< 6-bit oversampling shift */
+#define ADC_OVERSAMPLING_SHIFT_7B OVSAMPCTL_OVSS(7) /*!< 7-bit oversampling shift */
+#define ADC_OVERSAMPLING_SHIFT_8B OVSAMPCTL_OVSS(8) /*!< 8-bit oversampling shift */
+
+/* ADC oversampling ratio */
+#define OVSAMPCTL_OVSR(regval) (BITS(2,4) & ((uint32_t)(regval) << 2))
+#define ADC_OVERSAMPLING_RATIO_MUL2 OVSAMPCTL_OVSR(0) /*!< oversampling ratio multiple 2 */
+#define ADC_OVERSAMPLING_RATIO_MUL4 OVSAMPCTL_OVSR(1) /*!< oversampling ratio multiple 4 */
+#define ADC_OVERSAMPLING_RATIO_MUL8 OVSAMPCTL_OVSR(2) /*!< oversampling ratio multiple 8 */
+#define ADC_OVERSAMPLING_RATIO_MUL16 OVSAMPCTL_OVSR(3) /*!< oversampling ratio multiple 16 */
+#define ADC_OVERSAMPLING_RATIO_MUL32 OVSAMPCTL_OVSR(4) /*!< oversampling ratio multiple 32 */
+#define ADC_OVERSAMPLING_RATIO_MUL64 OVSAMPCTL_OVSR(5) /*!< oversampling ratio multiple 64 */
+#define ADC_OVERSAMPLING_RATIO_MUL128 OVSAMPCTL_OVSR(6) /*!< oversampling ratio multiple 128 */
+#define ADC_OVERSAMPLING_RATIO_MUL256 OVSAMPCTL_OVSR(7) /*!< oversampling ratio multiple 256 */
+
+/* ADC triggered oversampling */
+#define ADC_OVERSAMPLING_ALL_CONVERT 0U /*!< all oversampled conversions for a channel are done consecutively after a trigger */
+#define ADC_OVERSAMPLING_ONE_CONVERT 1U /*!< each oversampled conversion for a channel needs a trigger */
+
+/* ADC channel group definitions */
+#define ADC_REGULAR_CHANNEL ((uint8_t)0x01U) /*!< ADC regular channel group */
+#define ADC_INSERTED_CHANNEL ((uint8_t)0x02U) /*!< ADC inserted channel group */
+#define ADC_REGULAR_INSERTED_CHANNEL ((uint8_t)0x03U) /*!< both regular and inserted channel group */
+#define ADC_CHANNEL_DISCON_DISABLE ((uint8_t)0x04U) /*!< disable discontinuous mode of regular & inserted channel */
+
+/* ADC inserted channel definitions */
+#define ADC_INSERTED_CHANNEL_0 ((uint8_t)0x00U) /*!< ADC inserted channel 0 */
+#define ADC_INSERTED_CHANNEL_1 ((uint8_t)0x01U) /*!< ADC inserted channel 1 */
+#define ADC_INSERTED_CHANNEL_2 ((uint8_t)0x02U) /*!< ADC inserted channel 2 */
+#define ADC_INSERTED_CHANNEL_3 ((uint8_t)0x03U) /*!< ADC inserted channel 3 */
+
+/* ADC channel definitions */
+#define ADC_CHANNEL_0 ((uint8_t)0x00U) /*!< ADC channel 0 */
+#define ADC_CHANNEL_1 ((uint8_t)0x01U) /*!< ADC channel 1 */
+#define ADC_CHANNEL_2 ((uint8_t)0x02U) /*!< ADC channel 2 */
+#define ADC_CHANNEL_3 ((uint8_t)0x03U) /*!< ADC channel 3 */
+#define ADC_CHANNEL_4 ((uint8_t)0x04U) /*!< ADC channel 4 */
+#define ADC_CHANNEL_5 ((uint8_t)0x05U) /*!< ADC channel 5 */
+#define ADC_CHANNEL_6 ((uint8_t)0x06U) /*!< ADC channel 6 */
+#define ADC_CHANNEL_7 ((uint8_t)0x07U) /*!< ADC channel 7 */
+#define ADC_CHANNEL_8 ((uint8_t)0x08U) /*!< ADC channel 8 */
+#define ADC_CHANNEL_9 ((uint8_t)0x09U) /*!< ADC channel 9 */
+#define ADC_CHANNEL_10 ((uint8_t)0x0AU) /*!< ADC channel 10 */
+#define ADC_CHANNEL_11 ((uint8_t)0x0BU) /*!< ADC channel 11 */
+#define ADC_CHANNEL_12 ((uint8_t)0x0CU) /*!< ADC channel 12 */
+#define ADC_CHANNEL_13 ((uint8_t)0x0DU) /*!< ADC channel 13 */
+#define ADC_CHANNEL_14 ((uint8_t)0x0EU) /*!< ADC channel 14 */
+#define ADC_CHANNEL_15 ((uint8_t)0x0FU) /*!< ADC channel 15 */
+#define ADC_CHANNEL_16 ((uint8_t)0x10U) /*!< ADC channel 16 */
+#define ADC_CHANNEL_17 ((uint8_t)0x11U) /*!< ADC channel 17 */
+#define ADC_CHANNEL_18 ((uint8_t)0x12U) /*!< ADC channel 18 */
+
+/* ADC interrupt definitions */
+#define ADC_INT_WDE ADC_STAT_WDE /*!< analog watchdog event interrupt */
+#define ADC_INT_EOC ADC_STAT_EOC /*!< end of group conversion interrupt */
+#define ADC_INT_EOIC ADC_STAT_EOIC /*!< end of inserted group conversion interrupt */
+
+/* ADC interrupt flag */
+#define ADC_INT_FLAG_WDE ADC_STAT_WDE /*!< analog watchdog event interrupt flag */
+#define ADC_INT_FLAG_EOC ADC_STAT_EOC /*!< end of group conversion interrupt flag */
+#define ADC_INT_FLAG_EOIC ADC_STAT_EOIC /*!< end of inserted group conversion interrupt flag */
+
+/* function declarations */
+/* reset ADC */
+void adc_deinit(void);
+/* enable ADC interface */
+void adc_enable(void);
+/* disable ADC interface */
+void adc_disable(void);
+
+/* ADC calibration and reset calibration */
+void adc_calibration_enable(void);
+/* enable DMA request */
+void adc_dma_mode_enable(void);
+/* disable DMA request */
+void adc_dma_mode_disable(void);
+
+/* enable the temperature sensor and Vrefint channel */
+void adc_tempsensor_vrefint_enable(void);
+/* disable the temperature sensor and Vrefint channel */
+void adc_tempsensor_vrefint_disable(void);
+/* enable the Vbat channel */
+void adc_vbat_enable(void);
+/* disable the Vbat channel */
+void adc_vbat_disable(void);
+
+/* configure ADC discontinuous mode */
+void adc_discontinuous_mode_config(uint8_t channel_group, uint8_t length);
+/* enable or disable ADC special function */
+void adc_special_function_config(uint32_t function, ControlStatus newvalue);
+
+/* configure ADC data alignment */
+void adc_data_alignment_config(uint32_t data_alignment);
+/* configure the length of regular channel group or inserted channel group */
+void adc_channel_length_config(uint8_t channel_group, uint32_t length);
+/* configure ADC regular channel */
+void adc_regular_channel_config(uint8_t rank, uint8_t channel, uint32_t sample_time);
+/* configure ADC inserted channel */
+void adc_inserted_channel_config(uint8_t rank, uint8_t channel, uint32_t sample_time);
+/* configure ADC inserted channel offset */
+void adc_inserted_channel_offset_config(uint8_t inserted_channel, uint16_t offset);
+/* enable ADC external trigger */
+void adc_external_trigger_config(uint8_t channel_group, ControlStatus newvalue);
+/* configure ADC external trigger source */
+void adc_external_trigger_source_config(uint8_t channel_group, uint32_t external_trigger_source);
+/* enable ADC software trigger */
+void adc_software_trigger_enable(uint8_t channel_group);
+
+/* read ADC regular group data register */
+uint16_t adc_regular_data_read(void);
+/* read ADC inserted group data register */
+uint16_t adc_inserted_data_read(uint8_t inserted_channel);
+
+/* configure ADC analog watchdog single channel */
+void adc_watchdog_single_channel_enable(uint8_t channel);
+/* configure ADC analog watchdog group channel */
+void adc_watchdog_group_channel_enable(uint8_t channel_group);
+/* disable ADC analog watchdog */
+void adc_watchdog_disable(void);
+/* configure ADC analog watchdog threshold */
+void adc_watchdog_threshold_config(uint16_t low_threshold, uint16_t high_threshold);
+
+/* configure ADC resolution */
+void adc_resolution_config(uint32_t resolution);
+/* configure ADC oversample mode */
+void adc_oversample_mode_config(uint8_t mode, uint16_t shift, uint8_t ratio);
+/* enable ADC oversample mode */
+void adc_oversample_mode_enable(void);
+/* disable ADC oversample mode */
+void adc_oversample_mode_disable(void);
+
+/* get the ADC flag bits */
+FlagStatus adc_flag_get(uint32_t flag);
+/* clear the ADC flag bits */
+void adc_flag_clear(uint32_t flag);
+/* enable ADC interrupt */
+void adc_interrupt_enable(uint32_t interrupt);
+/* disable ADC interrupt */
+void adc_interrupt_disable(uint32_t interrupt);
+/* get the ADC interrupt bits */
+FlagStatus adc_interrupt_flag_get(uint32_t flag);
+/* clear the ADC interrupt flag */
+void adc_interrupt_flag_clear(uint32_t flag);
+
+#endif /* GD32F3X0_ADC_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_cec.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_cec.h
new file mode 100644
index 00000000..2c5f15da
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_cec.h
@@ -0,0 +1,252 @@
+/*!
+ \file gd32f3x0_cec.h
+ \brief definitions for the CEC
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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.
+*/
+
+#ifdef GD32F350
+
+#ifndef GD32F3X0_CEC_H
+#define GD32F3X0_CEC_H
+
+#include "gd32f3x0.h"
+
+/* CEC definitions */
+#define CEC CEC_BASE /*!< CEC base address */
+
+/* registers definitions */
+#define CEC_CTL REG32(CEC + 0x00000000U) /*!< CEC control register */
+#define CEC_CFG REG32(CEC + 0x00000004U) /*!< CEC configuration register */
+#define CEC_TDATA REG32(CEC + 0x00000008U) /*!< CEC transmit data register */
+#define CEC_RDATA REG32(CEC + 0x0000000CU) /*!< CEC receive data register */
+#define CEC_INTF REG32(CEC + 0x00000010U) /*!< CEC interrupt flag Register */
+#define CEC_INTEN REG32(CEC + 0x00000014U) /*!< CEC interrupt enable register */
+
+/* bits definitions */
+/* CEC_CTL */
+#define CEC_CTL_CECEN BIT(0) /*!< enable or disable HDMI-CEC controller bit */
+#define CEC_CTL_STAOM BIT(1) /*!< start of sending a message. */
+#define CEC_CTL_ENDOM BIT(2) /*!< ENDOM bit value in the next frame in Tx mode */
+
+/* CEC_CFG */
+#define CEC_CFG_SFT BITS(0,2) /*!< signal free time */
+#define CEC_CFG_RTOL BIT(3) /*!< reception bit timing tolerance */
+#define CEC_CFG_BRES BIT(4) /*!< whether stop receive message when detected BRE */
+#define CEC_CFG_BREG BIT(5) /*!< generate Error-bit when detected BRE in singlecast */
+#define CEC_CFG_BPLEG BIT(6) /*!< generate Error-bit when detected BPLE in singlecast */
+#define CEC_CFG_BCNG BIT(7) /*!< do not generate Error-bit in broadcast message */
+#define CEC_CFG_SFTOPT BIT(8) /*!< the SFT start option bit */
+#define CEC_CFG_OAD BITS(16,30) /*!< own address */
+#define CEC_CFG_LMEN BIT(31) /*!< listen mode enable bit */
+
+/* CEC_TDATA */
+#define CEC_TDATA_TDATA BITS(0,7) /*!< Tx data register */
+
+/* CEC_RDATA */
+#define CEC_RDATA_RDATA BITS(0,7) /*!< Rx data register */
+
+/* CEC_INTF */
+#define CEC_INTF_BR BIT(0) /*!< Rx-byte data received */
+#define CEC_INTF_REND BIT(1) /*!< end of reception */
+#define CEC_INTF_RO BIT(2) /*!< Rx overrun */
+#define CEC_INTF_BRE BIT(3) /*!< bit rising error */
+#define CEC_INTF_BPSE BIT(4) /*!< short bit period error */
+#define CEC_INTF_BPLE BIT(5) /*!< long bit period error */
+#define CEC_INTF_RAE BIT(6) /*!< Rx ACK error */
+#define CEC_INTF_ARBF BIT(7) /*!< arbitration fail */
+#define CEC_INTF_TBR BIT(8) /*!< Tx-byte data request */
+#define CEC_INTF_TEND BIT(9) /*!< transmission successfully end */
+#define CEC_INTF_TU BIT(10) /*!< Tx data buffer underrun */
+#define CEC_INTF_TERR BIT(11) /*!< Tx-error */
+#define CEC_INTF_TAERR BIT(12) /*!< Tx ACK error flag */
+
+/* CEC_INTEN */
+#define CEC_INTEN_BRIE BIT(0) /*!< BR interrupt enable */
+#define CEC_INTEN_RENDIE BIT(1) /*!< REND interrupt enable */
+#define CEC_INTEN_ROIE BIT(2) /*!< RO interrupt enable */
+#define CEC_INTEN_BREIE BIT(3) /*!< BRE interrupt enable. */
+#define CEC_INTEN_BPSEIE BIT(4) /*!< BPSE interrupt enable */
+#define CEC_INTEN_BPLEIE BIT(5) /*!< BPLE interrupt enable. */
+#define CEC_INTEN_RAEIE BIT(6) /*!< RAE interrupt enable */
+#define CEC_INTEN_ARBFIE BIT(7) /*!< ARBF interrupt enable */
+#define CEC_INTEN_TBRIE BIT(8) /*!< TBR interrupt enable */
+#define CEC_INTEN_TENDIE BIT(9) /*!< TEND interrupt enable */
+#define CEC_INTEN_TUIE BIT(10) /*!< TU interrupt enable */
+#define CEC_INTEN_TERRIE BIT(11) /*!< TE interrupt enable */
+#define CEC_INTEN_TAERRIE BIT(12) /*!< TAE interrupt enable */
+
+/* constants definitions */
+/* signal free time */
+#define CFG_SFT(regval) (BITS(0, 2) & ((regval) << 0U))
+#define CEC_SFT_PROTOCOL_PERIOD CFG_SFT(0) /*!< the signal free time will perform as HDMI-CEC protocol description */
+#define CEC_SFT_1POINT5_PERIOD CFG_SFT(1) /*!< 1.5 nominal data bit periods */
+#define CEC_SFT_2POINT5_PERIOD CFG_SFT(2) /*!< 2.5 nominal data bit periods */
+#define CEC_SFT_3POINT5_PERIOD CFG_SFT(3) /*!< 3.5 nominal data bit periods */
+#define CEC_SFT_4POINT5_PERIOD CFG_SFT(4) /*!< 4.5 nominal data bit periods */
+#define CEC_SFT_5POINT5_PERIOD CFG_SFT(5) /*!< 5.5 nominal data bit periods */
+#define CEC_SFT_6POINT5_PERIOD CFG_SFT(6) /*!< 6.5 nominal data bit periods */
+#define CEC_SFT_7POINT5_PERIOD CFG_SFT(7) /*!< 7.5 nominal data bit periods */
+
+/* signal free time start option */
+#define CEC_SFT_START_STAOM ((uint32_t)0x00000000U) /*!< signal free time counter starts counting when STAOM is asserted */
+#define CEC_SFT_START_LAST CEC_CFG_SFTOPT /*!< signal free time counter starts automatically after transmission/reception end */
+
+/* own address */
+#define CEC_OWN_ADDRESS_CLEAR ((uint32_t)0x00000000U) /*!< own address is cleared */
+#define CEC_OWN_ADDRESS0 BIT(16) /*!< own address is 0 */
+#define CEC_OWN_ADDRESS1 BIT(17) /*!< own address is 1 */
+#define CEC_OWN_ADDRESS2 BIT(18) /*!< own address is 2 */
+#define CEC_OWN_ADDRESS3 BIT(19) /*!< own address is 3 */
+#define CEC_OWN_ADDRESS4 BIT(20) /*!< own address is 4 */
+#define CEC_OWN_ADDRESS5 BIT(21) /*!< own address is 5 */
+#define CEC_OWN_ADDRESS6 BIT(22) /*!< own address is 6 */
+#define CEC_OWN_ADDRESS7 BIT(23) /*!< own address is 7 */
+#define CEC_OWN_ADDRESS8 BIT(24) /*!< own address is 8 */
+#define CEC_OWN_ADDRESS9 BIT(25) /*!< own address is 9 */
+#define CEC_OWN_ADDRESS10 BIT(26) /*!< own address is 10 */
+#define CEC_OWN_ADDRESS11 BIT(27) /*!< own address is 11 */
+#define CEC_OWN_ADDRESS12 BIT(28) /*!< own address is 12 */
+#define CEC_OWN_ADDRESS13 BIT(29) /*!< own address is 13 */
+#define CEC_OWN_ADDRESS14 BIT(30) /*!< own address is 14 */
+
+/* error-bit generate */
+#define CEC_BROADCAST_ERROR_BIT_ON ((uint32_t)0x00000000U) /*!< generate Error-bit in broadcast */
+#define CEC_BROADCAST_ERROR_BIT_OFF CEC_CFG_BCNG /*!< do not generate Error-bit in broadcast */
+#define CEC_LONG_PERIOD_ERROR_BIT_OFF ((uint32_t)0x00000000U) /*!< generate Error-bit on long bit period error */
+#define CEC_LONG_PERIOD_ERROR_BIT_ON CEC_CFG_BPLEG /*!< do not generate Error-bit on long bit period error */
+#define CEC_RISING_PERIOD_ERROR_BIT_OFF ((uint32_t)0x00000000U) /*!< generate Error-bit on bit rising error */
+#define CEC_RISING_PERIOD_ERROR_BIT_ON CEC_CFG_BREG /*!< do not generate Error-bit on bit rising error */
+
+/* whether stop receive message when detected bit rising error */
+#define CEC_STOP_RISING_ERROR_BIT_ON ((uint32_t)0x00000000U) /*!< stop reception when detected bit rising error */
+#define CEC_STOP_RISING_ERROR_BIT_OFF ((uint32_t)0x00000001U) /*!< do not stop reception when detected bit rising error */
+
+/* flag bits */
+#define CEC_FLAG_BR CEC_INTF_BR /*!< RX-byte data received */
+#define CEC_FLAG_REND CEC_INTF_REND /*!< end of reception */
+#define CEC_FLAG_RO CEC_INTF_RO /*!< RX overrun */
+#define CEC_FLAG_BRE CEC_INTF_BRE /*!< bit rising error */
+#define CEC_FLAG_BPSE CEC_INTF_BPSE /*!< short bit period error */
+#define CEC_FLAG_BPLE CEC_INTF_BPLE /*!< long bit period error */
+#define CEC_FLAG_RAE CEC_INTF_RAE /*!< RX ACK error */
+#define CEC_FLAG_ARBF CEC_INTF_ARBF /*!< arbitration lost */
+#define CEC_FLAG_TBR CEC_INTF_TBR /*!< TX-byte data request */
+#define CEC_FLAG_TEND CEC_INTF_TEND /*!< transmission successfully end */
+#define CEC_FLAG_TU CEC_INTF_TU /*!< TX data buffer underrun */
+#define CEC_FLAG_TERR CEC_INTF_TERR /*!< TX-error */
+#define CEC_FLAG_TAERR CEC_INTF_TAERR /*!< TX ACK error flag */
+
+/* interrupt flag bits */
+#define CEC_INT_FLAG_BR CEC_INTF_BR /*!< RX-byte data received */
+#define CEC_INT_FLAG_REND CEC_INTF_REND /*!< end of reception */
+#define CEC_INT_FLAG_RO CEC_INTF_RO /*!< RX overrun */
+#define CEC_INT_FLAG_BRE CEC_INTF_BRE /*!< bit rising error */
+#define CEC_INT_FLAG_BPSE CEC_INTF_BPSE /*!< short bit period error */
+#define CEC_INT_FLAG_BPLE CEC_INTF_BPLE /*!< long bit period error */
+#define CEC_INT_FLAG_RAE CEC_INTF_RAE /*!< RX ACK error */
+#define CEC_INT_FLAG_ARBF CEC_INTF_ARBF /*!< arbitration lost */
+#define CEC_INT_FLAG_TBR CEC_INTF_TBR /*!< TX-byte data request */
+#define CEC_INT_FLAG_TEND CEC_INTF_TEND /*!< transmission successfully end */
+#define CEC_INT_FLAG_TU CEC_INTF_TU /*!< TX data buffer underrun */
+#define CEC_INT_FLAG_TERR CEC_INTF_TERR /*!< TX-error */
+#define CEC_INT_FLAG_TAERR CEC_INTF_TAERR /*!< TX ACK error flag */
+
+/* interrupt enable bits */
+#define CEC_INT_BR CEC_INTEN_BRIE /*!< RBR interrupt enable */
+#define CEC_INT_REND CEC_INTEN_RENDIE /*!< REND interrupt enable */
+#define CEC_INT_RO CEC_INTEN_ROIE /*!< RO interrupt enable */
+#define CEC_INT_BRE CEC_INTEN_BREIE /*!< RBRE interrupt enable. */
+#define CEC_INT_BPSE CEC_INTEN_BPSEIE /*!< RSBPE interrupt enable */
+#define CEC_INT_BPLE CEC_INTEN_BPLEIE /*!< RLBPE interrupt enable. */
+#define CEC_INT_RAE CEC_INTEN_RAEIE /*!< RAE interrupt enable */
+#define CEC_INT_ARBF CEC_INTEN_ARBFIE /*!< ALRLST interrupt enable */
+#define CEC_INT_TBR CEC_INTEN_TBRIE /*!< TBR interrupt enable */
+#define CEC_INT_TEND CEC_INTEN_TENDIE /*!< TEND interrupt enable */
+#define CEC_INT_TU CEC_INTEN_TUIE /*!< TU interrupt enable */
+#define CEC_INT_TERR CEC_INTEN_TERRIE /*!< TE interrupt enable */
+#define CEC_INT_TAERR CEC_INTEN_TAERRIE /*!< TAE interrupt enable */
+
+/* function declarations */
+/* reset HDMI-CEC controller */
+void cec_deinit(void);
+/* configure signal free time,the signal free time counter start option,own address */
+void cec_init(uint32_t sftmopt, uint32_t sft, uint32_t address);
+/* configure generate Error-bit, whether stop receive message when detected bit rising error */
+void cec_error_config(uint32_t broadcast, uint32_t singlecast_lbpe, uint32_t singlecast_bre, uint32_t rxbrestp);
+/* enable HDMI-CEC controller */
+void cec_enable(void);
+/* disable HDMI-CEC controller */
+void cec_disable(void);
+
+/* start CEC message transmission */
+void cec_transmission_start(void);
+/* end CEC message transmission */
+void cec_transmission_end(void);
+/* enable CEC listen mode */
+void cec_listen_mode_enable(void);
+/* disable CEC listen mode */
+void cec_listen_mode_disable(void);
+/* configure and clear own address */
+void cec_own_address_config(uint32_t address);
+/* configure signal free time and the signal free time counter start option */
+void cec_sft_config(uint32_t sftmopt, uint32_t sft);
+/* configure generate Error-bit when detected some abnormal situation or not */
+void cec_generate_errorbit_config(uint32_t broadcast, uint32_t singlecast_lbpe, uint32_t singlecast_bre);
+/* whether stop receive message when detected bit rising error */
+void cec_stop_receive_bre_config(uint32_t rxbrestp);
+/* enable reception bit timing tolerance */
+void cec_reception_tolerance_enable(void);
+/* disable reception bit timing tolerance */
+void cec_reception_tolerance_disable(void);
+/* send a data by the CEC peripheral */
+void cec_data_send(uint8_t data);
+/* receive a data by the CEC peripheral */
+uint8_t cec_data_receive(void);
+
+/* enable interrupt */
+void cec_interrupt_enable(uint32_t flag);
+/* disable interrupt */
+void cec_interrupt_disable(uint32_t flag);
+/* get CEC status */
+FlagStatus cec_flag_get(uint32_t flag);
+/* clear CEC status */
+void cec_flag_clear(uint32_t flag);
+/* get CEC int flag and status */
+FlagStatus cec_interrupt_flag_get(uint32_t flag);
+/* clear CEC int flag and status */
+void cec_interrupt_flag_clear(uint32_t flag);
+
+#endif /* GD32F3X0_CEC_H */
+
+#endif /* GD32F350 */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_cmp.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_cmp.h
new file mode 100644
index 00000000..083dd4c2
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_cmp.h
@@ -0,0 +1,223 @@
+/*!
+ \file gd32f3x0_cmp.h
+ \brief definitions for the CMP
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2021-05-19, V2.1.1, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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 GD32F3X0_CMP_H
+#define GD32F3X0_CMP_H
+
+#include "gd32f3x0.h"
+
+/* CMP definitions */
+#define CMP CMP_BASE /*!< CMP base address */
+
+/* registers definitions */
+#define CMP_CS REG32((CMP) + 0x00000000U) /*!< CMP control and status register */
+
+/* CMP_CS bits definitions */
+#define CMP_CS_CMP0EN BIT(0) /*!< CMP0 enable */
+#define CMP_CS_CMP0SW BIT(1) /*!< CMP0 switch */
+#define CMP_CS_CMP0M BITS(2,3) /*!< CMP0 mode */
+#define CMP_CS_CMP0MSEL BITS(4,6) /*!< COMP0_M input selection */
+#define CMP_CS_CMP0OSEL BITS(8,10) /*!< CMP0 output selection */
+#define CMP_CS_CMP0PL BIT(11) /*!< polarity of CMP0 output */
+#define CMP_CS_CMP0HST BITS(12,13) /*!< CMP0 hysteresis */
+#define CMP_CS_CMP0O BIT(14) /*!< CMP0 output */
+#define CMP_CS_CMP0LK BIT(15) /*!< CMP0 lock */
+#define CMP_CS_CMP1EN BIT(16) /*!< CMP1 enable */
+#define CMP_CS_CMP1M BITS(18,19) /*!< CMP1 mode */
+#define CMP_CS_CMP1MSEL BITS(20,22) /*!< CMP1_M input selection */
+#define CMP_CS_WNDEN BIT(23) /*!< window mode enable */
+#define CMP_CS_CMP1OSEL BITS(24,26) /*!< CMP1 output selection */
+#define CMP_CS_CMP1PL BIT(27) /*!< polarity of CMP1 output */
+#define CMP_CS_CMP1HST BITS(28,29) /*!< CMP1 hysteresis */
+#define CMP_CS_CMP1O BIT(30) /*!< CMP1 output */
+#define CMP_CS_CMP1LK BIT(31) /*!< CMP1 lock */
+
+/* consts definitions */
+/* operating mode */
+typedef enum {
+ CMP_HIGHSPEED = 0, /*!< high speed mode */
+ CMP_MIDDLESPEED, /*!< medium speed mode */
+ CMP_LOWSPEED, /*!< low speed mode */
+ CMP_VERYLOWSPEED /*!< very-low speed mode */
+} operating_mode_enum;
+
+/* inverting input */
+typedef enum {
+ CMP_1_4VREFINT = 0, /*!< VREFINT /4 input */
+ CMP_1_2VREFINT, /*!< VREFINT /2 input */
+ CMP_3_4VREFINT, /*!< VREFINT *3/4 input */
+ CMP_VREFINT, /*!< VREFINT input */
+ CMP_DAC, /*!< PA4 (DAC) input */
+ CMP_PA5, /*!< PA5 input */
+ CMP_PA_0_2 /*!< PA0 or PA2 input */
+} inverting_input_enum;
+
+/* hysteresis */
+typedef enum {
+ CMP_HYSTERESIS_NO = 0, /*!< output no hysteresis */
+ CMP_HYSTERESIS_LOW, /*!< output low hysteresis */
+ CMP_HYSTERESIS_MIDDLE, /*!< output middle hysteresis */
+ CMP_HYSTERESIS_HIGH /*!< output high hysteresis */
+} cmp_hysteresis_enum;
+
+/* output */
+typedef enum {
+ CMP_OUTPUT_NONE = 0, /*!< output no selection */
+ CMP_OUTPUT_TIMER0BKIN, /*!< TIMER 0 break input */
+ CMP_OUTPUT_TIMER0IC0, /*!< TIMER 0 channel0 input capture */
+ CMP_OUTPUT_TIMER0OCPRECLR, /*!< TIMER 0 OCPRE_CLR input */
+ CMP_OUTPUT_TIMER1IC3, /*!< TIMER 1 channel3 input capture */
+ CMP_OUTPUT_TIMER1OCPRECLR, /*!< TIMER 1 OCPRE_CLR input */
+ CMP_OUTPUT_TIMER2IC0, /*!< TIMER 2 channel0 input capture */
+ CMP_OUTPUT_TIMER2OCPRECLR /*!< TIMER 2 OCPRE_CLR input */
+} cmp_output_enum;
+
+/* CMP0 mode */
+#define CS_CMP0M(regval) (BITS(2,3) & ((uint32_t)(regval) << 2))
+#define CS_CMP0M_HIGHSPEED CS_CMP0M(0) /*!< CMP0 mode high speed */
+#define CS_CMP0M_MIDDLESPEED CS_CMP0M(1) /*!< CMP0 mode middle speed */
+#define CS_CMP0M_LOWSPEED CS_CMP0M(2) /*!< CMP0 mode low speed */
+#define CS_CMP0M_VERYLOWSPEED CS_CMP0M(3) /*!< CMP0 mode very low speed */
+
+/* comparator 0 inverting input */
+#define CS_CMP0MSEL(regval) (BITS(4,6) & ((uint32_t)(regval) << 4))
+#define CS_CMP0MSEL_1_4VREFINT CS_CMP0MSEL(0) /*!< CMP0 inverting input 1/4 Vrefint */
+#define CS_CMP0MSEL_1_2VREFINT CS_CMP0MSEL(1) /*!< CMP0 inverting input 1/2 Vrefint */
+#define CS_CMP0MSEL_3_4VREFINT CS_CMP0MSEL(2) /*!< CMP0 inverting input 3/4 Vrefint */
+#define CS_CMP0MSEL_VREFINT CS_CMP0MSEL(3) /*!< CMP0 inverting input Vrefint */
+#define CS_CMP0MSEL_DAC CS_CMP0MSEL(4) /*!< CMP0 inverting input DAC*/
+#define CS_CMP0MSEL_PA5 CS_CMP0MSEL(5) /*!< CMP0 inverting input PA5*/
+#define CS_CMP0MSEL_PA0 CS_CMP0MSEL(6) /*!< CMP0 inverting input PA0*/
+
+/* CMP0 output */
+#define CS_CMP0OSEL(regval) (BITS(8,10) & ((uint32_t)(regval) << 8))
+#define CS_CMP0OSEL_OUTPUT_NONE CS_CMP0OSEL(0) /*!< CMP0 output none */
+#define CS_CMP0OSEL_OUTPUT_TIMER0BKIN CS_CMP0OSEL(1) /*!< CMP0 output TIMER 0 break input */
+#define CS_CMP0OSEL_OUTPUT_TIMER0IC0 CS_CMP0OSEL(2) /*!< CMP0 output TIMER 0 channel 0 input capture */
+#define CS_CMP0OSEL_OUTPUT_TIMER0OCPRECLR CS_CMP0OSEL(3) /*!< CMP0 output TIMER 0 ocpreclear input */
+#define CS_CMP0OSEL_OUTPUT_TIMER1IC3 CS_CMP0OSEL(4) /*!< CMP0 output TIMER 1 channel 3 input capture */
+#define CS_CMP0OSEL_OUTPUT_TIMER1OCPRECLR CS_CMP0OSEL(5) /*!< CMP0 output TIMER 1 ocpreclear input */
+#define CS_CMP0OSEL_OUTPUT_TIMER2IC0 CS_CMP0OSEL(6) /*!< CMP0 output TIMER 2 channle 0 input capture */
+#define CS_CMP0OSEL_OUTPUT_TIMER2OCPRECLR CS_CMP0OSEL(7) /*!< CMP0 output TIMER 2 ocpreclear input */
+
+/* CMP0 hysteresis */
+#define CS_CMP0HST(regval) (BITS(12,13) & ((uint32_t)(regval) << 12))
+#define CS_CMP0HST_HYSTERESIS_NO CS_CMP0HST(0) /*!< CMP0 output no hysteresis */
+#define CS_CMP0HST_HYSTERESIS_LOW CS_CMP0HST(1) /*!< CMP0 output low hysteresis */
+#define CS_CMP0HST_HYSTERESIS_MIDDLE CS_CMP0HST(2) /*!< CMP0 output middle hysteresis */
+#define CS_CMP0HST_HYSTERESIS_HIGH CS_CMP0HST(3) /*!< CMP0 output high hysteresis */
+
+/* CMP1 mode */
+#define CS_CMP1M(regval) (BITS(18,19) & ((uint32_t)(regval) << 18))
+#define CS_CMP1M_HIGHSPEED CS_CMP1M(0) /*!< CMP1 mode high speed */
+#define CS_CMP1M_MIDDLESPEED CS_CMP1M(1) /*!< CMP1 mode middle speed */
+#define CS_CMP1M_LOWSPEED CS_CMP1M(2) /*!< CMP1 mode low speed */
+#define CS_CMP1M_VERYLOWSPEED CS_CMP1M(3) /*!< CMP1 mode very low speed */
+
+/* CMP1 inverting input */
+#define CS_CMP1MSEL(regval) (BITS(20,22) & ((uint32_t)(regval) << 20))
+#define CS_CMP1MSEL_1_4VREFINT CS_CMP1MSEL(0) /*!< CMP1 inverting input 1/4 Vrefint */
+#define CS_CMP1MSEL_1_2VREFINT CS_CMP1MSEL(1) /*!< CMP1 inverting input 1/2 Vrefint */
+#define CS_CMP1MSEL_3_4VREFINT CS_CMP1MSEL(2) /*!< CMP1 inverting input 3/4 Vrefint */
+#define CS_CMP1MSEL_VREFINT CS_CMP1MSEL(3) /*!< CMP1 inverting input Vrefint */
+#define CS_CMP1MSEL_DAC CS_CMP1MSEL(4) /*!< CMP1 inverting input DAC */
+#define CS_CMP1MSEL_PA5 CS_CMP1MSEL(5) /*!< CMP1 inverting input PA5 */
+#define CS_CMP1MSEL_PA2 CS_CMP1MSEL(6) /*!< CMP1 inverting input PA2 */
+
+/* CMP1 output */
+#define CS_CMP1OSEL(regval) (BITS(24,26) & ((uint32_t)(regval) << 24))
+#define CS_CMP1OSEL_OUTPUT_NONE CS_CMP1OSEL(0) /*!< CMP1 output none */
+#define CS_CMP1OSEL_OUTPUT_TIMER0BKIN CS_CMP1OSEL(1) /*!< CMP1 output TIMER 0 break input */
+#define CS_CMP1OSEL_OUTPUT_TIMER0IC0 CS_CMP1OSEL(2) /*!< CMP1 output TIMER 0 channel 0 input capture */
+#define CS_CMP1OSEL_OUTPUT_TIMER0OCPRECLR CS_CMP1OSEL(3) /*!< CMP1 output TIMER 0 ocpreclear input */
+#define CS_CMP1OSEL_OUTPUT_TIMER1IC3 CS_CMP1OSEL(4) /*!< CMP1 output TIMER 1 channel 3 input capture */
+#define CS_CMP1OSEL_OUTPUT_TIMER1OCPRECLR CS_CMP1OSEL(5) /*!< CMP1 output TIMER 1 ocpreclear input */
+#define CS_CMP1OSEL_OUTPUT_TIMER2IC0 CS_CMP1OSEL(6) /*!< CMP1 output TIMER 2 channle 0 input capture */
+#define CS_CMP1OSEL_OUTPUT_TIMER2OCPRECLR CS_CMP1OSEL(7) /*!< CMP1 output TIMER 2 ocpreclear input */
+
+/* CMP1 hysteresis */
+#define CS_CMP1HST(regval) (BITS(28,29) & ((uint32_t)(regval) << 28))
+#define CS_CMP1HST_HSTHYSTERESIS_NO CS_CMP1HST(0) /*!< CMP1 output no hysteresis */
+#define CS_CMP1HST_HYSTERESIS_LOW CS_CMP1HST(1) /*!< CMP1 output low hysteresis */
+#define CS_CMP1HST_HYSTERESIS_MIDDLE CS_CMP1HST(2) /*!< CMP1 output middle hysteresis */
+#define CS_CMP1HST_HYSTERESIS_HIGH CS_CMP1HST(3) /*!< CMP1 output high hysteresis */
+
+/* comparator x definitions */
+#define CMP0 ((uint32_t)0x00000000U) /*!< comparator 0 */
+#define CMP1 ((uint32_t)0x00000010U) /*!< comparator 1 */
+
+/* comparator output level */
+#define CMP_OUTPUTLEVEL_HIGH ((uint32_t)0x00000001U) /*!< comparator output high */
+#define CMP_OUTPUTLEVEL_LOW ((uint32_t)0x00000000U) /*!< comparator output low */
+
+/* output polarity of comparator */
+#define CMP_OUTPUT_POLARITY_INVERTED ((uint32_t)0x00000001U) /*!< output is inverted */
+#define CMP_OUTPUT_POLARITY_NOINVERTED ((uint32_t)0x00000000U) /*!< output is not inverted */
+
+/* function declarations */
+
+/* initialization functions */
+/* CMP deinit */
+void cmp_deinit(void);
+/* CMP mode init */
+void cmp_mode_init(uint32_t cmp_periph, operating_mode_enum operating_mode, inverting_input_enum inverting_input,
+ cmp_hysteresis_enum output_hysteresis);
+/* CMP output init */
+void cmp_output_init(uint32_t cmp_periph, cmp_output_enum output_slection, uint32_t output_polarity);
+
+/* enable functions */
+/* enable CMP */
+void cmp_enable(uint32_t cmp_periph);
+/* disable CMP */
+void cmp_disable(uint32_t cmp_periph);
+/* enable CMP switch */
+void cmp_switch_enable(void);
+/* disable CMP switch */
+void cmp_switch_disable(void);
+/* enable the window mode */
+void cmp_window_enable(void);
+/* disable the window mode */
+void cmp_window_disable(void);
+/* lock the CMP */
+void cmp_lock_enable(uint32_t cmp_periph);
+
+/* output functions */
+/* get output level */
+uint32_t cmp_output_level_get(uint32_t cmp_periph);
+
+#endif /* GD32F3X0_CMP_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_crc.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_crc.h
new file mode 100644
index 00000000..3d6324f6
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_crc.h
@@ -0,0 +1,126 @@
+/*!
+ \file gd32f3x0_crc.h
+ \brief definitions for the CRC
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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 GD32F3X0_CRC_H
+#define GD32F3X0_CRC_H
+
+#include "gd32f3x0.h"
+
+/* CRC definitions */
+#define CRC CRC_BASE
+
+/* registers definitions */
+#define CRC_DATA REG32(CRC + 0x00000000U) /*!< CRC data register */
+#define CRC_FDATA REG32(CRC + 0x00000004U) /*!< CRC free data register */
+#define CRC_CTL REG32(CRC + 0x00000008U) /*!< CRC control register */
+#define CRC_IDATA REG32(CRC + 0x00000010U) /*!< CRC initialization data register */
+#define CRC_POLY REG32(CRC + 0x00000014U) /*!< CRC polynomial register */
+
+/* bits definitions */
+/* CRC_DATA */
+#define CRC_DATA_DATA BITS(0,31) /*!< CRC data bits */
+
+/* CRC_FDATA */
+#define CRC_FDATA_FDATA BITS(0,7) /*!< CRC free data bits */
+
+/* CRC_CTL */
+#define CRC_CTL_RST BIT(0) /*!< CRC reset bit */
+#define CRC_CTL_PS BITS(3,4) /*!< size of polynomial function bits */
+#define CRC_CTL_REV_I BITS(5,6) /*!< input data reverse function bits */
+#define CRC_CTL_REV_O BIT(7) /*!< output data reverse function bit */
+
+/* CRC_INIT */
+#define CRC_IDATA_IDATA BITS(0,31) /*!< CRC initialization data bits */
+
+/* CRC_POLY */
+#define CRC_POLY_POLY BITS(0,31) /*!< CRC polynomial value bits */
+
+/* constants definitions */
+/* size of polynomial function */
+#define CTL_PS(regval) (BITS(3, 4) & ((regval) << 3))
+#define CRC_CTL_PS_32 CTL_PS(0) /*!< 32-bit polynomial for CRC calculation */
+#define CRC_CTL_PS_16 CTL_PS(1) /*!< 16-bit polynomial for CRC calculation */
+#define CRC_CTL_PS_8 CTL_PS(2) /*!< 8-bit polynomial for CRC calculation */
+#define CRC_CTL_PS_7 CTL_PS(3) /*!< 7-bit polynomial for CRC calculation */
+
+/* input data reverse function */
+#define CTL_REV_I(regval) (BITS(5, 6) & ((regval) << 5))
+#define CRC_INPUT_DATA_NOT CTL_REV_I(0) /*!< input data not reverse */
+#define CRC_INPUT_DATA_BYTE CTL_REV_I(1) /*!< input data reversed by byte type */
+#define CRC_INPUT_DATA_HALFWORD CTL_REV_I(2) /*!< input data reversed by half-word type */
+#define CRC_INPUT_DATA_WORD CTL_REV_I(3) /*!< input data reversed by word type */
+
+/* input data format */
+#define INPUT_FORMAT_WORD 0U /*!< input data in word format */
+#define INPUT_FORMAT_HALFWORD 1U /*!< input data in half-word format */
+#define INPUT_FORMAT_BYTE 2U /*!< input data in byte format */
+
+/* function declarations */
+/* deinit CRC calculation unit */
+void crc_deinit(void);
+
+/* enable the reverse operation of output data */
+void crc_reverse_output_data_enable(void);
+/* disable the reverse operation of output data */
+void crc_reverse_output_data_disable(void);
+
+/* reset data register to the value of initializaiton data register */
+void crc_data_register_reset(void);
+/* read the data register */
+uint32_t crc_data_register_read(void);
+
+/* read the free data register */
+uint8_t crc_free_data_register_read(void);
+/* write the free data register */
+void crc_free_data_register_write(uint8_t free_data);
+
+/* write the initial value register */
+void crc_init_data_register_write(uint32_t init_data);
+/* configure the CRC input data function */
+void crc_input_data_reverse_config(uint32_t data_reverse);
+
+/* configure the CRC size of polynomial function */
+void crc_polynomial_size_set(uint32_t poly_size);
+/* configure the CRC polynomial value function */
+void crc_polynomial_set(uint32_t poly);
+
+/* CRC calculate single data */
+uint32_t crc_single_data_calculate(uint32_t sdata, uint8_t data_format);
+/* CRC calculate a data array */
+uint32_t crc_block_data_calculate(void *array, uint32_t size, uint8_t data_format);
+
+#endif /* GD32F3X0_CRC_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_ctc.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_ctc.h
new file mode 100644
index 00000000..364ac592
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_ctc.h
@@ -0,0 +1,193 @@
+/*!
+ \file gd32f3x0_ctc.h
+ \brief definitions for the CTC
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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 GD32F3X0_CTC_H
+#define GD32F3X0_CTC_H
+
+#include "gd32f3x0.h"
+
+/* CTC definitions */
+#define CTC CTC_BASE
+
+/* registers definitions */
+#define CTC_CTL0 REG32(CTC + 0x00000000U) /*!< CTC control register 0 */
+#define CTC_CTL1 REG32(CTC + 0x00000004U) /*!< CTC control register 1 */
+#define CTC_STAT REG32(CTC + 0x00000008U) /*!< CTC status register */
+#define CTC_INTC REG32(CTC + 0x0000000CU) /*!< CTC interrupt clear register */
+
+/* bits definitions */
+/* CTC_CTL0 */
+#define CTC_CTL0_CKOKIE BIT(0) /*!< clock trim OK(CKOKIF) interrupt enable */
+#define CTC_CTL0_CKWARNIE BIT(1) /*!< clock trim warning(CKWARNIF) interrupt enable */
+#define CTC_CTL0_ERRIE BIT(2) /*!< error(ERRIF) interrupt enable */
+#define CTC_CTL0_EREFIE BIT(3) /*!< EREFIF interrupt enable */
+#define CTC_CTL0_CNTEN BIT(5) /*!< CTC counter enable */
+#define CTC_CTL0_AUTOTRIM BIT(6) /*!< hardware automatically trim mode */
+#define CTC_CTL0_SWREFPUL BIT(7) /*!< software reference source sync pulse */
+#define CTC_CTL0_TRIMVALUE BITS(8,13) /*!< IRC48M trim value */
+
+/* CTC_CTL1 */
+#define CTC_CTL1_RLVALUE BITS(0,15) /*!< CTC counter reload value */
+#define CTC_CTL1_CKLIM BITS(16,23) /*!< clock trim base limit value */
+#define CTC_CTL1_REFPSC BITS(24,26) /*!< reference signal source prescaler */
+#define CTC_CTL1_REFSEL BITS(28,29) /*!< reference signal source selection */
+#define CTC_CTL1_REFPOL BIT(31) /*!< reference signal source polarity */
+
+/* CTC_STAT */
+#define CTC_STAT_CKOKIF BIT(0) /*!< clock trim OK interrupt flag */
+#define CTC_STAT_CKWARNIF BIT(1) /*!< clock trim warning interrupt flag */
+#define CTC_STAT_ERRIF BIT(2) /*!< error interrupt flag */
+#define CTC_STAT_EREFIF BIT(3) /*!< expect reference interrupt flag */
+#define CTC_STAT_CKERR BIT(8) /*!< clock trim error bit */
+#define CTC_STAT_REFMISS BIT(9) /*!< reference sync pulse miss */
+#define CTC_STAT_TRIMERR BIT(10) /*!< trim value error bit */
+#define CTC_STAT_REFDIR BIT(15) /*!< CTC trim counter direction when reference sync pulse occurred */
+#define CTC_STAT_REFCAP BITS(16,31) /*!< CTC counter capture when reference sync pulse occurred */
+
+/* CTC_INTC */
+#define CTC_INTC_CKOKIC BIT(0) /*!< CKOKIF interrupt clear bit */
+#define CTC_INTC_CKWARNIC BIT(1) /*!< CKWARNIF interrupt clear bit */
+#define CTC_INTC_ERRIC BIT(2) /*!< ERRIF interrupt clear bit */
+#define CTC_INTC_EREFIC BIT(3) /*!< EREFIF interrupt clear bit */
+
+/* constants definitions */
+#define CTL0_TRIMVALUE(regval) (BITS(8,13) & ((uint32_t)(regval) << 8))
+#define CTL1_CKLIM(regval) (BITS(16,23) & ((uint32_t)(regval) << 16))
+#define GET_STAT_REFCAP(regval) GET_BITS((regval),16,31)
+#define GET_CTL0_TRIMVALUE(regval) GET_BITS((regval),8,13)
+
+/* hardware automatically trim mode definitions */
+#define CTC_HARDWARE_TRIM_MODE_ENABLE CTC_CTL0_AUTOTRIM /*!< hardware automatically trim mode enable*/
+#define CTC_HARDWARE_TRIM_MODE_DISABLE ((uint32_t)0x00000000U) /*!< hardware automatically trim mode disable*/
+
+/* reference signal source polarity definitions */
+#define CTC_REFSOURCE_POLARITY_FALLING CTC_CTL1_REFPOL /*!< reference signal source polarity is falling edge*/
+#define CTC_REFSOURCE_POLARITY_RISING ((uint32_t)0x00000000U) /*!< reference signal source polarity is rising edge*/
+
+/* reference signal source selection definitions */
+#define CTL1_REFSEL(regval) (BITS(28,29) & ((uint32_t)(regval) << 28))
+#define CTC_REFSOURCE_GPIO CTL1_REFSEL(0) /*!< GPIO is selected */
+#define CTC_REFSOURCE_LXTAL CTL1_REFSEL(1) /*!< LXTAL is clock selected */
+#define CTC_REFSOURCE_USBSOF CTL1_REFSEL(2) /*!< USBFSSOF selected */
+
+/* reference signal source prescaler definitions */
+#define CTL1_REFPSC(regval) (BITS(24,26) & ((uint32_t)(regval) << 24))
+#define CTC_REFSOURCE_PSC_OFF CTL1_REFPSC(0) /*!< reference signal not divided */
+#define CTC_REFSOURCE_PSC_DIV2 CTL1_REFPSC(1) /*!< reference signal divided by 2 */
+#define CTC_REFSOURCE_PSC_DIV4 CTL1_REFPSC(2) /*!< reference signal divided by 4 */
+#define CTC_REFSOURCE_PSC_DIV8 CTL1_REFPSC(3) /*!< reference signal divided by 8 */
+#define CTC_REFSOURCE_PSC_DIV16 CTL1_REFPSC(4) /*!< reference signal divided by 16 */
+#define CTC_REFSOURCE_PSC_DIV32 CTL1_REFPSC(5) /*!< reference signal divided by 32 */
+#define CTC_REFSOURCE_PSC_DIV64 CTL1_REFPSC(6) /*!< reference signal divided by 64 */
+#define CTC_REFSOURCE_PSC_DIV128 CTL1_REFPSC(7) /*!< reference signal divided by 128 */
+
+/* CTC interrupt enable definitions */
+#define CTC_INT_CKOK CTC_CTL0_CKOKIE /*!< clock trim OK interrupt enable */
+#define CTC_INT_CKWARN CTC_CTL0_CKWARNIE /*!< clock trim warning interrupt enable */
+#define CTC_INT_ERR CTC_CTL0_ERRIE /*!< error interrupt enable */
+#define CTC_INT_EREF CTC_CTL0_EREFIE /*!< expect reference interrupt enable */
+
+/* CTC interrupt source definitions */
+#define CTC_INT_FLAG_CKOK CTC_STAT_CKOKIF /*!< clock trim OK interrupt flag */
+#define CTC_INT_FLAG_CKWARN CTC_STAT_CKWARNIF /*!< clock trim warning interrupt flag */
+#define CTC_INT_FLAG_ERR CTC_STAT_ERRIF /*!< error interrupt flag */
+#define CTC_INT_FLAG_EREF CTC_STAT_EREFIF /*!< expect reference interrupt flag */
+#define CTC_INT_FLAG_CKERR CTC_STAT_CKERR /*!< clock trim error bit */
+#define CTC_INT_FLAG_REFMISS CTC_STAT_REFMISS /*!< reference sync pulse miss */
+#define CTC_INT_FLAG_TRIMERR CTC_STAT_TRIMERR /*!< trim value error */
+
+/* CTC flag definitions */
+#define CTC_FLAG_CKOK CTC_STAT_CKOKIF /*!< clock trim OK flag */
+#define CTC_FLAG_CKWARN CTC_STAT_CKWARNIF /*!< clock trim warning flag */
+#define CTC_FLAG_ERR CTC_STAT_ERRIF /*!< error flag */
+#define CTC_FLAG_EREF CTC_STAT_EREFIF /*!< expect reference flag */
+#define CTC_FLAG_CKERR CTC_STAT_CKERR /*!< clock trim error bit */
+#define CTC_FLAG_REFMISS CTC_STAT_REFMISS /*!< reference sync pulse miss */
+#define CTC_FLAG_TRIMERR CTC_STAT_TRIMERR /*!< trim value error bit */
+
+/* function declarations */
+/* initialization functions */
+/* reset ctc clock trim controller */
+void ctc_deinit(void);
+/* configure reference signal source polarity */
+void ctc_refsource_polarity_config(uint32_t polarity);
+/* select reference signal source */
+void ctc_refsource_signal_select(uint32_t refs);
+/* configure reference signal source prescaler */
+void ctc_refsource_prescaler_config(uint32_t prescaler);
+/* configure clock trim base limit value */
+void ctc_clock_limit_value_config(uint8_t limit_value);
+/* configure CTC counter reload value */
+void ctc_counter_reload_value_config(uint16_t reload_value);
+/* enable CTC trim counter */
+void ctc_counter_enable(void);
+/* disable CTC trim counter */
+void ctc_counter_disable(void);
+
+/* function configuration */
+/* configure the IRC48M trim value */
+void ctc_irc48m_trim_value_config(uint8_t trim_value);
+/* generate software reference source sync pulse */
+void ctc_software_refsource_pulse_generate(void);
+/* configure hardware automatically trim mode */
+void ctc_hardware_trim_mode_config(uint32_t hardmode);
+
+/* reading functions */
+/* read CTC counter capture value when reference sync pulse occurred */
+uint16_t ctc_counter_capture_value_read(void);
+/* read CTC trim counter direction when reference sync pulse occurred */
+FlagStatus ctc_counter_direction_read(void);
+/* read CTC counter reload value */
+uint16_t ctc_counter_reload_value_read(void);
+/* read the IRC48M trim value */
+uint8_t ctc_irc48m_trim_value_read(void);
+
+/* interrupt & flag functions */
+/* enable the CTC interrupt */
+void ctc_interrupt_enable(uint32_t interrupt);
+/* disable the CTC interrupt */
+void ctc_interrupt_disable(uint32_t interrupt);
+/* get CTC flag */
+FlagStatus ctc_flag_get(uint32_t flag);
+/* clear CTC flag */
+void ctc_flag_clear(uint32_t flag);
+/* get CTC interrupt flag */
+FlagStatus ctc_interrupt_flag_get(uint32_t interrupt);
+/* clear CTC interrupt flag */
+void ctc_interrupt_flag_clear(uint32_t interrupt);
+
+#endif /* GD32F3X0_CTC_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_dac.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_dac.h
new file mode 100644
index 00000000..62027e1f
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_dac.h
@@ -0,0 +1,205 @@
+/*!
+ \file gd32f3x0_dac.h
+ \brief definitions for the DAC
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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.
+*/
+
+#ifdef GD32F350
+#ifndef GD32F3X0_DAC_H
+#define GD32F3X0_DAC_H
+
+#include "gd32f3x0.h"
+
+/* DAC definitions */
+#define DAC DAC_BASE /*!< DAC base address */
+
+/* registers definitions */
+#define DAC_CTL REG32(DAC + (0x00000000U)) /*!< DAC control register */
+#define DAC_SWT REG32(DAC + (0x00000004U)) /*!< DAC software trigger register */
+#define DAC_R12DH REG32(DAC + (0x00000008U)) /*!< DAC 12-bit right-aligned data holding register */
+#define DAC_L12DH REG32(DAC + (0x0000000CU)) /*!< DAC 12-bit left-aligned data holding register */
+#define DAC_R8DH REG32(DAC + (0x00000010U)) /*!< DAC 8-bit right-aligned data holding register */
+#define DAC_DO REG32(DAC + (0x0000002CU)) /*!< DAC output data register */
+#define DAC_STAT REG32(DAC + (0x00000034U)) /*!< DAC status register */
+
+/* bits definitions */
+/* DAC_CTL */
+#define DAC_CTL_DEN BIT(0) /*!< DAC enable/disable bit */
+#define DAC_CTL_DBOFF BIT(1) /*!< DAC output buffer turn on/turn off bit */
+#define DAC_CTL_DTEN BIT(2) /*!< DAC trigger enable/disable bit */
+#define DAC_CTL_DTSEL BITS(3,5) /*!< DAC trigger source selection enable/disable bits */
+#define DAC_CTL_DWM BITS(6,7) /*!< DAC noise wave mode */
+#define DAC_CTL_DWBW BITS(8,11) /*!< DAC noise wave bit width */
+#define DAC_CTL_DDMAEN BIT(12) /*!< DAC DMA enable/disable bit */
+#define DAC_CTL_DDUDRIE BIT(13) /*!< DAC DMA underrun interrupt enable/disable bit */
+
+/* DAC_SWT */
+#define DAC_SWT_SWTR BIT(0) /*!< DAC software trigger bit,cleared by hardware */
+
+/* DAC_R12DH */
+#define DAC_R12DH_DAC_DH BITS(0,11) /*!< DAC 12-bit right-aligned data bits */
+
+/* DAC_L12DH */
+#define DAC_L12DH_DAC_DH BITS(4,15) /*!< DAC 12-bit left-aligned data bits */
+
+/* DAC_R8DH */
+#define DAC_R8DH_DAC_DH BITS(0,7) /*!< DAC 8-bit right-aligned data bits */
+
+/* DAC_DO */
+#define DAC_DO_DAC_DO BITS(0,11) /*!< DAC 12-bit output data bits */
+
+/* DAC_STAT */
+#define DAC_STAT_DDUDR BIT(13) /*!< DAC DMA underrun flag */
+
+/* constants definitions */
+/* DAC trigger source */
+#define CTL_DTSEL(regval) (BITS(3,5) & ((uint32_t)(regval) << 3))
+#define DAC_TRIGGER_T5_TRGO CTL_DTSEL(0) /*!< TIMER5 TRGO */
+#define DAC_TRIGGER_T2_TRGO CTL_DTSEL(1) /*!< TIMER2 TRGO */
+#define DAC_TRIGGER_T14_TRGO CTL_DTSEL(3) /*!< TIMER14 TRGO */
+#define DAC_TRIGGER_T1_TRGO CTL_DTSEL(4) /*!< TIMER1 TRGO */
+#define DAC_TRIGGER_EXTI_9 CTL_DTSEL(6) /*!< EXTI interrupt line9 event */
+#define DAC_TRIGGER_SOFTWARE CTL_DTSEL(7) /*!< software trigger */
+
+/* DAC noise wave mode */
+#define CTL_DWM(regval) (BITS(6,7) & ((uint32_t)(regval) << 6))
+#define DAC_WAVE_DISABLE CTL_DWM(0) /*!< wave disable */
+#define DAC_WAVE_MODE_LFSR CTL_DWM(1) /*!< LFSR noise mode */
+#define DAC_WAVE_MODE_TRIANGLE CTL_DWM(2) /*!< triangle noise mode */
+
+/* DAC noise wave bit width */
+#define DWBW(regval) (BITS(8,11) & ((uint32_t)(regval) << 8))
+#define DAC_WAVE_BIT_WIDTH_1 DWBW(0) /*!< bit width of the wave signal is 1 */
+#define DAC_WAVE_BIT_WIDTH_2 DWBW(1) /*!< bit width of the wave signal is 2 */
+#define DAC_WAVE_BIT_WIDTH_3 DWBW(2) /*!< bit width of the wave signal is 3 */
+#define DAC_WAVE_BIT_WIDTH_4 DWBW(3) /*!< bit width of the wave signal is 4 */
+#define DAC_WAVE_BIT_WIDTH_5 DWBW(4) /*!< bit width of the wave signal is 5 */
+#define DAC_WAVE_BIT_WIDTH_6 DWBW(5) /*!< bit width of the wave signal is 6 */
+#define DAC_WAVE_BIT_WIDTH_7 DWBW(6) /*!< bit width of the wave signal is 7 */
+#define DAC_WAVE_BIT_WIDTH_8 DWBW(7) /*!< bit width of the wave signal is 8 */
+#define DAC_WAVE_BIT_WIDTH_9 DWBW(8) /*!< bit width of the wave signal is 9 */
+#define DAC_WAVE_BIT_WIDTH_10 DWBW(9) /*!< bit width of the wave signal is 10 */
+#define DAC_WAVE_BIT_WIDTH_11 DWBW(10) /*!< bit width of the wave signal is 11 */
+#define DAC_WAVE_BIT_WIDTH_12 DWBW(11) /*!< bit width of the wave signal is 12 */
+
+/* unmask LFSR bits in DAC LFSR noise mode */
+#define DAC_LFSR_BIT0 DAC_WAVE_BIT_WIDTH_1 /*!< unmask the LFSR bit0 */
+#define DAC_LFSR_BITS1_0 DAC_WAVE_BIT_WIDTH_2 /*!< unmask the LFSR bits[1:0] */
+#define DAC_LFSR_BITS2_0 DAC_WAVE_BIT_WIDTH_3 /*!< unmask the LFSR bits[2:0] */
+#define DAC_LFSR_BITS3_0 DAC_WAVE_BIT_WIDTH_4 /*!< unmask the LFSR bits[3:0] */
+#define DAC_LFSR_BITS4_0 DAC_WAVE_BIT_WIDTH_5 /*!< unmask the LFSR bits[4:0] */
+#define DAC_LFSR_BITS5_0 DAC_WAVE_BIT_WIDTH_6 /*!< unmask the LFSR bits[5:0] */
+#define DAC_LFSR_BITS6_0 DAC_WAVE_BIT_WIDTH_7 /*!< unmask the LFSR bits[6:0] */
+#define DAC_LFSR_BITS7_0 DAC_WAVE_BIT_WIDTH_8 /*!< unmask the LFSR bits[7:0] */
+#define DAC_LFSR_BITS8_0 DAC_WAVE_BIT_WIDTH_9 /*!< unmask the LFSR bits[8:0] */
+#define DAC_LFSR_BITS9_0 DAC_WAVE_BIT_WIDTH_10 /*!< unmask the LFSR bits[9:0] */
+#define DAC_LFSR_BITS10_0 DAC_WAVE_BIT_WIDTH_11 /*!< unmask the LFSR bits[10:0] */
+#define DAC_LFSR_BITS11_0 DAC_WAVE_BIT_WIDTH_12 /*!< unmask the LFSR bits[11:0] */
+
+/* triangle amplitude in DAC triangle noise mode */
+#define DAC_TRIANGLE_AMPLITUDE_1 DAC_WAVE_BIT_WIDTH_1 /*!< triangle amplitude is 1 */
+#define DAC_TRIANGLE_AMPLITUDE_3 DAC_WAVE_BIT_WIDTH_2 /*!< triangle amplitude is 3 */
+#define DAC_TRIANGLE_AMPLITUDE_7 DAC_WAVE_BIT_WIDTH_3 /*!< triangle amplitude is 7 */
+#define DAC_TRIANGLE_AMPLITUDE_15 DAC_WAVE_BIT_WIDTH_4 /*!< triangle amplitude is 15 */
+#define DAC_TRIANGLE_AMPLITUDE_31 DAC_WAVE_BIT_WIDTH_5 /*!< triangle amplitude is 31 */
+#define DAC_TRIANGLE_AMPLITUDE_63 DAC_WAVE_BIT_WIDTH_6 /*!< triangle amplitude is 63 */
+#define DAC_TRIANGLE_AMPLITUDE_127 DAC_WAVE_BIT_WIDTH_7 /*!< triangle amplitude is 127 */
+#define DAC_TRIANGLE_AMPLITUDE_255 DAC_WAVE_BIT_WIDTH_8 /*!< triangle amplitude is 255 */
+#define DAC_TRIANGLE_AMPLITUDE_511 DAC_WAVE_BIT_WIDTH_9 /*!< triangle amplitude is 511 */
+#define DAC_TRIANGLE_AMPLITUDE_1023 DAC_WAVE_BIT_WIDTH_10 /*!< triangle amplitude is 1023 */
+#define DAC_TRIANGLE_AMPLITUDE_2047 DAC_WAVE_BIT_WIDTH_11 /*!< triangle amplitude is 2047 */
+#define DAC_TRIANGLE_AMPLITUDE_4095 DAC_WAVE_BIT_WIDTH_12 /*!< triangle amplitude is 4095 */
+
+/* DAC data alignment */
+#define DATA_ALIGN(regval) (BITS(0,1) & ((uint32_t)(regval) << 0))
+#define DAC_ALIGN_12B_R DATA_ALIGN(0) /*!< data right 12b alignment */
+#define DAC_ALIGN_12B_L DATA_ALIGN(1) /*!< data left 12b alignment */
+#define DAC_ALIGN_8B_R DATA_ALIGN(2) /*!< data right 8b alignment */
+
+/* function declarations */
+/* deinitialize DAC */
+void dac_deinit(void);
+
+/* enable DAC */
+void dac_enable(void);
+/* disable DAC */
+void dac_disable(void);
+/* enable DAC DMA */
+void dac_dma_enable(void);
+/* disable DAC DMA */
+void dac_dma_disable(void);
+/* enable DAC output buffer */
+void dac_output_buffer_enable(void);
+/* disable DAC output buffer */
+void dac_output_buffer_disable(void);
+/* enable DAC trigger */
+void dac_trigger_enable(void);
+/* disable DAC trigger */
+void dac_trigger_disable(void);
+/* enable DAC software trigger */
+void dac_software_trigger_enable(void);
+/* disable DAC software trigger */
+void dac_software_trigger_disable(void);
+
+/* configure DAC trigger source */
+void dac_trigger_source_config(uint32_t triggersource);
+/* configure DAC wave mode */
+void dac_wave_mode_config(uint32_t wave_mode);
+/* configure DAC wave bit width */
+void dac_wave_bit_width_config(uint32_t bit_width);
+/* configure DAC LFSR noise mode */
+void dac_lfsr_noise_config(uint32_t unmask_bits);
+/* configure DAC triangle noise mode */
+void dac_triangle_noise_config(uint32_t amplitude);
+/* get the last data output value */
+uint16_t dac_output_value_get(void);
+/* set DAC data holding register value */
+void dac_data_set(uint32_t dac_align, uint16_t data);
+
+/* get the specified DAC flag(DAC DMA underrun flag) */
+FlagStatus dac_flag_get(void);
+/* clear the specified DAC flag(DAC DMA underrun flag) */
+void dac_flag_clear(void);
+/* enable DAC interrupt(DAC DMA underrun interrupt) */
+void dac_interrupt_enable(void);
+/* disable DAC interrupt(DAC DMA underrun interrupt) */
+void dac_interrupt_disable(void);
+/* get the specified DAC interrupt flag(DAC DMA underrun interrupt flag) */
+FlagStatus dac_interrupt_flag_get(void);
+/* clear the specified DAC interrupt flag(DAC DMA underrun interrupt flag) */
+void dac_interrupt_flag_clear(void);
+
+#endif /* GD32F3X0_DAC_H */
+
+#endif /* GD32F350 */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_dbg.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_dbg.h
new file mode 100644
index 00000000..99a12686
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_dbg.h
@@ -0,0 +1,132 @@
+/*!
+ \file gd32f3x0_dbg.h
+ \brief definitions for the DBG
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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 GD32F3X0_DBG_H
+#define GD32F3X0_DBG_H
+
+#include "gd32f3x0.h"
+
+/* DBG definitions */
+#define DBG DBG_BASE
+
+/* registers definitions */
+#define DBG_ID REG32(DBG + 0x00000000U) /*!< DBG_ID code register */
+#define DBG_CTL0 REG32(DBG + 0x00000004U) /*!< DBG control register 0 */
+#define DBG_CTL1 REG32(DBG + 0x00000008U) /*!< DBG control register 1 */
+
+/* bits definitions */
+/* DBG_ID */
+#define DBG_ID_ID_CODE BITS(0,31) /*!< DBG ID code values */
+
+/* DBG_CTL0 */
+#define DBG_CTL0_SLP_HOLD BIT(0) /*!< keep debugger connection during sleep mode */
+#define DBG_CTL0_DSLP_HOLD BIT(1) /*!< keep debugger connection during deepsleep mode */
+#define DBG_CTL0_STB_HOLD BIT(2) /*!< keep debugger connection during standby mode */
+#define DBG_CTL0_FWDGT_HOLD BIT(8) /*!< debug FWDGT kept when core is halted */
+#define DBG_CTL0_WWDGT_HOLD BIT(9) /*!< debug WWDGT kept when core is halted */
+#define DBG_CTL0_TIMER0_HOLD BIT(10) /*!< hold TIMER0 counter when core is halted */
+#if (defined(GD32F350) || defined(GD32F330))
+#define DBG_CTL0_TIMER1_HOLD BIT(11) /*!< hold TIMER1 counter when core is halted */
+#endif /* GD32F350 and GD32F330 */
+#define DBG_CTL0_TIMER2_HOLD BIT(12) /*!< hold TIMER2 counter when core is halted */
+#define DBG_CTL0_I2C0_HOLD BIT(15) /*!< hold I2C0 smbus when core is halted */
+#define DBG_CTL0_I2C1_HOLD BIT(16) /*!< hold I2C1 smbus when core is halted */
+#ifdef GD32F350
+#define DBG_CTL0_TIMER5_HOLD BIT(19) /*!< hold TIMER5 counter when core is halted */
+#endif /* GD32F350 */
+#define DBG_CTL0_TIMER13_HOLD BIT(27) /*!< hold TIMER13 counter when core is halted */
+
+/* DBG_CTL1 */
+#define DBG_CTL1_RTC_HOLD BIT(10) /*!< hold RTC calendar and wakeup counter when core is halted */
+#define DBG_CTL1_TIMER14_HOLD BIT(16) /*!< hold TIMER14 counter when core is halted */
+#define DBG_CTL1_TIMER15_HOLD BIT(17) /*!< hold TIMER15 counter when core is halted */
+#define DBG_CTL1_TIMER16_HOLD BIT(18) /*!< hold TIMER16 counter when core is halted */
+
+/* constants definitions */
+#define DBG_LOW_POWER_SLEEP DBG_CTL0_SLP_HOLD /*!< keep debugger connection during sleep mode */
+#define DBG_LOW_POWER_DEEPSLEEP DBG_CTL0_DSLP_HOLD /*!< keep debugger connection during deepsleep mode */
+#define DBG_LOW_POWER_STANDBY DBG_CTL0_STB_HOLD /*!< keep debugger connection during standby mode */
+
+/* define the peripheral debug hold bit position and its register index offset */
+#define DBG_REGIDX_BIT(regidx, bitpos) (((regidx) << 6) | (bitpos))
+#define DBG_REG_VAL(periph) (REG32(DBG + ((uint32_t)(periph) >> 6)))
+#define DBG_BIT_POS(val) ((uint32_t)(val) & 0x0000001FU)
+
+/* register index */
+typedef enum {
+ DBG_IDX_CTL0 = 0x04U, /*!< DBG control register 0 offset */
+ DBG_IDX_CTL1 = 0x08U, /*!< DBG control register 1 offset */
+} dbg_reg_idx;
+
+/* peripherals hold bit */
+typedef enum {
+ DBG_FWDGT_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL0, 8U), /*!< debug FWDGT kept when core is halted */
+ DBG_WWDGT_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL0, 9U), /*!< debug WWDGT kept when core is halted */
+ DBG_TIMER0_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL0, 10U), /*!< hold TIMER0 counter when core is halted */
+#if (defined(GD32F350) || defined(GD32F330))
+ DBG_TIMER1_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL0, 11U), /*!< hold TIMER1 counter when core is halted */
+#endif /* GD32F350 and GD32F330 */
+ DBG_TIMER2_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL0, 12U), /*!< hold TIMER2 counter when core is halted */
+#ifdef GD32F350
+ DBG_TIMER5_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL0, 19U), /*!< hold TIMER5 counter when core is halted */
+#endif /* GD32F350 */
+ DBG_TIMER13_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL0, 27U), /*!< hold TIMER13 counter when core is halted */
+ DBG_TIMER14_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL1, 16U), /*!< hold TIMER14 counter when core is halted */
+ DBG_TIMER15_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL1, 17U), /*!< hold TIMER15 counter when core is halted */
+ DBG_TIMER16_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL1, 18U), /*!< hold TIMER16 counter when core is halted */
+ DBG_I2C0_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL0, 15U), /*!< hold I2C0 smbus when core is halted */
+ DBG_I2C1_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL0, 16U), /*!< hold I2C1 smbus when core is halted */
+ DBG_RTC_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL1, 10U), /*!< hold RTC calendar and wakeup counter when core is halted */
+} dbg_periph_enum;
+
+/* function declarations */
+/* deinitialize the DBG */
+void dbg_deinit(void);
+/* read DBG_ID code register */
+uint32_t dbg_id_get(void);
+
+/* enable low power behavior when the MCU is in debug mode */
+void dbg_low_power_enable(uint32_t dbg_low_power);
+/* disable low power behavior when the MCU is in debug mode */
+void dbg_low_power_disable(uint32_t dbg_low_power);
+
+/* enable peripheral behavior when the MCU is in debug mode */
+void dbg_periph_enable(dbg_periph_enum dbg_periph);
+/* disable peripheral behavior when the MCU is in debug mode */
+void dbg_periph_disable(dbg_periph_enum dbg_periph);
+
+#endif /* GD32F3X0_DBG_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_dma.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_dma.h
new file mode 100644
index 00000000..57ab6f82
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_dma.h
@@ -0,0 +1,273 @@
+/*!
+ \file gd32f3x0_dma.h
+ \brief definitions for the DMA
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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 GD32F3X0_DMA_H
+#define GD32F3X0_DMA_H
+
+#include "gd32f3x0.h"
+
+/* DMA definitions */
+#define DMA DMA_BASE /*!< DMA base address */
+
+/* registers definitions */
+#define DMA_INTF REG32(DMA + 0x00000000U) /*!< DMA interrupt flag register */
+#define DMA_INTC REG32(DMA + 0x00000004U) /*!< DMA interrupt flag clear register */
+#define DMA_CH0CTL REG32(DMA + 0x00000008U) /*!< DMA channel 0 control register */
+#define DMA_CH0CNT REG32(DMA + 0x0000000CU) /*!< DMA channel 0 counter register */
+#define DMA_CH0PADDR REG32(DMA + 0x00000010U) /*!< DMA channel 0 peripheral base address register */
+#define DMA_CH0MADDR REG32(DMA + 0x00000014U) /*!< DMA channel 0 memory base address register */
+#define DMA_CH1CTL REG32(DMA + 0x0000001CU) /*!< DMA channel 1 control register */
+#define DMA_CH1CNT REG32(DMA + 0x00000020U) /*!< DMA channel 1 counter register */
+#define DMA_CH1PADDR REG32(DMA + 0x00000024U) /*!< DMA channel 1 peripheral base address register */
+#define DMA_CH1MADDR REG32(DMA + 0x00000028U) /*!< DMA channel 1 memory base address register */
+#define DMA_CH2CTL REG32(DMA + 0x00000030U) /*!< DMA channel 2 control register */
+#define DMA_CH2CNT REG32(DMA + 0x00000034U) /*!< DMA channel 2 counter register */
+#define DMA_CH2PADDR REG32(DMA + 0x00000038U) /*!< DMA channel 2 peripheral base address register */
+#define DMA_CH2MADDR REG32(DMA + 0x0000003CU) /*!< DMA channel 2 memory base address register */
+#define DMA_CH3CTL REG32(DMA + 0x00000044U) /*!< DMA channel 3 control register */
+#define DMA_CH3CNT REG32(DMA + 0x00000048U) /*!< DMA channel 3 counter register */
+#define DMA_CH3PADDR REG32(DMA + 0x0000004CU) /*!< DMA channel 3 peripheral base address register */
+#define DMA_CH3MADDR REG32(DMA + 0x00000050U) /*!< DMA channel 3 memory base address register */
+#define DMA_CH4CTL REG32(DMA + 0x00000058U) /*!< DMA channel 4 control register */
+#define DMA_CH4CNT REG32(DMA + 0x0000005CU) /*!< DMA channel 4 counter register */
+#define DMA_CH4PADDR REG32(DMA + 0x00000060U) /*!< DMA channel 4 peripheral base address register */
+#define DMA_CH4MADDR REG32(DMA + 0x00000064U) /*!< DMA channel 4 memory base address register */
+#define DMA_CH5CTL REG32(DMA + 0x0000006CU) /*!< DMA channel 5 control register */
+#define DMA_CH5CNT REG32(DMA + 0x00000070U) /*!< DMA channel 5 counter register */
+#define DMA_CH5PADDR REG32(DMA + 0x00000074U) /*!< DMA channel 5 peripheral base address register */
+#define DMA_CH5MADDR REG32(DMA + 0x00000078U) /*!< DMA channel 5 memory base address register */
+#define DMA_CH6CTL REG32(DMA + 0x00000080U) /*!< DMA channel 6 control register */
+#define DMA_CH6CNT REG32(DMA + 0x00000084U) /*!< DMA channel 6 counter register */
+#define DMA_CH6PADDR REG32(DMA + 0x00000088U) /*!< DMA channel 6 peripheral base address register */
+#define DMA_CH6MADDR REG32(DMA + 0x0000008CU) /*!< DMA channel 6 memory base address register */
+
+/* bits definitions */
+/* DMA_INTF */
+#define DMA_INTF_GIF BIT(0) /*!< global interrupt flag of channel */
+#define DMA_INTF_FTFIF BIT(1) /*!< full transfer finish flag of channel */
+#define DMA_INTF_HTFIF BIT(2) /*!< half transfer finish flag of channel */
+#define DMA_INTF_ERRIF BIT(3) /*!< error flag of channel */
+
+/* DMA_INTC */
+#define DMA_INTC_GIFC BIT(0) /*!< clear global interrupt flag of channel */
+#define DMA_INTC_FTFIFC BIT(1) /*!< clear transfer finish flag of channel */
+#define DMA_INTC_HTFIFC BIT(2) /*!< clear half transfer finish flag of channel */
+#define DMA_INTC_ERRIFC BIT(3) /*!< clear error flag of channel */
+
+/* DMA_CHxCTL,x=0..6 */
+#define DMA_CHXCTL_CHEN BIT(0) /*!< channel x enable */
+#define DMA_CHXCTL_FTFIE BIT(1) /*!< enable bit for channel x transfer complete interrupt */
+#define DMA_CHXCTL_HTFIE BIT(2) /*!< enable bit for channel x transfer half complete interrupt */
+#define DMA_CHXCTL_ERRIE BIT(3) /*!< enable bit for channel x error interrupt */
+#define DMA_CHXCTL_DIR BIT(4) /*!< direction of the data transfer on the channel */
+#define DMA_CHXCTL_CMEN BIT(5) /*!< circulation mode */
+#define DMA_CHXCTL_PNAGA BIT(6) /*!< next address generation algorithm of peripheral */
+#define DMA_CHXCTL_MNAGA BIT(7) /*!< next address generation algorithm of memory */
+#define DMA_CHXCTL_PWIDTH BITS(8,9) /*!< transfer data size of peripheral */
+#define DMA_CHXCTL_MWIDTH BITS(10,11) /*!< transfer data size of memory */
+#define DMA_CHXCTL_PRIO BITS(12,13) /*!< priority level of channelx */
+#define DMA_CHXCTL_M2M BIT(14) /*!< memory to memory mode */
+
+/* DMA_CHxCNT,x=0..6 */
+#define DMA_CHXCNT_CNT BITS(0,15) /*!< transfer counter */
+
+/* DMA_CHxPADDR,x=0..6 */
+#define DMA_CHXPADDR_PADDR BITS(0,31) /*!< peripheral base address */
+
+/* DMA_CHxMADDR,x=0..6 */
+#define DMA_CHXMADDR_MADDR BITS(0,31) /*!< memory base address */
+
+/* constants definitions */
+/* DMA channel select */
+typedef enum {
+ DMA_CH0 = 0, /*!< DMA Channel0 */
+ DMA_CH1, /*!< DMA Channel1 */
+ DMA_CH2, /*!< DMA Channel2 */
+ DMA_CH3, /*!< DMA Channel3 */
+ DMA_CH4, /*!< DMA Channel4 */
+ DMA_CH5, /*!< DMA Channel5 */
+ DMA_CH6 /*!< DMA Channel6 */
+} dma_channel_enum;
+
+/* DMA initialize struct */
+typedef struct {
+ uint32_t periph_addr; /*!< peripheral base address */
+ uint32_t periph_width; /*!< transfer data size of peripheral */
+ uint8_t periph_inc; /*!< peripheral increasing mode */
+ uint32_t memory_addr; /*!< memory base address */
+ uint32_t memory_width; /*!< transfer data size of memory */
+ uint8_t memory_inc; /*!< memory increasing mode */
+ uint8_t direction; /*!< channel data transfer direction */
+ uint32_t number; /*!< channel transfer number */
+ uint32_t priority; /*!< channel priority level */
+} dma_parameter_struct;
+
+/* DMA reset value */
+#define DMA_CHCTL_RESET_VALUE ((uint32_t)0x00000000U) /*!< the reset value of DMA channel CHXCTL register */
+#define DMA_CHCNT_RESET_VALUE ((uint32_t)0x00000000U) /*!< the reset value of DMA channel CHXCNT register */
+#define DMA_CHPADDR_RESET_VALUE ((uint32_t)0x00000000U) /*!< the reset value of DMA channel CHXPADDR register */
+#define DMA_CHMADDR_RESET_VALUE ((uint32_t)0x00000000U) /*!< the reset value of DMA channel CHXMADDR register */
+#define DMA_CHINTF_RESET_VALUE (DMA_INTF_GIF | DMA_INTF_FTFIF | \
+ DMA_INTF_HTFIF | DMA_INTF_ERRIF)
+
+#define DMA_FLAG_ADD(flag,shift) ((flag) << ((uint32_t)(shift) * 4U)) /*!< DMA channel flag shift */
+
+/* DMA_CHCTL base address */
+#define DMA_CHXCTL_BASE (DMA + (uint32_t)0x00000008U) /*!< the base address of DMA channel CHXCTL register */
+#define DMA_CHXCNT_BASE (DMA + (uint32_t)0x0000000CU) /*!< the base address of DMA channel CHXCNT register */
+#define DMA_CHXPADDR_BASE (DMA + (uint32_t)0x00000010U) /*!< the base address of DMA channel CHXPADDR register */
+#define DMA_CHXMADDR_BASE (DMA + (uint32_t)0x00000014U) /*!< the base address of DMA channel CHXMADDR register */
+
+/* DMA channel shift bit */
+#define DMA_CHCTL(channel) REG32(DMA_CHXCTL_BASE + (uint32_t)0x0000014U * (uint32_t)(channel)) /*!< the address of DMA channel CHXCTL register */
+#define DMA_CHCNT(channel) REG32(DMA_CHXCNT_BASE + (uint32_t)0x0000014U * (uint32_t)(channel)) /*!< the address of DMA channel CHXCNT register */
+#define DMA_CHPADDR(channel) REG32(DMA_CHXPADDR_BASE + (uint32_t)0x0000014U * (uint32_t)(channel)) /*!< the address of DMA channel CHXPADDR register */
+#define DMA_CHMADDR(channel) REG32(DMA_CHXMADDR_BASE + (uint32_t)0x0000014U * (uint32_t)(channel)) /*!< the address of DMA channel CHXMADDR register */
+
+/* DMA_INTF register */
+/* interrupt flag bits */
+#define DMA_INT_FLAG_G DMA_INTF_GIF /*!< global interrupt flag of channel */
+#define DMA_INT_FLAG_FTF DMA_INTF_FTFIF /*!< full transfer finish interrupt flag of channel */
+#define DMA_INT_FLAG_HTF DMA_INTF_HTFIF /*!< half transfer finish interrupt flag of channel */
+#define DMA_INT_FLAG_ERR DMA_INTF_ERRIF /*!< error interrupt flag of channel */
+
+/* flag bits */
+#define DMA_FLAG_G DMA_INTF_GIF /*!< global interrupt flag of channel */
+#define DMA_FLAG_FTF DMA_INTF_FTFIF /*!< full transfer finish flag of channel */
+#define DMA_FLAG_HTF DMA_INTF_HTFIF /*!< half transfer finish flag of channel */
+#define DMA_FLAG_ERR DMA_INTF_ERRIF /*!< error flag of channel */
+
+/* DMA_CHxCTL register */
+/* interrupt enable bits */
+#define DMA_INT_FTF DMA_CHXCTL_FTFIE /*!< enable bit for channel full transfer finish interrupt */
+#define DMA_INT_HTF DMA_CHXCTL_HTFIE /*!< enable bit for channel half transfer finish interrupt */
+#define DMA_INT_ERR DMA_CHXCTL_ERRIE /*!< enable bit for channel error interrupt */
+
+/* transfer direction */
+#define DMA_PERIPHERAL_TO_MEMORY ((uint32_t)0x00000000U) /*!< read from peripheral and write to memory */
+#define DMA_MEMORY_TO_PERIPHERAL ((uint32_t)0x00000001U) /*!< read from memory and write to peripheral */
+
+/* peripheral increasing mode */
+#define DMA_PERIPH_INCREASE_DISABLE ((uint32_t)0x00000000U) /*!< next address of peripheral is fixed address mode */
+#define DMA_PERIPH_INCREASE_ENABLE ((uint32_t)0x00000001U) /*!< next address of peripheral is increasing address mode */
+
+/* memory increasing mode */
+#define DMA_MEMORY_INCREASE_DISABLE ((uint32_t)0x00000000U) /*!< next address of memory is fixed address mode */
+#define DMA_MEMORY_INCREASE_ENABLE ((uint32_t)0x00000001U) /*!< next address of memory is increasing address mode */
+
+/* transfer data size of peripheral */
+#define CHCTL_PWIDTH(regval) (BITS(8,9) & ((regval) << 8)) /*!< transfer data size of peripheral */
+#define DMA_PERIPHERAL_WIDTH_8BIT CHCTL_PWIDTH(0) /*!< transfer data size of peripheral is 8-bit */
+#define DMA_PERIPHERAL_WIDTH_16BIT CHCTL_PWIDTH(1) /*!< transfer data size of peripheral is 16-bit */
+#define DMA_PERIPHERAL_WIDTH_32BIT CHCTL_PWIDTH(2) /*!< transfer data size of peripheral is 32-bit */
+
+/* transfer data size of memory */
+#define CHCTL_MWIDTH(regval) (BITS(10,11) & ((regval) << 10)) /*!< transfer data size of memory */
+#define DMA_MEMORY_WIDTH_8BIT CHCTL_MWIDTH(0) /*!< transfer data size of memory is 8-bit */
+#define DMA_MEMORY_WIDTH_16BIT CHCTL_MWIDTH(1) /*!< transfer data size of memory is 16-bit */
+#define DMA_MEMORY_WIDTH_32BIT CHCTL_MWIDTH(2) /*!< transfer data size of memory is 32-bit */
+
+/* channel priority level */
+#define CHCTL_PRIO(regval) (BITS(12,13) & ((uint32_t)(regval) << 12)) /*!< DMA channel priority level */
+#define DMA_PRIORITY_LOW CHCTL_PRIO(0) /*!< low priority */
+#define DMA_PRIORITY_MEDIUM CHCTL_PRIO(1) /*!< medium priority */
+#define DMA_PRIORITY_HIGH CHCTL_PRIO(2) /*!< high priority */
+#define DMA_PRIORITY_ULTRA_HIGH CHCTL_PRIO(3) /*!< ultra high priority */
+
+/* DMA_CHxCNT register */
+/* transfer counter */
+#define DMA_CHANNEL_CNT_MASK DMA_CHXCNT_CNT
+
+/* function declarations */
+/* deinitialize DMA a channel registers */
+void dma_deinit(dma_channel_enum channelx);
+/* initialize the parameters of DMA struct with the default values */
+void dma_struct_para_init(dma_parameter_struct *init_struct);
+/* initialize DMA channel */
+void dma_init(dma_channel_enum channelx, dma_parameter_struct *init_struct);
+/* enable DMA circulation mode */
+void dma_circulation_enable(dma_channel_enum channelx);
+/* disable DMA circulation mode */
+void dma_circulation_disable(dma_channel_enum channelx);
+/* enable memory to memory mode */
+void dma_memory_to_memory_enable(dma_channel_enum channelx);
+/* disable memory to memory mode */
+void dma_memory_to_memory_disable(dma_channel_enum channelx);
+/* enable DMA channel */
+void dma_channel_enable(dma_channel_enum channelx);
+/* disable DMA channel */
+void dma_channel_disable(dma_channel_enum channelx);
+
+/* set DMA peripheral base address */
+void dma_periph_address_config(dma_channel_enum channelx, uint32_t address);
+/* set DMA memory base address */
+void dma_memory_address_config(dma_channel_enum channelx, uint32_t address);
+/* set the number of remaining data to be transferred by the DMA */
+void dma_transfer_number_config(dma_channel_enum channelx, uint32_t number);
+/* get the number of remaining data to be transferred by the DMA */
+uint32_t dma_transfer_number_get(dma_channel_enum channelx);
+/* configure priority level of DMA channel */
+void dma_priority_config(dma_channel_enum channelx, uint32_t priority);
+/* configure transfer data size of memory */
+void dma_memory_width_config(dma_channel_enum channelx, uint32_t mwidth);
+/* configure transfer data size of peripheral */
+void dma_periph_width_config(dma_channel_enum channelx, uint32_t pwidth);
+/* enable next address increasement algorithm of memory */
+void dma_memory_increase_enable(dma_channel_enum channelx);
+/* disable next address increasement algorithm of memory */
+void dma_memory_increase_disable(dma_channel_enum channelx);
+/* enable next address increasement algorithm of peripheral */
+void dma_periph_increase_enable(dma_channel_enum channelx);
+/* disable next address increasement algorithm of peripheral */
+void dma_periph_increase_disable(dma_channel_enum channelx);
+/* configure the direction of data transfer on the channel */
+void dma_transfer_direction_config(dma_channel_enum channelx, uint32_t direction);
+
+/* check DMA flag is set or not */
+FlagStatus dma_flag_get(dma_channel_enum channelx, uint32_t flag);
+/* clear DMA a channel flag */
+void dma_flag_clear(dma_channel_enum channelx, uint32_t flag);
+/* enable DMA interrupt */
+void dma_interrupt_enable(dma_channel_enum channelx, uint32_t source);
+/* disable DMA interrupt */
+void dma_interrupt_disable(dma_channel_enum channelx, uint32_t source);
+/* check DMA flag and interrupt enable bit is set or not */
+FlagStatus dma_interrupt_flag_get(dma_channel_enum channelx, uint32_t flag);
+/* clear DMA a channel flag */
+void dma_interrupt_flag_clear(dma_channel_enum channelx, uint32_t flag);
+
+#endif /* GD32F3X0_DMA_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_exti.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_exti.h
new file mode 100644
index 00000000..b236c322
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_exti.h
@@ -0,0 +1,285 @@
+/*!
+ \file gd32f3x0_exti.h
+ \brief definitions for the EXTI
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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 GD32F3X0_EXTI_H
+#define GD32F3X0_EXTI_H
+
+#include "gd32f3x0.h"
+
+/* EXTI definitions */
+#define EXTI EXTI_BASE /*!< EXTI base address */
+
+/* registers definitions */
+#define EXTI_INTEN REG32(EXTI + 0x00000000U) /*!< interrupt enable register */
+#define EXTI_EVEN REG32(EXTI + 0x00000004U) /*!< event enable register */
+#define EXTI_RTEN REG32(EXTI + 0x00000008U) /*!< rising edge trigger enable register */
+#define EXTI_FTEN REG32(EXTI + 0x0000000CU) /*!< falling trigger enable register */
+#define EXTI_SWIEV REG32(EXTI + 0x00000010U) /*!< software interrupt event register */
+#define EXTI_PD REG32(EXTI + 0x00000014U) /*!< pending register */
+
+/* bits definitions */
+/* EXTI_INTEN */
+#define EXTI_INTEN_INTEN0 BIT(0) /*!< interrupt from line 0 */
+#define EXTI_INTEN_INTEN1 BIT(1) /*!< interrupt from line 1 */
+#define EXTI_INTEN_INTEN2 BIT(2) /*!< interrupt from line 2 */
+#define EXTI_INTEN_INTEN3 BIT(3) /*!< interrupt from line 3 */
+#define EXTI_INTEN_INTEN4 BIT(4) /*!< interrupt from line 4 */
+#define EXTI_INTEN_INTEN5 BIT(5) /*!< interrupt from line 5 */
+#define EXTI_INTEN_INTEN6 BIT(6) /*!< interrupt from line 6 */
+#define EXTI_INTEN_INTEN7 BIT(7) /*!< interrupt from line 7 */
+#define EXTI_INTEN_INTEN8 BIT(8) /*!< interrupt from line 8 */
+#define EXTI_INTEN_INTEN9 BIT(9) /*!< interrupt from line 9 */
+#define EXTI_INTEN_INTEN10 BIT(10) /*!< interrupt from line 10 */
+#define EXTI_INTEN_INTEN11 BIT(11) /*!< interrupt from line 11 */
+#define EXTI_INTEN_INTEN12 BIT(12) /*!< interrupt from line 12 */
+#define EXTI_INTEN_INTEN13 BIT(13) /*!< interrupt from line 13 */
+#define EXTI_INTEN_INTEN14 BIT(14) /*!< interrupt from line 14 */
+#define EXTI_INTEN_INTEN15 BIT(15) /*!< interrupt from line 15 */
+#define EXTI_INTEN_INTEN16 BIT(16) /*!< interrupt from line 16 */
+#define EXTI_INTEN_INTEN17 BIT(17) /*!< interrupt from line 17 */
+#define EXTI_INTEN_INTEN18 BIT(18) /*!< interrupt from line 18 */
+#define EXTI_INTEN_INTEN19 BIT(19) /*!< interrupt from line 19 */
+#define EXTI_INTEN_INTEN20 BIT(20) /*!< interrupt from line 20 */
+#define EXTI_INTEN_INTEN21 BIT(21) /*!< interrupt from line 21 */
+#define EXTI_INTEN_INTEN22 BIT(22) /*!< interrupt from line 22 */
+#define EXTI_INTEN_INTEN23 BIT(23) /*!< interrupt from line 23 */
+#define EXTI_INTEN_INTEN24 BIT(24) /*!< interrupt from line 24 */
+#define EXTI_INTEN_INTEN25 BIT(25) /*!< interrupt from line 25 */
+#define EXTI_INTEN_INTEN26 BIT(26) /*!< interrupt from line 26 */
+#define EXTI_INTEN_INTEN27 BIT(27) /*!< interrupt from line 27 */
+
+/* EXTI_EVEN */
+#define EXTI_EVEN_EVEN0 BIT(0) /*!< event from line 0 */
+#define EXTI_EVEN_EVEN1 BIT(1) /*!< event from line 1 */
+#define EXTI_EVEN_EVEN2 BIT(2) /*!< event from line 2 */
+#define EXTI_EVEN_EVEN3 BIT(3) /*!< event from line 3 */
+#define EXTI_EVEN_EVEN4 BIT(4) /*!< event from line 4 */
+#define EXTI_EVEN_EVEN5 BIT(5) /*!< event from line 5 */
+#define EXTI_EVEN_EVEN6 BIT(6) /*!< event from line 6 */
+#define EXTI_EVEN_EVEN7 BIT(7) /*!< event from line 7 */
+#define EXTI_EVEN_EVEN8 BIT(8) /*!< event from line 8 */
+#define EXTI_EVEN_EVEN9 BIT(9) /*!< event from line 9 */
+#define EXTI_EVEN_EVEN10 BIT(10) /*!< event from line 10 */
+#define EXTI_EVEN_EVEN11 BIT(11) /*!< event from line 11 */
+#define EXTI_EVEN_EVEN12 BIT(12) /*!< event from line 12 */
+#define EXTI_EVEN_EVEN13 BIT(13) /*!< event from line 13 */
+#define EXTI_EVEN_EVEN14 BIT(14) /*!< event from line 14 */
+#define EXTI_EVEN_EVEN15 BIT(15) /*!< event from line 15 */
+#define EXTI_EVEN_EVEN16 BIT(16) /*!< event from line 16 */
+#define EXTI_EVEN_EVEN17 BIT(17) /*!< event from line 17 */
+#define EXTI_EVEN_EVEN18 BIT(18) /*!< event from line 18 */
+#define EXTI_EVEN_EVEN19 BIT(19) /*!< event from line 19 */
+#define EXTI_EVEN_EVEN20 BIT(20) /*!< event from line 20 */
+#define EXTI_EVEN_EVEN21 BIT(21) /*!< event from line 21 */
+#define EXTI_EVEN_EVEN22 BIT(22) /*!< event from line 22 */
+#define EXTI_EVEN_EVEN23 BIT(23) /*!< event from line 23 */
+#define EXTI_EVEN_EVEN24 BIT(24) /*!< event from line 24 */
+#define EXTI_EVEN_EVEN25 BIT(25) /*!< event from line 25 */
+#define EXTI_EVEN_EVEN26 BIT(26) /*!< event from line 26 */
+#define EXTI_EVEN_EVEN27 BIT(27) /*!< event from line 27 */
+
+/* EXTI_RTEN */
+#define EXTI_RTEN_RTEN0 BIT(0) /*!< rising edge from line 0 */
+#define EXTI_RTEN_RTEN1 BIT(1) /*!< rising edge from line 1 */
+#define EXTI_RTEN_RTEN2 BIT(2) /*!< rising edge from line 2 */
+#define EXTI_RTEN_RTEN3 BIT(3) /*!< rising edge from line 3 */
+#define EXTI_RTEN_RTEN4 BIT(4) /*!< rising edge from line 4 */
+#define EXTI_RTEN_RTEN5 BIT(5) /*!< rising edge from line 5 */
+#define EXTI_RTEN_RTEN6 BIT(6) /*!< rising edge from line 6 */
+#define EXTI_RTEN_RTEN7 BIT(7) /*!< rising edge from line 7 */
+#define EXTI_RTEN_RTEN8 BIT(8) /*!< rising edge from line 8 */
+#define EXTI_RTEN_RTEN9 BIT(9) /*!< rising edge from line 9 */
+#define EXTI_RTEN_RTEN10 BIT(10) /*!< rising edge from line 10 */
+#define EXTI_RTEN_RTEN11 BIT(11) /*!< rising edge from line 11 */
+#define EXTI_RTEN_RTEN12 BIT(12) /*!< rising edge from line 12 */
+#define EXTI_RTEN_RTEN13 BIT(13) /*!< rising edge from line 13 */
+#define EXTI_RTEN_RTEN14 BIT(14) /*!< rising edge from line 14 */
+#define EXTI_RTEN_RTEN15 BIT(15) /*!< rising edge from line 15 */
+#define EXTI_RTEN_RTEN16 BIT(16) /*!< rising edge from line 16 */
+#define EXTI_RTEN_RTEN17 BIT(17) /*!< rising edge from line 17 */
+#define EXTI_RTEN_RTEN18 BIT(18) /*!< rising edge from line 18 */
+#define EXTI_RTEN_RTEN19 BIT(19) /*!< rising edge from line 19 */
+#define EXTI_RTEN_RTEN21 BIT(21) /*!< rising edge from line 21 */
+#define EXTI_RTEN_RTEN22 BIT(22) /*!< rising edge from line 22 */
+
+/* EXTI_FTEN */
+#define EXTI_FTEN_FTEN0 BIT(0) /*!< falling edge from line 0 */
+#define EXTI_FTEN_FTEN1 BIT(1) /*!< falling edge from line 1 */
+#define EXTI_FTEN_FTEN2 BIT(2) /*!< falling edge from line 2 */
+#define EXTI_FTEN_FTEN3 BIT(3) /*!< falling edge from line 3 */
+#define EXTI_FTEN_FTEN4 BIT(4) /*!< falling edge from line 4 */
+#define EXTI_FTEN_FTEN5 BIT(5) /*!< falling edge from line 5 */
+#define EXTI_FTEN_FTEN6 BIT(6) /*!< falling edge from line 6 */
+#define EXTI_FTEN_FTEN7 BIT(7) /*!< falling edge from line 7 */
+#define EXTI_FTEN_FTEN8 BIT(8) /*!< falling edge from line 8 */
+#define EXTI_FTEN_FTEN9 BIT(9) /*!< falling edge from line 9 */
+#define EXTI_FTEN_FTEN10 BIT(10) /*!< falling edge from line 10 */
+#define EXTI_FTEN_FTEN11 BIT(11) /*!< falling edge from line 11 */
+#define EXTI_FTEN_FTEN12 BIT(12) /*!< falling edge from line 12 */
+#define EXTI_FTEN_FTEN13 BIT(13) /*!< falling edge from line 13 */
+#define EXTI_FTEN_FTEN14 BIT(14) /*!< falling edge from line 14 */
+#define EXTI_FTEN_FTEN15 BIT(15) /*!< falling edge from line 15 */
+#define EXTI_FTEN_FTEN16 BIT(16) /*!< falling edge from line 16 */
+#define EXTI_FTEN_FTEN17 BIT(17) /*!< falling edge from line 17 */
+#define EXTI_FTEN_FTEN18 BIT(18) /*!< falling edge from line 18 */
+#define EXTI_FTEN_FTEN19 BIT(19) /*!< falling edge from line 19 */
+#define EXTI_FTEN_FTEN21 BIT(21) /*!< falling edge from line 21 */
+#define EXTI_FTEN_FTEN22 BIT(22) /*!< falling edge from line 22 */
+
+/* EXTI_SWIEV */
+#define EXTI_SWIEV_SWIEV0 BIT(0) /*!< software interrupt/event request from line 0 */
+#define EXTI_SWIEV_SWIEV1 BIT(1) /*!< software interrupt/event request from line 1 */
+#define EXTI_SWIEV_SWIEV2 BIT(2) /*!< software interrupt/event request from line 2 */
+#define EXTI_SWIEV_SWIEV3 BIT(3) /*!< software interrupt/event request from line 3 */
+#define EXTI_SWIEV_SWIEV4 BIT(4) /*!< software interrupt/event request from line 4 */
+#define EXTI_SWIEV_SWIEV5 BIT(5) /*!< software interrupt/event request from line 5 */
+#define EXTI_SWIEV_SWIEV6 BIT(6) /*!< software interrupt/event request from line 6 */
+#define EXTI_SWIEV_SWIEV7 BIT(7) /*!< software interrupt/event request from line 7 */
+#define EXTI_SWIEV_SWIEV8 BIT(8) /*!< software interrupt/event request from line 8 */
+#define EXTI_SWIEV_SWIEV9 BIT(9) /*!< software interrupt/event request from line 9 */
+#define EXTI_SWIEV_SWIEV10 BIT(10) /*!< software interrupt/event request from line 10 */
+#define EXTI_SWIEV_SWIEV11 BIT(11) /*!< software interrupt/event request from line 11 */
+#define EXTI_SWIEV_SWIEV12 BIT(12) /*!< software interrupt/event request from line 12 */
+#define EXTI_SWIEV_SWIEV13 BIT(13) /*!< software interrupt/event request from line 13 */
+#define EXTI_SWIEV_SWIEV14 BIT(14) /*!< software interrupt/event request from line 14 */
+#define EXTI_SWIEV_SWIEV15 BIT(15) /*!< software interrupt/event request from line 15 */
+#define EXTI_SWIEV_SWIEV16 BIT(16) /*!< software interrupt/event request from line 16 */
+#define EXTI_SWIEV_SWIEV17 BIT(17) /*!< software interrupt/event request from line 17 */
+#define EXTI_SWIEV_SWIEV18 BIT(18) /*!< software interrupt/event request from line 18 */
+#define EXTI_SWIEV_SWIEV19 BIT(19) /*!< software interrupt/event request from line 19 */
+#define EXTI_SWIEV_SWIEV21 BIT(21) /*!< software interrupt/event request from line 21 */
+#define EXTI_SWIEV_SWIEV22 BIT(22) /*!< software interrupt/event request from line 22 */
+
+/* EXTI_PD */
+#define EXTI_PD_PD0 BIT(0) /*!< interrupt/event pending status from line 0 */
+#define EXTI_PD_PD1 BIT(1) /*!< interrupt/event pending status from line 1 */
+#define EXTI_PD_PD2 BIT(2) /*!< interrupt/event pending status from line 2 */
+#define EXTI_PD_PD3 BIT(3) /*!< interrupt/event pending status from line 3 */
+#define EXTI_PD_PD4 BIT(4) /*!< interrupt/event pending status from line 4 */
+#define EXTI_PD_PD5 BIT(5) /*!< interrupt/event pending status from line 5 */
+#define EXTI_PD_PD6 BIT(6) /*!< interrupt/event pending status from line 6 */
+#define EXTI_PD_PD7 BIT(7) /*!< interrupt/event pending status from line 7 */
+#define EXTI_PD_PD8 BIT(8) /*!< interrupt/event pending status from line 8 */
+#define EXTI_PD_PD9 BIT(9) /*!< interrupt/event pending status from line 9 */
+#define EXTI_PD_PD10 BIT(10) /*!< interrupt/event pending status from line 10 */
+#define EXTI_PD_PD11 BIT(11) /*!< interrupt/event pending status from line 11 */
+#define EXTI_PD_PD12 BIT(12) /*!< interrupt/event pending status from line 12 */
+#define EXTI_PD_PD13 BIT(13) /*!< interrupt/event pending status from line 13 */
+#define EXTI_PD_PD14 BIT(14) /*!< interrupt/event pending status from line 14 */
+#define EXTI_PD_PD15 BIT(15) /*!< interrupt/event pending status from line 15 */
+#define EXTI_PD_PD16 BIT(16) /*!< interrupt/event pending status from line 16 */
+#define EXTI_PD_PD17 BIT(17) /*!< interrupt/event pending status from line 17 */
+#define EXTI_PD_PD18 BIT(18) /*!< interrupt/event pending status from line 18 */
+#define EXTI_PD_PD19 BIT(19) /*!< interrupt/event pending status from line 19 */
+#define EXTI_PD_PD21 BIT(21) /*!< interrupt/event pending status from line 21 */
+#define EXTI_PD_PD22 BIT(22) /*!< interrupt/event pending status from line 22 */
+
+/* constants definitions */
+/* EXTI line number */
+typedef enum {
+ EXTI_0 = BIT(0), /*!< EXTI line 0 */
+ EXTI_1 = BIT(1), /*!< EXTI line 1 */
+ EXTI_2 = BIT(2), /*!< EXTI line 2 */
+ EXTI_3 = BIT(3), /*!< EXTI line 3 */
+ EXTI_4 = BIT(4), /*!< EXTI line 4 */
+ EXTI_5 = BIT(5), /*!< EXTI line 5 */
+ EXTI_6 = BIT(6), /*!< EXTI line 6 */
+ EXTI_7 = BIT(7), /*!< EXTI line 7 */
+ EXTI_8 = BIT(8), /*!< EXTI line 8 */
+ EXTI_9 = BIT(9), /*!< EXTI line 9 */
+ EXTI_10 = BIT(10), /*!< EXTI line 10 */
+ EXTI_11 = BIT(11), /*!< EXTI line 11 */
+ EXTI_12 = BIT(12), /*!< EXTI line 12 */
+ EXTI_13 = BIT(13), /*!< EXTI line 13 */
+ EXTI_14 = BIT(14), /*!< EXTI line 14 */
+ EXTI_15 = BIT(15), /*!< EXTI line 15 */
+ EXTI_16 = BIT(16), /*!< EXTI line 16 */
+ EXTI_17 = BIT(17), /*!< EXTI line 17 */
+ EXTI_18 = BIT(18), /*!< EXTI line 18 */
+ EXTI_19 = BIT(19), /*!< EXTI line 19 */
+ EXTI_20 = BIT(20), /*!< EXTI line 20 */
+ EXTI_21 = BIT(21), /*!< EXTI line 21 */
+ EXTI_22 = BIT(22), /*!< EXTI line 22 */
+ EXTI_23 = BIT(23), /*!< EXTI line 23 */
+ EXTI_24 = BIT(24), /*!< EXTI line 24 */
+ EXTI_25 = BIT(25), /*!< EXTI line 25 */
+ EXTI_26 = BIT(26), /*!< EXTI line 26 */
+ EXTI_27 = BIT(27), /*!< EXTI line 27 */
+} exti_line_enum;
+
+/* external interrupt and event */
+typedef enum {
+ EXTI_INTERRUPT = 0, /*!< EXTI interrupt mode */
+ EXTI_EVENT /*!< EXTI event mode */
+} exti_mode_enum;
+
+/* interrupt trigger mode */
+typedef enum {
+ EXTI_TRIG_RISING = 0, /*!< EXTI rising edge trigger */
+ EXTI_TRIG_FALLING, /*!< EXTI falling edge trigger */
+ EXTI_TRIG_BOTH, /*!< EXTI rising and falling edge trigger */
+ EXTI_TRIG_NONE /*!< without rising edge or falling edge trigger */
+} exti_trig_type_enum;
+
+/* function declarations */
+/* reset EXTI, reset the value of all EXTI registers into initial values */
+void exti_deinit(void);
+/* initialize the EXTI, enable the configuration of EXTI initialize */
+void exti_init(exti_line_enum linex, exti_mode_enum mode, exti_trig_type_enum trig_type);
+/* enable the interrupts from EXTI line x */
+void exti_interrupt_enable(exti_line_enum linex);
+/* disable the interrupts from EXTI line x */
+void exti_interrupt_disable(exti_line_enum linex);
+/* enable the events from EXTI line x */
+void exti_event_enable(exti_line_enum linex);
+/* disable the events from EXTI line x */
+void exti_event_disable(exti_line_enum linex);
+
+/* enable EXTI software interrupt event */
+void exti_software_interrupt_enable(exti_line_enum linex);
+/* disable EXTI software interrupt event */
+void exti_software_interrupt_disable(exti_line_enum linex);
+/* get EXTI line x pending flag */
+FlagStatus exti_flag_get(exti_line_enum linex);
+/* clear EXTI line x pending flag */
+void exti_flag_clear(exti_line_enum linex);
+/* get EXTI line x flag when the interrupt flag is set */
+FlagStatus exti_interrupt_flag_get(exti_line_enum linex);
+/* clear EXTI line x pending flag */
+void exti_interrupt_flag_clear(exti_line_enum linex);
+
+#endif /* GD32F3X0_EXTI_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_fmc.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_fmc.h
new file mode 100644
index 00000000..d2bd5a78
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_fmc.h
@@ -0,0 +1,258 @@
+/*!
+ \file gd32f3x0_fmc.h
+ \brief definitions for the FMC
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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 GD32F3X0_FMC_H
+#define GD32F3X0_FMC_H
+
+#include "gd32f3x0.h"
+
+/* FMC and option byte definition */
+#define FMC FMC_BASE /*!< FMC register base address */
+#define OB OB_BASE /*!< option byte base address */
+
+/* registers definitions */
+#define FMC_WS REG32(FMC + 0x00000000U) /*!< FMC wait state register */
+#define FMC_KEY REG32(FMC + 0x00000004U) /*!< FMC unlock key register */
+#define FMC_OBKEY REG32(FMC + 0x00000008U) /*!< FMC option bytes unlock key register */
+#define FMC_STAT REG32(FMC + 0x0000000CU) /*!< FMC status register */
+#define FMC_CTL REG32(FMC + 0x00000010U) /*!< FMC control register */
+#define FMC_ADDR REG32(FMC + 0x00000014U) /*!< FMC address register */
+#define FMC_OBSTAT REG32(FMC + 0x0000001CU) /*!< FMC option bytes status register */
+#define FMC_WP REG32(FMC + 0x00000020U) /*!< FMC write protection register */
+#define FMC_WSEN REG32(FMC + 0x000000FCU) /*!< FMC wait state enable register */
+#define FMC_PID REG32(FMC + 0x00000100U) /*!< FMC product ID register */
+
+#define OB_SPC REG16(OB + 0x00000000U) /*!< option byte security protection value */
+#define OB_USER REG16(OB + 0x00000002U) /*!< option byte user value */
+#define OB_DATA0 REG16(OB + 0x00000004U) /*!< option byte data bit[7:0] value */
+#define OB_DATA1 REG16(OB + 0x00000006U) /*!< option byte data bit[15:8] value */
+#define OB_WP0 REG16(OB + 0x00000008U) /*!< option byte write protection 0 */
+#define OB_WP1 REG16(OB + 0x0000000AU) /*!< option byte write protection 1 */
+
+/* bits definitions */
+/* FMC_WS */
+#define FMC_WS_WSCNT BITS(0,2) /*!< wait state counter */
+
+/* FMC_KEY */
+#define FMC_KEY_KEY BITS(0,31) /*!< FMC main flash unlock key bits */
+
+/* FMC_OBKEY */
+#define FMC_OBKEY_OBKEY BITS(0,31) /*!< option bytes unlock key bits */
+
+/* FMC_STAT */
+#define FMC_STAT_BUSY BIT(0) /*!< flash busy flag bit */
+#define FMC_STAT_PGERR BIT(2) /*!< flash program error flag bit */
+#define FMC_STAT_WPERR BIT(4) /*!< flash write protection error flag bit */
+#define FMC_STAT_ENDF BIT(5) /*!< end of operation flag bit */
+
+/* FMC_CTL */
+#define FMC_CTL_PG BIT(0) /*!< main flash program command bit */
+#define FMC_CTL_PER BIT(1) /*!< main flash page erase bit */
+#define FMC_CTL_MER BIT(2) /*!< main flash mass erase bit */
+#define FMC_CTL_OBPG BIT(4) /*!< option bytes program command bit */
+#define FMC_CTL_OBER BIT(5) /*!< option bytes erase command bit */
+#define FMC_CTL_START BIT(6) /*!< send erase command to FMC bit */
+#define FMC_CTL_LK BIT(7) /*!< flash lock bit */
+#define FMC_CTL_OBWEN BIT(9) /*!< option bytes erase/program enable bit */
+#define FMC_CTL_ERRIE BIT(10) /*!< error interrupt enable bit */
+#define FMC_CTL_ENDIE BIT(12) /*!< end of operation interrupt enable bit */
+#define FMC_CTL_OBRLD BIT(13) /*!< option bytes reload bit */
+
+/* FMC_ADDR */
+#define FMC_ADDR_ADDR BITS(0,31) /*!< flash command address bits */
+
+/* FMC_OBSTAT */
+#define FMC_OBSTAT_OBERR BIT(0) /*!< option bytes read error bit */
+#define FMC_OBSTAT_PLEVEL_BIT0 BIT(1) /*!< protection level bit 0 */
+#define FMC_OBSTAT_PLEVEL_BIT1 BIT(2) /*!< protection level bit 1 */
+#define FMC_OBSTAT_USER BITS(8,15) /*!< option bytes user bits */
+#define FMC_OBSTAT_DATA BITS(16,31) /*!< option byte data bits */
+
+/* FMC_WSEN */
+#define FMC_WSEN_WSEN BIT(0) /*!< FMC wait state enable bit */
+#define FMC_WSEN_BPEN BIT(1) /*!< FMC bit program enable bit */
+
+/* FMC_PID */
+#define FMC_PID_PID BITS(0,31) /*!< product ID bits */
+
+/* constants definitions */
+/* fmc state */
+typedef enum {
+ FMC_READY, /*!< the operation has been completed */
+ FMC_BUSY, /*!< the operation is in progress */
+ FMC_PGERR, /*!< program error */
+ FMC_WPERR, /*!< erase/program protection error */
+ FMC_TOERR, /*!< timeout error */
+ FMC_OB_HSPC /*!< option byte security protection code high */
+} fmc_state_enum;
+
+/* option byte parameter */
+typedef struct {
+ uint8_t spc; /*!< option byte parameter spc */
+ uint8_t user; /*!< option byte parameter user */
+ uint8_t data0; /*!< option byte parameter data0 */
+ uint8_t data1; /*!< option byte parameter data1 */
+ uint8_t wp0; /*!< option byte parameter wp0 */
+ uint8_t wp1; /*!< option byte parameter wp1 */
+} ob_parm_struct;
+
+/* unlock key */
+#define UNLOCK_KEY0 ((uint32_t)0x45670123U) /*!< unlock key 0 */
+#define UNLOCK_KEY1 ((uint32_t)0xCDEF89ABU) /*!< unlock key 1 */
+
+/* wait state counter value */
+#define WS_WSCNT_0 ((uint8_t)0x00U) /*!< 0 wait state added */
+#define WS_WSCNT_1 ((uint8_t)0x01U) /*!< 1 wait state added */
+#define WS_WSCNT_2 ((uint8_t)0x02U) /*!< 2 wait state added */
+
+/* read protect configure */
+#define FMC_NSPC ((uint8_t)0xA5U) /*!< no security protection */
+#define FMC_LSPC ((uint8_t)0xBBU) /*!< low security protection, any value except 0xA5 or 0xCC */
+#define FMC_HSPC ((uint8_t)0xCCU) /*!< high security protection */
+
+/* option byte write protection */
+#define OB_LWP ((uint32_t)0x000000FFU) /*!< write protection low bits */
+#define OB_HWP ((uint32_t)0x0000FF00U) /*!< write protection high bits */
+
+#define OB_FWDGT_HW ((uint8_t)(~BIT(0))) /*!< hardware free watchdog timer */
+#define OB_DEEPSLEEP_RST ((uint8_t)(~BIT(1))) /*!< generate a reset instead of entering deepsleep mode */
+#define OB_STDBY_RST ((uint8_t)(~BIT(2))) /*!< generate a reset instead of entering standby mode */
+#define OB_BOOT1_SET_1 ((uint8_t)(~BIT(4))) /*!< BOOT1 bit is 1 */
+#define OB_VDDA_DISABLE ((uint8_t)(~BIT(5))) /*!< disable VDDA monitor */
+#define OB_SRAM_PARITY_ENABLE ((uint8_t)(~BIT(6))) /*!< enable SRAM parity check */
+
+/* option byte security protection level in FMC_OBSTAT register */
+#define OB_OBSTAT_PLEVEL_NO ((uint32_t)0x00000000U) /*!< no security protection */
+#define OB_OBSTAT_PLEVEL_LOW ((uint32_t)0x00000002U) /*!< low security protection */
+#define OB_OBSTAT_PLEVEL_HIGH ((uint32_t)0x00000006U) /*!< high security protection */
+
+#define OB_USER_DEFAULT ((uint8_t)0xDFU) /*!< OB_USER default value */
+
+/* option byte parameter address */
+#define OB_SPC_ADDR (uint32_t)(OB + 0x00000000U)/*!< option byte spc address */
+#define OB_USER_ADDR (uint32_t)(OB + 0x00000002U)/*!< option byte user address */
+#define OB_DATA_ADDR0 (uint32_t)(OB + 0x00000004U)/*!< option byte data address 0 */
+#define OB_DATA_ADDR1 (uint32_t)(OB + 0x00000006U)/*!< option byte data address 1 */
+#define OB_WP_ADDR0 (uint32_t)(OB + 0x00000008U)/*!< option byte wp address 0 */
+#define OB_WP_ADDR1 (uint32_t)(OB + 0x0000000AU)/*!< option byte wp address 1 */
+
+/* FMC flags */
+#define FMC_FLAG_BUSY FMC_STAT_BUSY /*!< FMC busy flag */
+#define FMC_FLAG_PGERR FMC_STAT_PGERR /*!< FMC programming error flag */
+#define FMC_FLAG_WPERR FMC_STAT_WPERR /*!< FMC write protection error flag */
+#define FMC_FLAG_END FMC_STAT_ENDF /*!< FMC end of programming flag */
+
+/* FMC interrupt enable */
+#define FMC_INTEN_END FMC_CTL_ENDIE /*!< enable FMC end of operation interrupt */
+#define FMC_INTEN_ERR FMC_CTL_ERRIE /*!< enable FMC error interrupt */
+
+/* FMC time out */
+#define FMC_TIMEOUT_COUNT ((uint32_t)0x000F0000U) /*!< count to judge of FMC timeout */
+
+/* function declarations */
+/* FMC main memory programming functions */
+/* unlock the main FMC operation */
+void fmc_unlock(void);
+/* lock the main FMC operation */
+void fmc_lock(void);
+/* set the wait state counter value */
+void fmc_wscnt_set(uint8_t wscnt);
+/* fmc wait state enable */
+void fmc_wait_state_enable(void);
+/* fmc wait state disable */
+void fmc_wait_state_disable(void);
+/* FMC erase page */
+fmc_state_enum fmc_page_erase(uint32_t page_address);
+/* FMC erase whole chip */
+fmc_state_enum fmc_mass_erase(void);
+/* FMC program a word at the corresponding address */
+fmc_state_enum fmc_word_program(uint32_t address, uint32_t data);
+/* FMC program a half word at the corresponding address */
+fmc_state_enum fmc_halfword_program(uint32_t address, uint16_t data);
+/* FMC program a word at the corresponding address without erasing */
+fmc_state_enum fmc_word_reprogram(uint32_t address, uint32_t data);
+
+/* FMC option bytes programming functions */
+/* unlock the option byte operation */
+void ob_unlock(void);
+/* lock the option byte operation */
+void ob_lock(void);
+/* reload the option byte and generate a system reset */
+void ob_reset(void);
+/* erase option byte */
+fmc_state_enum ob_erase(void);
+/* enable option byte write protection (OB_WP) */
+fmc_state_enum ob_write_protection_enable(uint16_t ob_wp);
+/* configure read out protect */
+fmc_state_enum ob_security_protection_config(uint8_t ob_spc);
+/* write the FMC option byte user */
+fmc_state_enum ob_user_write(uint8_t ob_user);
+/* write the FMC option byte data */
+fmc_state_enum ob_data_program(uint32_t address, uint8_t data);
+/* get the FMC option byte OB_USER */
+uint8_t ob_user_get(void);
+/* get the FMC option byte OB_DATA */
+uint16_t ob_data_get(void);
+/* get the FMC option byte write protection */
+uint16_t ob_write_protection_get(void);
+/* get the value of FMC option byte security protection level (PLEVEL) in FMC_OBSTAT register */
+uint32_t ob_obstat_plevel_get(void);
+
+/* FMC interrupts and flags management functions */
+/* enable FMC interrupt */
+void fmc_interrupt_enable(uint32_t interrupt);
+/* disable FMC interrupt */
+void fmc_interrupt_disable(uint32_t interrupt);
+/* get flag set or reset */
+FlagStatus fmc_flag_get(uint32_t flag);
+/* clear the FMC pending flag */
+void fmc_flag_clear(uint32_t flag);
+/* get interrupt flag set or reset */
+FlagStatus fmc_interrupt_flag_get(uint32_t flag);
+/* clear the FMC interrupt pending flag */
+void fmc_interrupt_flag_clear(uint32_t flag);
+/* return the FMC state */
+fmc_state_enum fmc_state_get(void);
+/* check FMC ready or not */
+fmc_state_enum fmc_ready_wait(uint32_t timeout);
+/* get current option byte value */
+void ob_parm_get(ob_parm_struct *ob_parm);
+/* modify the target option byte depending on the original value */
+void ob_value_modify(uint32_t address, uint16_t value, ob_parm_struct *ob_parm);
+
+#endif /* GD32F3X0_FMC_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_fwdgt.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_fwdgt.h
new file mode 100644
index 00000000..852aa009
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_fwdgt.h
@@ -0,0 +1,126 @@
+/*!
+ \file gd32f3x0_fwdgt.h
+ \brief definitions for the FWDGT
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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 GD32F3X0_FWDGT_H
+#define GD32F3X0_FWDGT_H
+
+#include "gd32f3x0.h"
+
+/* FWDGT definitions */
+#define FWDGT FWDGT_BASE
+
+/* registers definitions */
+#define FWDGT_CTL REG32(FWDGT + 0x00000000U) /*!< FWDGT control register */
+#define FWDGT_PSC REG32(FWDGT + 0x00000004U) /*!< FWDGT prescaler register */
+#define FWDGT_RLD REG32(FWDGT + 0x00000008U) /*!< FWDGT reload register */
+#define FWDGT_STAT REG32(FWDGT + 0x0000000CU) /*!< FWDGT status register */
+#define FWDGT_WND REG32(FWDGT + 0x00000010U) /*!< FWDGT window register */
+
+/* bits definitions */
+/* FWDGT_CTL */
+#define FWDGT_CTL_CMD BITS(0,15) /*!< FWDGT command value */
+
+/* FWDGT_PSC */
+#define FWDGT_PSC_PSC BITS(0,2) /*!< FWDGT prescaler divider value */
+
+/* FWDGT_RLD */
+#define FWDGT_RLD_RLD BITS(0,11) /*!< FWDGT counter reload value */
+
+/* FWDGT_STAT */
+#define FWDGT_STAT_PUD BIT(0) /*!< FWDGT prescaler divider value update */
+#define FWDGT_STAT_RUD BIT(1) /*!< FWDGT counter reload value update */
+#define FWDGT_STAT_WUD BIT(2) /*!< FWDGT counter window value update */
+
+/* FWDGT_WND */
+#define FWDGT_WND_WND BITS(0,11) /*!< FWDGT counter window value */
+
+/* constants definitions */
+/* FWDGT_CTL register value */
+#define CTL_CMD(regval) (BITS(0,15) & ((uint32_t)(regval) << 0U)) /*!< write value to FWDGT_CTL_CMD bit field */
+
+/* FWDGT_PSC register value */
+#define PSC_PSC(regval) (BITS(0,2) & ((uint32_t)(regval) << 0U))
+#define FWDGT_PSC_DIV4 ((uint8_t)PSC_PSC(0)) /*!< FWDGT prescaler set to 4 */
+#define FWDGT_PSC_DIV8 ((uint8_t)PSC_PSC(1)) /*!< FWDGT prescaler set to 8 */
+#define FWDGT_PSC_DIV16 ((uint8_t)PSC_PSC(2)) /*!< FWDGT prescaler set to 16 */
+#define FWDGT_PSC_DIV32 ((uint8_t)PSC_PSC(3)) /*!< FWDGT prescaler set to 32 */
+#define FWDGT_PSC_DIV64 ((uint8_t)PSC_PSC(4)) /*!< FWDGT prescaler set to 64 */
+#define FWDGT_PSC_DIV128 ((uint8_t)PSC_PSC(5)) /*!< FWDGT prescaler set to 128 */
+#define FWDGT_PSC_DIV256 ((uint8_t)PSC_PSC(6)) /*!< FWDGT prescaler set to 256 */
+
+/* FWDGT_RLD register value */
+#define RLD_RLD(regval) (BITS(0,11) & ((uint32_t)(regval) << 0U)) /*!< write value to FWDGT_RLD_RLD bit field */
+
+/* FWDGT_WND register value */
+#define WND_WND(regval) (BITS(0,11) & ((uint32_t)(regval) << 0U)) /*!< write value to FWDGT_WND_WND bit field */
+
+/* control value */
+#define FWDGT_WRITEACCESS_ENABLE ((uint16_t)0x5555U) /*!< FWDGT_CTL bits write access enable value */
+#define FWDGT_WRITEACCESS_DISABLE ((uint16_t)0x0000U) /*!< FWDGT_CTL bits write access disable value */
+#define FWDGT_KEY_RELOAD ((uint16_t)0xAAAAU) /*!< FWDGT_CTL bits fwdgt counter reload value */
+#define FWDGT_KEY_ENABLE ((uint16_t)0xCCCCU) /*!< FWDGT_CTL bits fwdgt counter enable value */
+
+/* FWDGT timeout value */
+#define FWDGT_WND_TIMEOUT ((uint32_t)0x000FFFFFU) /*!< FWDGT_WND register write operation state flag timeout */
+#define FWDGT_PSC_TIMEOUT ((uint32_t)0x000FFFFFU) /*!< FWDGT_PSC register write operation state flag timeout */
+#define FWDGT_RLD_TIMEOUT ((uint32_t)0x000FFFFFU) /*!< FWDGT_RLD register write operation state flag timeout */
+
+/* FWDGT flag definitions */
+#define FWDGT_FLAG_PUD FWDGT_STAT_PUD /*!< a write operation to FWDGT_PSC register is on going */
+#define FWDGT_FLAG_RUD FWDGT_STAT_RUD /*!< a write operation to FWDGT_RLD register is on going */
+#define FWDGT_FLAG_WUD FWDGT_STAT_WUD /*!< a write operation to FWDGT_WND register is on going */
+
+/* function declarations */
+/* enable write access to FWDGT_PSC,FWDGT_RLD and FWDGT_WND */
+void fwdgt_write_enable(void);
+/* disable write access to FWDGT_PSC,FWDGT_RLD and FWDGT_WND */
+void fwdgt_write_disable(void);
+/* start the free watchdog timer counter */
+void fwdgt_enable(void);
+
+/* configure the free watchdog timer counter window value */
+ErrStatus fwdgt_window_value_config(uint16_t window_value);
+/* reload the counter of FWDGT */
+void fwdgt_counter_reload(void);
+/* configure counter reload value, and prescaler divider value */
+ErrStatus fwdgt_config(uint16_t reload_value, uint8_t prescaler_div);
+
+/* get flag state of FWDGT */
+FlagStatus fwdgt_flag_get(uint16_t flag);
+
+#endif /* GD32F3X0_FWDGT_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_gpio.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_gpio.h
new file mode 100644
index 00000000..02dc0a7b
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_gpio.h
@@ -0,0 +1,410 @@
+/*!
+ \file gd32f3x0_gpio.h
+ \brief definitions for the GPIO
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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 GD32F3X0_GPIO_H
+#define GD32F3X0_GPIO_H
+
+#include "gd32f3x0.h"
+
+/* GPIOx(x=A,B,C,D,F) definitions */
+#define GPIOA (GPIO_BASE + 0x00000000U)
+#define GPIOB (GPIO_BASE + 0x00000400U)
+#define GPIOC (GPIO_BASE + 0x00000800U)
+#define GPIOD (GPIO_BASE + 0x00000C00U)
+#define GPIOF (GPIO_BASE + 0x00001400U)
+
+/* registers definitions */
+#define GPIO_CTL(gpiox) REG32((gpiox) + 0x00000000U) /*!< GPIO port control register */
+#define GPIO_OMODE(gpiox) REG32((gpiox) + 0x00000004U) /*!< GPIO port output mode register */
+#define GPIO_OSPD0(gpiox) REG32((gpiox) + 0x00000008U) /*!< GPIO port output speed register 0 */
+#define GPIO_PUD(gpiox) REG32((gpiox) + 0x0000000CU) /*!< GPIO port pull-up/pull-down register */
+#define GPIO_ISTAT(gpiox) REG32((gpiox) + 0x00000010U) /*!< GPIO port input status register */
+#define GPIO_OCTL(gpiox) REG32((gpiox) + 0x00000014U) /*!< GPIO port output control register */
+#define GPIO_BOP(gpiox) REG32((gpiox) + 0x00000018U) /*!< GPIO port bit operation register */
+#define GPIO_LOCK(gpiox) REG32((gpiox) + 0x0000001CU) /*!< GPIO port configuration lock register */
+#define GPIO_AFSEL0(gpiox) REG32((gpiox) + 0x00000020U) /*!< GPIO alternate function selected register 0 */
+#define GPIO_AFSEL1(gpiox) REG32((gpiox) + 0x00000024U) /*!< GPIO alternate function selected register 1 */
+#define GPIO_BC(gpiox) REG32((gpiox) + 0x00000028U) /*!< GPIO bit clear register */
+#define GPIO_TG(gpiox) REG32((gpiox) + 0x0000002CU) /*!< GPIO port bit toggle register */
+#define GPIO_OSPD1(gpiox) REG32((gpiox) + 0x0000003CU) /*!< GPIO port output speed register 1 */
+
+/* bits definitions */
+/* GPIO_CTL */
+#define GPIO_CTL_CTL0 BITS(0,1) /*!< pin 0 configuration bits */
+#define GPIO_CTL_CTL1 BITS(2,3) /*!< pin 1 configuration bits */
+#define GPIO_CTL_CTL2 BITS(4,5) /*!< pin 2 configuration bits */
+#define GPIO_CTL_CTL3 BITS(6,7) /*!< pin 3 configuration bits */
+#define GPIO_CTL_CTL4 BITS(8,9) /*!< pin 4 configuration bits */
+#define GPIO_CTL_CTL5 BITS(10,11) /*!< pin 5 configuration bits */
+#define GPIO_CTL_CTL6 BITS(12,13) /*!< pin 6 configuration bits */
+#define GPIO_CTL_CTL7 BITS(14,15) /*!< pin 7 configuration bits */
+#define GPIO_CTL_CTL8 BITS(16,17) /*!< pin 8 configuration bits */
+#define GPIO_CTL_CTL9 BITS(18,19) /*!< pin 9 configuration bits */
+#define GPIO_CTL_CTL10 BITS(20,21) /*!< pin 10 configuration bits */
+#define GPIO_CTL_CTL11 BITS(22,23) /*!< pin 11 configuration bits */
+#define GPIO_CTL_CTL12 BITS(24,25) /*!< pin 12 configuration bits */
+#define GPIO_CTL_CTL13 BITS(26,27) /*!< pin 13 configuration bits */
+#define GPIO_CTL_CTL14 BITS(28,29) /*!< pin 14 configuration bits */
+#define GPIO_CTL_CTL15 BITS(30,31) /*!< pin 15 configuration bits */
+
+/* GPIO_OMODE */
+#define GPIO_OMODE_OM0 BIT(0) /*!< pin 0 output mode bit */
+#define GPIO_OMODE_OM1 BIT(1) /*!< pin 1 output mode bit */
+#define GPIO_OMODE_OM2 BIT(2) /*!< pin 2 output mode bit */
+#define GPIO_OMODE_OM3 BIT(3) /*!< pin 3 output mode bit */
+#define GPIO_OMODE_OM4 BIT(4) /*!< pin 4 output mode bit */
+#define GPIO_OMODE_OM5 BIT(5) /*!< pin 5 output mode bit */
+#define GPIO_OMODE_OM6 BIT(6) /*!< pin 6 output mode bit */
+#define GPIO_OMODE_OM7 BIT(7) /*!< pin 7 output mode bit */
+#define GPIO_OMODE_OM8 BIT(8) /*!< pin 8 output mode bit */
+#define GPIO_OMODE_OM9 BIT(9) /*!< pin 9 output mode bit */
+#define GPIO_OMODE_OM10 BIT(10) /*!< pin 10 output mode bit */
+#define GPIO_OMODE_OM11 BIT(11) /*!< pin 11 output mode bit */
+#define GPIO_OMODE_OM12 BIT(12) /*!< pin 12 output mode bit */
+#define GPIO_OMODE_OM13 BIT(13) /*!< pin 13 output mode bit */
+#define GPIO_OMODE_OM14 BIT(14) /*!< pin 14 output mode bit */
+#define GPIO_OMODE_OM15 BIT(15) /*!< pin 15 output mode bit */
+
+/* GPIO_OSPD0 */
+#define GPIO_OSPD0_OSPD0 BITS(0,1) /*!< pin 0 output max speed bits */
+#define GPIO_OSPD0_OSPD1 BITS(2,3) /*!< pin 1 output max speed bits */
+#define GPIO_OSPD0_OSPD2 BITS(4,5) /*!< pin 2 output max speed bits */
+#define GPIO_OSPD0_OSPD3 BITS(6,7) /*!< pin 3 output max speed bits */
+#define GPIO_OSPD0_OSPD4 BITS(8,9) /*!< pin 4 output max speed bits */
+#define GPIO_OSPD0_OSPD5 BITS(10,11) /*!< pin 5 output max speed bits */
+#define GPIO_OSPD0_OSPD6 BITS(12,13) /*!< pin 6 output max speed bits */
+#define GPIO_OSPD0_OSPD7 BITS(14,15) /*!< pin 7 output max speed bits */
+#define GPIO_OSPD0_OSPD8 BITS(16,17) /*!< pin 8 output max speed bits */
+#define GPIO_OSPD0_OSPD9 BITS(18,19) /*!< pin 9 output max speed bits */
+#define GPIO_OSPD0_OSPD10 BITS(20,21) /*!< pin 10 output max speed bits */
+#define GPIO_OSPD0_OSPD11 BITS(22,23) /*!< pin 11 output max speed bits */
+#define GPIO_OSPD0_OSPD12 BITS(24,25) /*!< pin 12 output max speed bits */
+#define GPIO_OSPD0_OSPD13 BITS(26,27) /*!< pin 13 output max speed bits */
+#define GPIO_OSPD0_OSPD14 BITS(28,29) /*!< pin 14 output max speed bits */
+#define GPIO_OSPD0_OSPD15 BITS(30,31) /*!< pin 15 output max speed bits */
+
+/* GPIO_PUD */
+#define GPIO_PUD_PUD0 BITS(0,1) /*!< pin 0 pull-up or pull-down bits */
+#define GPIO_PUD_PUD1 BITS(2,3) /*!< pin 1 pull-up or pull-down bits */
+#define GPIO_PUD_PUD2 BITS(4,5) /*!< pin 2 pull-up or pull-down bits */
+#define GPIO_PUD_PUD3 BITS(6,7) /*!< pin 3 pull-up or pull-down bits */
+#define GPIO_PUD_PUD4 BITS(8,9) /*!< pin 4 pull-up or pull-down bits */
+#define GPIO_PUD_PUD5 BITS(10,11) /*!< pin 5 pull-up or pull-down bits */
+#define GPIO_PUD_PUD6 BITS(12,13) /*!< pin 6 pull-up or pull-down bits */
+#define GPIO_PUD_PUD7 BITS(14,15) /*!< pin 7 pull-up or pull-down bits */
+#define GPIO_PUD_PUD8 BITS(16,17) /*!< pin 8 pull-up or pull-down bits */
+#define GPIO_PUD_PUD9 BITS(18,19) /*!< pin 9 pull-up or pull-down bits */
+#define GPIO_PUD_PUD10 BITS(20,21) /*!< pin 10 pull-up or pull-down bits */
+#define GPIO_PUD_PUD11 BITS(22,23) /*!< pin 11 pull-up or pull-down bits */
+#define GPIO_PUD_PUD12 BITS(24,25) /*!< pin 12 pull-up or pull-down bits */
+#define GPIO_PUD_PUD13 BITS(26,27) /*!< pin 13 pull-up or pull-down bits */
+#define GPIO_PUD_PUD14 BITS(28,29) /*!< pin 14 pull-up or pull-down bits */
+#define GPIO_PUD_PUD15 BITS(30,31) /*!< pin 15 pull-up or pull-down bits */
+
+/* GPIO_ISTAT */
+#define GPIO_ISTAT_ISTAT0 BIT(0) /*!< pin 0 input status */
+#define GPIO_ISTAT_ISTAT1 BIT(1) /*!< pin 1 input status */
+#define GPIO_ISTAT_ISTAT2 BIT(2) /*!< pin 2 input status */
+#define GPIO_ISTAT_ISTAT3 BIT(3) /*!< pin 3 input status */
+#define GPIO_ISTAT_ISTAT4 BIT(4) /*!< pin 4 input status */
+#define GPIO_ISTAT_ISTAT5 BIT(5) /*!< pin 5 input status */
+#define GPIO_ISTAT_ISTAT6 BIT(6) /*!< pin 6 input status */
+#define GPIO_ISTAT_ISTAT7 BIT(7) /*!< pin 7 input status */
+#define GPIO_ISTAT_ISTAT8 BIT(8) /*!< pin 8 input status */
+#define GPIO_ISTAT_ISTAT9 BIT(9) /*!< pin 9 input status */
+#define GPIO_ISTAT_ISTAT10 BIT(10) /*!< pin 10 input status */
+#define GPIO_ISTAT_ISTAT11 BIT(11) /*!< pin 11 input status */
+#define GPIO_ISTAT_ISTAT12 BIT(12) /*!< pin 12 input status */
+#define GPIO_ISTAT_ISTAT13 BIT(13) /*!< pin 13 input status */
+#define GPIO_ISTAT_ISTAT14 BIT(14) /*!< pin 14 input status */
+#define GPIO_ISTAT_ISTAT15 BIT(15) /*!< pin 15 input status */
+
+/* GPIO_OCTL */
+#define GPIO_OCTL_OCTL0 BIT(0) /*!< pin 0 output bit */
+#define GPIO_OCTL_OCTL1 BIT(1) /*!< pin 1 output bit */
+#define GPIO_OCTL_OCTL2 BIT(2) /*!< pin 2 output bit */
+#define GPIO_OCTL_OCTL3 BIT(3) /*!< pin 3 output bit */
+#define GPIO_OCTL_OCTL4 BIT(4) /*!< pin 4 output bit */
+#define GPIO_OCTL_OCTL5 BIT(5) /*!< pin 5 output bit */
+#define GPIO_OCTL_OCTL6 BIT(6) /*!< pin 6 output bit */
+#define GPIO_OCTL_OCTL7 BIT(7) /*!< pin 7 output bit */
+#define GPIO_OCTL_OCTL8 BIT(8) /*!< pin 8 output bit */
+#define GPIO_OCTL_OCTL9 BIT(9) /*!< pin 9 output bit */
+#define GPIO_OCTL_OCTL10 BIT(10) /*!< pin 10 output bit */
+#define GPIO_OCTL_OCTL11 BIT(11) /*!< pin 11 output bit */
+#define GPIO_OCTL_OCTL12 BIT(12) /*!< pin 12 output bit */
+#define GPIO_OCTL_OCTL13 BIT(13) /*!< pin 13 output bit */
+#define GPIO_OCTL_OCTL14 BIT(14) /*!< pin 14 output bit */
+#define GPIO_OCTL_OCTL15 BIT(15) /*!< pin 15 output bit */
+
+/* GPIO_BOP */
+#define GPIO_BOP_BOP0 BIT(0) /*!< pin 0 set bit */
+#define GPIO_BOP_BOP1 BIT(1) /*!< pin 1 set bit */
+#define GPIO_BOP_BOP2 BIT(2) /*!< pin 2 set bit */
+#define GPIO_BOP_BOP3 BIT(3) /*!< pin 3 set bit */
+#define GPIO_BOP_BOP4 BIT(4) /*!< pin 4 set bit */
+#define GPIO_BOP_BOP5 BIT(5) /*!< pin 5 set bit */
+#define GPIO_BOP_BOP6 BIT(6) /*!< pin 6 set bit */
+#define GPIO_BOP_BOP7 BIT(7) /*!< pin 7 set bit */
+#define GPIO_BOP_BOP8 BIT(8) /*!< pin 8 set bit */
+#define GPIO_BOP_BOP9 BIT(9) /*!< pin 9 set bit */
+#define GPIO_BOP_BOP10 BIT(10) /*!< pin 10 set bit */
+#define GPIO_BOP_BOP11 BIT(11) /*!< pin 11 set bit */
+#define GPIO_BOP_BOP12 BIT(12) /*!< pin 12 set bit */
+#define GPIO_BOP_BOP13 BIT(13) /*!< pin 13 set bit */
+#define GPIO_BOP_BOP14 BIT(14) /*!< pin 14 set bit */
+#define GPIO_BOP_BOP15 BIT(15) /*!< pin 15 set bit */
+#define GPIO_BOP_CR0 BIT(16) /*!< pin 0 clear bit */
+#define GPIO_BOP_CR1 BIT(17) /*!< pin 1 clear bit */
+#define GPIO_BOP_CR2 BIT(18) /*!< pin 2 clear bit */
+#define GPIO_BOP_CR3 BIT(19) /*!< pin 3 clear bit */
+#define GPIO_BOP_CR4 BIT(20) /*!< pin 4 clear bit */
+#define GPIO_BOP_CR5 BIT(21) /*!< pin 5 clear bit */
+#define GPIO_BOP_CR6 BIT(22) /*!< pin 6 clear bit */
+#define GPIO_BOP_CR7 BIT(23) /*!< pin 7 clear bit */
+#define GPIO_BOP_CR8 BIT(24) /*!< pin 8 clear bit */
+#define GPIO_BOP_CR9 BIT(25) /*!< pin 9 clear bit */
+#define GPIO_BOP_CR10 BIT(26) /*!< pin 10 clear bit */
+#define GPIO_BOP_CR11 BIT(27) /*!< pin 11 clear bit */
+#define GPIO_BOP_CR12 BIT(28) /*!< pin 12 clear bit */
+#define GPIO_BOP_CR13 BIT(29) /*!< pin 13 clear bit */
+#define GPIO_BOP_CR14 BIT(30) /*!< pin 14 clear bit */
+#define GPIO_BOP_CR15 BIT(31) /*!< pin 15 clear bit */
+
+/* GPIO_LOCK */
+#define GPIO_LOCK_LK0 BIT(0) /*!< pin 0 lock bit */
+#define GPIO_LOCK_LK1 BIT(1) /*!< pin 1 lock bit */
+#define GPIO_LOCK_LK2 BIT(2) /*!< pin 2 lock bit */
+#define GPIO_LOCK_LK3 BIT(3) /*!< pin 3 lock bit */
+#define GPIO_LOCK_LK4 BIT(4) /*!< pin 4 lock bit */
+#define GPIO_LOCK_LK5 BIT(5) /*!< pin 5 lock bit */
+#define GPIO_LOCK_LK6 BIT(6) /*!< pin 6 lock bit */
+#define GPIO_LOCK_LK7 BIT(7) /*!< pin 7 lock bit */
+#define GPIO_LOCK_LK8 BIT(8) /*!< pin 8 lock bit */
+#define GPIO_LOCK_LK9 BIT(9) /*!< pin 9 lock bit */
+#define GPIO_LOCK_LK10 BIT(10) /*!< pin 10 lock bit */
+#define GPIO_LOCK_LK11 BIT(11) /*!< pin 11 lock bit */
+#define GPIO_LOCK_LK12 BIT(12) /*!< pin 12 lock bit */
+#define GPIO_LOCK_LK13 BIT(13) /*!< pin 13 lock bit */
+#define GPIO_LOCK_LK14 BIT(14) /*!< pin 14 lock bit */
+#define GPIO_LOCK_LK15 BIT(15) /*!< pin 15 lock bit */
+#define GPIO_LOCK_LKK BIT(16) /*!< pin sequence lock key */
+
+/* GPIO_AFSEL0 */
+#define GPIO_AFSEL0_SEL0 BITS(0,3) /*!< pin 0 alternate function selected */
+#define GPIO_AFSEL0_SEL1 BITS(4,7) /*!< pin 1 alternate function selected */
+#define GPIO_AFSEL0_SEL2 BITS(8,11) /*!< pin 2 alternate function selected */
+#define GPIO_AFSEL0_SEL3 BITS(12,15) /*!< pin 3 alternate function selected */
+#define GPIO_AFSEL0_SEL4 BITS(16,19) /*!< pin 4 alternate function selected */
+#define GPIO_AFSEL0_SEL5 BITS(20,23) /*!< pin 5 alternate function selected */
+#define GPIO_AFSEL0_SEL6 BITS(24,27) /*!< pin 6 alternate function selected */
+#define GPIO_AFSEL0_SEL7 BITS(28,31) /*!< pin 7 alternate function selected */
+
+/* GPIO_AFSEL1 */
+#define GPIO_AFSEL1_SEL8 BITS(0,3) /*!< pin 8 alternate function selected */
+#define GPIO_AFSEL1_SEL9 BITS(4,7) /*!< pin 9 alternate function selected */
+#define GPIO_AFSEL1_SEL10 BITS(8,11) /*!< pin 10 alternate function selected */
+#define GPIO_AFSEL1_SEL11 BITS(12,15) /*!< pin 11 alternate function selected */
+#define GPIO_AFSEL1_SEL12 BITS(16,19) /*!< pin 12 alternate function selected */
+#define GPIO_AFSEL1_SEL13 BITS(20,23) /*!< pin 13 alternate function selected */
+#define GPIO_AFSEL1_SEL14 BITS(24,27) /*!< pin 14 alternate function selected */
+#define GPIO_AFSEL1_SEL15 BITS(28,31) /*!< pin 15 alternate function selected */
+
+/* GPIO_BC */
+#define GPIO_BC_CR0 BIT(0) /*!< pin 0 clear bit */
+#define GPIO_BC_CR1 BIT(1) /*!< pin 1 clear bit */
+#define GPIO_BC_CR2 BIT(2) /*!< pin 2 clear bit */
+#define GPIO_BC_CR3 BIT(3) /*!< pin 3 clear bit */
+#define GPIO_BC_CR4 BIT(4) /*!< pin 4 clear bit */
+#define GPIO_BC_CR5 BIT(5) /*!< pin 5 clear bit */
+#define GPIO_BC_CR6 BIT(6) /*!< pin 6 clear bit */
+#define GPIO_BC_CR7 BIT(7) /*!< pin 7 clear bit */
+#define GPIO_BC_CR8 BIT(8) /*!< pin 8 clear bit */
+#define GPIO_BC_CR9 BIT(9) /*!< pin 9 clear bit */
+#define GPIO_BC_CR10 BIT(10) /*!< pin 10 clear bit */
+#define GPIO_BC_CR11 BIT(11) /*!< pin 11 clear bit */
+#define GPIO_BC_CR12 BIT(12) /*!< pin 12 clear bit */
+#define GPIO_BC_CR13 BIT(13) /*!< pin 13 clear bit */
+#define GPIO_BC_CR14 BIT(14) /*!< pin 14 clear bit */
+#define GPIO_BC_CR15 BIT(15) /*!< pin 15 clear bit */
+
+/* GPIO_TG */
+#define GPIO_TG_TG0 BIT(0) /*!< pin 0 toggle bit */
+#define GPIO_TG_TG1 BIT(1) /*!< pin 1 toggle bit */
+#define GPIO_TG_TG2 BIT(2) /*!< pin 2 toggle bit */
+#define GPIO_TG_TG3 BIT(3) /*!< pin 3 toggle bit */
+#define GPIO_TG_TG4 BIT(4) /*!< pin 4 toggle bit */
+#define GPIO_TG_TG5 BIT(5) /*!< pin 5 toggle bit */
+#define GPIO_TG_TG6 BIT(6) /*!< pin 6 toggle bit */
+#define GPIO_TG_TG7 BIT(7) /*!< pin 7 toggle bit */
+#define GPIO_TG_TG8 BIT(8) /*!< pin 8 toggle bit */
+#define GPIO_TG_TG9 BIT(9) /*!< pin 9 toggle bit */
+#define GPIO_TG_TG10 BIT(10) /*!< pin 10 toggle bit */
+#define GPIO_TG_TG11 BIT(11) /*!< pin 11 toggle bit */
+#define GPIO_TG_TG12 BIT(12) /*!< pin 12 toggle bit */
+#define GPIO_TG_TG13 BIT(13) /*!< pin 13 toggle bit */
+#define GPIO_TG_TG14 BIT(14) /*!< pin 14 toggle bit */
+#define GPIO_TG_TG15 BIT(15) /*!< pin 15 toggle bit */
+
+/* GPIO_OSPD1 */
+#define GPIO_OSPD1_SPD0 BIT(0) /*!< set pin 0 very high output speed when OSPD0 is "11" */
+#define GPIO_OSPD1_SPD1 BIT(1) /*!< set pin 1 very high output speed when OSPD1 is "11" */
+#define GPIO_OSPD1_SPD2 BIT(2) /*!< set pin 2 very high output speed when OSPD2 is "11" */
+#define GPIO_OSPD1_SPD3 BIT(3) /*!< set pin 3 very high output speed when OSPD3 is "11" */
+#define GPIO_OSPD1_SPD4 BIT(4) /*!< set pin 4 very high output speed when OSPD4 is "11" */
+#define GPIO_OSPD1_SPD5 BIT(5) /*!< set pin 5 very high output speed when OSPD5 is "11" */
+#define GPIO_OSPD1_SPD6 BIT(6) /*!< set pin 6 very high output speed when OSPD6 is "11" */
+#define GPIO_OSPD1_SPD7 BIT(7) /*!< set pin 7 very high output speed when OSPD7 is "11" */
+#define GPIO_OSPD1_SPD8 BIT(8) /*!< set pin 8 very high output speed when OSPD8 is "11" */
+#define GPIO_OSPD1_SPD9 BIT(9) /*!< set pin 9 very high output speed when OSPD9 is "11" */
+#define GPIO_OSPD1_SPD10 BIT(10) /*!< set pin 10 very high output speed when OSPD10 is "11" */
+#define GPIO_OSPD1_SPD11 BIT(11) /*!< set pin 11 very high output speed when OSPD11 is "11" */
+#define GPIO_OSPD1_SPD12 BIT(12) /*!< set pin 12 very high output speed when OSPD12 is "11" */
+#define GPIO_OSPD1_SPD13 BIT(13) /*!< set pin 13 very high output speed when OSPD13 is "11" */
+#define GPIO_OSPD1_SPD14 BIT(14) /*!< set pin 14 very high output speed when OSPD14 is "11" */
+#define GPIO_OSPD1_SPD15 BIT(15) /*!< set pin 15 very high output speed when OSPD15 is "11" */
+
+/* constants definitions */
+typedef FlagStatus bit_status;
+
+/* output mode definitions */
+#define CTL_CLTR(regval) (BITS(0,1) & ((uint32_t)(regval) << 0))
+#define GPIO_MODE_INPUT CTL_CLTR(0) /*!< input mode */
+#define GPIO_MODE_OUTPUT CTL_CLTR(1) /*!< output mode */
+#define GPIO_MODE_AF CTL_CLTR(2) /*!< alternate function mode */
+#define GPIO_MODE_ANALOG CTL_CLTR(3) /*!< analog mode */
+
+/* pull-up/pull-down definitions */
+#define PUD_PUPD(regval) (BITS(0,1) & ((uint32_t)(regval) << 0))
+#define GPIO_PUPD_NONE PUD_PUPD(0) /*!< floating mode, no pull-up and pull-down resistors */
+#define GPIO_PUPD_PULLUP PUD_PUPD(1) /*!< with pull-up resistor */
+#define GPIO_PUPD_PULLDOWN PUD_PUPD(2) /*!< with pull-down resistor */
+
+/* GPIO pin definitions */
+#define GPIO_PIN_0 BIT(0) /*!< GPIO pin 0 */
+#define GPIO_PIN_1 BIT(1) /*!< GPIO pin 1 */
+#define GPIO_PIN_2 BIT(2) /*!< GPIO pin 2 */
+#define GPIO_PIN_3 BIT(3) /*!< GPIO pin 3 */
+#define GPIO_PIN_4 BIT(4) /*!< GPIO pin 4 */
+#define GPIO_PIN_5 BIT(5) /*!< GPIO pin 5 */
+#define GPIO_PIN_6 BIT(6) /*!< GPIO pin 6 */
+#define GPIO_PIN_7 BIT(7) /*!< GPIO pin 7 */
+#define GPIO_PIN_8 BIT(8) /*!< GPIO pin 8 */
+#define GPIO_PIN_9 BIT(9) /*!< GPIO pin 9 */
+#define GPIO_PIN_10 BIT(10) /*!< GPIO pin 10 */
+#define GPIO_PIN_11 BIT(11) /*!< GPIO pin 11 */
+#define GPIO_PIN_12 BIT(12) /*!< GPIO pin 12 */
+#define GPIO_PIN_13 BIT(13) /*!< GPIO pin 13 */
+#define GPIO_PIN_14 BIT(14) /*!< GPIO pin 14 */
+#define GPIO_PIN_15 BIT(15) /*!< GPIO pin 15 */
+#define GPIO_PIN_ALL BITS(0,15) /*!< GPIO pin all */
+
+/* GPIO mode configuration values */
+#define GPIO_MODE_SET(n, mode) ((uint32_t)((uint32_t)(mode) << (2U * (n))))
+#define GPIO_MODE_MASK(n) ((uint32_t)((uint32_t)0x00000003U << (2U * (n))))
+
+/* GPIO pull-up/pull-down values */
+#define GPIO_PUPD_SET(n, pupd) ((uint32_t)((uint32_t)(pupd) << (2U * (n))))
+#define GPIO_PUPD_MASK(n) ((uint32_t)((uint32_t)0x00000003U << (2U * (n))))
+
+/* GPIO output speed values */
+#define GPIO_OSPEED_SET(n, speed) ((uint32_t)((uint32_t)(speed) << (2U * (n))))
+#define GPIO_OSPEED_MASK(n) ((uint32_t)((uint32_t)0x00000003U << (2U * (n))))
+
+/* GPIO output type */
+#define GPIO_OTYPE_PP ((uint8_t)(0x00U)) /*!< push pull mode */
+#define GPIO_OTYPE_OD ((uint8_t)(0x01U)) /*!< open drain mode */
+
+/* GPIO output max speed value */
+#define OSPD_OSPD0(regval) (BITS(0,1) & ((uint32_t)(regval) << 0))
+#define GPIO_OSPEED_2MHZ OSPD_OSPD0(0) /*!< output max speed 2MHz */
+#define GPIO_OSPEED_10MHZ OSPD_OSPD0(1) /*!< output max speed 10MHz */
+#define GPIO_OSPEED_50MHZ OSPD_OSPD0(3) /*!< output max speed 50MHz */
+#define GPIO_OSPEED_MAX ((uint32_t)0x0000FFFFU) /*!< GPIO very high output speed, max speed more than 50MHz */
+
+/* GPIO alternate function values */
+#define GPIO_AFR_SET(n, af) ((uint32_t)((uint32_t)(af) << (4U * (n))))
+#define GPIO_AFR_MASK(n) ((uint32_t)((uint32_t)0x0000000FU << (4U * (n))))
+
+/* GPIO alternate function */
+#define AF(regval) (BITS(0,3) & ((uint32_t)(regval) << 0))
+#define GPIO_AF_0 AF(0) /*!< alternate function 0 selected */
+#define GPIO_AF_1 AF(1) /*!< alternate function 1 selected */
+#define GPIO_AF_2 AF(2) /*!< alternate function 2 selected */
+#define GPIO_AF_3 AF(3) /*!< alternate function 3 selected */
+#define GPIO_AF_4 AF(4) /*!< alternate function 4 selected (port A,B only) */
+#define GPIO_AF_5 AF(5) /*!< alternate function 5 selected (port A,B only) */
+#define GPIO_AF_6 AF(6) /*!< alternate function 6 selected (port A,B only) */
+#define GPIO_AF_7 AF(7) /*!< alternate function 7 selected (port A,B only) */
+
+/* function declarations */
+/* reset GPIO port */
+void gpio_deinit(uint32_t gpio_periph);
+/* set GPIO mode */
+void gpio_mode_set(uint32_t gpio_periph, uint32_t mode, uint32_t pull_up_down, uint32_t pin);
+/* set GPIO output type and speed */
+void gpio_output_options_set(uint32_t gpio_periph, uint8_t otype, uint32_t speed, uint32_t pin);
+
+/* set GPIO pin bit */
+void gpio_bit_set(uint32_t gpio_periph, uint32_t pin);
+/* reset GPIO pin bit */
+void gpio_bit_reset(uint32_t gpio_periph, uint32_t pin);
+/* write data to the specified GPIO pin */
+void gpio_bit_write(uint32_t gpio_periph, uint32_t pin, bit_status bit_value);
+/* write data to the specified GPIO port */
+void gpio_port_write(uint32_t gpio_periph, uint16_t data);
+
+/* get GPIO pin input status */
+FlagStatus gpio_input_bit_get(uint32_t gpio_periph, uint32_t pin);
+/* get GPIO port input status */
+uint16_t gpio_input_port_get(uint32_t gpio_periph);
+/* get GPIO pin output status */
+FlagStatus gpio_output_bit_get(uint32_t gpio_periph, uint32_t pin);
+/* get GPIO port output status */
+uint16_t gpio_output_port_get(uint32_t gpio_periph);
+
+/* set GPIO alternate function */
+void gpio_af_set(uint32_t gpio_periph, uint32_t alt_func_num, uint32_t pin);
+/* lock GPIO pin bit */
+void gpio_pin_lock(uint32_t gpio_periph, uint32_t pin);
+
+/* toggle GPIO pin status */
+void gpio_bit_toggle(uint32_t gpio_periph, uint32_t pin);
+/* toggle GPIO port status */
+void gpio_port_toggle(uint32_t gpio_periph);
+
+#endif /* GD32F3X0_GPIO_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_i2c.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_i2c.h
new file mode 100644
index 00000000..fa00a6fc
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_i2c.h
@@ -0,0 +1,347 @@
+/*!
+ \file gd32f3x0_i2c.h
+ \brief definitions for the I2C
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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 GD32F3X0_I2C_H
+#define GD32F3X0_I2C_H
+
+#include "gd32f3x0.h"
+
+/* I2Cx(x=0,1) definitions */
+#define I2C0 I2C_BASE /*!< I2C0 base address */
+#define I2C1 (I2C_BASE+0x00000400U) /*!< I2C1 base address */
+
+/* registers definitions */
+#define I2C_CTL0(i2cx) REG32((i2cx) + 0x00000000U) /*!< I2C control register 0 */
+#define I2C_CTL1(i2cx) REG32((i2cx) + 0x00000004U) /*!< I2C control register 1 */
+#define I2C_SADDR0(i2cx) REG32((i2cx) + 0x00000008U) /*!< I2C slave address register 0*/
+#define I2C_SADDR1(i2cx) REG32((i2cx) + 0x0000000CU) /*!< I2C slave address register */
+#define I2C_DATA(i2cx) REG32((i2cx) + 0x00000010U) /*!< I2C transfer buffer register */
+#define I2C_STAT0(i2cx) REG32((i2cx) + 0x00000014U) /*!< I2C transfer status register 0 */
+#define I2C_STAT1(i2cx) REG32((i2cx) + 0x00000018U) /*!< I2C transfer status register */
+#define I2C_CKCFG(i2cx) REG32((i2cx) + 0x0000001CU) /*!< I2C clock configure register */
+#define I2C_RT(i2cx) REG32((i2cx) + 0x00000020U) /*!< I2C rise time register */
+#define I2C_FMPCFG(i2cx) REG32((i2cx) + 0x00000090U) /*!< I2C fast-mode-plus configure register */
+
+/* bits definitions */
+/* I2Cx_CTL0 */
+#define I2C_CTL0_I2CEN BIT(0) /*!< peripheral enable */
+#define I2C_CTL0_SMBEN BIT(1) /*!< SMBus mode */
+#define I2C_CTL0_SMBSEL BIT(3) /*!< SMBus type */
+#define I2C_CTL0_ARPEN BIT(4) /*!< ARP enable */
+#define I2C_CTL0_PECEN BIT(5) /*!< PEC enable */
+#define I2C_CTL0_GCEN BIT(6) /*!< general call enable */
+#define I2C_CTL0_SS BIT(7) /*!< clock stretching disable (slave mode) */
+#define I2C_CTL0_START BIT(8) /*!< start generation */
+#define I2C_CTL0_STOP BIT(9) /*!< stop generation */
+#define I2C_CTL0_ACKEN BIT(10) /*!< acknowledge enable */
+#define I2C_CTL0_POAP BIT(11) /*!< acknowledge/PEC position (for data reception) */
+#define I2C_CTL0_PECTRANS BIT(12) /*!< packet error checking */
+#define I2C_CTL0_SALT BIT(13) /*!< SMBus alert */
+#define I2C_CTL0_SRESET BIT(15) /*!< software reset */
+
+/* I2Cx_CTL1 */
+#define I2C_CTL1_I2CCLK BITS(0,5) /*!< I2CCLK[5:0] bits (peripheral clock frequency) */
+#define I2C_CTL1_ERRIE BIT(8) /*!< error interrupt inable */
+#define I2C_CTL1_EVIE BIT(9) /*!< event interrupt enable */
+#define I2C_CTL1_BUFIE BIT(10) /*!< buffer interrupt enable */
+#define I2C_CTL1_DMAON BIT(11) /*!< DMA requests enable */
+#define I2C_CTL1_DMALST BIT(12) /*!< DMA last transfer */
+
+/* I2Cx_SADDR0 */
+#define I2C_SADDR0_ADDRESS0 BIT(0) /*!< bit 0 of a 10-bit address */
+#define I2C_SADDR0_ADDRESS BITS(1,7) /*!< 7-bit address or bits 7:1 of a 10-bit address */
+#define I2C_SADDR0_ADDRESS_H BITS(8,9) /*!< highest two bits of a 10-bit address */
+#define I2C_SADDR0_ADDFORMAT BIT(15) /*!< address mode for the I2C slave */
+
+/* I2Cx_SADDR1 */
+#define I2C_SADDR1_DUADEN BIT(0) /*!< aual-address mode switch */
+#define I2C_SADDR1_ADDRESS2 BITS(1,7) /*!< second I2C address for the slave in dual-address mode */
+
+/* I2Cx_DATA */
+#define I2C_DATA_TRB BITS(0,7) /*!< 8-bit data register */
+
+/* I2Cx_STAT0 */
+#define I2C_STAT0_SBSEND BIT(0) /*!< start bit (master mode) */
+#define I2C_STAT0_ADDSEND BIT(1) /*!< address sent (master mode)/matched (slave mode) */
+#define I2C_STAT0_BTC BIT(2) /*!< byte transfer finished */
+#define I2C_STAT0_ADD10SEND BIT(3) /*!< 10-bit header sent (master mode) */
+#define I2C_STAT0_STPDET BIT(4) /*!< stop detection (slave mode) */
+#define I2C_STAT0_RBNE BIT(6) /*!< data register not empty (receivers) */
+#define I2C_STAT0_TBE BIT(7) /*!< data register empty (transmitters) */
+#define I2C_STAT0_BERR BIT(8) /*!< bus error */
+#define I2C_STAT0_LOSTARB BIT(9) /*!< arbitration lost (master mode) */
+#define I2C_STAT0_AERR BIT(10) /*!< acknowledge failure */
+#define I2C_STAT0_OUERR BIT(11) /*!< overrun/underrun */
+#define I2C_STAT0_PECERR BIT(12) /*!< PEC error in reception */
+#define I2C_STAT0_SMBTO BIT(14) /*!< timeout signal in SMBus mode */
+#define I2C_STAT0_SMBALT BIT(15) /*!< SMBus alert status */
+
+/* I2Cx_STAT1 */
+#define I2C_STAT1_MASTER BIT(0) /*!< master/slave */
+#define I2C_STAT1_I2CBSY BIT(1) /*!< bus busy */
+#define I2C_STAT1_TR BIT(2) /*!< transmitter/receiver */
+#define I2C_STAT1_RXGC BIT(4) /*!< general call address (slave mode) */
+#define I2C_STAT1_DEFSMB BIT(5) /*!< SMBus device default address (slave mode) */
+#define I2C_STAT1_HSTSMB BIT(6) /*!< SMBus host header (slave mode) */
+#define I2C_STAT1_DUMODF BIT(7) /*!< dual flag (slave mode) */
+#define I2C_STAT1_PECV BITS(8,15) /*!< packet error checking value */
+
+/* I2Cx_CKCFG */
+#define I2C_CKCFG_CLKC BITS(0,11) /*!< clock control register in fast/standard mode or fast mode plus(master mode) */
+#define I2C_CKCFG_DTCY BIT(14) /*!< duty cycle of fast mode or fast mode plus */
+#define I2C_CKCFG_FAST BIT(15) /*!< I2C speed selection in master mode */
+
+/* I2Cx_RT */
+#define I2C_RT_RISETIME BITS(0,6) /*!< maximum rise time in fast/standard mode or fast mode plus(master mode) */
+
+/* I2Cx_FMPCFG */
+#define I2C_FMPCFG_FMPEN BIT(0) /*!< fast mode plus enable bit */
+
+/* constants definitions */
+/* define the I2C bit position and its register index offset */
+#define I2C_REGIDX_BIT(regidx, bitpos) (((uint32_t)(regidx) << 6) | (uint32_t)(bitpos))
+#define I2C_REG_VAL(i2cx, offset) (REG32((i2cx) + (((uint32_t)(offset) & 0x0000FFFFU) >> 6)))
+#define I2C_BIT_POS(val) ((uint32_t)(val) & 0x0000001FU)
+#define I2C_REGIDX_BIT2(regidx, bitpos, regidx2, bitpos2) (((uint32_t)(regidx2) << 22) | (uint32_t)((bitpos2) << 16)\
+ | (((uint32_t)(regidx) << 6) | (uint32_t)(bitpos)))
+#define I2C_REG_VAL2(i2cx, offset) (REG32((i2cx) + ((uint32_t)(offset) >> 22)))
+#define I2C_BIT_POS2(val) (((uint32_t)(val) & 0x001F0000U) >> 16)
+
+/* register offset */
+#define I2C_CTL1_REG_OFFSET (0x00000004U) /*!< CTL1 register offset */
+#define I2C_STAT0_REG_OFFSET (0x00000014U) /*!< STAT0 register offset */
+#define I2C_STAT1_REG_OFFSET (0x00000018U) /*!< STAT1 register offset */
+
+/* I2C flags */
+typedef enum {
+ /* flags in STAT0 register */
+ I2C_FLAG_SBSEND = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 0U), /*!< start condition sent out in master mode */
+ I2C_FLAG_ADDSEND = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 1U), /*!< address is sent in master mode or received and matches in slave mode */
+ I2C_FLAG_BTC = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 2U), /*!< byte transmission finishes */
+ I2C_FLAG_ADD10SEND = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 3U), /*!< header of 10-bit address is sent in master mode */
+ I2C_FLAG_STPDET = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 4U), /*!< stop condition detected in slave mode */
+ I2C_FLAG_RBNE = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 6U), /*!< I2C_DATA is not empty during receiving */
+ I2C_FLAG_TBE = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 7U), /*!< I2C_DATA is empty during transmitting */
+ I2C_FLAG_BERR = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 8U), /*!< a bus error occurs indication a unexpected start or stop condition on I2C bus */
+ I2C_FLAG_LOSTARB = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 9U), /*!< arbitration lost in master mode */
+ I2C_FLAG_AERR = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 10U), /*!< acknowledge error */
+ I2C_FLAG_OUERR = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 11U), /*!< over-run or under-run situation occurs in slave mode */
+ I2C_FLAG_PECERR = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 12U), /*!< PEC error when receiving data */
+ I2C_FLAG_SMBTO = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 14U), /*!< timeout signal in SMBus mode */
+ I2C_FLAG_SMBALT = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 15U), /*!< SMBus alert status */
+ /* flags in STAT1 register */
+ I2C_FLAG_MASTER = I2C_REGIDX_BIT(I2C_STAT1_REG_OFFSET, 0U), /*!< a flag indicating whether I2C block is in master or slave mode */
+ I2C_FLAG_I2CBSY = I2C_REGIDX_BIT(I2C_STAT1_REG_OFFSET, 1U), /*!< busy flag */
+ I2C_FLAG_TR = I2C_REGIDX_BIT(I2C_STAT1_REG_OFFSET, 2U), /*!< whether the I2C is a transmitter or a receiver */
+ I2C_FLAG_RXGC = I2C_REGIDX_BIT(I2C_STAT1_REG_OFFSET, 4U), /*!< general call address (00h) received */
+ I2C_FLAG_DEFSMB = I2C_REGIDX_BIT(I2C_STAT1_REG_OFFSET, 5U), /*!< default address of SMBus device */
+ I2C_FLAG_HSTSMB = I2C_REGIDX_BIT(I2C_STAT1_REG_OFFSET, 6U), /*!< SMBus host header detected in slave mode */
+ I2C_FLAG_DUMOD = I2C_REGIDX_BIT(I2C_STAT1_REG_OFFSET, 7U) /*!< dual flag in slave mode indicating which address is matched in dual-address mode */
+} i2c_flag_enum;
+
+/* I2C interrupt flags */
+typedef enum {
+ /* interrupt flags in CTL1 register */
+ I2C_INT_FLAG_SBSEND = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 9U, I2C_STAT0_REG_OFFSET, 0U), /*!< start condition sent out in master mode interrupt flag */
+ I2C_INT_FLAG_ADDSEND = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 9U, I2C_STAT0_REG_OFFSET, 1U), /*!< address is sent in master mode or received and matches in slave mode interrupt flag */
+ I2C_INT_FLAG_BTC = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 9U, I2C_STAT0_REG_OFFSET, 2U), /*!< byte transmission finishes */
+ I2C_INT_FLAG_ADD10SEND = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 9U, I2C_STAT0_REG_OFFSET, 3U), /*!< header of 10-bit address is sent in master mode interrupt flag */
+ I2C_INT_FLAG_STPDET = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 9U, I2C_STAT0_REG_OFFSET, 4U), /*!< stop condition detected in slave mode interrupt flag */
+ I2C_INT_FLAG_RBNE = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 9U, I2C_STAT0_REG_OFFSET, 6U), /*!< I2C_DATA is not empty during receiving interrupt flag */
+ I2C_INT_FLAG_TBE = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 9U, I2C_STAT0_REG_OFFSET, 7U), /*!< I2C_DATA is empty during transmitting interrupt flag */
+ I2C_INT_FLAG_BERR = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 8U, I2C_STAT0_REG_OFFSET, 8U), /*!< a bus error occurs indication a unexpected start or stop condition on I2C bus interrupt flag */
+ I2C_INT_FLAG_LOSTARB = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 8U, I2C_STAT0_REG_OFFSET, 9U), /*!< arbitration lost in master mode interrupt flag */
+ I2C_INT_FLAG_AERR = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 8U, I2C_STAT0_REG_OFFSET, 10U), /*!< acknowledge error interrupt flag */
+ I2C_INT_FLAG_OUERR = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 8U, I2C_STAT0_REG_OFFSET, 11U), /*!< over-run or under-run situation occurs in slave mode interrupt flag */
+ I2C_INT_FLAG_PECERR = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 8U, I2C_STAT0_REG_OFFSET, 12U), /*!< PEC error when receiving data interrupt flag */
+ I2C_INT_FLAG_SMBTO = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 8U, I2C_STAT0_REG_OFFSET, 14U), /*!< timeout signal in SMBus mode interrupt flag */
+ I2C_INT_FLAG_SMBALT = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 8U, I2C_STAT0_REG_OFFSET, 15U), /*!< SMBus Alert status interrupt flag */
+} i2c_interrupt_flag_enum;
+
+/* I2C interrupt enable or disable */
+typedef enum {
+ /* interrupt in CTL1 register */
+ I2C_INT_ERR = I2C_REGIDX_BIT(I2C_CTL1_REG_OFFSET, 8U), /*!< error interrupt enable */
+ I2C_INT_EV = I2C_REGIDX_BIT(I2C_CTL1_REG_OFFSET, 9U), /*!< event interrupt enable */
+ I2C_INT_BUF = I2C_REGIDX_BIT(I2C_CTL1_REG_OFFSET, 10U), /*!< buffer interrupt enable */
+} i2c_interrupt_enum;
+
+/* SMBus/I2C mode switch and SMBus type selection */
+#define I2C_I2CMODE_ENABLE ((uint32_t)0x00000000U) /*!< I2C mode */
+#define I2C_SMBUSMODE_ENABLE I2C_CTL0_SMBEN /*!< SMBus mode */
+
+/* SMBus/I2C mode switch and SMBus type selection */
+#define I2C_SMBUS_DEVICE ((uint32_t)0x00000000U) /*!< SMBus mode device type */
+#define I2C_SMBUS_HOST I2C_CTL0_SMBSEL /*!< SMBus mode host type */
+
+/* I2C transfer direction */
+#define I2C_RECEIVER ((uint32_t)0x00000001U) /*!< receiver */
+#define I2C_TRANSMITTER ((uint32_t)0xFFFFFFFEU) /*!< transmitter */
+
+/* whether or not to send an ACK */
+#define I2C_ACK_DISABLE ((uint32_t)0x00000000U) /*!< ACK will be not sent */
+#define I2C_ACK_ENABLE ((uint32_t)0x00000001U) /*!< ACK will be sent */
+
+/* I2C POAP position*/
+#define I2C_ACKPOS_NEXT ((uint32_t)0x00000000U) /*!< ACKEN bit decides whether or not to send ACK for the next byte */
+#define I2C_ACKPOS_CURRENT ((uint32_t)0x00000001U) /*!< ACKEN bit decides whether or not to send ACK or not for the current byte */
+
+/* whether or not to stretch SCL low */
+#define I2C_SCLSTRETCH_DISABLE I2C_CTL0_SS /*!< SCL stretching is enabled */
+#define I2C_SCLSTRETCH_ENABLE ((uint32_t)0x00000000U) /*!< SCL stretching is disabled */
+
+/* whether or not to response to a general call */
+#define I2C_GCEN_ENABLE I2C_CTL0_GCEN /*!< slave will response to a general call */
+#define I2C_GCEN_DISABLE ((uint32_t)0x00000000U) /*!< slave will not response to a general call */
+
+/* software reset I2C */
+#define I2C_SRESET_SET I2C_CTL0_SRESET /*!< I2C is under reset */
+#define I2C_SRESET_RESET ((uint32_t)0x00000000U) /*!< I2C is not under reset */
+
+/* I2C DMA mode configure */
+/* DMA mode switch */
+#define I2C_DMA_ON I2C_CTL1_DMAON /*!< DMA mode enabled */
+#define I2C_DMA_OFF ((uint32_t)0x00000000U) /*!< DMA mode disabled */
+
+/* flag indicating DMA last transfer */
+#define I2C_DMALST_ON I2C_CTL1_DMALST /*!< next DMA EOT is the last transfer */
+#define I2C_DMALST_OFF ((uint32_t)0x00000000U) /*!< next DMA EOT is not the last transfer */
+
+/* I2C PEC configure */
+/* PEC enable */
+#define I2C_PEC_ENABLE I2C_CTL0_PECEN /*!< PEC calculation on */
+#define I2C_PEC_DISABLE ((uint32_t)0x00000000U) /*!< PEC calculation off */
+
+/* PEC transfer */
+#define I2C_PECTRANS_ENABLE I2C_CTL0_PECTRANS /*!< transfer PEC */
+#define I2C_PECTRANS_DISABLE ((uint32_t)0x00000000U) /*!< not transfer PEC value */
+
+/* I2C SMBus configure */
+/* issue or not alert through SMBA pin */
+#define I2C_SALTSEND_ENABLE I2C_CTL0_SALT /*!< issue alert through SMBA pin */
+#define I2C_SALTSEND_DISABLE ((uint32_t)0x00000000U) /*!< not issue alert through SMBA */
+
+/* ARP protocol in SMBus switch */
+#define I2C_ARP_ENABLE I2C_CTL0_ARPEN /*!< ARP enable */
+#define I2C_ARP_DISABLE ((uint32_t)0x00000000U) /*!< ARP disable */
+
+/* fast mode plus enable */
+#define I2C_FAST_MODE_PLUS_ENABLE I2C_FMPCFG_FMPEN /*!< fast mode plus enable */
+#define I2C_FAST_MODE_PLUS_DISABLE ((uint32_t)0x00000000U) /*!< fast mode plus disable */
+
+/* transmit I2C data */
+#define DATA_TRANS(regval) (BITS(0,7) & ((uint32_t)(regval) << 0))
+
+/* receive I2C data */
+#define DATA_RECV(regval) GET_BITS((uint32_t)(regval), 0, 7)
+
+/* I2C duty cycle in fast mode or fast mode plus */
+#define I2C_DTCY_2 ((uint32_t)0x00000000U) /*!< in I2C fast mode or fast mode plus Tlow/Thigh = 2 */
+#define I2C_DTCY_16_9 I2C_CKCFG_DTCY /*!< in I2C fast mode or fast mode plus Tlow/Thigh = 16/9 */
+
+/* address mode for the I2C slave */
+#define I2C_ADDFORMAT_7BITS ((uint32_t)0x00000000U) /*!< address:7 bits */
+#define I2C_ADDFORMAT_10BITS I2C_SADDR0_ADDFORMAT /*!< address:10 bits */
+
+/* function declarations */
+/* reset I2C */
+void i2c_deinit(uint32_t i2c_periph);
+/* configure I2C clock */
+void i2c_clock_config(uint32_t i2c_periph, uint32_t clkspeed, uint32_t dutycyc);
+/* configure I2C address */
+void i2c_mode_addr_config(uint32_t i2c_periph, uint32_t mode, uint32_t addformat, uint32_t addr);
+/* SMBus type selection */
+void i2c_smbus_type_config(uint32_t i2c_periph, uint32_t type);
+/* whether or not to send an ACK */
+void i2c_ack_config(uint32_t i2c_periph, uint32_t ack);
+/* configure I2C position of ACK and PEC when receiving */
+void i2c_ackpos_config(uint32_t i2c_periph, uint32_t pos);
+/* master sends slave address */
+void i2c_master_addressing(uint32_t i2c_periph, uint32_t addr, uint32_t trandirection);
+/* enable dual-address mode */
+void i2c_dualaddr_enable(uint32_t i2c_periph, uint32_t addr);
+/* disable dual-address mode */
+void i2c_dualaddr_disable(uint32_t i2c_periph);
+/* enable I2C */
+void i2c_enable(uint32_t i2c_periph);
+/* disable I2C */
+void i2c_disable(uint32_t i2c_periph);
+
+/* generate a START condition on I2C bus */
+void i2c_start_on_bus(uint32_t i2c_periph);
+/* generate a STOP condition on I2C bus */
+void i2c_stop_on_bus(uint32_t i2c_periph);
+/* I2C transmit data function */
+void i2c_data_transmit(uint32_t i2c_periph, uint8_t data);
+/* I2C receive data function */
+uint8_t i2c_data_receive(uint32_t i2c_periph);
+/* enable I2C DMA mode */
+void i2c_dma_enable(uint32_t i2c_periph, uint32_t dmastate);
+/* configure whether next DMA EOT is DMA last transfer or not */
+void i2c_dma_last_transfer_config(uint32_t i2c_periph, uint32_t dmalast);
+/* whether to stretch SCL low when data is not ready in slave mode */
+void i2c_stretch_scl_low_config(uint32_t i2c_periph, uint32_t stretchpara);
+/* whether or not to response to a general call */
+void i2c_slave_response_to_gcall_config(uint32_t i2c_periph, uint32_t gcallpara);
+/* software reset I2C */
+void i2c_software_reset_config(uint32_t i2c_periph, uint32_t sreset);
+
+/* whether to enable I2C PEC calculation or not */
+void i2c_pec_enable(uint32_t i2c_periph, uint32_t pecstate);
+/* I2C whether to transfer PEC value */
+void i2c_pec_transfer_enable(uint32_t i2c_periph, uint32_t pecpara);
+/* packet error checking value */
+uint8_t i2c_pec_value_get(uint32_t i2c_periph);
+/* I2C issue alert through SMBA pin */
+void i2c_smbus_issue_alert(uint32_t i2c_periph, uint32_t smbuspara);
+/* whether ARP is enabled under SMBus */
+void i2c_smbus_arp_enable(uint32_t i2c_periph, uint32_t arpstate);
+
+/* check I2C flag is set or not */
+FlagStatus i2c_flag_get(uint32_t i2c_periph, i2c_flag_enum flag);
+/* clear I2C flag */
+void i2c_flag_clear(uint32_t i2c_periph, i2c_flag_enum flag);
+/* enable I2C interrupt */
+void i2c_interrupt_enable(uint32_t i2c_periph, i2c_interrupt_enum interrupt);
+/* disable I2C interrupt */
+void i2c_interrupt_disable(uint32_t i2c_periph, i2c_interrupt_enum interrupt);
+/* check I2C interrupt flag */
+FlagStatus i2c_interrupt_flag_get(uint32_t i2c_periph, i2c_interrupt_flag_enum int_flag);
+/* clear I2C interrupt flag */
+void i2c_interrupt_flag_clear(uint32_t i2c_periph, i2c_interrupt_flag_enum int_flag);
+
+#endif /* GD32F3X0_I2C_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_misc.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_misc.h
new file mode 100644
index 00000000..1ec6111e
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_misc.h
@@ -0,0 +1,94 @@
+/*!
+ \file gd32f3x0_misc.h
+ \brief definitions for the MISC
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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 GD32F3X0_MISC_H
+#define GD32F3X0_MISC_H
+
+#include "gd32f3x0.h"
+
+/* constants definitions */
+/* set the RAM and FLASH base address */
+#define NVIC_VECTTAB_RAM ((uint32_t)0x20000000) /*!< RAM base address */
+#define NVIC_VECTTAB_FLASH ((uint32_t)0x08000000) /*!< Flash base address */
+
+/* set the NVIC vector table offset mask */
+#define NVIC_VECTTAB_OFFSET_MASK ((uint32_t)0x1FFFFF80) /*!< NVIC vector table offset mask */
+
+/* the register key mask, if you want to do the write operation, you should write 0x5FA to VECTKEY bits */
+#define NVIC_AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000) /*!< NVIC VECTKEY mask */
+
+/* priority group - define the pre-emption priority and the subpriority */
+#define NVIC_PRIGROUP_PRE0_SUB4 ((uint32_t)0x00000700) /*!< 0 bits for pre-emption priority 4 bits for subpriority */
+#define NVIC_PRIGROUP_PRE1_SUB3 ((uint32_t)0x00000600) /*!< 1 bits for pre-emption priority 3 bits for subpriority */
+#define NVIC_PRIGROUP_PRE2_SUB2 ((uint32_t)0x00000500) /*!< 2 bits for pre-emption priority 2 bits for subpriority */
+#define NVIC_PRIGROUP_PRE3_SUB1 ((uint32_t)0x00000400) /*!< 3 bits for pre-emption priority 1 bits for subpriority */
+#define NVIC_PRIGROUP_PRE4_SUB0 ((uint32_t)0x00000300) /*!< 4 bits for pre-emption priority 0 bits for subpriority */
+
+/* choose the method to enter or exit the lowpower mode */
+#define SCB_SCR_SLEEPONEXIT ((uint8_t)0x02) /*!< choose the the system whether enter low power mode by exiting from ISR */
+#define SCB_SCR_SLEEPDEEP ((uint8_t)0x04) /*!< choose the the system enter the DEEPSLEEP mode or SLEEP mode */
+#define SCB_SCR_SEVONPEND ((uint8_t)0x10) /*!< choose the interrupt source that can wake up the lowpower mode */
+
+#define SCB_LPM_SLEEP_EXIT_ISR SCB_SCR_SLEEPONEXIT /*!< low power mode by exiting from ISR */
+#define SCB_LPM_DEEPSLEEP SCB_SCR_SLEEPDEEP /*!< DEEPSLEEP mode or SLEEP mode */
+#define SCB_LPM_WAKE_BY_ALL_INT SCB_SCR_SEVONPEND /*!< wakeup by all interrupt */
+
+/* choose the systick clock source */
+#define SYSTICK_CLKSOURCE_HCLK_DIV8 ((uint32_t)0xFFFFFFFBU) /*!< systick clock source is from HCLK/8 */
+#define SYSTICK_CLKSOURCE_HCLK ((uint32_t)0x00000004U) /*!< systick clock source is from HCLK */
+
+/* function declarations */
+/* set the priority group */
+void nvic_priority_group_set(uint32_t nvic_prigroup);
+
+/* enable NVIC request */
+void nvic_irq_enable(uint8_t nvic_irq, uint8_t nvic_irq_pre_priority, uint8_t nvic_irq_sub_priority);
+/* disable NVIC request */
+void nvic_irq_disable(uint8_t nvic_irq);
+
+/* set the NVIC vector table base address */
+void nvic_vector_table_set(uint32_t nvic_vict_tab, uint32_t offset);
+
+/* set the state of the low power mode */
+void system_lowpower_set(uint8_t lowpower_mode);
+/* reset the state of the low power mode */
+void system_lowpower_reset(uint8_t lowpower_mode);
+
+/* set the systick clock source */
+void systick_clksource_set(uint32_t systick_clksource);
+
+#endif /* GD32F3X0_MISC_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_pmu.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_pmu.h
new file mode 100644
index 00000000..e5efb4a7
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_pmu.h
@@ -0,0 +1,199 @@
+/*!
+ \file gd32f3x0_pmu.h
+ \brief definitions for the PMU
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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 GD32F3X0_PMU_H
+#define GD32F3X0_PMU_H
+
+#include "gd32f3x0.h"
+
+/* PMU definitions */
+#define PMU PMU_BASE /*!< PMU base address */
+
+/* registers definitions */
+#define PMU_CTL REG32(PMU + 0x00000000U) /*!< PMU control register */
+#define PMU_CS REG32(PMU + 0x00000004U) /*!< PMU control and status register */
+
+/* bits definitions */
+/* PMU_CTL */
+#define PMU_CTL_LDOLP BIT(0) /*!< LDO low power mode */
+#define PMU_CTL_STBMOD BIT(1) /*!< standby mode */
+#define PMU_CTL_WURST BIT(2) /*!< wakeup flag reset */
+#define PMU_CTL_STBRST BIT(3) /*!< standby flag reset */
+#define PMU_CTL_LVDEN BIT(4) /*!< low voltage detector enable */
+#define PMU_CTL_LVDT BITS(5,7) /*!< low voltage detector threshold */
+#define PMU_CTL_BKPWEN BIT(8) /*!< backup domain write enable */
+#define PMU_CTL_LDLP BIT(10) /*!< low-driver mode when use low power LDO */
+#define PMU_CTL_LDNP BIT(11) /*!< low-driver mode when use normal power LDO */
+#define PMU_CTL_LDOVS BITS(14,15) /*!< LDO output voltage select */
+#define PMU_CTL_HDEN BIT(16) /*!< high-driver mode enable */
+#define PMU_CTL_HDS BIT(17) /*!< high-driver mode switch */
+#define PMU_CTL_LDEN BITS(18,19) /*!< low-driver mode enable in deep-sleep mode */
+
+/* PMU_CS */
+#define PMU_CS_WUF BIT(0) /*!< wakeup flag */
+#define PMU_CS_STBF BIT(1) /*!< standby flag */
+#define PMU_CS_LVDF BIT(2) /*!< low voltage detector status flag */
+#define PMU_CS_WUPEN0 BIT(8) /*!< wakeup pin enable */
+#define PMU_CS_WUPEN1 BIT(9) /*!< wakeup pin enable */
+#define PMU_CS_WUPEN4 BIT(12) /*!< wakeup pin enable */
+#define PMU_CS_WUPEN5 BIT(13) /*!< wakeup pin enable */
+#define PMU_CS_WUPEN6 BIT(14) /*!< wakeup pin enable */
+#define PMU_CS_LDOVSRF BIT(15) /*!< LDO voltage select ready flag */
+#define PMU_CS_HDRF BIT(16) /*!< high-driver ready flag */
+#define PMU_CS_HDSRF BIT(17) /*!< high-driver switch ready flag */
+#define PMU_CS_LDRF BITS(18,19) /*!< low-driver mode ready flag */
+
+/* constants definitions */
+/* PMU low voltage detector threshold definitions */
+#define CTL_LVDT(regval) (BITS(5,7)&((uint32_t)(regval)<<5))
+#define PMU_LVDT_0 CTL_LVDT(0) /*!< voltage threshold is 2.1V */
+#define PMU_LVDT_1 CTL_LVDT(1) /*!< voltage threshold is 2.3V */
+#define PMU_LVDT_2 CTL_LVDT(2) /*!< voltage threshold is 2.4V */
+#define PMU_LVDT_3 CTL_LVDT(3) /*!< voltage threshold is 2.6V */
+#define PMU_LVDT_4 CTL_LVDT(4) /*!< voltage threshold is 2.7V */
+#define PMU_LVDT_5 CTL_LVDT(5) /*!< voltage threshold is 2.9V */
+#define PMU_LVDT_6 CTL_LVDT(6) /*!< voltage threshold is 3.0V */
+#define PMU_LVDT_7 CTL_LVDT(7) /*!< voltage threshold is 3.1V */
+
+/* PMU LDO output voltage select definitions */
+#define CTL_LDOVS(regval) (BITS(14,15)&((uint32_t)(regval)<<14))
+#define PMU_LDOVS_LOW CTL_LDOVS(1) /*!< LDO output voltage low mode */
+#define PMU_LDOVS_MID CTL_LDOVS(2) /*!< LDO output voltage mid mode */
+#define PMU_LDOVS_HIGH CTL_LDOVS(3) /*!< LDO output voltage high mode */
+
+/* PMU low-driver mode enable in deep-sleep mode */
+#define CTL_LDEN(regval) (BITS(18,19)&((uint32_t)(regval)<<18))
+#define PMU_LOWDRIVER_DISABLE CTL_LDEN(0) /*!< low-driver mode disable in deep-sleep mode */
+#define PMU_LOWDRIVER_ENABLE CTL_LDEN(3) /*!< low-driver mode enable in deep-sleep mode */
+
+/* PMU low power mode ready flag definitions */
+#define CS_LDRF(regval) (BITS(18,19)&((uint32_t)(regval)<<18))
+#define PMU_LDRF_NORMAL CS_LDRF(0) /*!< normal-driver in deep-sleep mode */
+#define PMU_LDRF_LOWDRIVER CS_LDRF(3) /*!< low-driver mode in deep-sleep mode */
+
+/* PMU high-driver mode switch */
+#define PMU_HIGHDR_SWITCH_NONE ((uint32_t)0x00000000U) /*!< no high-driver mode switch */
+#define PMU_HIGHDR_SWITCH_EN PMU_CTL_HDS /*!< high-driver mode switch */
+
+/* PMU low-driver mode when use normal power LDO */
+#define PMU_NORMALDR_NORMALPWR ((uint32_t)0x00000000U) /*!< normal-driver when use normal power LDO */
+#define PMU_LOWDR_NORMALPWR PMU_CTL_LDNP /*!< low-driver mode enabled when LDEN is 11 and use normal power LDO */
+
+/* PMU low-driver mode when use low power LDO */
+#define PMU_NORMALDR_LOWPWR ((uint32_t)0x00000000U) /*!< normal-driver when use low power LDO */
+#define PMU_LOWDR_LOWPWR PMU_CTL_LDLP /*!< low-driver mode enabled when LDEN is 11 and use low power LDO */
+
+/* PMU ldo definitions */
+#define PMU_LDO_NORMAL ((uint32_t)0x00000000U) /*!< LDO operates normally when PMU enter deepsleep mode */
+#define PMU_LDO_LOWPOWER PMU_CTL_LDOLP /*!< LDO work at low power status when PMU enter deepsleep mode */
+
+/* PMU flag definitions */
+#define PMU_FLAG_WAKEUP PMU_CS_WUF /*!< wakeup flag status */
+#define PMU_FLAG_STANDBY PMU_CS_STBF /*!< standby flag status */
+#define PMU_FLAG_LVD PMU_CS_LVDF /*!< LVD flag status */
+#define PMU_FLAG_LDOVSR PMU_CS_LDOVSRF /*!< LDO voltage select ready flag */
+#define PMU_FLAG_HDR PMU_CS_HDRF /*!< high-driver ready flag */
+#define PMU_FLAG_HDSR PMU_CS_HDSRF /*!< high-driver switch ready flag */
+#define PMU_FLAG_LDR PMU_CS_LDRF /*!< low-driver mode ready flag */
+
+/* PMU WKUP pin definitions */
+#define PMU_WAKEUP_PIN0 PMU_CS_WUPEN0 /*!< WKUP Pin 0 (PA0) enable */
+#define PMU_WAKEUP_PIN1 PMU_CS_WUPEN1 /*!< WKUP Pin 1 (PC13) enable */
+#define PMU_WAKEUP_PIN4 PMU_CS_WUPEN4 /*!< WKUP Pin 4 (PC5) enable */
+#define PMU_WAKEUP_PIN5 PMU_CS_WUPEN5 /*!< WKUP Pin 5 (PB5) enable */
+#define PMU_WAKEUP_PIN6 PMU_CS_WUPEN6 /*!< WKUP Pin 6 (PB15) enable */
+
+/* PMU flag reset definitions */
+#define PMU_FLAG_RESET_WAKEUP PMU_CTL_WURST /*!< wakeup flag reset */
+#define PMU_FLAG_RESET_STANDBY PMU_CTL_STBRST /*!< standby flag reset */
+
+/* PMU command constants definitions */
+#define WFI_CMD ((uint8_t)0x00U) /*!< use WFI command */
+#define WFE_CMD ((uint8_t)0x01U) /*!< use WFE command */
+
+/* function declarations */
+/* function configuration */
+/* reset PMU registers */
+void pmu_deinit(void);
+/* select low voltage detector threshold */
+void pmu_lvd_select(uint32_t lvdt_n);
+/* select LDO output voltage */
+void pmu_ldo_output_select(uint32_t ldo_output);
+/* disable PMU lvd */
+void pmu_lvd_disable(void);
+
+/* functions of low-driver mode and high-driver mode in deep-sleep mode */
+/* enable low-driver mode in deep-sleep mode */
+void pmu_lowdriver_mode_enable(void);
+/* disable low-driver mode in deep-sleep mode */
+void pmu_lowdriver_mode_disable(void);
+/* enable high-driver mode */
+void pmu_highdriver_mode_enable(void);
+/* disable high-driver mode */
+void pmu_highdriver_mode_disable(void);
+/* switch high-driver mode */
+void pmu_highdriver_switch_select(uint32_t highdr_switch);
+/* in deep-sleep mode, low-driver mode when use low power LDO */
+void pmu_lowpower_driver_config(uint32_t mode);
+/* in deep-sleep mode, low-driver mode when use normal power LDO */
+void pmu_normalpower_driver_config(uint32_t mode);
+
+/* set PMU mode */
+/* PMU work in sleep mode */
+void pmu_to_sleepmode(uint8_t sleepmodecmd);
+/* PMU work in deepsleep mode */
+void pmu_to_deepsleepmode(uint32_t ldo, uint32_t lowdrive, uint8_t deepsleepmodecmd);
+/* PMU work in standby mode */
+void pmu_to_standbymode(uint8_t standbymodecmd);
+/* enable PMU wakeup pin */
+void pmu_wakeup_pin_enable(uint32_t wakeup_pin);
+/* disable PMU wakeup pin */
+void pmu_wakeup_pin_disable(uint32_t wakeup_pin);
+
+/* backup related functions */
+/* enable backup domain write */
+void pmu_backup_write_enable(void);
+/* disable backup domain write */
+void pmu_backup_write_disable(void);
+
+/* flag functions */
+/* get flag state */
+FlagStatus pmu_flag_get(uint32_t flag);
+/* clear flag bit */
+void pmu_flag_clear(uint32_t flag);
+
+#endif /* GD32F3X0_PMU_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_rcu.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_rcu.h
new file mode 100644
index 00000000..49883164
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_rcu.h
@@ -0,0 +1,788 @@
+/*!
+ \file gd32f3x0_rcu.h
+ \brief definitions for the RCU
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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 GD32F3X0_RCU_H
+#define GD32F3X0_RCU_H
+
+#include "gd32f3x0.h"
+
+/* RCU definitions */
+#define RCU RCU_BASE
+
+/* registers definitions */
+#define RCU_CTL0 REG32(RCU + 0x00000000U) /*!< control register 0 */
+#define RCU_CFG0 REG32(RCU + 0x00000004U) /*!< configuration register 0 */
+#define RCU_INT REG32(RCU + 0x00000008U) /*!< interrupt register */
+#define RCU_APB2RST REG32(RCU + 0x0000000CU) /*!< APB2 reset register */
+#define RCU_APB1RST REG32(RCU + 0x00000010U) /*!< APB1 reset register */
+#define RCU_AHBEN REG32(RCU + 0x00000014U) /*!< AHB enable register */
+#define RCU_APB2EN REG32(RCU + 0x00000018U) /*!< APB2 enable register */
+#define RCU_APB1EN REG32(RCU + 0x0000001CU) /*!< APB1 enable register */
+#define RCU_BDCTL REG32(RCU + 0x00000020U) /*!< backup domain control register */
+#define RCU_RSTSCK REG32(RCU + 0x00000024U) /*!< reset source /clock register */
+#define RCU_AHBRST REG32(RCU + 0x00000028U) /*!< AHB reset register */
+#define RCU_CFG1 REG32(RCU + 0x0000002CU) /*!< configuration register 1 */
+#define RCU_CFG2 REG32(RCU + 0x00000030U) /*!< configuration register 2 */
+#define RCU_CTL1 REG32(RCU + 0x00000034U) /*!< control register 1 */
+#define RCU_ADDCTL REG32(RCU + 0x000000C0U) /*!< additional clock control register */
+#define RCU_ADDINT REG32(RCU + 0x000000CCU) /*!< additional clock interrupt register */
+#define RCU_ADDAPB1EN REG32(RCU + 0x000000F8U) /*!< APB1 additional enable register */
+#define RCU_ADDAPB1RST REG32(RCU + 0x000000FCU) /*!< APB1 additional reset register */
+#define RCU_VKEY REG32(RCU + 0x00000100U) /*!< voltage key register */
+#define RCU_DSV REG32(RCU + 0x00000134U) /*!< deep-sleep mode voltage register */
+
+/* bits definitions */
+/* RCU_CTL0 */
+#define RCU_CTL0_IRC8MEN BIT(0) /*!< internal high speed oscillator enable */
+#define RCU_CTL0_IRC8MSTB BIT(1) /*!< IRC8M high speed internal oscillator stabilization flag */
+#define RCU_CTL0_IRC8MADJ BITS(3,7) /*!< high speed internal oscillator clock trim adjust value */
+#define RCU_CTL0_IRC8MCALIB BITS(8,15) /*!< high speed internal oscillator calibration value register */
+#define RCU_CTL0_HXTALEN BIT(16) /*!< external high speed oscillator enable */
+#define RCU_CTL0_HXTALSTB BIT(17) /*!< external crystal oscillator clock stabilization flag */
+#define RCU_CTL0_HXTALBPS BIT(18) /*!< external crystal oscillator clock bypass mode enable */
+#define RCU_CTL0_CKMEN BIT(19) /*!< HXTAL clock monitor enable */
+#define RCU_CTL0_PLLEN BIT(24) /*!< PLL enable */
+#define RCU_CTL0_PLLSTB BIT(25) /*!< PLL clock stabilization flag */
+
+/* RCU_CFG0 */
+#define RCU_CFG0_SCS BITS(0,1) /*!< system clock switch */
+#define RCU_CFG0_SCSS BITS(2,3) /*!< system clock switch status */
+#define RCU_CFG0_AHBPSC BITS(4,7) /*!< AHB prescaler selection */
+#define RCU_CFG0_APB1PSC BITS(8,10) /*!< APB1 prescaler selection */
+#define RCU_CFG0_APB2PSC BITS(11,13) /*!< APB2 prescaler selection */
+#define RCU_CFG0_ADCPSC BITS(14,15) /*!< ADC clock prescaler selection */
+#define RCU_CFG0_PLLSEL BIT(16) /*!< PLL clock source selection */
+#define RCU_CFG0_PLLPREDV BIT(17) /*!< divider for PLL source clock selection */
+#define RCU_CFG0_PLLMF (BIT(27) | BITS(18,21)) /*!< PLL multiply factor */
+#define RCU_CFG0_USBFSPSC BITS(22,23) /*!< USBFS clock prescaler selection */
+#define RCU_CFG0_CKOUTSEL BITS(24,26) /*!< CK_OUT clock source selection */
+#define RCU_CFG0_PLLMF4 BIT(27) /*!< bit 4 of PLLMF */
+#define RCU_CFG0_CKOUTDIV BITS(28,30) /*!< CK_OUT divider which the CK_OUT frequency can be reduced */
+#define RCU_CFG0_PLLDV BIT(31) /*!< CK_PLL divide by 1 or 2 */
+
+/* RCU_INT */
+#define RCU_INT_IRC40KSTBIF BIT(0) /*!< IRC40K stabilization interrupt flag */
+#define RCU_INT_LXTALSTBIF BIT(1) /*!< LXTAL stabilization interrupt flag */
+#define RCU_INT_IRC8MSTBIF BIT(2) /*!< IRC8M stabilization interrupt flag */
+#define RCU_INT_HXTALSTBIF BIT(3) /*!< HXTAL stabilization interrupt flag */
+#define RCU_INT_PLLSTBIF BIT(4) /*!< PLL stabilization interrupt flag */
+#define RCU_INT_IRC28MSTBIF BIT(5) /*!< IRC28M stabilization interrupt flag */
+#define RCU_INT_CKMIF BIT(7) /*!< HXTAL clock stuck interrupt flag */
+#define RCU_INT_IRC40KSTBIE BIT(8) /*!< IRC40K stabilization interrupt enable */
+#define RCU_INT_LXTALSTBIE BIT(9) /*!< LXTAL stabilization interrupt enable */
+#define RCU_INT_IRC8MSTBIE BIT(10) /*!< IRC8M stabilization interrupt enable */
+#define RCU_INT_HXTALSTBIE BIT(11) /*!< HXTAL stabilization interrupt enable */
+#define RCU_INT_PLLSTBIE BIT(12) /*!< PLL stabilization interrupt enable */
+#define RCU_INT_IRC28MSTBIE BIT(13) /*!< IRC28M stabilization interrupt enable */
+#define RCU_INT_IRC40KSTBIC BIT(16) /*!< IRC40K stabilization interrupt clear */
+#define RCU_INT_LXTALSTBIC BIT(17) /*!< LXTAL stabilization interrupt clear */
+#define RCU_INT_IRC8MSTBIC BIT(18) /*!< IRC8M stabilization interrupt clear */
+#define RCU_INT_HXTALSTBIC BIT(19) /*!< HXTAL stabilization interrupt clear */
+#define RCU_INT_PLLSTBIC BIT(20) /*!< PLL stabilization interrupt clear */
+#define RCU_INT_IRC28MSTBIC BIT(21) /*!< IRC28M stabilization interrupt clear */
+#define RCU_INT_CKMIC BIT(23) /*!< HXTAL clock stuck interrupt clear */
+
+/* RCU_APB2RST */
+#define RCU_APB2RST_CFGRST BIT(0) /*!< system configuration reset */
+#define RCU_APB2RST_ADCRST BIT(9) /*!< ADC reset */
+#define RCU_APB2RST_TIMER0RST BIT(11) /*!< TIMER0 reset */
+#define RCU_APB2RST_SPI0RST BIT(12) /*!< SPI0 reset */
+#define RCU_APB2RST_USART0RST BIT(14) /*!< USART0 reset */
+#define RCU_APB2RST_TIMER14RST BIT(16) /*!< TIMER14 reset */
+#define RCU_APB2RST_TIMER15RST BIT(17) /*!< TIMER15 reset */
+#define RCU_APB2RST_TIMER16RST BIT(18) /*!< TIMER16 reset */
+
+/* RCU_APB1RST */
+#define RCU_APB1RST_TIMER1RST BIT(0) /*!< TIMER1 timer reset */
+#define RCU_APB1RST_TIMER2RST BIT(1) /*!< TIMER2 timer reset */
+#define RCU_APB1RST_TIMER5RST BIT(4) /*!< TIMER5 timer reset */
+#define RCU_APB1RST_TIMER13RST BIT(8) /*!< TIMER13 timer reset */
+#define RCU_APB1RST_WWDGTRST BIT(11) /*!< window watchdog timer reset */
+#define RCU_APB1RST_SPI1RST BIT(14) /*!< SPI1 reset */
+#define RCU_APB1RST_USART1RST BIT(17) /*!< USART1 reset */
+#define RCU_APB1RST_I2C0RST BIT(21) /*!< I2C0 reset */
+#define RCU_APB1RST_I2C1RST BIT(22) /*!< I2C1 reset */
+#define RCU_APB1RST_PMURST BIT(28) /*!< power control reset */
+#define RCU_APB1RST_DACRST BIT(29) /*!< DAC reset */
+#define RCU_APB1RST_CECRST BIT(30) /*!< HDMI CEC reset */
+
+/* RCU_AHBEN */
+#define RCU_AHBEN_DMAEN BIT(0) /*!< DMA clock enable */
+#define RCU_AHBEN_SRAMSPEN BIT(2) /*!< SRAM interface clock enable */
+#define RCU_AHBEN_FMCSPEN BIT(4) /*!< FMC clock enable */
+#define RCU_AHBEN_CRCEN BIT(6) /*!< CRC clock enable */
+#define RCU_AHBEN_USBFS BIT(12) /*!< USBFS clock enable */
+#define RCU_AHBEN_PAEN BIT(17) /*!< GPIO port A clock enable */
+#define RCU_AHBEN_PBEN BIT(18) /*!< GPIO port B clock enable */
+#define RCU_AHBEN_PCEN BIT(19) /*!< GPIO port C clock enable */
+#define RCU_AHBEN_PDEN BIT(20) /*!< GPIO port D clock enable */
+#define RCU_AHBEN_PFEN BIT(22) /*!< GPIO port F clock enable */
+#define RCU_AHBEN_TSIEN BIT(24) /*!< TSI clock enable */
+
+/* RCU_APB2EN */
+#define RCU_APB2EN_CFGCMPEN BIT(0) /*!< system configuration and comparator clock enable */
+#define RCU_APB2EN_ADCEN BIT(9) /*!< ADC interface clock enable */
+#define RCU_APB2EN_TIMER0EN BIT(11) /*!< TIMER0 timer clock enable */
+#define RCU_APB2EN_SPI0EN BIT(12) /*!< SPI0 clock enable */
+#define RCU_APB2EN_USART0EN BIT(14) /*!< USART0 clock enable */
+#define RCU_APB2EN_TIMER14EN BIT(16) /*!< TIMER14 timer clock enable */
+#define RCU_APB2EN_TIMER15EN BIT(17) /*!< TIMER15 timer clock enable */
+#define RCU_APB2EN_TIMER16EN BIT(18) /*!< TIMER16 timer clock enable */
+
+/* RCU_APB1EN */
+#define RCU_APB1EN_TIMER1EN BIT(0) /*!< TIMER1 timer clock enable */
+#define RCU_APB1EN_TIMER2EN BIT(1) /*!< TIMER2 timer clock enable */
+#define RCU_APB1EN_TIMER5EN BIT(4) /*!< TIMER5 timer clock enable */
+#define RCU_APB1EN_TIMER13EN BIT(8) /*!< TIMER13 timer clock enable */
+#define RCU_APB1EN_WWDGTEN BIT(11) /*!< window watchdog timer clock enable */
+#define RCU_APB1EN_SPI1EN BIT(14) /*!< SPI1 clock enable */
+#define RCU_APB1EN_USART1EN BIT(17) /*!< USART1 clock enable */
+#define RCU_APB1EN_I2C0EN BIT(21) /*!< I2C0 clock enable */
+#define RCU_APB1EN_I2C1EN BIT(22) /*!< I2C1 clock enable */
+#define RCU_APB1EN_PMUEN BIT(28) /*!< power interface clock enable */
+#define RCU_APB1EN_DACEN BIT(29) /*!< DAC interface clock enable */
+#define RCU_APB1EN_CECEN BIT(30) /*!< HDMI CEC interface clock enable */
+
+/* RCU_BDCTL */
+#define RCU_BDCTL_LXTALEN BIT(0) /*!< LXTAL enable */
+#define RCU_BDCTL_LXTALSTB BIT(1) /*!< external low-speed oscillator stabilization */
+#define RCU_BDCTL_LXTALBPS BIT(2) /*!< LXTAL bypass mode enable */
+#define RCU_BDCTL_LXTALDRI BITS(3,4) /*!< LXTAL drive capability */
+#define RCU_BDCTL_RTCSRC BITS(8,9) /*!< RTC clock entry selection */
+#define RCU_BDCTL_RTCEN BIT(15) /*!< RTC clock enable */
+#define RCU_BDCTL_BKPRST BIT(16) /*!< backup domain reset */
+
+/* RCU_RSTSCK */
+#define RCU_RSTSCK_IRC40KEN BIT(0) /*!< IRC40K enable */
+#define RCU_RSTSCK_IRC40KSTB BIT(1) /*!< IRC40K stabilization */
+#define RCU_RSTSCK_V12RSTF BIT(23) /*!< V12 domain power reset flag */
+#define RCU_RSTSCK_RSTFC BIT(24) /*!< reset flag clear */
+#define RCU_RSTSCK_OBLRSTF BIT(25) /*!< option byte loader reset flag */
+#define RCU_RSTSCK_EPRSTF BIT(26) /*!< external pin reset flag */
+#define RCU_RSTSCK_PORRSTF BIT(27) /*!< power reset flag */
+#define RCU_RSTSCK_SWRSTF BIT(28) /*!< software reset flag */
+#define RCU_RSTSCK_FWDGTRSTF BIT(29) /*!< free watchdog timer reset flag */
+#define RCU_RSTSCK_WWDGTRSTF BIT(30) /*!< window watchdog timer reset flag */
+#define RCU_RSTSCK_LPRSTF BIT(31) /*!< low-power reset flag */
+
+/* RCU_AHBRST */
+#define RCU_AHBRST_USBFSRST BIT(12) /*!< USBFS reset */
+#define RCU_AHBRST_PARST BIT(17) /*!< GPIO port A reset */
+#define RCU_AHBRST_PBRST BIT(18) /*!< GPIO port B reset */
+#define RCU_AHBRST_PCRST BIT(19) /*!< GPIO port C reset */
+#define RCU_AHBRST_PDRST BIT(20) /*!< GPIO port D reset */
+#define RCU_AHBRST_PFRST BIT(22) /*!< GPIO port F reset */
+#define RCU_AHBRST_TSIRST BIT(24) /*!< TSI unit reset */
+
+/* RCU_CFG1 */
+#define RCU_CFG1_PREDV BITS(0,3) /*!< CK_HXTAL divider previous PLL */
+#define RCU_CFG1_PLLPRESEL BIT(30) /*!< PLL clock source preselection */
+#define RCU_CFG1_PLLMF5 BIT(31) /*!< bit 5 of PLLMF */
+
+/* RCU_CFG2 */
+#define RCU_CFG2_USART0SEL BITS(0,1) /*!< CK_USART0 clock source selection */
+#define RCU_CFG2_CECSEL BIT(6) /*!< CK_CEC clock source selection */
+#define RCU_CFG2_ADCSEL BIT(8) /*!< CK_ADC clock source selection */
+#define RCU_CFG2_IRC28MDIV BIT(16) /*!< CK_IRC28M divider 2 or not */
+#define RCU_CFG2_USBFSPSC2 BIT(30) /*!< bit 2 of USBFSPSC */
+#define RCU_CFG2_ADCPSC2 BIT(31) /*!< bit 2 of ADCPSC */
+
+/* RCU_CTL1 */
+#define RCU_CTL1_IRC28MEN BIT(0) /*!< IRC28M internal 28M RC oscillator enable */
+#define RCU_CTL1_IRC28MSTB BIT(1) /*!< IRC28M internal 28M RC oscillator stabilization flag */
+#define RCU_CTL1_IRC28MADJ BITS(3,7) /*!< internal 28M RC oscillator clock trim adjust value */
+#define RCU_CTL1_IRC28MCALIB BITS(8,15) /*!< internal 28M RC oscillator calibration value register */
+
+/* RCU_ADDCTL */
+#define RCU_ADDCTL_CK48MSEL BIT(0) /*!< 48M clock selection */
+#define RCU_ADDCTL_IRC48MEN BIT(16) /*!< IRC48M internal 48M RC oscillator enable */
+#define RCU_ADDCTL_IRC48MSTB BIT(17) /*!< internal 48M RC oscillator stabilization flag */
+#define RCU_ADDCTL_IRC48MCALIB BITS(24,31) /*!< internal 48M RC oscillator calibration value register */
+
+/* RCU_ADDINT */
+#define RCU_ADDINT_IRC48MSTBIF BIT(6) /*!< IRC48M stabilization interrupt flag */
+#define RCU_ADDINT_IRC48MSTBIE BIT(14) /*!< IRC48M stabilization interrupt enable */
+#define RCU_ADDINT_IRC48MSTBIC BIT(22) /*!< IRC48M stabilization interrupt clear */
+
+/* RCU_ADDAPB1EN */
+#define RCU_ADDAPB1EN_CTCEN BIT(27) /*!< CTC unit clock enable */
+
+/* RCU_ADDAPB1RST */
+#define RCU_ADDAPB1RST_CTCRST BIT(27) /*!< CTC unit reset */
+
+/* RCU_VKEY */
+#define RCU_VKEY_KEY BITS(0,31) /*!< key of RCU_DSV register */
+
+/* RCU_DSV */
+#define RCU_DSV_DSLPVS BITS(0,1) /*!< deep-sleep mode voltage select */
+
+/* constants definitions */
+/* define the peripheral clock enable bit position and its register index offset */
+#define RCU_REGIDX_BIT(regidx, bitpos) (((uint32_t)(regidx)<<6) | (uint32_t)(bitpos))
+#define RCU_REG_VAL(periph) (REG32(RCU + ((uint32_t)(periph)>>6)))
+#define RCU_BIT_POS(val) ((uint32_t)(val) & (uint32_t)0x0000001FU)
+/* define the voltage key unlock value */
+#define RCU_VKEY_UNLOCK ((uint32_t)0x1A2B3C4DU)
+
+/* register index */
+typedef enum {
+ /* peripherals enable */
+ IDX_AHBEN = ((uint32_t)0x00000014U),
+ IDX_APB2EN = ((uint32_t)0x00000018U),
+ IDX_APB1EN = ((uint32_t)0x0000001CU),
+ IDX_ADDAPB1EN = ((uint32_t)0x000000F8U),
+ /* peripherals reset */
+ IDX_AHBRST = ((uint32_t)0x00000028U),
+ IDX_APB2RST = ((uint32_t)0x0000000CU),
+ IDX_APB1RST = ((uint32_t)0x00000010U),
+ IDX_ADDAPB1RST = ((uint32_t)0x000000FCU),
+ /* clock stabilization */
+ IDX_CTL0 = ((uint32_t)0x00000000U),
+ IDX_BDCTL = ((uint32_t)0x00000020U),
+ IDX_CTL1 = ((uint32_t)0x00000034U),
+ IDX_ADDCTL = ((uint32_t)0x000000C0U),
+ /* peripheral reset */
+ IDX_RSTSCK = ((uint32_t)0x00000024U),
+ /* clock stabilization and stuck interrupt */
+ IDX_INT = ((uint32_t)0x00000008U),
+ IDX_ADDINT = ((uint32_t)0x000000CCU),
+ /* configuration register */
+ IDX_CFG0 = ((uint32_t)0x00000004U),
+ IDX_CFG2 = ((uint32_t)0x00000030U)
+} reg_idx;
+
+/* peripheral clock enable */
+typedef enum {
+ /* AHB peripherals */
+ RCU_DMA = RCU_REGIDX_BIT(IDX_AHBEN, 0U), /*!< DMA clock */
+ RCU_CRC = RCU_REGIDX_BIT(IDX_AHBEN, 6U), /*!< CRC clock */
+ RCU_GPIOA = RCU_REGIDX_BIT(IDX_AHBEN, 17U), /*!< GPIOA clock */
+ RCU_GPIOB = RCU_REGIDX_BIT(IDX_AHBEN, 18U), /*!< GPIOB clock */
+ RCU_GPIOC = RCU_REGIDX_BIT(IDX_AHBEN, 19U), /*!< GPIOC clock */
+ RCU_GPIOD = RCU_REGIDX_BIT(IDX_AHBEN, 20U), /*!< GPIOD clock */
+ RCU_GPIOF = RCU_REGIDX_BIT(IDX_AHBEN, 22U), /*!< GPIOF clock */
+ RCU_TSI = RCU_REGIDX_BIT(IDX_AHBEN, 24U), /*!< TSI clock */
+
+ /* APB2 peripherals */
+ RCU_CFGCMP = RCU_REGIDX_BIT(IDX_APB2EN, 0U), /*!< CFGCMP clock */
+ RCU_ADC = RCU_REGIDX_BIT(IDX_APB2EN, 9U), /*!< ADC clock */
+ RCU_TIMER0 = RCU_REGIDX_BIT(IDX_APB2EN, 11U), /*!< TIMER0 clock */
+ RCU_SPI0 = RCU_REGIDX_BIT(IDX_APB2EN, 12U), /*!< SPI0 clock */
+ RCU_USART0 = RCU_REGIDX_BIT(IDX_APB2EN, 14U), /*!< USART0 clock */
+ RCU_TIMER14 = RCU_REGIDX_BIT(IDX_APB2EN, 16U), /*!< TIMER14 clock */
+ RCU_TIMER15 = RCU_REGIDX_BIT(IDX_APB2EN, 17U), /*!< TIMER15 clock */
+ RCU_TIMER16 = RCU_REGIDX_BIT(IDX_APB2EN, 18U), /*!< TIMER16 clock */
+
+ /* APB1 peripherals */
+ RCU_TIMER1 = RCU_REGIDX_BIT(IDX_APB1EN, 0U), /*!< TIMER1 clock */
+ RCU_TIMER2 = RCU_REGIDX_BIT(IDX_APB1EN, 1U), /*!< TIMER2 clock */
+ RCU_TIMER13 = RCU_REGIDX_BIT(IDX_APB1EN, 8U), /*!< TIMER13 clock */
+ RCU_WWDGT = RCU_REGIDX_BIT(IDX_APB1EN, 11U), /*!< WWDGT clock */
+ RCU_SPI1 = RCU_REGIDX_BIT(IDX_APB1EN, 14U), /*!< SPI1 clock */
+ RCU_USART1 = RCU_REGIDX_BIT(IDX_APB1EN, 17U), /*!< USART1 clock */
+ RCU_I2C0 = RCU_REGIDX_BIT(IDX_APB1EN, 21U), /*!< I2C0 clock */
+ RCU_I2C1 = RCU_REGIDX_BIT(IDX_APB1EN, 22U), /*!< I2C1 clock */
+ RCU_PMU = RCU_REGIDX_BIT(IDX_APB1EN, 28U), /*!< PMU clock */
+#if defined(GD32F350)
+ RCU_DAC = RCU_REGIDX_BIT(IDX_APB1EN, 29U), /*!< DAC clock */
+ RCU_CEC = RCU_REGIDX_BIT(IDX_APB1EN, 30U), /*!< CEC clock */
+ RCU_TIMER5 = RCU_REGIDX_BIT(IDX_APB1EN, 4U), /*!< TIMER5 clock */
+ RCU_USBFS = RCU_REGIDX_BIT(IDX_AHBEN, 12U), /*!< USBFS clock */
+#endif /* GD32F350 */
+ RCU_RTC = RCU_REGIDX_BIT(IDX_BDCTL, 15U), /*!< RTC clock */
+
+ /* RCU_ADDAPB1EN */
+ RCU_CTC = RCU_REGIDX_BIT(IDX_ADDAPB1EN, 27U) /*!< CTC clock */
+} rcu_periph_enum;
+
+/* peripheral clock enable when sleep mode*/
+typedef enum {
+ /* AHB peripherals */
+ RCU_SRAM_SLP = RCU_REGIDX_BIT(IDX_AHBEN, 2U), /*!< SRAM clock */
+ RCU_FMC_SLP = RCU_REGIDX_BIT(IDX_AHBEN, 4U), /*!< FMC clock */
+} rcu_periph_sleep_enum;
+
+/* peripherals reset */
+typedef enum {
+ /* AHB peripherals reset */
+ RCU_GPIOARST = RCU_REGIDX_BIT(IDX_AHBRST, 17U), /*!< GPIOA reset */
+ RCU_GPIOBRST = RCU_REGIDX_BIT(IDX_AHBRST, 18U), /*!< GPIOB reset */
+ RCU_GPIOCRST = RCU_REGIDX_BIT(IDX_AHBRST, 19U), /*!< GPIOC reset */
+ RCU_GPIODRST = RCU_REGIDX_BIT(IDX_AHBRST, 20U), /*!< GPIOD reset */
+ RCU_GPIOFRST = RCU_REGIDX_BIT(IDX_AHBRST, 22U), /*!< GPIOF reset */
+ RCU_TSIRST = RCU_REGIDX_BIT(IDX_AHBRST, 24U), /*!< TSI reset */
+
+ /* APB2 peripherals reset */
+ RCU_CFGCMPRST = RCU_REGIDX_BIT(IDX_APB2RST, 0U), /*!< CFGCMP reset */
+ RCU_ADCRST = RCU_REGIDX_BIT(IDX_APB2RST, 9U), /*!< ADC reset */
+ RCU_TIMER0RST = RCU_REGIDX_BIT(IDX_APB2RST, 11U), /*!< TIMER0 reset */
+ RCU_SPI0RST = RCU_REGIDX_BIT(IDX_APB2RST, 12U), /*!< SPI0 reset */
+ RCU_USART0RST = RCU_REGIDX_BIT(IDX_APB2RST, 14U), /*!< USART0 reset */
+ RCU_TIMER14RST = RCU_REGIDX_BIT(IDX_APB2RST, 16U), /*!< TIMER14 reset */
+ RCU_TIMER15RST = RCU_REGIDX_BIT(IDX_APB2RST, 17U), /*!< TIMER15 reset */
+ RCU_TIMER16RST = RCU_REGIDX_BIT(IDX_APB2RST, 18U), /*!< TIMER16 reset */
+
+ /* APB1 peripherals reset */
+ RCU_TIMER1RST = RCU_REGIDX_BIT(IDX_APB1RST, 0U), /*!< TIMER1 reset */
+ RCU_TIMER2RST = RCU_REGIDX_BIT(IDX_APB1RST, 1U), /*!< TIMER2 reset */
+ RCU_TIMER13RST = RCU_REGIDX_BIT(IDX_APB1RST, 8U), /*!< TIMER13 reset */
+ RCU_WWDGTRST = RCU_REGIDX_BIT(IDX_APB1RST, 11U), /*!< WWDGT reset */
+ RCU_SPI1RST = RCU_REGIDX_BIT(IDX_APB1RST, 14U), /*!< SPI1 reset */
+ RCU_USART1RST = RCU_REGIDX_BIT(IDX_APB1RST, 17U), /*!< USART1 reset */
+ RCU_I2C0RST = RCU_REGIDX_BIT(IDX_APB1RST, 21U), /*!< I2C0 reset */
+ RCU_I2C1RST = RCU_REGIDX_BIT(IDX_APB1RST, 22U), /*!< I2C1 reset */
+ RCU_PMURST = RCU_REGIDX_BIT(IDX_APB1RST, 28U), /*!< PMU reset */
+#if defined(GD32F350)
+ RCU_DACRST = RCU_REGIDX_BIT(IDX_APB1RST, 29U), /*!< DAC reset */
+ RCU_CECRST = RCU_REGIDX_BIT(IDX_APB1RST, 30U), /*!< CEC reset */
+ RCU_TIMER5RST = RCU_REGIDX_BIT(IDX_APB1RST, 4U), /*!< TIMER5 reset */
+ RCU_USBFSRST = RCU_REGIDX_BIT(IDX_AHBRST, 12U), /*!< USBFS reset */
+#endif /* GD32F350 */
+ /* RCU_ADDAPB1RST */
+ RCU_CTCRST = RCU_REGIDX_BIT(IDX_ADDAPB1RST, 27U), /*!< CTC reset */
+} rcu_periph_reset_enum;
+
+/* clock stabilization and peripheral reset flags */
+typedef enum {
+ RCU_FLAG_IRC40KSTB = RCU_REGIDX_BIT(IDX_RSTSCK, 1U), /*!< IRC40K stabilization flags */
+ RCU_FLAG_LXTALSTB = RCU_REGIDX_BIT(IDX_BDCTL, 1U), /*!< LXTAL stabilization flags */
+ RCU_FLAG_IRC8MSTB = RCU_REGIDX_BIT(IDX_CTL0, 1U), /*!< IRC8M stabilization flags */
+ RCU_FLAG_HXTALSTB = RCU_REGIDX_BIT(IDX_CTL0, 17U), /*!< HXTAL stabilization flags */
+ RCU_FLAG_PLLSTB = RCU_REGIDX_BIT(IDX_CTL0, 25U), /*!< PLL stabilization flags */
+ RCU_FLAG_IRC28MSTB = RCU_REGIDX_BIT(IDX_CTL1, 1U), /*!< IRC28M stabilization flags */
+ RCU_FLAG_IRC48MSTB = RCU_REGIDX_BIT(IDX_ADDCTL, 17U), /*!< IRC48M stabilization flags */
+
+ RCU_FLAG_V12RST = RCU_REGIDX_BIT(IDX_RSTSCK, 23U), /*!< V12 reset flags */
+ RCU_FLAG_OBLRST = RCU_REGIDX_BIT(IDX_RSTSCK, 25U), /*!< OBL reset flags */
+ RCU_FLAG_EPRST = RCU_REGIDX_BIT(IDX_RSTSCK, 26U), /*!< EPR reset flags */
+ RCU_FLAG_PORRST = RCU_REGIDX_BIT(IDX_RSTSCK, 27U), /*!< power reset flags */
+ RCU_FLAG_SWRST = RCU_REGIDX_BIT(IDX_RSTSCK, 28U), /*!< SW reset flags */
+ RCU_FLAG_FWDGTRST = RCU_REGIDX_BIT(IDX_RSTSCK, 29U), /*!< FWDGT reset flags */
+ RCU_FLAG_WWDGTRST = RCU_REGIDX_BIT(IDX_RSTSCK, 30U), /*!< WWDGT reset flags */
+ RCU_FLAG_LPRST = RCU_REGIDX_BIT(IDX_RSTSCK, 31U) /*!< LP reset flags */
+} rcu_flag_enum;
+
+/* clock stabilization and ckm interrupt flags */
+typedef enum {
+ RCU_INT_FLAG_IRC40KSTB = RCU_REGIDX_BIT(IDX_INT, 0U), /*!< IRC40K stabilization interrupt flag */
+ RCU_INT_FLAG_LXTALSTB = RCU_REGIDX_BIT(IDX_INT, 1U), /*!< LXTAL stabilization interrupt flag */
+ RCU_INT_FLAG_IRC8MSTB = RCU_REGIDX_BIT(IDX_INT, 2U), /*!< IRC8M stabilization interrupt flag */
+ RCU_INT_FLAG_HXTALSTB = RCU_REGIDX_BIT(IDX_INT, 3U), /*!< HXTAL stabilization interrupt flag */
+ RCU_INT_FLAG_PLLSTB = RCU_REGIDX_BIT(IDX_INT, 4U), /*!< PLL stabilization interrupt flag */
+ RCU_INT_FLAG_IRC28MSTB = RCU_REGIDX_BIT(IDX_INT, 5U), /*!< IRC28M stabilization interrupt flag */
+ RCU_INT_FLAG_CKM = RCU_REGIDX_BIT(IDX_INT, 7U), /*!< CKM interrupt flag */
+ RCU_INT_FLAG_IRC48MSTB = RCU_REGIDX_BIT(IDX_ADDINT, 6U) /*!< IRC48M stabilization interrupt flag */
+} rcu_int_flag_enum;
+
+/* clock stabilization and stuck interrupt flags clear */
+typedef enum {
+ RCU_INT_FLAG_IRC40KSTB_CLR = RCU_REGIDX_BIT(IDX_INT, 16U), /*!< IRC40K stabilization interrupt flags clear */
+ RCU_INT_FLAG_LXTALSTB_CLR = RCU_REGIDX_BIT(IDX_INT, 17U), /*!< LXTAL stabilization interrupt flags clear */
+ RCU_INT_FLAG_IRC8MSTB_CLR = RCU_REGIDX_BIT(IDX_INT, 18U), /*!< IRC8M stabilization interrupt flags clear */
+ RCU_INT_FLAG_HXTALSTB_CLR = RCU_REGIDX_BIT(IDX_INT, 19U), /*!< HXTAL stabilization interrupt flags clear */
+ RCU_INT_FLAG_PLLSTB_CLR = RCU_REGIDX_BIT(IDX_INT, 20U), /*!< PLL stabilization interrupt flags clear */
+ RCU_INT_FLAG_IRC28MSTB_CLR = RCU_REGIDX_BIT(IDX_INT, 21U), /*!< IRC28M stabilization interrupt flags clear */
+ RCU_INT_FLAG_CKM_CLR = RCU_REGIDX_BIT(IDX_INT, 23U), /*!< CKM interrupt flags clear */
+ RCU_INT_FLAG_IRC48MSTB_CLR = RCU_REGIDX_BIT(IDX_ADDINT, 22U) /*!< IRC48M stabilization interrupt flag clear */
+} rcu_int_flag_clear_enum;
+
+/* clock stabilization interrupt enable or disable */
+typedef enum {
+ RCU_INT_IRC40KSTB = RCU_REGIDX_BIT(IDX_INT, 8U), /*!< IRC40K stabilization interrupt */
+ RCU_INT_LXTALSTB = RCU_REGIDX_BIT(IDX_INT, 9U), /*!< LXTAL stabilization interrupt */
+ RCU_INT_IRC8MSTB = RCU_REGIDX_BIT(IDX_INT, 10U), /*!< IRC8M stabilization interrupt */
+ RCU_INT_HXTALSTB = RCU_REGIDX_BIT(IDX_INT, 11U), /*!< HXTAL stabilization interrupt */
+ RCU_INT_PLLSTB = RCU_REGIDX_BIT(IDX_INT, 12U), /*!< PLL stabilization interrupt */
+ RCU_INT_IRC28MSTB = RCU_REGIDX_BIT(IDX_INT, 13U), /*!< IRC28M stabilization interrupt */
+ RCU_INT_IRC48MSTB = RCU_REGIDX_BIT(IDX_ADDINT, 14U) /*!< IRC48M stabilization interrupt */
+} rcu_int_enum;
+
+/* ADC clock source */
+typedef enum {
+ RCU_ADCCK_IRC28M_DIV2 = 0U, /*!< ADC clock source select IRC28M/2 */
+ RCU_ADCCK_IRC28M, /*!< ADC clock source select IRC28M */
+ RCU_ADCCK_APB2_DIV2, /*!< ADC clock source select APB2/2 */
+ RCU_ADCCK_AHB_DIV3, /*!< ADC clock source select AHB/3 */
+ RCU_ADCCK_APB2_DIV4, /*!< ADC clock source select APB2/4 */
+ RCU_ADCCK_AHB_DIV5, /*!< ADC clock source select AHB/5 */
+ RCU_ADCCK_APB2_DIV6, /*!< ADC clock source select APB2/6 */
+ RCU_ADCCK_AHB_DIV7, /*!< ADC clock source select AHB/7 */
+ RCU_ADCCK_APB2_DIV8, /*!< ADC clock source select APB2/8 */
+ RCU_ADCCK_AHB_DIV9 /*!< ADC clock source select AHB/9 */
+} rcu_adc_clock_enum;
+
+/* oscillator types */
+typedef enum {
+ RCU_HXTAL = RCU_REGIDX_BIT(IDX_CTL0, 16U), /*!< HXTAL */
+ RCU_LXTAL = RCU_REGIDX_BIT(IDX_BDCTL, 0U), /*!< LXTAL */
+ RCU_IRC8M = RCU_REGIDX_BIT(IDX_CTL0, 0U), /*!< IRC8M */
+ RCU_IRC28M = RCU_REGIDX_BIT(IDX_CTL1, 0U), /*!< IRC28M */
+ RCU_IRC48M = RCU_REGIDX_BIT(IDX_ADDCTL, 16U), /*!< IRC48M */
+ RCU_IRC40K = RCU_REGIDX_BIT(IDX_RSTSCK, 0U), /*!< IRC40K */
+ RCU_PLL_CK = RCU_REGIDX_BIT(IDX_CTL0, 24U) /*!< PLL */
+} rcu_osci_type_enum;
+
+/* rcu clock frequency */
+typedef enum {
+ CK_SYS = 0U, /*!< system clock */
+ CK_AHB, /*!< AHB clock */
+ CK_APB1, /*!< APB1 clock */
+ CK_APB2, /*!< APB2 clock */
+ CK_ADC, /*!< ADC clock */
+ CK_CEC, /*!< CEC clock */
+ CK_USART /*!< USART clock */
+} rcu_clock_freq_enum;
+
+/* system clock source select */
+#define CFG0_SCS(regval) (BITS(0,1) & ((uint32_t)(regval) << 0))
+#define RCU_CKSYSSRC_IRC8M CFG0_SCS(0) /*!< system clock source select IRC8M */
+#define RCU_CKSYSSRC_HXTAL CFG0_SCS(1) /*!< system clock source select HXTAL */
+#define RCU_CKSYSSRC_PLL CFG0_SCS(2) /*!< system clock source select PLL */
+
+/* system clock source select status */
+#define CFG0_SCSS(regval) (BITS(2,3) & ((uint32_t)(regval) << 2))
+#define RCU_SCSS_IRC8M CFG0_SCSS(0) /*!< system clock source select IRC8M */
+#define RCU_SCSS_HXTAL CFG0_SCSS(1) /*!< system clock source select HXTAL */
+#define RCU_SCSS_PLL CFG0_SCSS(2) /*!< system clock source select PLL */
+
+/* AHB prescaler selection */
+#define CFG0_AHBPSC(regval) (BITS(4,7) & ((uint32_t)(regval) << 4))
+#define RCU_AHB_CKSYS_DIV1 CFG0_AHBPSC(0) /*!< AHB prescaler select CK_SYS */
+#define RCU_AHB_CKSYS_DIV2 CFG0_AHBPSC(8) /*!< AHB prescaler select CK_SYS/2 */
+#define RCU_AHB_CKSYS_DIV4 CFG0_AHBPSC(9) /*!< AHB prescaler select CK_SYS/4 */
+#define RCU_AHB_CKSYS_DIV8 CFG0_AHBPSC(10) /*!< AHB prescaler select CK_SYS/8 */
+#define RCU_AHB_CKSYS_DIV16 CFG0_AHBPSC(11) /*!< AHB prescaler select CK_SYS/16 */
+#define RCU_AHB_CKSYS_DIV64 CFG0_AHBPSC(12) /*!< AHB prescaler select CK_SYS/64 */
+#define RCU_AHB_CKSYS_DIV128 CFG0_AHBPSC(13) /*!< AHB prescaler select CK_SYS/128 */
+#define RCU_AHB_CKSYS_DIV256 CFG0_AHBPSC(14) /*!< AHB prescaler select CK_SYS/256 */
+#define RCU_AHB_CKSYS_DIV512 CFG0_AHBPSC(15) /*!< AHB prescaler select CK_SYS/512 */
+
+/* APB1 prescaler selection */
+#define CFG0_APB1PSC(regval) (BITS(8,10) & ((uint32_t)(regval) << 8))
+#define RCU_APB1_CKAHB_DIV1 CFG0_APB1PSC(0) /*!< APB1 prescaler select CK_AHB */
+#define RCU_APB1_CKAHB_DIV2 CFG0_APB1PSC(4) /*!< APB1 prescaler select CK_AHB/2 */
+#define RCU_APB1_CKAHB_DIV4 CFG0_APB1PSC(5) /*!< APB1 prescaler select CK_AHB/4 */
+#define RCU_APB1_CKAHB_DIV8 CFG0_APB1PSC(6) /*!< APB1 prescaler select CK_AHB/8 */
+#define RCU_APB1_CKAHB_DIV16 CFG0_APB1PSC(7) /*!< APB1 prescaler select CK_AHB/16 */
+
+/* APB2 prescaler selection */
+#define CFG0_APB2PSC(regval) (BITS(11,13) & ((uint32_t)(regval) << 11))
+#define RCU_APB2_CKAHB_DIV1 CFG0_APB2PSC(0) /*!< APB2 prescaler select CK_AHB */
+#define RCU_APB2_CKAHB_DIV2 CFG0_APB2PSC(4) /*!< APB2 prescaler select CK_AHB/2 */
+#define RCU_APB2_CKAHB_DIV4 CFG0_APB2PSC(5) /*!< APB2 prescaler select CK_AHB/4 */
+#define RCU_APB2_CKAHB_DIV8 CFG0_APB2PSC(6) /*!< APB2 prescaler select CK_AHB/8 */
+#define RCU_APB2_CKAHB_DIV16 CFG0_APB2PSC(7) /*!< APB2 prescaler select CK_AHB/16 */
+
+/* ADC clock prescaler selection */
+#define CFG0_ADCPSC(regval) (BITS(14,15) & ((uint32_t)(regval) << 14))
+#define RCU_ADC_CKAPB2_DIV2 CFG0_ADCPSC(0) /*!< ADC clock prescaler select CK_APB2/2 */
+#define RCU_ADC_CKAPB2_DIV4 CFG0_ADCPSC(1) /*!< ADC clock prescaler select CK_APB2/4 */
+#define RCU_ADC_CKAPB2_DIV6 CFG0_ADCPSC(2) /*!< ADC clock prescaler select CK_APB2/6 */
+#define RCU_ADC_CKAPB2_DIV8 CFG0_ADCPSC(3) /*!< ADC clock prescaler select CK_APB2/8 */
+
+/* PLL clock source selection */
+#define RCU_PLLSRC_IRC8M_DIV2 ((uint32_t)0x00000000U) /*!< PLL clock source select IRC8M/2 */
+#define RCU_PLLSRC_HXTAL_IRC48M RCU_CFG0_PLLSEL /*!< PLL clock source select HXTAL or IRC48M*/
+
+/* PLL clock source preselection */
+#define RCU_PLLPRESEL_HXTAL ((uint32_t)0x00000000U) /*!< PLL clock source preselection HXTAL */
+#define RCU_PLLPRESEL_IRC48M RCU_CFG1_PLLPRESEL /*!< PLL clock source preselection IRC48M */
+
+/* HXTAL or IRC48M divider for PLL source clock selection */
+#define RCU_PLLPREDV ((uint32_t)0x00000000U) /*!< HXTAL or IRC48M clock selected */
+#define RCU_PLLPREDV_DIV2 RCU_CFG0_PLLPREDV /*!< (HXTAL or IRC48M) /2 clock selected */
+
+/* PLL multiply factor */
+#define CFG0_PLLMF(regval) (BITS(18,21) & ((uint32_t)(regval) << 18))
+#define RCU_PLL_MUL2 CFG0_PLLMF(0) /*!< PLL source clock multiply by 2 */
+#define RCU_PLL_MUL3 CFG0_PLLMF(1) /*!< PLL source clock multiply by 3 */
+#define RCU_PLL_MUL4 CFG0_PLLMF(2) /*!< PLL source clock multiply by 4 */
+#define RCU_PLL_MUL5 CFG0_PLLMF(3) /*!< PLL source clock multiply by 5 */
+#define RCU_PLL_MUL6 CFG0_PLLMF(4) /*!< PLL source clock multiply by 6 */
+#define RCU_PLL_MUL7 CFG0_PLLMF(5) /*!< PLL source clock multiply by 7 */
+#define RCU_PLL_MUL8 CFG0_PLLMF(6) /*!< PLL source clock multiply by 8 */
+#define RCU_PLL_MUL9 CFG0_PLLMF(7) /*!< PLL source clock multiply by 9 */
+#define RCU_PLL_MUL10 CFG0_PLLMF(8) /*!< PLL source clock multiply by 10 */
+#define RCU_PLL_MUL11 CFG0_PLLMF(9) /*!< PLL source clock multiply by 11 */
+#define RCU_PLL_MUL12 CFG0_PLLMF(10) /*!< PLL source clock multiply by 12 */
+#define RCU_PLL_MUL13 CFG0_PLLMF(11) /*!< PLL source clock multiply by 13 */
+#define RCU_PLL_MUL14 CFG0_PLLMF(12) /*!< PLL source clock multiply by 14 */
+#define RCU_PLL_MUL15 CFG0_PLLMF(13) /*!< PLL source clock multiply by 15 */
+#define RCU_PLL_MUL16 CFG0_PLLMF(14) /*!< PLL source clock multiply by 16 */
+#define RCU_PLL_MUL17 (RCU_CFG0_PLLMF4 | CFG0_PLLMF(0)) /*!< PLL source clock multiply by 17 */
+#define RCU_PLL_MUL18 (RCU_CFG0_PLLMF4 | CFG0_PLLMF(1)) /*!< PLL source clock multiply by 18 */
+#define RCU_PLL_MUL19 (RCU_CFG0_PLLMF4 | CFG0_PLLMF(2)) /*!< PLL source clock multiply by 19 */
+#define RCU_PLL_MUL20 (RCU_CFG0_PLLMF4 | CFG0_PLLMF(3)) /*!< PLL source clock multiply by 20 */
+#define RCU_PLL_MUL21 (RCU_CFG0_PLLMF4 | CFG0_PLLMF(4)) /*!< PLL source clock multiply by 21 */
+#define RCU_PLL_MUL22 (RCU_CFG0_PLLMF4 | CFG0_PLLMF(5)) /*!< PLL source clock multiply by 22 */
+#define RCU_PLL_MUL23 (RCU_CFG0_PLLMF4 | CFG0_PLLMF(6)) /*!< PLL source clock multiply by 23 */
+#define RCU_PLL_MUL24 (RCU_CFG0_PLLMF4 | CFG0_PLLMF(7)) /*!< PLL source clock multiply by 24 */
+#define RCU_PLL_MUL25 (RCU_CFG0_PLLMF4 | CFG0_PLLMF(8)) /*!< PLL source clock multiply by 25 */
+#define RCU_PLL_MUL26 (RCU_CFG0_PLLMF4 | CFG0_PLLMF(9)) /*!< PLL source clock multiply by 26 */
+#define RCU_PLL_MUL27 (RCU_CFG0_PLLMF4 | CFG0_PLLMF(10)) /*!< PLL source clock multiply by 27 */
+#define RCU_PLL_MUL28 (RCU_CFG0_PLLMF4 | CFG0_PLLMF(11)) /*!< PLL source clock multiply by 28 */
+#define RCU_PLL_MUL29 (RCU_CFG0_PLLMF4 | CFG0_PLLMF(12)) /*!< PLL source clock multiply by 29 */
+#define RCU_PLL_MUL30 (RCU_CFG0_PLLMF4 | CFG0_PLLMF(13)) /*!< PLL source clock multiply by 30 */
+#define RCU_PLL_MUL31 (RCU_CFG0_PLLMF4 | CFG0_PLLMF(14)) /*!< PLL source clock multiply by 31 */
+#define RCU_PLL_MUL32 (RCU_CFG0_PLLMF4 | CFG0_PLLMF(15)) /*!< PLL source clock multiply by 32 */
+#define RCU_PLL_MUL33 (CFG0_PLLMF(0) | RCU_CFG1_PLLMF5) /*!< PLL source clock multiply by 33 */
+#define RCU_PLL_MUL34 (CFG0_PLLMF(1) | RCU_CFG1_PLLMF5) /*!< PLL source clock multiply by 34 */
+#define RCU_PLL_MUL35 (CFG0_PLLMF(2) | RCU_CFG1_PLLMF5) /*!< PLL source clock multiply by 35 */
+#define RCU_PLL_MUL36 (CFG0_PLLMF(3) | RCU_CFG1_PLLMF5) /*!< PLL source clock multiply by 36 */
+#define RCU_PLL_MUL37 (CFG0_PLLMF(4) | RCU_CFG1_PLLMF5) /*!< PLL source clock multiply by 37 */
+#define RCU_PLL_MUL38 (CFG0_PLLMF(5) | RCU_CFG1_PLLMF5) /*!< PLL source clock multiply by 38 */
+#define RCU_PLL_MUL39 (CFG0_PLLMF(6) | RCU_CFG1_PLLMF5) /*!< PLL source clock multiply by 39 */
+#define RCU_PLL_MUL40 (CFG0_PLLMF(7) | RCU_CFG1_PLLMF5) /*!< PLL source clock multiply by 40 */
+#define RCU_PLL_MUL41 (CFG0_PLLMF(8) | RCU_CFG1_PLLMF5) /*!< PLL source clock multiply by 41 */
+#define RCU_PLL_MUL42 (CFG0_PLLMF(9) | RCU_CFG1_PLLMF5) /*!< PLL source clock multiply by 42 */
+#define RCU_PLL_MUL43 (CFG0_PLLMF(10) | RCU_CFG1_PLLMF5) /*!< PLL source clock multiply by 43 */
+#define RCU_PLL_MUL44 (CFG0_PLLMF(11) | RCU_CFG1_PLLMF5) /*!< PLL source clock multiply by 44 */
+#define RCU_PLL_MUL45 (CFG0_PLLMF(12) | RCU_CFG1_PLLMF5) /*!< PLL source clock multiply by 45 */
+#define RCU_PLL_MUL46 (CFG0_PLLMF(13) | RCU_CFG1_PLLMF5) /*!< PLL source clock multiply by 46 */
+#define RCU_PLL_MUL47 (CFG0_PLLMF(14) | RCU_CFG1_PLLMF5) /*!< PLL source clock multiply by 47 */
+#define RCU_PLL_MUL48 (CFG0_PLLMF(15) | RCU_CFG1_PLLMF5) /*!< PLL source clock multiply by 48 */
+#define RCU_PLL_MUL49 (RCU_CFG0_PLLMF4 | RCU_CFG1_PLLMF5) /*!< PLL source clock multiply by 49 */
+#define RCU_PLL_MUL50 (RCU_PLL_MUL18 | RCU_CFG1_PLLMF5) /*!< PLL source clock multiply by 50 */
+#define RCU_PLL_MUL51 (RCU_PLL_MUL19 | RCU_CFG1_PLLMF5) /*!< PLL source clock multiply by 51 */
+#define RCU_PLL_MUL52 (RCU_PLL_MUL20 | RCU_CFG1_PLLMF5) /*!< PLL source clock multiply by 52 */
+#define RCU_PLL_MUL53 (RCU_PLL_MUL21 | RCU_CFG1_PLLMF5) /*!< PLL source clock multiply by 53 */
+#define RCU_PLL_MUL54 (RCU_PLL_MUL22 | RCU_CFG1_PLLMF5) /*!< PLL source clock multiply by 54 */
+#define RCU_PLL_MUL55 (RCU_PLL_MUL23 | RCU_CFG1_PLLMF5) /*!< PLL source clock multiply by 55 */
+#define RCU_PLL_MUL56 (RCU_PLL_MUL24 | RCU_CFG1_PLLMF5) /*!< PLL source clock multiply by 56 */
+#define RCU_PLL_MUL57 (RCU_PLL_MUL25 | RCU_CFG1_PLLMF5) /*!< PLL source clock multiply by 57 */
+#define RCU_PLL_MUL58 (RCU_PLL_MUL26 | RCU_CFG1_PLLMF5) /*!< PLL source clock multiply by 58 */
+#define RCU_PLL_MUL59 (RCU_PLL_MUL27 | RCU_CFG1_PLLMF5) /*!< PLL source clock multiply by 59 */
+#define RCU_PLL_MUL60 (RCU_PLL_MUL28 | RCU_CFG1_PLLMF5) /*!< PLL source clock multiply by 60 */
+#define RCU_PLL_MUL61 (RCU_PLL_MUL29 | RCU_CFG1_PLLMF5) /*!< PLL source clock multiply by 61 */
+#define RCU_PLL_MUL62 (RCU_PLL_MUL30 | RCU_CFG1_PLLMF5) /*!< PLL source clock multiply by 62 */
+#define RCU_PLL_MUL63 (RCU_PLL_MUL31 | RCU_CFG1_PLLMF5) /*!< PLL source clock multiply by 63 */
+#define RCU_PLL_MUL64 (RCU_PLL_MUL32 | RCU_CFG1_PLLMF5) /*!< PLL source clock multiply by 64 */
+
+/* USBFS clock prescaler selection */
+#define CFG0_USBFSPSC(regval) (BITS(22,23) & ((uint32_t)(regval) << 22))
+#define RCU_USBFS_CKPLL_DIV1_5 CFG0_USBFSPSC(0) /*!< USBFS clock prescaler select CK_PLL/1.5 */
+#define RCU_USBFS_CKPLL_DIV1 CFG0_USBFSPSC(1) /*!< USBFS clock prescaler select CK_PLL */
+#define RCU_USBFS_CKPLL_DIV2_5 CFG0_USBFSPSC(2) /*!< USBFS clock prescaler select CK_PLL/2.5 */
+#define RCU_USBFS_CKPLL_DIV2 CFG0_USBFSPSC(3) /*!< USBFS clock prescaler select CK_PLL/2 */
+#define RCU_USBFS_CKPLL_DIV3 RCU_CFG2_USBFSPSC2 /*!< USBFS clock prescaler select CK_PLL/3 */
+#define RCU_USBFS_CKPLL_DIV3_5 (CFG0_USBFSPSC(1)|RCU_CFG2_USBFSPSC2) /*!< USBFS clock prescaler select CK_PLL/3.5 */
+
+/* CK_OUT clock source selection */
+#define CFG0_CKOUTSEL(regval) (BITS(24,26) & ((uint32_t)(regval) << 24))
+#define RCU_CKOUTSRC_NONE CFG0_CKOUTSEL(0) /*!< no clock selected */
+#define RCU_CKOUTSRC_IRC28M CFG0_CKOUTSEL(1) /*!< CK_OUT clock source select IRC28M */
+#define RCU_CKOUTSRC_IRC40K CFG0_CKOUTSEL(2) /*!< CK_OUT clock source select IRC40K */
+#define RCU_CKOUTSRC_LXTAL CFG0_CKOUTSEL(3) /*!< CK_OUT clock source select LXTAL */
+#define RCU_CKOUTSRC_CKSYS CFG0_CKOUTSEL(4) /*!< CK_OUT clock source select CKSYS */
+#define RCU_CKOUTSRC_IRC8M CFG0_CKOUTSEL(5) /*!< CK_OUT clock source select IRC8M */
+#define RCU_CKOUTSRC_HXTAL CFG0_CKOUTSEL(6) /*!< CK_OUT clock source select HXTAL */
+#define RCU_CKOUTSRC_CKPLL_DIV1 (RCU_CFG0_PLLDV | CFG0_CKOUTSEL(7)) /*!< CK_OUT clock source select CK_PLL */
+#define RCU_CKOUTSRC_CKPLL_DIV2 CFG0_CKOUTSEL(7) /*!< CK_OUT clock source select CK_PLL/2 */
+
+/* CK_OUT divider */
+#define CFG0_CKOUTDIV(regval) (BITS(28,30) & ((uint32_t)(regval) << 28))
+#define RCU_CKOUT_DIV1 CFG0_CKOUTDIV(0) /*!< CK_OUT is divided by 1 */
+#define RCU_CKOUT_DIV2 CFG0_CKOUTDIV(1) /*!< CK_OUT is divided by 2 */
+#define RCU_CKOUT_DIV4 CFG0_CKOUTDIV(2) /*!< CK_OUT is divided by 4 */
+#define RCU_CKOUT_DIV8 CFG0_CKOUTDIV(3) /*!< CK_OUT is divided by 8 */
+#define RCU_CKOUT_DIV16 CFG0_CKOUTDIV(4) /*!< CK_OUT is divided by 16 */
+#define RCU_CKOUT_DIV32 CFG0_CKOUTDIV(5) /*!< CK_OUT is divided by 32 */
+#define RCU_CKOUT_DIV64 CFG0_CKOUTDIV(6) /*!< CK_OUT is divided by 64 */
+#define RCU_CKOUT_DIV128 CFG0_CKOUTDIV(7) /*!< CK_OUT is divided by 128 */
+
+/* CK_PLL divide by 1 or 2 for CK_OUT */
+#define RCU_PLLDV_CKPLL_DIV2 ((uint32_t)0x00000000U) /*!< CK_PLL divide by 2 for CK_OUT */
+#define RCU_PLLDV_CKPLL RCU_CFG0_PLLDV /*!< CK_PLL divide by 1 for CK_OUT */
+
+/* LXTAL drive capability */
+#define BDCTL_LXTALDRI(regval) (BITS(3,4) & ((uint32_t)(regval) << 3))
+#define RCU_LXTAL_LOWDRI BDCTL_LXTALDRI(0) /*!< lower driving capability */
+#define RCU_LXTAL_MED_LOWDRI BDCTL_LXTALDRI(1) /*!< medium low driving capability */
+#define RCU_LXTAL_MED_HIGHDRI BDCTL_LXTALDRI(2) /*!< medium high driving capability */
+#define RCU_LXTAL_HIGHDRI BDCTL_LXTALDRI(3) /*!< higher driving capability */
+
+/* RTC clock entry selection */
+#define BDCTL_RTCSRC(regval) (BITS(8,9) & ((uint32_t)(regval) << 8))
+#define RCU_RTCSRC_NONE BDCTL_RTCSRC(0) /*!< no clock selected */
+#define RCU_RTCSRC_LXTAL BDCTL_RTCSRC(1) /*!< LXTAL selected as RTC source clock */
+#define RCU_RTCSRC_IRC40K BDCTL_RTCSRC(2) /*!< IRC40K selected as RTC source clock */
+#define RCU_RTCSRC_HXTAL_DIV32 BDCTL_RTCSRC(3) /*!< HXTAL/32 selected as RTC source clock */
+
+/* CK_HXTAL divider previous PLL */
+#define CFG1_PREDV(regval) (BITS(0,3) & ((uint32_t)(regval) << 0))
+#define RCU_PLL_PREDV1 CFG1_PREDV(0) /*!< PLL not divided */
+#define RCU_PLL_PREDV2 CFG1_PREDV(1) /*!< PLL divided by 2 */
+#define RCU_PLL_PREDV3 CFG1_PREDV(2) /*!< PLL divided by 3 */
+#define RCU_PLL_PREDV4 CFG1_PREDV(3) /*!< PLL divided by 4 */
+#define RCU_PLL_PREDV5 CFG1_PREDV(4) /*!< PLL divided by 5 */
+#define RCU_PLL_PREDV6 CFG1_PREDV(5) /*!< PLL divided by 6 */
+#define RCU_PLL_PREDV7 CFG1_PREDV(6) /*!< PLL divided by 7 */
+#define RCU_PLL_PREDV8 CFG1_PREDV(7) /*!< PLL divided by 8 */
+#define RCU_PLL_PREDV9 CFG1_PREDV(8) /*!< PLL divided by 9 */
+#define RCU_PLL_PREDV10 CFG1_PREDV(9) /*!< PLL divided by 10 */
+#define RCU_PLL_PREDV11 CFG1_PREDV(10) /*!< PLL divided by 11 */
+#define RCU_PLL_PREDV12 CFG1_PREDV(11) /*!< PLL divided by 12 */
+#define RCU_PLL_PREDV13 CFG1_PREDV(12) /*!< PLL divided by 13 */
+#define RCU_PLL_PREDV14 CFG1_PREDV(13) /*!< PLL divided by 14 */
+#define RCU_PLL_PREDV15 CFG1_PREDV(14) /*!< PLL divided by 15 */
+#define RCU_PLL_PREDV16 CFG1_PREDV(15) /*!< PLL divided by 16 */
+
+/* USART0 clock source selection */
+#define CFG2_USART0SEL(regval) (BITS(0,1) & ((uint32_t)(regval) << 0))
+#define RCU_USART0SRC_CKAPB2 CFG2_USART0SEL(0) /*!< CK_USART0 select CK_APB2 */
+#define RCU_USART0SRC_CKSYS CFG2_USART0SEL(1) /*!< CK_USART0 select CK_SYS */
+#define RCU_USART0SRC_LXTAL CFG2_USART0SEL(2) /*!< CK_USART0 select LXTAL */
+#define RCU_USART0SRC_IRC8M CFG2_USART0SEL(3) /*!< CK_USART0 select IRC8M */
+
+/* CEC clock source selection */
+#define RCU_CECSRC_IRC8M_DIV244 ((uint32_t)0x00000000U) /*!< CK_CEC clock source select IRC8M/244 */
+#define RCU_CECSRC_LXTAL RCU_CFG2_CECSEL /*!< CK_CEC clock source select LXTAL */
+
+/* ADC clock source selection */
+#define RCU_ADCSRC_IRC28M ((uint32_t)0x00000000U) /*!< ADC clock source select */
+#define RCU_ADCSRC_AHB_APB2DIV RCU_CFG2_ADCSEL /*!< ADC clock source select */
+
+/* IRC28M clock divider for ADC */
+#define RCU_ADC_IRC28M_DIV2 ((uint32_t)0x00000000U) /*!< IRC28M/2 select to ADC clock */
+#define RCU_ADC_IRC28M_DIV1 RCU_CFG2_IRC28MDIV /*!< IRC28M select to ADC clock */
+
+/* CK48M clock source selection */
+#define RCU_CK48MSRC_PLL48M ((uint32_t)0x00000000U) /*!< CK48M source clock select PLL48M */
+#define RCU_CK48MSRC_IRC48M RCU_ADDCTL_CK48MSEL /*!< CK48M source clock select IRC48M */
+
+/* Deep-sleep mode voltage */
+#define DSV_DSLPVS(regval) (BITS(0,1) & ((uint32_t)(regval) << 0))
+#define RCU_DEEPSLEEP_V_0 DSV_DSLPVS(0) /*!< core voltage is default value in deep-sleep mode */
+#define RCU_DEEPSLEEP_V_1 DSV_DSLPVS(1) /*!< core voltage is (default value-0.1)V in deep-sleep mode */
+#define RCU_DEEPSLEEP_V_2 DSV_DSLPVS(2) /*!< core voltage is (default value-0.2)V in deep-sleep mode */
+#define RCU_DEEPSLEEP_V_3 DSV_DSLPVS(3) /*!< core voltage is (default value-0.3)V in deep-sleep mode */
+
+/* function declarations */
+/* deinitialize the RCU */
+void rcu_deinit(void);
+/* enable the peripherals clock */
+void rcu_periph_clock_enable(rcu_periph_enum periph);
+/* disable the peripherals clock */
+void rcu_periph_clock_disable(rcu_periph_enum periph);
+/* enable the peripherals clock when sleep mode */
+void rcu_periph_clock_sleep_enable(rcu_periph_sleep_enum periph);
+/* disable the peripherals clock when sleep mode */
+void rcu_periph_clock_sleep_disable(rcu_periph_sleep_enum periph);
+/* reset the peripherals */
+void rcu_periph_reset_enable(rcu_periph_reset_enum periph_reset);
+/* disable reset the peripheral */
+void rcu_periph_reset_disable(rcu_periph_reset_enum periph_reset);
+/* reset the BKP */
+void rcu_bkp_reset_enable(void);
+/* disable the BKP reset */
+void rcu_bkp_reset_disable(void);
+
+/* configure the system clock source */
+void rcu_system_clock_source_config(uint32_t ck_sys);
+/* get the system clock source */
+uint32_t rcu_system_clock_source_get(void);
+/* configure the AHB prescaler selection */
+void rcu_ahb_clock_config(uint32_t ck_ahb);
+/* configure the APB1 prescaler selection */
+void rcu_apb1_clock_config(uint32_t ck_apb1);
+/* configure the APB2 prescaler selection */
+void rcu_apb2_clock_config(uint32_t ck_apb2);
+/* configure the ADC clock source and prescaler selection */
+void rcu_adc_clock_config(rcu_adc_clock_enum ck_adc);
+/* configure the USBFS prescaler selection */
+void rcu_usbfs_clock_config(uint32_t ck_usbfs);
+/* configure the CK_OUT clock source and divider */
+void rcu_ckout_config(uint32_t ckout_src, uint32_t ckout_div);
+
+/* configure the PLL clock source preselection */
+void rcu_pll_preselection_config(uint32_t pll_presel);
+/* configure the PLL clock source selection and PLL multiply factor */
+void rcu_pll_config(uint32_t pll_src, uint32_t pll_mul);
+/* configure the USART clock source selection */
+void rcu_usart_clock_config(uint32_t ck_usart);
+/* configure the CEC clock source selection */
+void rcu_cec_clock_config(uint32_t ck_cec);
+/* configure the RTC clock source selection */
+void rcu_rtc_clock_config(uint32_t rtc_clock_source);
+/* configure the CK48M clock selection */
+void rcu_ck48m_clock_config(uint32_t ck48m_clock_source);
+/* configure the HXTAL divider used as input of PLL */
+void rcu_hxtal_prediv_config(uint32_t hxtal_prediv);
+/* configure the LXTAL drive capability */
+void rcu_lxtal_drive_capability_config(uint32_t lxtal_dricap);
+
+/* get the clock stabilization and periphral reset flags */
+FlagStatus rcu_flag_get(rcu_flag_enum flag);
+/* clear the reset flag */
+void rcu_all_reset_flag_clear(void);
+/* get the clock stabilization interrupt and ckm flags */
+FlagStatus rcu_interrupt_flag_get(rcu_int_flag_enum int_flag);
+/* clear the interrupt flags */
+void rcu_interrupt_flag_clear(rcu_int_flag_clear_enum int_flag_clear);
+/* enable the stabilization interrupt */
+void rcu_interrupt_enable(rcu_int_enum stab_int);
+/* disable the stabilization interrupt */
+void rcu_interrupt_disable(rcu_int_enum stab_int);
+
+/* wait until oscillator stabilization flags is SET */
+ErrStatus rcu_osci_stab_wait(rcu_osci_type_enum osci);
+/* turn on the oscillator */
+void rcu_osci_on(rcu_osci_type_enum osci);
+/* turn off the oscillator */
+void rcu_osci_off(rcu_osci_type_enum osci);
+/* enable the oscillator bypass mode */
+void rcu_osci_bypass_mode_enable(rcu_osci_type_enum osci);
+/* disable the oscillator bypass mode */
+void rcu_osci_bypass_mode_disable(rcu_osci_type_enum osci);
+/* enable the HXTAL clock monitor */
+void rcu_hxtal_clock_monitor_enable(void);
+/* disable the HXTAL clock monitor */
+void rcu_hxtal_clock_monitor_disable(void);
+
+/* set the IRC8M adjust value */
+void rcu_irc8m_adjust_value_set(uint8_t irc8m_adjval);
+/* set the IRC28M adjust value */
+void rcu_irc28m_adjust_value_set(uint8_t irc28m_adjval);
+/* unlock the voltage key */
+void rcu_voltage_key_unlock(void);
+/* set the deep sleep mode voltage */
+void rcu_deepsleep_voltage_set(uint32_t dsvol);
+
+/* get the system clock, bus and peripheral clock frequency */
+uint32_t rcu_clock_freq_get(rcu_clock_freq_enum clock);
+
+#endif /* GD32F3X0_RCU_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_rtc.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_rtc.h
new file mode 100644
index 00000000..7df0ebf5
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_rtc.h
@@ -0,0 +1,559 @@
+/*!
+ \file gd32f3x0_rtc.h
+ \brief definitions for the RTC
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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 GD32F3X0_RTC_H
+#define GD32F3X0_RTC_H
+
+#include "gd32f3x0.h"
+
+/* RTC definitions */
+#define RTC RTC_BASE
+
+/* registers definitions */
+#define RTC_TIME REG32(RTC + 0x00000000U) /*!< RTC time of day register */
+#define RTC_DATE REG32(RTC + 0x00000004U) /*!< RTC date register */
+#define RTC_CTL REG32(RTC + 0x00000008U) /*!< RTC control register */
+#define RTC_STAT REG32(RTC + 0x0000000CU) /*!< RTC status register */
+#define RTC_PSC REG32(RTC + 0x00000010U) /*!< RTC time prescaler register */
+#define RTC_ALRM0TD REG32(RTC + 0x0000001CU) /*!< RTC alarm 0 time and date register */
+#define RTC_WPK REG32(RTC + 0x00000024U) /*!< RTC write protection key register */
+#define RTC_SS REG32(RTC + 0x00000028U) /*!< RTC sub second register */
+#define RTC_SHIFTCTL REG32(RTC + 0x0000002CU) /*!< RTC shift function control register */
+#define RTC_TTS REG32(RTC + 0x00000030U) /*!< RTC time of timestamp register */
+#define RTC_DTS REG32(RTC + 0x00000034U) /*!< RTC date of timestamp register */
+#define RTC_SSTS REG32(RTC + 0x00000038U) /*!< RTC sub second of timestamp register */
+#define RTC_HRFC REG32(RTC + 0x0000003CU) /*!< RTC high resolution frequency compensation registor */
+#define RTC_TAMP REG32(RTC + 0x00000040U) /*!< RTC tamper register */
+#define RTC_ALRM0SS REG32(RTC + 0x00000044U) /*!< RTC alarm 0 sub second register */
+#define RTC_BKP0 REG32(RTC + 0x00000050U) /*!< RTC backup 0 register */
+#define RTC_BKP1 REG32(RTC + 0x00000054U) /*!< RTC backup 1 register */
+#define RTC_BKP2 REG32(RTC + 0x00000058U) /*!< RTC backup 2 register */
+#define RTC_BKP3 REG32(RTC + 0x0000005CU) /*!< RTC backup 3 register */
+#define RTC_BKP4 REG32(RTC + 0x00000060U) /*!< RTC backup 4 register */
+
+/* bits definitions */
+/* RTC_TIME */
+#define RTC_TIME_SCU BITS(0,3) /*!< second units in BCD code */
+#define RTC_TIME_SCT BITS(4,6) /*!< second tens in BCD code */
+#define RTC_TIME_MNU BITS(8,11) /*!< minute units in BCD code */
+#define RTC_TIME_MNT BITS(12,14) /*!< minute tens in BCD code */
+#define RTC_TIME_HRU BITS(16,19) /*!< hour units in BCD code */
+#define RTC_TIME_HRT BITS(20,21) /*!< hour tens in BCD code */
+#define RTC_TIME_PM BIT(22) /*!< AM/PM notation */
+
+/* RTC_DATE */
+#define RTC_DATE_DAYU BITS(0,3) /*!< date units in BCD code */
+#define RTC_DATE_DAYT BITS(4,5) /*!< date tens in BCD code */
+#define RTC_DATE_MONU BITS(8,11) /*!< month units in BCD code */
+#define RTC_DATE_MONT BIT(12) /*!< month tens in BCD code */
+#define RTC_DATE_DOW BITS(13,15) /*!< day of week units */
+#define RTC_DATE_YRU BITS(16,19) /*!< year units in BCD code */
+#define RTC_DATE_YRT BITS(20,23) /*!< year tens in BCD code */
+
+/* RTC_CTL */
+#define RTC_CTL_TSEG BIT(3) /*!< valid event edge of time-stamp */
+#define RTC_CTL_REFEN BIT(4) /*!< reference clock detection function enable */
+#define RTC_CTL_BPSHAD BIT(5) /*!< shadow registers bypass control */
+#define RTC_CTL_CS BIT(6) /*!< display format of clock system */
+#define RTC_CTL_ALRM0EN BIT(8) /*!< alarm function enable */
+#define RTC_CTL_TSEN BIT(11) /*!< time-stamp function enable */
+#define RTC_CTL_ALRM0IE BIT(12) /*!< RTC alarm interrupt enable */
+#define RTC_CTL_TSIE BIT(15) /*!< time-stamp interrupt enable */
+#define RTC_CTL_A1H BIT(16) /*!< add 1 hour(summer time change) */
+#define RTC_CTL_S1H BIT(17) /*!< subtract 1 hour(winter time change) */
+#define RTC_CTL_DSM BIT(18) /*!< daylight saving mark */
+#define RTC_CTL_COS BIT(19) /*!< calibration output selection */
+#define RTC_CTL_OPOL BIT(20) /*!< output polarity */
+#define RTC_CTL_OS BITS(21,22) /*!< output selection */
+#define RTC_CTL_COEN BIT(23) /*!< calibration output enable */
+
+/* RTC_STAT */
+#define RTC_STAT_ALRM0WF BIT(0) /*!< alarm configuration can be write flag */
+#define RTC_STAT_SOPF BIT(3) /*!< shift function operation pending flag */
+#define RTC_STAT_YCM BIT(4) /*!< year configuration mark status flag */
+#define RTC_STAT_RSYNF BIT(5) /*!< register synchronization flag */
+#define RTC_STAT_INITF BIT(6) /*!< initialization state flag */
+#define RTC_STAT_INITM BIT(7) /*!< enter initialization mode */
+#define RTC_STAT_ALRM0F BIT(8) /*!< alarm occurs flag */
+#define RTC_STAT_TSF BIT(11) /*!< time-stamp flag */
+#define RTC_STAT_TSOVRF BIT(12) /*!< time-stamp overflow flag */
+#define RTC_STAT_TP0F BIT(13) /*!< RTC tamp 0 detected flag */
+#define RTC_STAT_TP1F BIT(14) /*!< RTC tamp 1 detected flag */
+#define RTC_STAT_SCPF BIT(16) /*!< recalibration pending flag */
+
+/* RTC_PSC */
+#define RTC_PSC_FACTOR_S BITS(0,14) /*!< synchronous prescaler factor */
+#define RTC_PSC_FACTOR_A BITS(16,22) /*!< asynchronous prescaler factor */
+
+/* RTC_ALRM0TD */
+#define RTC_ALRM0TD_SCU BITS(0,3) /*!< second units in BCD code */
+#define RTC_ALRM0TD_SCT BITS(4,6) /*!< second tens in BCD code */
+#define RTC_ALRM0TD_MSKS BIT(7) /*!< alarm second mask bit */
+#define RTC_ALRM0TD_MNU BITS(8,11) /*!< minutes units in BCD code */
+#define RTC_ALRM0TD_MNT BITS(12,14) /*!< minutes tens in BCD code */
+#define RTC_ALRM0TD_MSKM BIT(15) /*!< alarm minutes mask bit */
+#define RTC_ALRM0TD_HRU BITS(16,19) /*!< hour units in BCD code */
+#define RTC_ALRM0TD_HRT BITS(20,21) /*!< hour units in BCD code */
+#define RTC_ALRM0TD_PM BIT(22) /*!< AM/PM flag */
+#define RTC_ALRM0TD_MSKH BIT(23) /*!< alarm hour mask bit */
+#define RTC_ALRM0TD_DAYU BITS(24,27) /*!< date units or week day in BCD code */
+#define RTC_ALRM0TD_DAYT BITS(28,29) /*!< date tens in BCD code */
+#define RTC_ALRM0TD_DOWS BIT(30) /*!< day of week selection */
+#define RTC_ALRM0TD_MSKD BIT(31) /*!< alarm date mask bit */
+
+/* RTC_WPK */
+#define RTC_WPK_WPK BITS(0,7) /*!< key for write protection */
+
+/* RTC_SS */
+#define RTC_SS_SSC BITS(0,15) /*!< sub second value */
+
+/* RTC_SHIFTCTL */
+#define RTC_SHIFTCTL_SFS BITS(0,14) /*!< subtract a fraction of a second */
+#define RTC_SHIFTCTL_A1S BIT(31) /*!< one second add */
+
+/* RTC_TTS */
+#define RTC_TTS_SCU BITS(0,3) /*!< second units in BCD code */
+#define RTC_TTS_SCT BITS(4,6) /*!< second units in BCD code */
+#define RTC_TTS_MNU BITS(8,11) /*!< minute units in BCD code */
+#define RTC_TTS_MNT BITS(12,14) /*!< minute tens in BCD code */
+#define RTC_TTS_HRU BITS(16,19) /*!< hour units in BCD code */
+#define RTC_TTS_HRT BITS(20,21) /*!< hour tens in BCD code */
+#define RTC_TTS_PM BIT(22) /*!< AM/PM notation */
+
+/* RTC_DTS */
+#define RTC_DTS_DAYU BITS(0,3) /*!< date units in BCD code */
+#define RTC_DTS_DAYT BITS(4,5) /*!< date tens in BCD code */
+#define RTC_DTS_MONU BITS(8,11) /*!< month units in BCD code */
+#define RTC_DTS_MONT BIT(12) /*!< month tens in BCD code */
+#define RTC_DTS_DOW BITS(13,15) /*!< day of week units */
+
+/* RTC_SSTS */
+#define RTC_SSTS_SSC BITS(0,15) /*!< timestamp sub second units */
+
+/* RTC_HRFC */
+#define RTC_HRFC_CMSK BITS(0,8) /*!< calibration mask number */
+#define RTC_HRFC_CWND16 BIT(13) /*!< calibration window select 16 seconds */
+#define RTC_HRFC_CWND8 BIT(14) /*!< calibration window select 16 seconds */
+#define RTC_HRFC_FREQI BIT(15) /*!< increase RTC frequency by 488.5ppm */
+
+/* RTC_TAMP */
+#define RTC_TAMP_TP0EN BIT(0) /*!< tamper 0 detection enable */
+#define RTC_TAMP_TP0EG BIT(1) /*!< tamper 0 event trigger edge for RTC tamp 0 input */
+#define RTC_TAMP_TPIE BIT(2) /*!< tamper detection interrupt enable */
+#define RTC_TAMP_TP1EN BIT(3) /*!< tamper 1 detection enable */
+#define RTC_TAMP_TP1EG BIT(4) /*!< tamper 1 event trigger edge for RTC tamp 1 input */
+#define RTC_TAMP_TPTS BIT(7) /*!< make tamper function used for timestamp function */
+#define RTC_TAMP_FREQ BITS(8,10) /*!< sample frequency of tamper event detection */
+#define RTC_TAMP_FLT BITS(11,12) /*!< RTC tamp x filter count setting */
+#define RTC_TAMP_PRCH BITS(13,14) /*!< precharge duration time of RTC tamp x */
+#define RTC_TAMP_DISPU BIT(15) /*!< RTC tamp x pull up disable bit */
+#define RTC_TAMP_PC13VAL BIT(18) /*!< alarm output type control/PC13 output value */
+#define RTC_TAMP_PC13MDE BIT(19) /*!< PC13 mode */
+#define RTC_TAMP_PC14VAL BIT(20) /*!< PC14 output value */
+#define RTC_TAMP_PC14MDE BIT(21) /*!< PC14 mode */
+#define RTC_TAMP_PC15VAL BIT(22) /*!< PC15 output value */
+#define RTC_TAMP_PC15MDE BIT(23) /*!< PC15 mode */
+
+/* RTC_ALRM0SS */
+#define RTC_ALRM0SS_SSC BITS(0,14) /*!< alarm sub second value */
+#define RTC_ALRM0SS_MASKSSC BITS(24,27) /*!< mask control bit of SS */
+
+/* RTC_BKP0 */
+#define RTC_BKP0_DATA BITS(0,31) /*!< backup domain registers */
+
+/* RTC_BKP1 */
+#define RTC_BKP1_DATA BITS(0,31) /*!< backup domain registers */
+
+/* RTC_BKP2 */
+#define RTC_BKP2_DATA BITS(0,31) /*!< backup domain registers */
+
+/* RTC_BKP3 */
+#define RTC_BKP3_DATA BITS(0,31) /*!< backup domain registers */
+
+/* RTC_BKP4 */
+#define RTC_BKP4_DATA BITS(0,31) /*!< backup domain registers */
+
+/* constants definitions */
+/* structure for initialization of the RTC */
+typedef struct {
+ uint8_t rtc_year; /*!< RTC year value: 0x0 - 0x99(BCD format) */
+ uint8_t rtc_month; /*!< RTC month value */
+ uint8_t rtc_date; /*!< RTC date value: 0x1 - 0x31(BCD format) */
+ uint8_t rtc_day_of_week; /*!< RTC weekday value */
+ uint8_t rtc_hour; /*!< RTC hour value */
+ uint8_t rtc_minute; /*!< RTC minute value: 0x0 - 0x59(BCD format) */
+ uint8_t rtc_second; /*!< RTC second value: 0x0 - 0x59(BCD format) */
+ uint16_t rtc_factor_asyn; /*!< RTC asynchronous prescaler value: 0x0 - 0x7F */
+ uint16_t rtc_factor_syn; /*!< RTC synchronous prescaler value: 0x0 - 0x7FFF */
+ uint32_t rtc_am_pm; /*!< RTC AM/PM value */
+ uint32_t rtc_display_format; /*!< RTC time notation */
+} rtc_parameter_struct;
+
+/* structure for RTC alarm configuration */
+typedef struct {
+ uint32_t rtc_alarm_mask; /*!< RTC alarm mask */
+ uint32_t rtc_weekday_or_date; /*!< specify RTC alarm is on date or weekday */
+ uint8_t rtc_alarm_day; /*!< RTC alarm date or weekday value*/
+ uint8_t rtc_alarm_hour; /*!< RTC alarm hour value */
+ uint8_t rtc_alarm_minute; /*!< RTC alarm minute value: 0x0 - 0x59(BCD format) */
+ uint8_t rtc_alarm_second; /*!< RTC alarm second value: 0x0 - 0x59(BCD format) */
+ uint32_t rtc_am_pm; /*!< RTC alarm AM/PM value */
+} rtc_alarm_struct;
+
+/* structure for RTC time-stamp configuration */
+typedef struct {
+ uint8_t rtc_timestamp_month; /*!< RTC time-stamp month value */
+ uint8_t rtc_timestamp_date; /*!< RTC time-stamp date value: 0x1 - 0x31(BCD format) */
+ uint8_t rtc_timestamp_day; /*!< RTC time-stamp weekday value */
+ uint8_t rtc_timestamp_hour; /*!< RTC time-stamp hour value */
+ uint8_t rtc_timestamp_minute; /*!< RTC time-stamp minute value: 0x0 - 0x59(BCD format) */
+ uint8_t rtc_timestamp_second; /*!< RTC time-stamp second value: 0x0 - 0x59(BCD format) */
+ uint32_t rtc_am_pm; /*!< RTC time-stamp AM/PM value */
+} rtc_timestamp_struct;
+
+/* structure for RTC tamper configuration */
+typedef struct {
+ uint32_t rtc_tamper_source; /*!< RTC tamper source */
+ uint32_t rtc_tamper_trigger; /*!< RTC tamper trigger */
+ uint32_t rtc_tamper_filter; /*!< RTC tamper consecutive samples needed during a voltage level detection */
+ uint32_t rtc_tamper_sample_frequency; /*!< RTC tamper sampling frequency during a voltage level detection */
+ ControlStatus
+ rtc_tamper_precharge_enable; /*!< RTC tamper precharge feature during a voltage level detection */
+ uint32_t rtc_tamper_precharge_time; /*!< RTC tamper precharge duration if precharge feature is enabled */
+ ControlStatus rtc_tamper_with_timestamp; /*!< RTC tamper time-stamp feature */
+} rtc_tamper_struct;
+
+/* time register value */
+#define TIME_SC(regval) (BITS(0,6) & ((uint32_t)(regval) << 0U)) /*!< write value to RTC_TIME_SC bit field */
+#define GET_TIME_SC(regval) GET_BITS((regval),0,6) /*!< get value of RTC_TIME_SC bit field */
+
+#define TIME_MN(regval) (BITS(8,14) & ((uint32_t)(regval) << 8U)) /*!< write value to RTC_TIME_MN bit field */
+#define GET_TIME_MN(regval) GET_BITS((regval),8,14) /*!< get value of RTC_TIME_MN bit field */
+
+#define TIME_HR(regval) (BITS(16,21) & ((uint32_t)(regval) << 16U)) /*!< write value to RTC_TIME_HR bit field */
+#define GET_TIME_HR(regval) GET_BITS((regval),16,21) /*!< get value of RTC_TIME_HR bit field */
+
+#define RTC_AM ((uint32_t)0x00000000U) /*!< AM format */
+#define RTC_PM RTC_TIME_PM /*!< PM format */
+
+/* date register value */
+#define DATE_DAY(regval) (BITS(0,5) & ((uint32_t)(regval) << 0U)) /*!< write value to RTC_DATE_DAY bit field */
+#define GET_DATE_DAY(regval) GET_BITS((regval),0,5) /*!< get value of RTC_DATE_DAY bit field */
+
+#define DATE_MON(regval) (BITS(8,12) & ((uint32_t)(regval) << 8U)) /*!< write value to RTC_DATE_MON bit field */
+#define GET_DATE_MON(regval) GET_BITS((regval),8,12) /*!< get value of RTC_DATE_MON bit field */
+#define RTC_JAN ((uint8_t)0x01U) /*!< Janurary */
+#define RTC_FEB ((uint8_t)0x02U) /*!< February */
+#define RTC_MAR ((uint8_t)0x03U) /*!< March */
+#define RTC_APR ((uint8_t)0x04U) /*!< April */
+#define RTC_MAY ((uint8_t)0x05U) /*!< May */
+#define RTC_JUN ((uint8_t)0x06U) /*!< June */
+#define RTC_JUL ((uint8_t)0x07U) /*!< July */
+#define RTC_AUG ((uint8_t)0x08U) /*!< August */
+#define RTC_SEP ((uint8_t)0x09U) /*!< September */
+#define RTC_OCT ((uint8_t)0x10U) /*!< October */
+#define RTC_NOV ((uint8_t)0x11U) /*!< November */
+#define RTC_DEC ((uint8_t)0x12U) /*!< December */
+
+#define DATE_DOW(regval) (BITS(13,15) & ((uint32_t)(regval) << 13U)) /*!< write value to RTC_DATE_DOW bit field */
+#define GET_DATE_DOW(regval) GET_BITS((regval),13,15) /*!< get value of RTC_DATE_DOW bit field */
+#define RTC_MONDAY ((uint8_t)0x01U) /*!< Monday */
+#define RTC_TUESDAY ((uint8_t)0x02U) /*!< Tuesday */
+#define RTC_WEDSDAY ((uint8_t)0x03U) /*!< Wednesday */
+#define RTC_THURSDAY ((uint8_t)0x04U) /*!< Thursday */
+#define RTC_FRIDAY ((uint8_t)0x05U) /*!< Friday */
+#define RTC_SATURDAY ((uint8_t)0x06U) /*!< Saturday */
+#define RTC_SUNDAY ((uint8_t)0x07U) /*!< Sunday */
+
+#define DATE_YR(regval) (BITS(16,23) & ((uint32_t)(regval) << 16U)) /*!< write value to RTC_DATE_YR bit field */
+#define GET_DATE_YR(regval) GET_BITS((regval),16,23) /*!< get value of RTC_DATE_YR bit field */
+
+/* ctl register value */
+#define CTL_OS(regval) (BITS(21,22) & ((uint32_t)(regval) << 21U)) /*!< write value to RTC_CTL_OS bit field */
+#define RTC_OS_DISABLE CTL_OS(0) /*!< disable output RTC_ALARM */
+#define RTC_OS_ENABLE CTL_OS(1) /*!< enable alarm flag output */
+
+#define RTC_CALIBRATION_512HZ RTC_CTL_COEN /*!< calibration output of 512Hz is enable */
+#define RTC_CALIBRATION_1HZ RTC_CTL_COEN | RTC_CTL_COS /*!< calibration output of 1Hz is enable */
+#define RTC_ALARM_HIGH RTC_OS_ENABLE /*!< enable alarm flag output with high level */
+#define RTC_ALARM_LOW RTC_OS_ENABLE | RTC_CTL_OPOL /*!< enable alarm flag output with low level*/
+
+#define RTC_24HOUR ((uint32_t)0x00000000U) /*!< 24-hour format */
+#define RTC_12HOUR RTC_CTL_CS /*!< 12-hour format */
+
+#define RTC_TIMESTAMP_RISING_EDGE ((uint32_t)0x00000000U) /*!< rising edge is valid event edge for time-stamp event */
+#define RTC_TIMESTAMP_FALLING_EDGE RTC_CTL_TSEG /*!< falling edge is valid event edge for time-stamp event */
+
+/* psc register value */
+#define PSC_FACTOR_S(regval) (BITS(0,14) & ((uint32_t)(regval) << 0U)) /*!< write value to RTC_PSC_FACTOR_S bit field */
+#define GET_PSC_FACTOR_S(regval) GET_BITS((regval),0,14) /*!< get value of RTC_PSC_FACTOR_S bit field */
+
+#define PSC_FACTOR_A(regval) (BITS(16,22) & ((uint32_t)(regval) << 16U)) /*!< write value to RTC_PSC_FACTOR_A bit field */
+#define GET_PSC_FACTOR_A(regval) GET_BITS((regval),16,22) /*!< get value of RTC_PSC_FACTOR_A bit field */
+
+/* alrm0td register value */
+#define ALRM0TD_SC(regval) (BITS(0,6) & ((uint32_t)(regval)<< 0U)) /*!< write value to RTC_ALRM0TD_SC bit field */
+#define GET_ALRM0TD_SC(regval) GET_BITS((regval),0,6) /*!< get value of RTC_ALRM0TD_SC bit field */
+
+#define ALRM0TD_MN(regval) (BITS(8,14) & ((uint32_t)(regval) << 8U)) /*!< write value to RTC_ALRM0TD_MN bit field */
+#define GET_ALRM0TD_MN(regval) GET_BITS((regval),8,14) /*!< get value of RTC_ALRM0TD_MN bit field */
+
+#define ALRM0TD_HR(regval) (BITS(16,21) & ((uint32_t)(regval) << 16U)) /*!< write value to RTC_ALRM0TD_HR bit field */
+#define GET_ALRM0TD_HR(regval) GET_BITS((regval),16,21) /*!< get value of RTC_ALRM0TD_HR bit field */
+
+#define ALRM0TD_DAY(regval) (BITS(24,29) & ((uint32_t)(regval) << 24U)) /*!< write value to RTC_ALRM0TD_DAY bit field */
+#define GET_ALRM0TD_DAY(regval) GET_BITS((regval),24,29) /*!< get value of RTC_ALRM0TD_DAY bit field */
+
+#define RTC_ALARM_NONE_MASK ((uint32_t)0x00000000U) /*!< alarm none mask */
+#define RTC_ALARM_DATE_MASK RTC_ALRM0TD_MSKD /*!< alarm date mask */
+#define RTC_ALARM_HOUR_MASK RTC_ALRM0TD_MSKH /*!< alarm hour mask */
+#define RTC_ALARM_MINUTE_MASK RTC_ALRM0TD_MSKM /*!< alarm minute mask */
+#define RTC_ALARM_SECOND_MASK RTC_ALRM0TD_MSKS /*!< alarm second mask */
+#define RTC_ALARM_ALL_MASK (RTC_ALRM0TD_MSKD|RTC_ALRM0TD_MSKH|RTC_ALRM0TD_MSKM|RTC_ALRM0TD_MSKS) /*!< alarm all mask */
+
+#define RTC_ALARM_DATE_SELECTED ((uint32_t)0x00000000U) /*!< alarm date format selected */
+#define RTC_ALARM_WEEKDAY_SELECTED RTC_ALRM0TD_DOWS /*!< alarm weekday format selected */
+
+/* wpk register value */
+#define WPK_WPK(regval) (BITS(0,7) & ((uint32_t)(regval) << 0U)) /*!< write value to RTC_WPK_WPK bit field */
+
+/* ss register value */
+#define SS_SSC(regval) (BITS(0,15) & ((uint32_t)(regval) << 0U)) /*!< write value to RTC_SS_SSC bit field */
+
+/* shiftctl register value */
+#define SHIFTCTL_SFS(regval) (BITS(0,14) & ((uint32_t)(regval) << 0U)) /*!< write value to RTC_SHIFTCTL_SFS bit field */
+
+#define RTC_SHIFT_ADD1S_RESET ((uint32_t)0x00000000U) /*!< not add 1 second */
+#define RTC_SHIFT_ADD1S_SET RTC_SHIFTCTL_A1S /*!< add one second to the clock */
+
+/* tts register value */
+#define TTS_SC(regval) (BITS(0,6) & ((uint32_t)(regval) << 0U)) /*!< write value to RTC_TTS_SC bit field */
+#define GET_TTS_SC(regval) GET_BITS((regval),0,6) /*!< get value of RTC_TTS_SC bit field */
+
+#define TTS_MN(regval) (BITS(8,14) & ((uint32_t)(regval) << 8U)) /*!< write value to RTC_TTS_MN bit field */
+#define GET_TTS_MN(regval) GET_BITS((regval),8,14) /*!< get value of RTC_TTS_MN bit field */
+
+#define TTS_HR(regval) (BITS(16,21) & ((uint32_t)(regval) << 16U)) /*!< write value to RTC_TTS_HR bit field */
+#define GET_TTS_HR(regval) GET_BITS((regval),16,21) /*!< get value of RTC_TTS_HR bit field */
+
+/* dts register value */
+#define DTS_DAY(regval) (BITS(0,5) & ((uint32_t)(regval) << 0U)) /*!< write value to RTC_DTS_DAY bit field */
+#define GET_DTS_DAY(regval) GET_BITS((regval),0,5) /*!< get value of RTC_DTS_DAY bit field */
+
+#define DTS_MON(regval) (BITS(8,12) & ((uint32_t)(regval) << 8U)) /*!< write value to RTC_DTS_MON bit field */
+#define GET_DTS_MON(regval) GET_BITS((regval),8,12) /*!< get value of RTC_DTS_MON bit field */
+
+#define DTS_DOW(regval) (BITS(13,15) & ((uint32_t)(regval) << 13U)) /*!< write value to RTC_DTS_DOW bit field */
+#define GET_DTS_DOW(regval) GET_BITS((regval),13,15) /*!< get value of RTC_DTS_DOW bit field */
+
+/* ssts register value */
+#define SSTS_SSC(regval) (BITS(0,15) & ((uint32_t)(regval) << 0U)) /*!< write value to RTC_SSTS_SSC bit field */
+
+/* hrfc register value */
+#define HRFC_CMSK(regval) (BITS(0,8) & ((uint32_t)(regval) << 0U)) /*!< write value to RTC_HRFC_CMSK bit field */
+
+#define RTC_CALIBRATION_WINDOW_32S ((uint32_t)0x00000000U) /*!< 2exp20 RTCCLK cycles, 32s if RTCCLK = 32768 Hz */
+#define RTC_CALIBRATION_WINDOW_16S RTC_HRFC_CWND16 /*!< 2exp19 RTCCLK cycles, 16s if RTCCLK = 32768 Hz */
+#define RTC_CALIBRATION_WINDOW_8S RTC_HRFC_CWND8 /*!< 2exp18 RTCCLK cycles, 8s if RTCCLK = 32768 Hz */
+
+#define RTC_CALIBRATION_PLUS_SET RTC_HRFC_FREQI /*!< increase RTC frequency by 488.5ppm */
+#define RTC_CALIBRATION_PLUS_RESET ((uint32_t)0x00000000U) /*!< no effect */
+
+/* tamp register value */
+#define TAMP_FREQ(regval) (BITS(8,10) & ((uint32_t)(regval) << 8U)) /*!< write value to RTC_TAMP_FREQ bit field */
+#define RTC_FREQ_DIV32768 TAMP_FREQ(0) /*!< sample once every 32768 RTCCLK(1Hz if RTCCLK=32.768KHz) */
+#define RTC_FREQ_DIV16384 TAMP_FREQ(1) /*!< sample once every 16384 RTCCLK(2Hz if RTCCLK=32.768KHz) */
+#define RTC_FREQ_DIV8192 TAMP_FREQ(2) /*!< sample once every 8192 RTCCLK(4Hz if RTCCLK=32.768KHz) */
+#define RTC_FREQ_DIV4096 TAMP_FREQ(3) /*!< sample once every 4096 RTCCLK(8Hz if RTCCLK=32.768KHz) */
+#define RTC_FREQ_DIV2048 TAMP_FREQ(4) /*!< sample once every 2048 RTCCLK(16Hz if RTCCLK=32.768KHz) */
+#define RTC_FREQ_DIV1024 TAMP_FREQ(5) /*!< sample once every 1024 RTCCLK(32Hz if RTCCLK=32.768KHz) */
+#define RTC_FREQ_DIV512 TAMP_FREQ(6) /*!< sample once every 512 RTCCLK(64Hz if RTCCLK=32.768KHz) */
+#define RTC_FREQ_DIV256 TAMP_FREQ(7) /*!< sample once every 256 RTCCLK(128Hz if RTCCLK=32.768KHz) */
+
+#define TAMP_FLT(regval) (BITS(11,12) & ((uint32_t)(regval) << 11U)) /*!< write value to RTC_TAMP_FLT bit field */
+#define RTC_FLT_EDGE TAMP_FLT(0) /*!< detecting tamper event using edge mode. precharge duration is disabled automatically */
+#define RTC_FLT_2S TAMP_FLT(1) /*!< detecting tamper event using level mode.2 consecutive valid level samples will make a effective tamper event */
+#define RTC_FLT_4S TAMP_FLT(2) /*!< detecting tamper event using level mode.4 consecutive valid level samples will make an effective tamper event */
+#define RTC_FLT_8S TAMP_FLT(3) /*!< detecting tamper event using level mode.8 consecutive valid level samples will make a effective tamper event */
+
+#define TAMP_PRCH(regval) (BITS(13,14) & ((uint32_t)(regval) << 13U)) /*!< write value to RTC_TAMP_PRCH bit field */
+#define RTC_PRCH_1C TAMP_PRCH(0) /*!< 1 RTC clock prechagre time before each sampling */
+#define RTC_PRCH_2C TAMP_PRCH(1) /*!< 2 RTC clock prechagre time before each sampling */
+#define RTC_PRCH_4C TAMP_PRCH(2) /*!< 4 RTC clock prechagre time before each sampling */
+#define RTC_PRCH_8C TAMP_PRCH(3) /*!< 8 RTC clock prechagre time before each sampling */
+
+#define RTC_TAMPER0 RTC_TAMP_TP0EN /*!< tamper 0 detection enable */
+#define RTC_TAMPER1 RTC_TAMP_TP1EN /*!< tamper 1 detection enable */
+
+#define RTC_TAMPER_TRIGGER_EDGE_RISING ((uint32_t)0x00000000U) /*!< tamper detection is in rising edge mode */
+#define RTC_TAMPER_TRIGGER_EDGE_FALLING RTC_TAMP_TP0EG /*!< tamper detection is in falling edge mode */
+#define RTC_TAMPER_TRIGGER_LEVEL_LOW ((uint32_t)0x00000000U) /*!< tamper detection is in low level mode */
+#define RTC_TAMPER_TRIGGER_LEVEL_HIGH RTC_TAMP_TP0EG /*!< tamper detection is in high level mode */
+
+#define RTC_TAMPER_TRIGGER_POS ((uint32_t)0x00000001U) /* shift position of trigger relative to source */
+
+#define RTC_ALARM_OUTPUT_OD ((uint32_t)0x00000000U) /*!< RTC alarm output open-drain mode */
+#define RTC_ALARM_OUTPUT_PP RTC_TAMP_PC13VAL /*!< RTC alarm output push-pull mode */
+
+/* alrm0ss register value */
+#define ALRM0SS_SSC(regval) (BITS(0,14) & ((uint32_t)(regval)<< 0U)) /*!< write value to RTC_ALRM0SS_SSC bit field */
+
+#define ALRM0SS_MASKSSC(regval) (BITS(24,27) & ((uint32_t)(regval) << 24U)) /*!< write value to RTC_ALRM0SS_MASKSSC bit field */
+#define RTC_MASKSSC_0_14 ALRM0SS_MASKSSC(0) /*!< mask alarm subsecond configuration */
+#define RTC_MASKSSC_1_14 ALRM0SS_MASKSSC(1) /*!< mask RTC_ALRM0SS_SSC[14:1], and RTC_ALRM0SS_SSC[0] is to be compared */
+#define RTC_MASKSSC_2_14 ALRM0SS_MASKSSC(2) /*!< mask RTC_ALRM0SS_SSC[14:2], and RTC_ALRM0SS_SSC[1:0] is to be compared */
+#define RTC_MASKSSC_3_14 ALRM0SS_MASKSSC(3) /*!< mask RTC_ALRM0SS_SSC[14:3], and RTC_ALRM0SS_SSC[2:0] is to be compared */
+#define RTC_MASKSSC_4_14 ALRM0SS_MASKSSC(4) /*!< mask RTC_ALRM0SS_SSC[14:4], and RTC_ALRM0SS_SSC[3:0] is to be compared */
+#define RTC_MASKSSC_5_14 ALRM0SS_MASKSSC(5) /*!< mask RTC_ALRM0SS_SSC[14:5], and RTC_ALRM0SS_SSC[4:0] is to be compared */
+#define RTC_MASKSSC_6_14 ALRM0SS_MASKSSC(6) /*!< mask RTC_ALRM0SS_SSC[14:6], and RTC_ALRM0SS_SSC[5:0] is to be compared */
+#define RTC_MASKSSC_7_14 ALRM0SS_MASKSSC(7) /*!< mask RTC_ALRM0SS_SSC[14:7], and RTC_ALRM0SS_SSC[6:0] is to be compared */
+#define RTC_MASKSSC_8_14 ALRM0SS_MASKSSC(8) /*!< mask RTC_ALRM0SS_SSC[14:8], and RTC_ALRM0SS_SSC[7:0] is to be compared */
+#define RTC_MASKSSC_9_14 ALRM0SS_MASKSSC(9) /*!< mask RTC_ALRM0SS_SSC[14:9], and RTC_ALRM0SS_SSC[8:0] is to be compared */
+#define RTC_MASKSSC_10_14 ALRM0SS_MASKSSC(10) /*!< mask RTC_ALRM0SS_SSC[14:10], and RTC_ALRM0SS_SSC[9:0] is to be compared */
+#define RTC_MASKSSC_11_14 ALRM0SS_MASKSSC(11) /*!< mask RTC_ALRM0SS_SSC[14:11], and RTC_ALRM0SS_SSC[10:0] is to be compared */
+#define RTC_MASKSSC_12_14 ALRM0SS_MASKSSC(12) /*!< mask RTC_ALRM0SS_SSC[14:12], and RTC_ALRM0SS_SSC[11:0] is to be compared */
+#define RTC_MASKSSC_13_14 ALRM0SS_MASKSSC(13) /*!< mask RTC_ALRM0SS_SSC[14:13], and RTC_ALRM0SS_SSC[12:0] is to be compared */
+#define RTC_MASKSSC_14 ALRM0SS_MASKSSC(14) /*!< mask RTC_ALRM0SS_SSC[14], and RTC_ALRM0SS_SSC[13:0] is to be compared */
+#define RTC_MASKSSC_NONE ALRM0SS_MASKSSC(15) /*!< mask none, and RTC_ALRM0SS_SSC[14:0] is to be compared */
+
+/* RTC interrupt source */
+#define RTC_INT_TIMESTAMP RTC_CTL_TSIE /*!< time-stamp interrupt enable */
+#define RTC_INT_ALARM RTC_CTL_ALRM0IE /*!< RTC alarm interrupt enable */
+#define RTC_INT_TAMP RTC_TAMP_TPIE /*!< tamper detection interrupt enable */
+
+/* write protect key */
+#define RTC_UNLOCK_KEY1 ((uint8_t)0xCAU) /*!< RTC unlock key1 */
+#define RTC_UNLOCK_KEY2 ((uint8_t)0x53U) /*!< RTC unlock key2 */
+#define RTC_LOCK_KEY ((uint8_t)0xFFU) /*!< RTC lock key */
+
+/* registers reset value */
+#define RTC_REGISTER_RESET ((uint32_t)0x00000000U) /*!< RTC common register reset value */
+#define RTC_DATE_RESET ((uint32_t)0x00002101U) /*!< RTC_DATE register reset value */
+#define RTC_STAT_RESET ((uint32_t)0x00000007U) /*!< RTC_STAT register reset value */
+#define RTC_PSC_RESET ((uint32_t)0x007F00FFU) /*!< RTC_PSC register reset value */
+
+/* RTC timeout value */
+#define RTC_INITM_TIMEOUT ((uint32_t)0x00004000U) /*!< initialization state flag timeout */
+#define RTC_RSYNF_TIMEOUT ((uint32_t)0x00008000U) /*!< register synchronization flag timeout */
+#define RTC_HRFC_TIMEOUT ((uint32_t)0x00001000U) /*!< recalibration pending flag timeout */
+#define RTC_SHIFTCTL_TIMEOUT ((uint32_t)0x00001000U) /*!< shift function operation pending flag timeout */
+#define RTC_ALRM0WF_TIMEOUT ((uint32_t)0x00008000U) /*!< alarm configuration can be write flag timeout */
+
+/* RTC flag */
+#define RTC_FLAG_RECALIBRATION RTC_STAT_SCPF /*!< recalibration pending flag */
+#define RTC_FLAG_TAMP1 RTC_STAT_TP1F /*!< tamper 1 event flag */
+#define RTC_FLAG_TAMP0 RTC_STAT_TP0F /*!< tamper 0 event flag */
+#define RTC_FLAG_TIMESTAMP_OVERFLOW RTC_STAT_TSOVRF /*!< time-stamp overflow event flag */
+#define RTC_FLAG_TIMESTAMP RTC_STAT_TSF /*!< time-stamp event flag */
+#define RTC_FLAG_ALARM0 RTC_STAT_ALRM0F /*!< alarm event flag */
+#define RTC_FLAG_INIT RTC_STAT_INITF /*!< init mode event flag */
+#define RTC_FLAG_RSYN RTC_STAT_RSYNF /*!< registers synchronized flag */
+#define RTC_FLAG_YCM RTC_STAT_YCM /*!< year parameter configured event flag */
+#define RTC_FLAG_SHIFT RTC_STAT_SOPF /*!< shift operation pending flag */
+#define RTC_FLAG_ALARM0_WRITTEN RTC_STAT_ALRM0WF /*!< alarm written available flag */
+
+/* function declarations */
+/* reset most of the RTC registers */
+ErrStatus rtc_deinit(void);
+/* initialize RTC registers */
+ErrStatus rtc_init(rtc_parameter_struct *rtc_initpara_struct);
+/* enter RTC init mode */
+ErrStatus rtc_init_mode_enter(void);
+/* exit RTC init mode */
+void rtc_init_mode_exit(void);
+/* wait until RTC_TIME and RTC_DATE registers are synchronized with APB clock, and the shadow registers are updated */
+ErrStatus rtc_register_sync_wait(void);
+
+/* get current time and date */
+void rtc_current_time_get(rtc_parameter_struct *rtc_initpara_struct);
+/* get current subsecond value */
+uint32_t rtc_subsecond_get(void);
+
+/* configure RTC alarm */
+void rtc_alarm_config(rtc_alarm_struct *rtc_alarm_time);
+/* configure subsecond of RTC alarm */
+void rtc_alarm_subsecond_config(uint32_t mask_subsecond, uint32_t subsecond);
+/* get RTC alarm */
+void rtc_alarm_get(rtc_alarm_struct *rtc_alarm_time);
+/* get RTC alarm subsecond */
+uint32_t rtc_alarm_subsecond_get(void);
+/* enable RTC alarm */
+void rtc_alarm_enable(void);
+/* disable RTC alarm */
+ErrStatus rtc_alarm_disable(void);
+
+/* enable RTC time-stamp */
+void rtc_timestamp_enable(uint32_t edge);
+/* disable RTC time-stamp */
+void rtc_timestamp_disable(void);
+/* get RTC timestamp time and date */
+void rtc_timestamp_get(rtc_timestamp_struct *rtc_timestamp);
+/* get RTC time-stamp subsecond */
+uint32_t rtc_timestamp_subsecond_get(void);
+
+/* enable RTC tamper */
+void rtc_tamper_enable(rtc_tamper_struct *rtc_tamper);
+/* disable RTC tamper */
+void rtc_tamper_disable(uint32_t source);
+
+/* enable specified RTC interrupt */
+void rtc_interrupt_enable(uint32_t interrupt);
+/* disble specified RTC interrupt */
+void rtc_interrupt_disable(uint32_t interrupt);
+/* check specified flag */
+FlagStatus rtc_flag_get(uint32_t flag);
+/* clear specified flag */
+void rtc_flag_clear(uint32_t flag);
+
+/* configure RTC alternate output source */
+void rtc_alter_output_config(uint32_t source, uint32_t mode);
+/* configure RTC calibration register */
+ErrStatus rtc_calibration_config(uint32_t window, uint32_t plus, uint32_t minus);
+/* ajust the daylight saving time by adding or substracting one hour from the current time */
+void rtc_hour_adjust(uint32_t operation);
+/* ajust RTC second or subsecond value of current time */
+ErrStatus rtc_second_adjust(uint32_t add, uint32_t minus);
+/* enable RTC bypass shadow registers function */
+void rtc_bypass_shadow_enable(void);
+/* disable RTC bypass shadow registers function */
+void rtc_bypass_shadow_disable(void);
+/* enable RTC reference clock detection function */
+ErrStatus rtc_refclock_detection_enable(void);
+/* disable RTC reference clock detection function */
+ErrStatus rtc_refclock_detection_disable(void);
+
+#endif /* GD32F3X0_RTC_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_spi.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_spi.h
new file mode 100644
index 00000000..d42a6798
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_spi.h
@@ -0,0 +1,369 @@
+/*!
+ \file gd32f3x0_spi.h
+ \brief definitions for the SPI
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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 GD32F3X0_SPI_H
+#define GD32F3X0_SPI_H
+
+#include "gd32f3x0.h"
+
+/* SPIx(x=0,1) definitions */
+#define SPI0 (SPI_BASE + 0x0000F800U)
+#define SPI1 SPI_BASE
+
+/* SPI registers definitions */
+#define SPI_CTL0(spix) REG32((spix) + 0x00000000U) /*!< SPI control register 0 */
+#define SPI_CTL1(spix) REG32((spix) + 0x00000004U) /*!< SPI control register 1*/
+#define SPI_STAT(spix) REG32((spix) + 0x00000008U) /*!< SPI status register */
+#define SPI_DATA(spix) REG32((spix) + 0x0000000CU) /*!< SPI data register */
+#define SPI_CRCPOLY(spix) REG32((spix) + 0x00000010U) /*!< SPI CRC polynomial register */
+#define SPI_RCRC(spix) REG32((spix) + 0x00000014U) /*!< SPI receive CRC register */
+#define SPI_TCRC(spix) REG32((spix) + 0x00000018U) /*!< SPI transmit CRC register */
+#define SPI_I2SCTL(spix) REG32((spix) + 0x0000001CU) /*!< SPI I2S control register */
+#define SPI_I2SPSC(spix) REG32((spix) + 0x00000020U) /*!< SPI I2S clock prescaler register */
+#define SPI_QCTL(spix) REG32((spix) + 0x00000080U) /*!< SPI quad mode control register(only SPI1) */
+
+/* bits definitions */
+/* SPI_CTL0 */
+#define SPI_CTL0_CKPH BIT(0) /*!< clock phase selection*/
+#define SPI_CTL0_CKPL BIT(1) /*!< clock polarity selection */
+#define SPI_CTL0_MSTMOD BIT(2) /*!< master mode enable */
+#define SPI_CTL0_PSC BITS(3,5) /*!< master clock prescaler selection */
+#define SPI_CTL0_SPIEN BIT(6) /*!< SPI enable*/
+#define SPI_CTL0_LF BIT(7) /*!< LSB first mode */
+#define SPI_CTL0_SWNSS BIT(8) /*!< NSS pin selection in NSS software mode */
+#define SPI_CTL0_SWNSSEN BIT(9) /*!< NSS software mode selection */
+#define SPI_CTL0_RO BIT(10) /*!< receive only */
+#define SPI_CTL0_FF16 BIT(11) /*!< data frame size */
+#define SPI_CTL0_CRCNT BIT(12) /*!< CRC next transfer */
+#define SPI_CTL0_CRCEN BIT(13) /*!< CRC calculation enable */
+#define SPI_CTL0_BDOEN BIT(14) /*!< bidirectional transmit output enable*/
+#define SPI_CTL0_BDEN BIT(15) /*!< bidirectional enable */
+
+/* SPI_CTL1 */
+#define SPI_CTL1_DMAREN BIT(0) /*!< receive buffer dma enable */
+#define SPI_CTL1_DMATEN BIT(1) /*!< transmit buffer dma enable */
+#define SPI_CTL1_NSSDRV BIT(2) /*!< drive NSS output */
+#define SPI_CTL1_NSSP BIT(3) /*!< SPI NSS pulse mode enable */
+#define SPI_CTL1_TMOD BIT(4) /*!< SPI TI mode enable */
+#define SPI_CTL1_ERRIE BIT(5) /*!< errors interrupt enable */
+#define SPI_CTL1_RBNEIE BIT(6) /*!< receive buffer not empty interrupt enable */
+#define SPI_CTL1_TBEIE BIT(7) /*!< transmit buffer empty interrupt enable */
+
+/* SPI_STAT */
+#define SPI_STAT_RBNE BIT(0) /*!< receive buffer not empty */
+#define SPI_STAT_TBE BIT(1) /*!< transmit buffer empty */
+#define SPI_STAT_I2SCH BIT(2) /*!< I2S channel side */
+#define SPI_STAT_TXURERR BIT(3) /*!< I2S transmission underrun error bit */
+#define SPI_STAT_CRCERR BIT(4) /*!< SPI CRC error bit */
+#define SPI_STAT_CONFERR BIT(5) /*!< SPI configuration error bit */
+#define SPI_STAT_RXORERR BIT(6) /*!< SPI reception overrun error bit */
+#define SPI_STAT_TRANS BIT(7) /*!< transmitting on-going bit */
+#define SPI_STAT_FERR BIT(8) /*!< format error bit */
+
+/* SPI_DATA */
+#define SPI_DATA_DATA BITS(0,15) /*!< data transfer register */
+
+/* SPI_CRCPOLY */
+#define SPI_CRCPOLY_CRCPOLY BITS(0,15) /*!< CRC polynomial value */
+
+/* SPI_RCRC */
+#define SPI_RCRC_RCRC BITS(0,15) /*!< RX CRC value */
+
+/* SPI_TCRC */
+#define SPI_TCRC_TCRC BITS(0,15) /*!< TX CRC value */
+
+/* SPI_I2SCTL */
+#define SPI_I2SCTL_CHLEN BIT(0) /*!< channel length */
+#define SPI_I2SCTL_DTLEN BITS(1,2) /*!< data length */
+#define SPI_I2SCTL_CKPL BIT(3) /*!< idle state clock polarity */
+#define SPI_I2SCTL_I2SSTD BITS(4,5) /*!< I2S standard selection */
+#define SPI_I2SCTL_PCMSMOD BIT(7) /*!< PCM frame synchronization mode */
+#define SPI_I2SCTL_I2SOPMOD BITS(8,9) /*!< I2S operation mode */
+#define SPI_I2SCTL_I2SEN BIT(10) /*!< I2S enable */
+#define SPI_I2SCTL_I2SSEL BIT(11) /*!< I2S mode selection */
+
+/* SPI_I2SPSC */
+#define SPI_I2SPSC_DIV BITS(0,7) /*!< dividing factor for the prescaler */
+#define SPI_I2SPSC_OF BIT(8) /*!< odd factor for the prescaler */
+#define SPI_I2SPSC_MCKOEN BIT(9) /*!< I2S MCK output enable */
+
+/* SPI_QCTL(only for SPI1) */
+#define SPI_QCTL_QMOD BIT(0) /*!< quad-SPI mode enable */
+#define SPI_QCTL_QRD BIT(1) /*!< quad-SPI mode read select */
+#define SPI_QCTL_IO23_DRV BIT(2) /*!< drive SPI_IO2 and SPI_IO3 enable */
+
+/* constants definitions */
+/* SPI and I2S parameter struct definitions */
+typedef struct {
+ uint32_t device_mode; /*!< SPI master or slave */
+ uint32_t trans_mode; /*!< SPI transtype */
+ uint32_t frame_size; /*!< SPI frame size */
+ uint32_t nss; /*!< SPI NSS control by handware or software */
+ uint32_t endian; /*!< SPI big endian or little endian */
+ uint32_t clock_polarity_phase; /*!< SPI clock phase and polarity */
+ uint32_t prescale; /*!< SPI prescale factor */
+} spi_parameter_struct;
+
+/* SPI mode definitions */
+#define SPI_MASTER (SPI_CTL0_MSTMOD | SPI_CTL0_SWNSS) /*!< SPI as master */
+#define SPI_SLAVE ((uint32_t)0x00000000U) /*!< SPI as slave */
+
+/* SPI bidirectional transfer direction */
+#define SPI_BIDIRECTIONAL_TRANSMIT SPI_CTL0_BDOEN /*!< SPI work in transmit-only mode */
+#define SPI_BIDIRECTIONAL_RECEIVE (~SPI_CTL0_BDOEN) /*!< SPI work in receive-only mode */
+
+/* SPI transmit type */
+#define SPI_TRANSMODE_FULLDUPLEX ((uint32_t)0x00000000U) /*!< SPI receive and send data at fullduplex communication */
+#define SPI_TRANSMODE_RECEIVEONLY SPI_CTL0_RO /*!< SPI only receive data */
+#define SPI_TRANSMODE_BDRECEIVE SPI_CTL0_BDEN /*!< bidirectional receive data */
+#define SPI_TRANSMODE_BDTRANSMIT (SPI_CTL0_BDEN | SPI_CTL0_BDOEN) /*!< bidirectional transmit data*/
+
+/* SPI frame size */
+#define SPI_FRAMESIZE_16BIT SPI_CTL0_FF16 /*!< SPI frame size is 16 bits */
+#define SPI_FRAMESIZE_8BIT ((uint32_t)0x00000000U) /*!< SPI frame size is 8 bits */
+
+/* SPI NSS control mode */
+#define SPI_NSS_SOFT SPI_CTL0_SWNSSEN /*!< SPI NSS control by sofrware */
+#define SPI_NSS_HARD ((uint32_t)0x00000000U) /*!< SPI NSS control by hardware */
+
+/* SPI transmit way */
+#define SPI_ENDIAN_MSB ((uint32_t)0x00000000U) /*!< SPI transmit way is big endian: transmit MSB first */
+#define SPI_ENDIAN_LSB SPI_CTL0_LF /*!< SPI transmit way is little endian: transmit LSB first */
+
+/* SPI clock phase and polarity */
+#define SPI_CK_PL_LOW_PH_1EDGE ((uint32_t)0x00000000U) /*!< SPI clock polarity is low level and phase is first edge */
+#define SPI_CK_PL_HIGH_PH_1EDGE SPI_CTL0_CKPL /*!< SPI clock polarity is high level and phase is first edge */
+#define SPI_CK_PL_LOW_PH_2EDGE SPI_CTL0_CKPH /*!< SPI clock polarity is low level and phase is second edge */
+#define SPI_CK_PL_HIGH_PH_2EDGE (SPI_CTL0_CKPL | SPI_CTL0_CKPH) /*!< SPI clock polarity is high level and phase is second edge */
+
+/* SPI clock prescale factor */
+#define CTL0_PSC(regval) (BITS(3,5) & ((uint32_t)(regval) << 3))
+#define SPI_PSC_2 CTL0_PSC(0) /*!< SPI clock prescale factor is 2 */
+#define SPI_PSC_4 CTL0_PSC(1) /*!< SPI clock prescale factor is 4 */
+#define SPI_PSC_8 CTL0_PSC(2) /*!< SPI clock prescale factor is 8 */
+#define SPI_PSC_16 CTL0_PSC(3) /*!< SPI clock prescale factor is 16 */
+#define SPI_PSC_32 CTL0_PSC(4) /*!< SPI clock prescale factor is 32 */
+#define SPI_PSC_64 CTL0_PSC(5) /*!< SPI clock prescale factor is 64 */
+#define SPI_PSC_128 CTL0_PSC(6) /*!< SPI clock prescale factor is 128 */
+#define SPI_PSC_256 CTL0_PSC(7) /*!< SPI clock prescale factor is 256 */
+
+#if (defined(GD32F350) || defined(GD32F310))
+/* I2S audio sample rate */
+#define I2S_AUDIOSAMPLE_8K ((uint32_t)8000U) /*!< I2S audio sample rate is 8KHz */
+#define I2S_AUDIOSAMPLE_11K ((uint32_t)11025U) /*!< I2S audio sample rate is 11KHz */
+#define I2S_AUDIOSAMPLE_16K ((uint32_t)16000U) /*!< I2S audio sample rate is 16KHz */
+#define I2S_AUDIOSAMPLE_22K ((uint32_t)22050U) /*!< I2S audio sample rate is 22KHz */
+#define I2S_AUDIOSAMPLE_32K ((uint32_t)32000U) /*!< I2S audio sample rate is 32KHz */
+#define I2S_AUDIOSAMPLE_44K ((uint32_t)44100U) /*!< I2S audio sample rate is 44KHz */
+#define I2S_AUDIOSAMPLE_48K ((uint32_t)48000U) /*!< I2S audio sample rate is 48KHz */
+#define I2S_AUDIOSAMPLE_96K ((uint32_t)96000U) /*!< I2S audio sample rate is 96KHz */
+#define I2S_AUDIOSAMPLE_192K ((uint32_t)192000U) /*!< I2S audio sample rate is 192KHz */
+
+/* I2S frame format */
+#define I2SCTL_DTLEN(regval) (BITS(1,2) & ((uint32_t)(regval) << 1))
+#define I2S_FRAMEFORMAT_DT16B_CH16B I2SCTL_DTLEN(0) /*!< I2S data length is 16 bit and channel length is 16 bit */
+#define I2S_FRAMEFORMAT_DT16B_CH32B (I2SCTL_DTLEN(0) | SPI_I2SCTL_CHLEN) /*!< I2S data length is 16 bit and channel length is 32 bit */
+#define I2S_FRAMEFORMAT_DT24B_CH32B (I2SCTL_DTLEN(1) | SPI_I2SCTL_CHLEN) /*!< I2S data length is 24 bit and channel length is 32 bit */
+#define I2S_FRAMEFORMAT_DT32B_CH32B (I2SCTL_DTLEN(2) | SPI_I2SCTL_CHLEN) /*!< I2S data length is 32 bit and channel length is 32 bit */
+
+/* I2S master clock output */
+#define I2S_MCKOUT_DISABLE ((uint32_t)0x00000000U) /*!< I2S master clock output disable */
+#define I2S_MCKOUT_ENABLE SPI_I2SPSC_MCKOEN /*!< I2S master clock output enable */
+
+/* I2S operation mode */
+#define I2SCTL_I2SOPMOD(regval) (BITS(8,9) & ((uint32_t)(regval) << 8))
+#define I2S_MODE_SLAVETX I2SCTL_I2SOPMOD(0) /*!< I2S slave transmit mode */
+#define I2S_MODE_SLAVERX I2SCTL_I2SOPMOD(1) /*!< I2S slave receive mode */
+#define I2S_MODE_MASTERTX I2SCTL_I2SOPMOD(2) /*!< I2S master transmit mode */
+#define I2S_MODE_MASTERRX I2SCTL_I2SOPMOD(3) /*!< I2S master receive mode */
+
+/* I2S standard */
+#define I2SCTL_I2SSTD(regval) (BITS(4,5) & ((uint32_t)(regval) << 4))
+#define I2S_STD_PHILLIPS I2SCTL_I2SSTD(0) /*!< I2S phillips standard */
+#define I2S_STD_MSB I2SCTL_I2SSTD(1) /*!< I2S MSB standard */
+#define I2S_STD_LSB I2SCTL_I2SSTD(2) /*!< I2S LSB standard */
+#define I2S_STD_PCMSHORT I2SCTL_I2SSTD(3) /*!< I2S PCM short standard */
+#define I2S_STD_PCMLONG (I2SCTL_I2SSTD(3) | SPI_I2SCTL_PCMSMOD) /*!< I2S PCM long standard */
+
+/* I2S clock polarity */
+#define I2S_CKPL_LOW ((uint32_t)0x00000000U) /*!< I2S clock polarity low level */
+#define I2S_CKPL_HIGH SPI_I2SCTL_CKPL /*!< I2S clock polarity high level */
+#endif /* GD32F350 and GD32F310 */
+
+/* SPI DMA constants definitions */
+#define SPI_DMA_TRANSMIT ((uint8_t)0x00U) /*!< SPI transmit data use DMA */
+#define SPI_DMA_RECEIVE ((uint8_t)0x01U) /*!< SPI receive data use DMA */
+
+/* SPI CRC constants definitions */
+#define SPI_CRC_TX ((uint8_t)0x00U) /*!< SPI transmit CRC value */
+#define SPI_CRC_RX ((uint8_t)0x01U) /*!< SPI receive CRC value */
+
+/* SPI/I2S interrupt enable/disable constants definitions */
+#define SPI_I2S_INT_TBE ((uint8_t)0x00U) /*!< transmit buffer empty interrupt */
+#define SPI_I2S_INT_RBNE ((uint8_t)0x01U) /*!< receive buffer not empty interrupt */
+#define SPI_I2S_INT_ERR ((uint8_t)0x02U) /*!< error interrupt */
+
+/* SPI/I2S interrupt flag constants definitions */
+#define SPI_I2S_INT_FLAG_TBE ((uint8_t)0x00U) /*!< transmit buffer empty interrupt flag */
+#define SPI_I2S_INT_FLAG_RBNE ((uint8_t)0x01U) /*!< receive buffer not empty interrupt flag */
+#define SPI_I2S_INT_FLAG_RXORERR ((uint8_t)0x02U) /*!< overrun interrupt flag */
+#define SPI_INT_FLAG_CONFERR ((uint8_t)0x03U) /*!< config error interrupt flag */
+#define SPI_INT_FLAG_CRCERR ((uint8_t)0x04U) /*!< CRC error interrupt flag */
+#define I2S_INT_FLAG_TXURERR ((uint8_t)0x05U) /*!< underrun error interrupt flag */
+#define SPI_I2S_INT_FLAG_FERR ((uint8_t)0x06U) /*!< format error interrupt flag */
+
+/* SPI flag definitions */
+#define SPI_FLAG_RBNE SPI_STAT_RBNE /*!< receive buffer not empty flag */
+#define SPI_FLAG_TBE SPI_STAT_TBE /*!< transmit buffer empty flag */
+#define SPI_FLAG_CRCERR SPI_STAT_CRCERR /*!< CRC error flag */
+#define SPI_FLAG_CONFERR SPI_STAT_CONFERR /*!< mode config error flag */
+#define SPI_FLAG_RXORERR SPI_STAT_RXORERR /*!< receive overrun error flag */
+#define SPI_FLAG_TRANS SPI_STAT_TRANS /*!< transmit on-going flag */
+#define SPI_FLAG_FERR SPI_STAT_FERR /*!< format error interrupt flag */
+
+#if (defined(GD32F350) || defined(GD32F310))
+/* I2S flag definitions */
+#define I2S_FLAG_RBNE SPI_STAT_RBNE /*!< receive buffer not empty flag */
+#define I2S_FLAG_TBE SPI_STAT_TBE /*!< transmit buffer empty flag */
+#define I2S_FLAG_CH SPI_STAT_I2SCH /*!< channel side flag */
+#define I2S_FLAG_TXURERR SPI_STAT_TXURERR /*!< underrun error flag */
+#define I2S_FLAG_RXORERR SPI_STAT_RXORERR /*!< overrun error flag */
+#define I2S_FLAG_TRANS SPI_STAT_TRANS /*!< transmit on-going flag */
+#define I2S_FLAG_FERR SPI_STAT_FERR /*!< format error interrupt flag */
+#endif /* GD32F350 and GD32F310 */
+
+/* function declarations */
+/* SPI/I2S deinitialization and initialization functions */
+/* reset SPI and I2S */
+void spi_i2s_deinit(uint32_t spi_periph);
+/* initialize the parameters of SPI struct with the default values */
+void spi_struct_para_init(spi_parameter_struct *spi_struct);
+/* initialize SPI parameter */
+void spi_init(uint32_t spi_periph, spi_parameter_struct *spi_struct);
+/* enable SPI */
+void spi_enable(uint32_t spi_periph);
+/* disable SPI */
+void spi_disable(uint32_t spi_periph);
+
+#if (defined(GD32F350) || defined(GD32F310))
+/* initialize I2S parameter */
+void i2s_init(uint32_t spi_periph, uint32_t mode, uint32_t standard, uint32_t ckpl);
+/* configure I2S prescaler */
+void i2s_psc_config(uint32_t spi_periph, uint32_t audiosample, uint32_t frameformat, uint32_t mckout);
+/* enable I2S */
+void i2s_enable(uint32_t spi_periph);
+/* disable I2S */
+void i2s_disable(uint32_t spi_periph);
+#endif /* GD32F350 and GD32F310 */
+
+/* NSS functions */
+/* enable SPI NSS output */
+void spi_nss_output_enable(uint32_t spi_periph);
+/* disable SPI NSS output */
+void spi_nss_output_disable(uint32_t spi_periph);
+/* SPI NSS pin high level in software mode */
+void spi_nss_internal_high(uint32_t spi_periph);
+/* SPI NSS pin low level in software mode */
+void spi_nss_internal_low(uint32_t spi_periph);
+
+/* enable SPI DMA */
+void spi_dma_enable(uint32_t spi_periph, uint8_t dma);
+/* disable SPI DMA */
+void spi_dma_disable(uint32_t spi_periph, uint8_t dma);
+
+/* configure SPI/I2S data frame format */
+void spi_i2s_data_frame_format_config(uint32_t spi_periph, uint16_t frame_format);
+/* SPI transmit data */
+void spi_i2s_data_transmit(uint32_t spi_periph, uint16_t data);
+/* SPI receive data */
+uint16_t spi_i2s_data_receive(uint32_t spi_periph);
+/* configure SPI bidirectional transfer direction */
+void spi_bidirectional_transfer_config(uint32_t spi_periph, uint32_t transfer_direction);
+
+/* SPI CRC functions */
+/* set SPI CRC polynomial */
+void spi_crc_polynomial_set(uint32_t spi_periph, uint16_t crc_poly);
+/* get SPI CRC polynomial */
+uint16_t spi_crc_polynomial_get(uint32_t spi_periph);
+/* turn on SPI CRC function */
+void spi_crc_on(uint32_t spi_periph);
+/* turn off SPI CRC function */
+void spi_crc_off(uint32_t spi_periph);
+/* SPI next data is CRC value */
+void spi_crc_next(uint32_t spi_periph);
+/* get SPI CRC send value or receive value */
+uint16_t spi_crc_get(uint32_t spi_periph, uint8_t crc);
+
+/* SPI TI mode functions */
+/* enable SPI TI mode */
+void spi_ti_mode_enable(uint32_t spi_periph);
+/* disable SPI TI mode */
+void spi_ti_mode_disable(uint32_t spi_periph);
+
+/* SPI NSS pulse mode functions */
+/* enable SPI NSS pulse mode */
+void spi_nssp_mode_enable(uint32_t spi_periph);
+/* disable SPI NSS pulse mode */
+void spi_nssp_mode_disable(uint32_t spi_periph);
+
+/* quad wire SPI functions */
+/* enable quad wire SPI */
+void qspi_enable(uint32_t spi_periph);
+/* disable quad wire SPI */
+void qspi_disable(uint32_t spi_periph);
+/* enable quad wire SPI write */
+void qspi_write_enable(uint32_t spi_periph);
+/* enable quad wire SPI read */
+void qspi_read_enable(uint32_t spi_periph);
+/* enable quad wire SPI_IO2 and SPI_IO3 pin output */
+void qspi_io23_output_enable(uint32_t spi_periph);
+/* disable quad wire SPI_IO2 and SPI_IO3 pin output */
+void qspi_io23_output_disable(uint32_t spi_periph);
+
+/* flag and interrupt functions */
+/* enable SPI and I2S interrupt */
+void spi_i2s_interrupt_enable(uint32_t spi_periph, uint8_t interrupt);
+/* disable SPI and I2S interrupt */
+void spi_i2s_interrupt_disable(uint32_t spi_periph, uint8_t interrupt);
+/* get SPI and I2S interrupt status */
+FlagStatus spi_i2s_interrupt_flag_get(uint32_t spi_periph, uint8_t interrupt);
+/* get SPI and I2S flag status */
+FlagStatus spi_i2s_flag_get(uint32_t spi_periph, uint32_t flag);
+/* clear SPI CRC error flag status */
+void spi_crc_error_clear(uint32_t spi_periph);
+
+#endif /* GD32F3X0_SPI_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_syscfg.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_syscfg.h
new file mode 100644
index 00000000..61940659
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_syscfg.h
@@ -0,0 +1,192 @@
+/*!
+ \file gd32f3x0_syscfg.h
+ \brief definitions for the SYSCFG
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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 GD32F3X0_SYSCFG_H
+#define GD32F3X0_SYSCFG_H
+
+#include "gd32f3x0.h"
+
+/* SYSCFG definitions */
+#define SYSCFG SYSCFG_BASE
+
+/* registers definitions */
+#define SYSCFG_CFG0 REG32(SYSCFG + 0x00000000U) /*!< system configuration register 0 */
+#define SYSCFG_EXTISS0 REG32(SYSCFG + 0x00000008U) /*!< EXTI sources selection register 0 */
+#define SYSCFG_EXTISS1 REG32(SYSCFG + 0x0000000CU) /*!< EXTI sources selection register 1 */
+#define SYSCFG_EXTISS2 REG32(SYSCFG + 0x00000010U) /*!< EXTI sources selection register 2 */
+#define SYSCFG_EXTISS3 REG32(SYSCFG + 0x00000014U) /*!< EXTI sources selection register 3 */
+#define SYSCFG_CFG2 REG32(SYSCFG + 0x00000018U) /*!< system configuration register 2 */
+#define SYSCFG_CPSCTL REG32(SYSCFG + 0x00000020U) /*!< system I/O compensation control register */
+
+/* SYSCFG_CFG0 bits definitions */
+#define SYSCFG_CFG0_BOOT_MODE BITS(0,1) /*!< SYSCFG memory remap config */
+#define SYSCFG_CFG0_ADC_DMA_RMP BIT(8) /*!< ADC DMA remap config */
+#define SYSCFG_CFG0_USART0_TX_DMA_RMP BIT(9) /*!< USART0 Tx DMA remap config */
+#define SYSCFG_CFG0_USART0_RX_DMA_RMP BIT(10) /*!< USART0 Rx DMA remap config */
+#define SYSCFG_CFG0_TIMER15_DMA_RMP BIT(11) /*!< TIMER 15 DMA remap config */
+#define SYSCFG_CFG0_TIMER16_DMA_RMP BIT(12) /*!< TIMER 16 DMA remap config */
+#define SYSCFG_CFG0_PB9_HCCE BIT(19) /*!< PB9 pin high current capability enable */
+
+/* SYSCFG_EXTISS0 bits definitions */
+#define SYSCFG_EXTISS0_EXTI0_SS BITS(0,3) /*!< EXTI 0 configuration */
+#define SYSCFG_EXTISS0_EXTI1_SS BITS(4,7) /*!< EXTI 1 configuration */
+#define SYSCFG_EXTISS0_EXTI2_SS BITS(8,11) /*!< EXTI 2 configuration */
+#define SYSCFG_EXTISS0_EXTI3_SS BITS(12,15) /*!< EXTI 3 configuration */
+
+/* SYSCFG_EXTISS1 bits definitions */
+#define SYSCFG_EXTISS1_EXTI4_SS BITS(0,3) /*!< EXTI 4 configuration */
+#define SYSCFG_EXTISS1_EXTI5_SS BITS(4,7) /*!< EXTI 5 configuration */
+#define SYSCFG_EXTISS1_EXTI6_SS BITS(8,11) /*!< EXTI 6 configuration */
+#define SYSCFG_EXTISS1_EXTI7_SS BITS(12,15) /*!< EXTI 7 configuration */
+
+/* SYSCFG_EXTISS2 bits definitions */
+#define SYSCFG_EXTISS2_EXTI8_SS BITS(0,3) /*!< EXTI 8 configuration */
+#define SYSCFG_EXTISS2_EXTI9_SS BITS(4,7) /*!< EXTI 9 configuration */
+#define SYSCFG_EXTISS2_EXTI10_SS BITS(8,11) /*!< EXTI 10 configuration */
+#define SYSCFG_EXTISS2_EXTI11_SS BITS(12,15) /*!< EXTI 11 configuration */
+
+/* SYSCFG_EXTISS3 bits definitions */
+#define SYSCFG_EXTISS3_EXTI12_SS BITS(0,3) /*!< EXTI 12 configuration */
+#define SYSCFG_EXTISS3_EXTI13_SS BITS(4,7) /*!< EXTI 13 configuration */
+#define SYSCFG_EXTISS3_EXTI14_SS BITS(8,11) /*!< EXTI 14 configuration */
+#define SYSCFG_EXTISS3_EXTI15_SS BITS(12,15) /*!< EXTI 15 configuration */
+
+/* SYSCFG_CFG2 bits definitions */
+#define SYSCFG_CFG2_LOCKUP_LOCK BIT(0) /*!< enable and lock the LOCKUP (Hardfault) output of Cortex-M4 with break input of TIMER0/14/15/16 */
+#define SYSCFG_CFG2_SRAM_PARITY_ERROR_LOCK BIT(1) /*!< enable and lock the SRAM_PARITY error signal with break input of TIMER0/14/15/16 */
+#define SYSCFG_CFG2_LVD_LOCK BIT(2) /*!< enable and lock the LVD connection with TIMER0 break input and also the LVD_EN and LVDSEL[2:0] bits of the power control interface */
+#define SYSCFG_CFG2_SRAM_PCEF BIT(8) /*!< SRAM parity check error flag */
+
+/* SYSCFG_CPSCTL bits definitions */
+#define SYSCFG_CPSCTL_CPS_EN BIT(0) /*!< I/O compensation cell enable */
+#define SYSCFG_CPSCTL_CPS_RDY BIT(8) /*!< I/O compensation cell is ready or not */
+
+/* constants definitions */
+/* DMA remap definitions */
+#define SYSCFG_DMA_REMAP_ADC SYSCFG_CFG0_ADC_DMA_RMP /*!< ADC DMA remap */
+#define SYSCFG_DMA_REMAP_USART0TX SYSCFG_CFG0_USART0_TX_DMA_RMP /*!< USART0_TX DMA remap */
+#define SYSCFG_DMA_REMAP_USART0RX SYSCFG_CFG0_USART0_RX_DMA_RMP /*!< USART0_RX DMA remap */
+#define SYSCFG_DMA_REMAP_TIMER15 SYSCFG_CFG0_TIMER15_DMA_RMP /*!< TIMER15 DMA remap */
+#define SYSCFG_DMA_REMAP_TIMER16 SYSCFG_CFG0_TIMER16_DMA_RMP /*!< TIMER16 DMA remap */
+
+/* high current definitions */
+#define SYSCFG_HIGH_CURRENT_ENABLE SYSCFG_CFG0_PB9_HCCE /*!< high current enable */
+#define SYSCFG_HIGH_CURRENT_DISABLE (~SYSCFG_CFG0_PB9_HCCE) /*!< high current disable */
+
+/* EXTI source select definition */
+#define EXTISS0 ((uint8_t)0x00U) /*!< EXTI source select register 0 */
+#define EXTISS1 ((uint8_t)0x01U) /*!< EXTI source select register 1 */
+#define EXTISS2 ((uint8_t)0x02U) /*!< EXTI source select register 2 */
+#define EXTISS3 ((uint8_t)0x03U) /*!< EXTI source select register 3 */
+
+/* EXTI source select mask bits definition */
+#define EXTI_SS_MASK BITS(0,3) /*!< EXTI source select mask */
+
+/* EXTI source select jumping step definition */
+#define EXTI_SS_JSTEP ((uint8_t)0x04U) /*!< EXTI source select jumping step */
+
+/* EXTI source select moving step definition */
+#define EXTI_SS_MSTEP(pin) (EXTI_SS_JSTEP * ((pin) % EXTI_SS_JSTEP)) /*!< EXTI source select moving step */
+
+/* EXTI source port definitions */
+#define EXTI_SOURCE_GPIOA ((uint8_t)0x00U) /*!< EXTI GPIOA configuration */
+#define EXTI_SOURCE_GPIOB ((uint8_t)0x01U) /*!< EXTI GPIOB configuration */
+#define EXTI_SOURCE_GPIOC ((uint8_t)0x02U) /*!< EXTI GPIOC configuration */
+#define EXTI_SOURCE_GPIOD ((uint8_t)0x03U) /*!< EXTI GPIOD configuration */
+#define EXTI_SOURCE_GPIOF ((uint8_t)0x05U) /*!< EXTI GPIOF configuration */
+
+/* EXTI source pin definitions */
+#define EXTI_SOURCE_PIN0 ((uint8_t)0x00U) /*!< EXTI GPIO pin0 configuration */
+#define EXTI_SOURCE_PIN1 ((uint8_t)0x01U) /*!< EXTI GPIO pin1 configuration */
+#define EXTI_SOURCE_PIN2 ((uint8_t)0x02U) /*!< EXTI GPIO pin2 configuration */
+#define EXTI_SOURCE_PIN3 ((uint8_t)0x03U) /*!< EXTI GPIO pin3 configuration */
+#define EXTI_SOURCE_PIN4 ((uint8_t)0x04U) /*!< EXTI GPIO pin4 configuration */
+#define EXTI_SOURCE_PIN5 ((uint8_t)0x05U) /*!< EXTI GPIO pin5 configuration */
+#define EXTI_SOURCE_PIN6 ((uint8_t)0x06U) /*!< EXTI GPIO pin6 configuration */
+#define EXTI_SOURCE_PIN7 ((uint8_t)0x07U) /*!< EXTI GPIO pin7 configuration */
+#define EXTI_SOURCE_PIN8 ((uint8_t)0x08U) /*!< EXTI GPIO pin8 configuration */
+#define EXTI_SOURCE_PIN9 ((uint8_t)0x09U) /*!< EXTI GPIO pin9 configuration */
+#define EXTI_SOURCE_PIN10 ((uint8_t)0x0AU) /*!< EXTI GPIO pin10 configuration */
+#define EXTI_SOURCE_PIN11 ((uint8_t)0x0BU) /*!< EXTI GPIO pin11 configuration */
+#define EXTI_SOURCE_PIN12 ((uint8_t)0x0CU) /*!< EXTI GPIO pin12 configuration */
+#define EXTI_SOURCE_PIN13 ((uint8_t)0x0DU) /*!< EXTI GPIO pin13 configuration */
+#define EXTI_SOURCE_PIN14 ((uint8_t)0x0EU) /*!< EXTI GPIO pin14 configuration */
+#define EXTI_SOURCE_PIN15 ((uint8_t)0x0FU) /*!< EXTI GPIO pin15 configuration */
+
+/* lock definitions */
+#define SYSCFG_LOCK_LOCKUP SYSCFG_CFG2_LOCKUP_LOCK /*!< LOCKUP output lock */
+#define SYSCFG_LOCK_SRAM_PARITY_ERROR SYSCFG_CFG2_SRAM_PARITY_ERROR_LOCK /*!< SRAM parity error lock */
+#define SYSCFG_LOCK_LVD SYSCFG_CFG2_LVD_LOCK /*!< LVD lock */
+
+/* SRAM parity check error flag definitions */
+#define SYSCFG_SRAM_PCEF SYSCFG_CFG2_SRAM_PCEF /*!< SRAM parity check error flag */
+
+/* I/O compensation cell enable/disable */
+#define SYSCFG_COMPENSATION(regval) (BIT(0) & ((uint32_t)(regval) << 0))
+#define SYSCFG_COMPENSATION_DISABLE SYSCFG_COMPENSATION(0) /*!< I/O compensation cell is power-down */
+#define SYSCFG_COMPENSATION_ENABLE SYSCFG_COMPENSATION(1) /*!< I/O compensation cell is enabled */
+
+/* function declarations */
+/* deinit syscfg module */
+void syscfg_deinit(void);
+
+/* enable the DMA channels remapping */
+void syscfg_dma_remap_enable(uint32_t syscfg_dma_remap);
+/* disable the DMA channels remapping */
+void syscfg_dma_remap_disable(uint32_t syscfg_dma_remap);
+
+/* enable PB9 high current capability */
+void syscfg_high_current_enable(void);
+/* disable PB9 high current capability */
+void syscfg_high_current_disable(void);
+
+/* configure the GPIO pin as EXTI Line */
+void syscfg_exti_line_config(uint8_t exti_port, uint8_t exti_pin);
+/* connect TIMER0/14/15/16 break input to the selected parameter */
+void syscfg_lock_config(uint32_t syscfg_lock);
+
+/* check if the specified flag in SYSCFG_CFG2 is set or not */
+FlagStatus syscfg_flag_get(uint32_t syscfg_flag);
+/* clear the flag in SYSCFG_CFG2 by writing 1 */
+void syscfg_flag_clear(uint32_t syscfg_flag);
+
+/* configure the I/O compensation cell */
+void syscfg_compensation_config(uint32_t syscfg_compensation);
+/* check if the I/O compensation cell ready flag is set or not */
+FlagStatus syscfg_cps_rdy_flag_get(void);
+
+#endif /* GD32F3X0_SYSCFG_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_timer.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_timer.h
new file mode 100644
index 00000000..c9f4a895
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_timer.h
@@ -0,0 +1,765 @@
+/*!
+ \file gd32f3x0_timer.h
+ \brief definitions for the TIMER
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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 GD32F3X0_TIMER_H
+#define GD32F3X0_TIMER_H
+
+#include "gd32f3x0.h"
+
+/* TIMERx(x=0,1,2,5,13..16) definitions */
+#define TIMER0 (TIMER_BASE + 0x00012C00U) /*!< TIMER0 base address */
+#define TIMER1 (TIMER_BASE + 0x00000000U) /*!< TIMER1 base address */
+#define TIMER2 (TIMER_BASE + 0x00000400U) /*!< TIMER2 base address */
+#ifdef GD32F350
+#define TIMER5 (TIMER_BASE + 0x00001000U) /*!< TIMER5 base address */
+#endif
+#define TIMER13 (TIMER_BASE + 0x00002000U) /*!< TIMER13 base address */
+#define TIMER14 (TIMER_BASE + 0x00014000U) /*!< TIMER14 base address */
+#define TIMER15 (TIMER_BASE + 0x00014400U) /*!< TIMER15 base address */
+#define TIMER16 (TIMER_BASE + 0x00014800U) /*!< TIMER16 base address */
+
+/* registers definitions */
+#define TIMER_CTL0(timerx) REG32((timerx) + 0x00000000U) /*!< TIMER control register 0 */
+#define TIMER_CTL1(timerx) REG32((timerx) + 0x00000004U) /*!< TIMER control register 1 */
+#define TIMER_SMCFG(timerx) REG32((timerx) + 0x00000008U) /*!< TIMER slave mode configuration register */
+#define TIMER_DMAINTEN(timerx) REG32((timerx) + 0x0000000CU) /*!< TIMER DMA and interrupt enable register */
+#define TIMER_INTF(timerx) REG32((timerx) + 0x00000010U) /*!< TIMER interrupt flag register */
+#define TIMER_SWEVG(timerx) REG32((timerx) + 0x00000014U) /*!< TIMER software event generation register */
+#define TIMER_CHCTL0(timerx) REG32((timerx) + 0x00000018U) /*!< TIMER channel control register 0 */
+#define TIMER_CHCTL1(timerx) REG32((timerx) + 0x0000001CU) /*!< TIMER channel control register 1 */
+#define TIMER_CHCTL2(timerx) REG32((timerx) + 0x00000020U) /*!< TIMER channel control register 2 */
+#define TIMER_CNT(timerx) REG32((timerx) + 0x00000024U) /*!< TIMER counter register */
+#define TIMER_PSC(timerx) REG32((timerx) + 0x00000028U) /*!< TIMER prescaler register */
+#define TIMER_CAR(timerx) REG32((timerx) + 0x0000002CU) /*!< TIMER counter auto reload register */
+#define TIMER_CREP(timerx) REG32((timerx) + 0x00000030U) /*!< TIMER counter repetition register */
+#define TIMER_CH0CV(timerx) REG32((timerx) + 0x00000034U) /*!< TIMER channel 0 capture/compare value register */
+#define TIMER_CH1CV(timerx) REG32((timerx) + 0x00000038U) /*!< TIMER channel 1 capture/compare value register */
+#define TIMER_CH2CV(timerx) REG32((timerx) + 0x0000003CU) /*!< TIMER channel 2 capture/compare value register */
+#define TIMER_CH3CV(timerx) REG32((timerx) + 0x00000040U) /*!< TIMER channel 3 capture/compare value register */
+#define TIMER_CCHP(timerx) REG32((timerx) + 0x00000044U) /*!< TIMER complementary channel protection register */
+#define TIMER_DMACFG(timerx) REG32((timerx) + 0x00000048U) /*!< TIMER DMA configuration register */
+#define TIMER_DMATB(timerx) REG32((timerx) + 0x0000004CU) /*!< TIMER DMA transfer buffer register */
+#define TIMER_IRMP(timerx) REG32((timerx) + 0x00000050U) /*!< TIMER channel input remap register */
+#define TIMER_CFG(timerx) REG32((timerx) + 0x000000FCU) /*!< TIMER configuration register */
+
+/* bits definitions */
+/* TIMER_CTL0 */
+#define TIMER_CTL0_CEN BIT(0) /*!< TIMER counter enable */
+#define TIMER_CTL0_UPDIS BIT(1) /*!< update disable */
+#define TIMER_CTL0_UPS BIT(2) /*!< update source */
+#define TIMER_CTL0_SPM BIT(3) /*!< single pulse mode */
+#define TIMER_CTL0_DIR BIT(4) /*!< timer counter direction */
+#define TIMER_CTL0_CAM BITS(5,6) /*!< center-aligned mode selection */
+#define TIMER_CTL0_ARSE BIT(7) /*!< auto-reload shadow enable */
+#define TIMER_CTL0_CKDIV BITS(8,9) /*!< clock division */
+
+/* TIMER_CTL1 */
+#define TIMER_CTL1_CCSE BIT(0) /*!< commutation control shadow enable */
+#define TIMER_CTL1_CCUC BIT(2) /*!< commutation control shadow register update control */
+#define TIMER_CTL1_DMAS BIT(3) /*!< DMA request source selection */
+#define TIMER_CTL1_MMC BITS(4,6) /*!< master mode control */
+#define TIMER_CTL1_TI0S BIT(7) /*!< channel 0 trigger input selection(hall mode selection) */
+#define TIMER_CTL1_ISO0 BIT(8) /*!< idle state of channel 0 output */
+#define TIMER_CTL1_ISO0N BIT(9) /*!< idle state of channel 0 complementary output */
+#define TIMER_CTL1_ISO1 BIT(10) /*!< idle state of channel 1 output */
+#define TIMER_CTL1_ISO1N BIT(11) /*!< idle state of channel 1 complementary output */
+#define TIMER_CTL1_ISO2 BIT(12) /*!< idle state of channel 2 output */
+#define TIMER_CTL1_ISO2N BIT(13) /*!< idle state of channel 2 complementary output */
+#define TIMER_CTL1_ISO3 BIT(14) /*!< idle state of channel 3 output */
+
+/* TIMER_SMCFG */
+#define TIMER_SMCFG_SMC BITS(0,2) /*!< slave mode control */
+#define TIMER_SMCFG_OCRC BIT(3) /*!< OCPRE clear source selection */
+#define TIMER_SMCFG_TRGS BITS(4,6) /*!< trigger selection */
+#define TIMER_SMCFG_MSM BIT(7) /*!< master-slave mode */
+#define TIMER_SMCFG_ETFC BITS(8,11) /*!< external trigger filter control */
+#define TIMER_SMCFG_ETPSC BITS(12,13) /*!< external trigger prescaler */
+#define TIMER_SMCFG_SMC1 BIT(14) /*!< part of SMC for enable external clock mode 1 */
+#define TIMER_SMCFG_ETP BIT(15) /*!< external trigger polarity */
+
+/* TIMER_DMAINTEN */
+#define TIMER_DMAINTEN_UPIE BIT(0) /*!< update interrupt enable */
+#define TIMER_DMAINTEN_CH0IE BIT(1) /*!< channel 0 capture/compare interrupt enable */
+#define TIMER_DMAINTEN_CH1IE BIT(2) /*!< channel 1 capture/compare interrupt enable */
+#define TIMER_DMAINTEN_CH2IE BIT(3) /*!< channel 2 capture/compare interrupt enable */
+#define TIMER_DMAINTEN_CH3IE BIT(4) /*!< channel 3 capture/compare interrupt enable */
+#define TIMER_DMAINTEN_CMTIE BIT(5) /*!< commutation interrupt request enable */
+#define TIMER_DMAINTEN_TRGIE BIT(6) /*!< trigger interrupt enable */
+#define TIMER_DMAINTEN_BRKIE BIT(7) /*!< break interrupt enable */
+#define TIMER_DMAINTEN_UPDEN BIT(8) /*!< update DMA request enable */
+#define TIMER_DMAINTEN_CH0DEN BIT(9) /*!< channel 0 DMA request enable */
+#define TIMER_DMAINTEN_CH1DEN BIT(10) /*!< channel 1 DMA request enable */
+#define TIMER_DMAINTEN_CH2DEN BIT(11) /*!< channel 2 DMA request enable */
+#define TIMER_DMAINTEN_CH3DEN BIT(12) /*!< channel 3 DMA request enable */
+#define TIMER_DMAINTEN_CMTDEN BIT(13) /*!< commutation DMA request enable */
+#define TIMER_DMAINTEN_TRGDEN BIT(14) /*!< trigger DMA request enable */
+
+/* TIMER_INTF */
+#define TIMER_INTF_UPIF BIT(0) /*!< update interrupt flag */
+#define TIMER_INTF_CH0IF BIT(1) /*!< channel 0 capture/compare interrupt flag */
+#define TIMER_INTF_CH1IF BIT(2) /*!< channel 1 capture/compare interrupt flag */
+#define TIMER_INTF_CH2IF BIT(3) /*!< channel 2 capture/compare interrupt flag */
+#define TIMER_INTF_CH3IF BIT(4) /*!< channel 3 capture/compare interrupt flag */
+#define TIMER_INTF_CMTIF BIT(5) /*!< channel commutation interrupt flag */
+#define TIMER_INTF_TRGIF BIT(6) /*!< trigger interrupt flag */
+#define TIMER_INTF_BRKIF BIT(7) /*!< break interrupt flag */
+#define TIMER_INTF_CH0OF BIT(9) /*!< channel 0 overcapture flag */
+#define TIMER_INTF_CH1OF BIT(10) /*!< channel 1 overcapture flag */
+#define TIMER_INTF_CH2OF BIT(11) /*!< channel 2 overcapture flag */
+#define TIMER_INTF_CH3OF BIT(12) /*!< channel 3 overcapture flag */
+
+/* TIMER_SWEVG */
+#define TIMER_SWEVG_UPG BIT(0) /*!< update event generate */
+#define TIMER_SWEVG_CH0G BIT(1) /*!< channel 0 capture or compare event generation */
+#define TIMER_SWEVG_CH1G BIT(2) /*!< channel 1 capture or compare event generation */
+#define TIMER_SWEVG_CH2G BIT(3) /*!< channel 2 capture or compare event generation */
+#define TIMER_SWEVG_CH3G BIT(4) /*!< channel 3 capture or compare event generation */
+#define TIMER_SWEVG_CMTG BIT(5) /*!< channel commutation event generation */
+#define TIMER_SWEVG_TRGG BIT(6) /*!< trigger event generation */
+#define TIMER_SWEVG_BRKG BIT(7) /*!< break event generation */
+
+/* TIMER_CHCTL0 */
+/* output compare mode */
+#define TIMER_CHCTL0_CH0MS BITS(0,1) /*!< channel 0 mode selection */
+#define TIMER_CHCTL0_CH0COMFEN BIT(2) /*!< channel 0 output compare fast enable */
+#define TIMER_CHCTL0_CH0COMSEN BIT(3) /*!< channel 0 output compare shadow enable */
+#define TIMER_CHCTL0_CH0COMCTL BITS(4,6) /*!< channel 0 output compare mode */
+#define TIMER_CHCTL0_CH0COMCEN BIT(7) /*!< channel 0 output compare clear enable */
+#define TIMER_CHCTL0_CH1MS BITS(8,9) /*!< channel 1 mode selection */
+#define TIMER_CHCTL0_CH1COMFEN BIT(10) /*!< channel 1 output compare fast enable */
+#define TIMER_CHCTL0_CH1COMSEN BIT(11) /*!< channel 1 output compare shadow enable */
+#define TIMER_CHCTL0_CH1COMCTL BITS(12,14) /*!< channel 1 output compare mode */
+#define TIMER_CHCTL0_CH1COMCEN BIT(15) /*!< channel 1 output compare clear enable */
+/* input capture mode */
+#define TIMER_CHCTL0_CH0CAPPSC BITS(2,3) /*!< channel 0 input capture prescaler */
+#define TIMER_CHCTL0_CH0CAPFLT BITS(4,7) /*!< channel 0 input capture filter control */
+#define TIMER_CHCTL0_CH1CAPPSC BITS(10,11) /*!< channel 1 input capture prescaler */
+#define TIMER_CHCTL0_CH1CAPFLT BITS(12,15) /*!< channel 1 input capture filter control */
+
+/* TIMER_CHCTL1 */
+/* output compare mode */
+#define TIMER_CHCTL1_CH2MS BITS(0,1) /*!< channel 2 mode selection */
+#define TIMER_CHCTL1_CH2COMFEN BIT(2) /*!< channel 2 output compare fast enable */
+#define TIMER_CHCTL1_CH2COMSEN BIT(3) /*!< channel 2 output compare shadow enable */
+#define TIMER_CHCTL1_CH2COMCTL BITS(4,6) /*!< channel 2 output compare mode */
+#define TIMER_CHCTL1_CH2COMCEN BIT(7) /*!< channel 2 output compare clear enable */
+#define TIMER_CHCTL1_CH3MS BITS(8,9) /*!< channel 3 mode selection */
+#define TIMER_CHCTL1_CH3COMFEN BIT(10) /*!< channel 3 output compare fast enable */
+#define TIMER_CHCTL1_CH3COMSEN BIT(11) /*!< channel 3 output compare shadow enable */
+#define TIMER_CHCTL1_CH3COMCTL BITS(12,14) /*!< channel 3 output compare mode */
+#define TIMER_CHCTL1_CH3COMCEN BIT(15) /*!< channel 3 output compare clear enable */
+/* input capture mode */
+#define TIMER_CHCTL1_CH2CAPPSC BITS(2,3) /*!< channel 2 input capture prescaler */
+#define TIMER_CHCTL1_CH2CAPFLT BITS(4,7) /*!< channel 2 input capture filter control */
+#define TIMER_CHCTL1_CH3CAPPSC BITS(10,11) /*!< channel 3 input capture prescaler */
+#define TIMER_CHCTL1_CH3CAPFLT BITS(12,15) /*!< channel 3 input capture filter control */
+
+/* TIMER_CHCTL2 */
+#define TIMER_CHCTL2_CH0EN BIT(0) /*!< channel 0 capture/compare function enable */
+#define TIMER_CHCTL2_CH0P BIT(1) /*!< channel 0 capture/compare function polarity */
+#define TIMER_CHCTL2_CH0NEN BIT(2) /*!< channel 0 complementary output enable */
+#define TIMER_CHCTL2_CH0NP BIT(3) /*!< channel 0 complementary output polarity */
+#define TIMER_CHCTL2_CH1EN BIT(4) /*!< channel 1 capture/compare function enable */
+#define TIMER_CHCTL2_CH1P BIT(5) /*!< channel 1 capture/compare function polarity */
+#define TIMER_CHCTL2_CH1NEN BIT(6) /*!< channel 1 complementary output enable */
+#define TIMER_CHCTL2_CH1NP BIT(7) /*!< channel 1 complementary output polarity */
+#define TIMER_CHCTL2_CH2EN BIT(8) /*!< channel 2 capture/compare function enable */
+#define TIMER_CHCTL2_CH2P BIT(9) /*!< channel 2 capture/compare function polarity */
+#define TIMER_CHCTL2_CH2NEN BIT(10) /*!< channel 2 complementary output enable */
+#define TIMER_CHCTL2_CH2NP BIT(11) /*!< channel 2 complementary output polarity */
+#define TIMER_CHCTL2_CH3EN BIT(12) /*!< channel 3 capture/compare function enable */
+#define TIMER_CHCTL2_CH3P BIT(13) /*!< channel 3 capture/compare function polarity */
+#define TIMER_CHCTL2_CH3NP BIT(15) /*!< channel 3 complementary output polarity */
+
+/* TIMER_CNT */
+#define TIMER_CNT_CNT16 BITS(0,15) /*!< 16 bit timer counter */
+#define TIMER_CNT_CNT32 BITS(0,31) /*!< 32 bit(TIMER1) timer counter */
+
+/* TIMER_PSC */
+#define TIMER_PSC_PSC BITS(0,15) /*!< prescaler value of the counter clock */
+
+/* TIMER_CAR */
+#define TIMER_CAR_CARL16 BITS(0,15) /*!< 16 bit counter auto reload value */
+#define TIMER_CAR_CARL32 BITS(0,31) /*!< 32 bit(TIMER1) counter auto reload value */
+
+/* TIMER_CREP */
+#define TIMER_CREP_CREP BITS(0,7) /*!< counter repetition value */
+
+/* TIMER_CH0CV */
+#define TIMER_CH0CV_CH0VAL16 BITS(0,15) /*!< 16 bit capture/compare value of channel 0 */
+#define TIMER_CH0CV_CH0VAL32 BITS(0,31) /*!< 32 bit(TIMER1) capture/compare value of channel 0 */
+
+/* TIMER_CH1CV */
+#define TIMER_CH1CV_CH1VAL16 BITS(0,15) /*!< 16 bit capture/compare value of channel 1 */
+#define TIMER_CH1CV_CH1VAL32 BITS(0,31) /*!< 32 bit(TIMER1) capture/compare value of channel 1 */
+
+/* TIMER_CH2CV */
+#define TIMER_CH2CV_CH2VAL16 BITS(0,15) /*!< 16 bit capture/compare value of channel 2 */
+#define TIMER_CH2CV_CH2VAL32 BITS(0,31) /*!< 32 bit(TIMER1) capture/compare value of channel 2 */
+
+/* TIMER_CH3CV */
+#define TIMER_CH3CV_CH3VAL16 BITS(0,15) /*!< 16 bit capture/compare value of channel 3 */
+#define TIMER_CH3CV_CH3VAL32 BITS(0,31) /*!< 32 bit(TIMER1) capture/compare value of channel 3 */
+
+/* TIMER_CCHP */
+#define TIMER_CCHP_DTCFG BITS(0,7) /*!< dead time configure */
+#define TIMER_CCHP_PROT BITS(8,9) /*!< complementary register protect control */
+#define TIMER_CCHP_IOS BIT(10) /*!< idle mode off-state configure */
+#define TIMER_CCHP_ROS BIT(11) /*!< run mode off-state configure */
+#define TIMER_CCHP_BRKEN BIT(12) /*!< break enable */
+#define TIMER_CCHP_BRKP BIT(13) /*!< break polarity */
+#define TIMER_CCHP_OAEN BIT(14) /*!< output automatic enable */
+#define TIMER_CCHP_POEN BIT(15) /*!< primary output enable */
+
+/* TIMER_DMACFG */
+#define TIMER_DMACFG_DMATA BITS(0,4) /*!< DMA transfer access start address */
+#define TIMER_DMACFG_DMATC BITS(8,12) /*!< DMA transfer count */
+
+/* TIMER_DMATB */
+#define TIMER_DMATB_DMATB BITS(0,15) /*!< DMA transfer buffer address */
+
+/* TIMER_IRMP */
+#define TIMER13_IRMP_CI0_RMP BITS(0,1) /*!< TIMER13 channel 0 input remap */
+
+/* TIMER_CFG */
+#define TIMER_CFG_OUTSEL BIT(0) /*!< the output value selection */
+#define TIMER_CFG_CHVSEL BIT(1) /*!< write CHxVAL register selection */
+
+/* constants definitions */
+/* TIMER init parameter struct definitions*/
+typedef struct {
+ uint16_t prescaler; /*!< prescaler value */
+ uint16_t alignedmode; /*!< aligned mode */
+ uint16_t counterdirection; /*!< counter direction */
+ uint16_t clockdivision; /*!< clock division value */
+ uint32_t period; /*!< period value */
+ uint8_t repetitioncounter; /*!< the counter repetition value */
+} timer_parameter_struct;
+
+/* break parameter struct definitions*/
+typedef struct {
+ uint32_t runoffstate; /*!< run mode off-state */
+ uint32_t ideloffstate; /*!< idle mode off-state */
+ uint16_t deadtime; /*!< dead time */
+ uint16_t breakpolarity; /*!< break polarity */
+ uint32_t outputautostate; /*!< output automatic enable */
+ uint32_t protectmode; /*!< complementary register protect control */
+ uint32_t breakstate; /*!< break enable */
+} timer_break_parameter_struct;
+
+/* channel output parameter struct definitions */
+typedef struct {
+ uint32_t outputstate; /*!< channel output state */
+ uint16_t outputnstate; /*!< channel complementary output state */
+ uint16_t ocpolarity; /*!< channel output polarity */
+ uint16_t ocnpolarity; /*!< channel complementary output polarity */
+ uint16_t ocidlestate; /*!< idle state of channel output */
+ uint16_t ocnidlestate; /*!< idle state of channel complementary output */
+} timer_oc_parameter_struct;
+
+/* channel input parameter struct definitions */
+typedef struct {
+ uint16_t icpolarity; /*!< channel input polarity */
+ uint16_t icselection; /*!< channel input mode selection */
+ uint16_t icprescaler; /*!< channel input capture prescaler */
+ uint16_t icfilter; /*!< channel input capture filter control */
+} timer_ic_parameter_struct;
+
+/* TIMER interrupt enable or disable */
+#define TIMER_INT_UP TIMER_DMAINTEN_UPIE /*!< update interrupt */
+#define TIMER_INT_CH0 TIMER_DMAINTEN_CH0IE /*!< channel 0 interrupt */
+#define TIMER_INT_CH1 TIMER_DMAINTEN_CH1IE /*!< channel 1 interrupt */
+#define TIMER_INT_CH2 TIMER_DMAINTEN_CH2IE /*!< channel 2 interrupt */
+#define TIMER_INT_CH3 TIMER_DMAINTEN_CH3IE /*!< channel 3 interrupt */
+#define TIMER_INT_CMT TIMER_DMAINTEN_CMTIE /*!< channel commutation interrupt flag */
+#define TIMER_INT_TRG TIMER_DMAINTEN_TRGIE /*!< trigger interrupt */
+#define TIMER_INT_BRK TIMER_DMAINTEN_BRKIE /*!< break interrupt */
+
+/* TIMER flag */
+#define TIMER_FLAG_UP TIMER_INTF_UPIF /*!< update flag */
+#define TIMER_FLAG_CH0 TIMER_INTF_CH0IF /*!< channel 0 flag */
+#define TIMER_FLAG_CH1 TIMER_INTF_CH1IF /*!< channel 1 flag */
+#define TIMER_FLAG_CH2 TIMER_INTF_CH2IF /*!< channel 2 flag */
+#define TIMER_FLAG_CH3 TIMER_INTF_CH3IF /*!< channel 3 flag */
+#define TIMER_FLAG_CMT TIMER_INTF_CMTIF /*!< channel commutation flag */
+#define TIMER_FLAG_TRG TIMER_INTF_TRGIF /*!< trigger flag */
+#define TIMER_FLAG_BRK TIMER_INTF_BRKIF /*!< break flag */
+#define TIMER_FLAG_CH0O TIMER_INTF_CH0OF /*!< channel 0 overcapture flag */
+#define TIMER_FLAG_CH1O TIMER_INTF_CH1OF /*!< channel 1 overcapture flag */
+#define TIMER_FLAG_CH2O TIMER_INTF_CH2OF /*!< channel 2 overcapture flag */
+#define TIMER_FLAG_CH3O TIMER_INTF_CH3OF /*!< channel 3 overcapture flag */
+
+/* TIMER interrupt flag */
+#define TIMER_INT_FLAG_UP TIMER_INTF_UPIF /*!< update interrupt flag */
+#define TIMER_INT_FLAG_CH0 TIMER_INTF_CH0IF /*!< channel 0 interrupt flag */
+#define TIMER_INT_FLAG_CH1 TIMER_INTF_CH1IF /*!< channel 1 interrupt flag */
+#define TIMER_INT_FLAG_CH2 TIMER_INTF_CH2IF /*!< channel 2 interrupt flag */
+#define TIMER_INT_FLAG_CH3 TIMER_INTF_CH3IF /*!< channel 3 interrupt flag */
+#define TIMER_INT_FLAG_CMT TIMER_INTF_CMTIF /*!< channel commutation interrupt flag */
+#define TIMER_INT_FLAG_TRG TIMER_INTF_TRGIF /*!< trigger interrupt flag */
+#define TIMER_INT_FLAG_BRK TIMER_INTF_BRKIF
+
+/* TIMER DMA source enable */
+#define TIMER_DMA_UPD ((uint16_t)TIMER_DMAINTEN_UPDEN) /*!< update DMA enable */
+#define TIMER_DMA_CH0D ((uint16_t)TIMER_DMAINTEN_CH0DEN) /*!< channel 0 DMA enable */
+#define TIMER_DMA_CH1D ((uint16_t)TIMER_DMAINTEN_CH1DEN) /*!< channel 1 DMA enable */
+#define TIMER_DMA_CH2D ((uint16_t)TIMER_DMAINTEN_CH2DEN) /*!< channel 2 DMA enable */
+#define TIMER_DMA_CH3D ((uint16_t)TIMER_DMAINTEN_CH3DEN) /*!< channel 3 DMA enable */
+#define TIMER_DMA_CMTD ((uint16_t)TIMER_DMAINTEN_CMTDEN) /*!< commutation DMA request enable */
+#define TIMER_DMA_TRGD ((uint16_t)TIMER_DMAINTEN_TRGDEN) /*!< trigger DMA enable */
+
+/* channel DMA request source selection */
+#define TIMER_DMAREQUEST_UPDATEEVENT ((uint8_t)0x00U) /*!< DMA request of channel y is sent when update event occurs */
+#define TIMER_DMAREQUEST_CHANNELEVENT ((uint8_t)0x01U) /*!< DMA request of channel y is sent when channel y event occurs */
+
+/* DMA access base address */
+#define DMACFG_DMATA(regval) (BITS(0, 4) & ((uint32_t)(regval) << 0U))
+#define TIMER_DMACFG_DMATA_CTL0 DMACFG_DMATA(0) /*!< DMA transfer address is TIMER_CTL0 */
+#define TIMER_DMACFG_DMATA_CTL1 DMACFG_DMATA(1) /*!< DMA transfer address is TIMER_CTL1 */
+#define TIMER_DMACFG_DMATA_SMCFG DMACFG_DMATA(2) /*!< DMA transfer address is TIMER_SMCFG */
+#define TIMER_DMACFG_DMATA_DMAINTEN DMACFG_DMATA(3) /*!< DMA transfer address is TIMER_DMAINTEN */
+#define TIMER_DMACFG_DMATA_INTF DMACFG_DMATA(4) /*!< DMA transfer address is TIMER_INTF */
+#define TIMER_DMACFG_DMATA_SWEVG DMACFG_DMATA(5) /*!< DMA transfer address is TIMER_SWEVG */
+#define TIMER_DMACFG_DMATA_CHCTL0 DMACFG_DMATA(6) /*!< DMA transfer address is TIMER_CHCTL0 */
+#define TIMER_DMACFG_DMATA_CHCTL1 DMACFG_DMATA(7) /*!< DMA transfer address is TIMER_CHCTL1 */
+#define TIMER_DMACFG_DMATA_CHCTL2 DMACFG_DMATA(8) /*!< DMA transfer address is TIMER_CHCTL2 */
+#define TIMER_DMACFG_DMATA_CNT DMACFG_DMATA(9) /*!< DMA transfer address is TIMER_CNT */
+#define TIMER_DMACFG_DMATA_PSC DMACFG_DMATA(10) /*!< DMA transfer address is TIMER_PSC */
+#define TIMER_DMACFG_DMATA_CAR DMACFG_DMATA(11) /*!< DMA transfer address is TIMER_CAR */
+#define TIMER_DMACFG_DMATA_CREP DMACFG_DMATA(12) /*!< DMA transfer address is TIMER_CREP */
+#define TIMER_DMACFG_DMATA_CH0CV DMACFG_DMATA(13) /*!< DMA transfer address is TIMER_CH0CV */
+#define TIMER_DMACFG_DMATA_CH1CV DMACFG_DMATA(14) /*!< DMA transfer address is TIMER_CH1CV */
+#define TIMER_DMACFG_DMATA_CH2CV DMACFG_DMATA(15) /*!< DMA transfer address is TIMER_CH2CV */
+#define TIMER_DMACFG_DMATA_CH3CV DMACFG_DMATA(16) /*!< DMA transfer address is TIMER_CH3CV */
+#define TIMER_DMACFG_DMATA_CCHP DMACFG_DMATA(17) /*!< DMA transfer address is TIMER_CCHP */
+#define TIMER_DMACFG_DMATA_DMACFG DMACFG_DMATA(18) /*!< DMA transfer address is TIMER_DMACFG */
+#define TIMER_DMACFG_DMATA_DMATB DMACFG_DMATA(19) /*!< DMA transfer address is TIMER_DMATB */
+
+/* DMA access burst length */
+#define DMACFG_DMATC(regval) (BITS(8, 12) & ((uint32_t)(regval) << 8U))
+#define TIMER_DMACFG_DMATC_1TRANSFER DMACFG_DMATC(0) /*!< DMA transfer 1 time */
+#define TIMER_DMACFG_DMATC_2TRANSFER DMACFG_DMATC(1) /*!< DMA transfer 2 times */
+#define TIMER_DMACFG_DMATC_3TRANSFER DMACFG_DMATC(2) /*!< DMA transfer 3 times */
+#define TIMER_DMACFG_DMATC_4TRANSFER DMACFG_DMATC(3) /*!< DMA transfer 4 times */
+#define TIMER_DMACFG_DMATC_5TRANSFER DMACFG_DMATC(4) /*!< DMA transfer 5 times */
+#define TIMER_DMACFG_DMATC_6TRANSFER DMACFG_DMATC(5) /*!< DMA transfer 6 times */
+#define TIMER_DMACFG_DMATC_7TRANSFER DMACFG_DMATC(6) /*!< DMA transfer 7 times */
+#define TIMER_DMACFG_DMATC_8TRANSFER DMACFG_DMATC(7) /*!< DMA transfer 8 times */
+#define TIMER_DMACFG_DMATC_9TRANSFER DMACFG_DMATC(8) /*!< DMA transfer 9 times */
+#define TIMER_DMACFG_DMATC_10TRANSFER DMACFG_DMATC(9) /*!< DMA transfer 10 times */
+#define TIMER_DMACFG_DMATC_11TRANSFER DMACFG_DMATC(10) /*!< DMA transfer 11 times */
+#define TIMER_DMACFG_DMATC_12TRANSFER DMACFG_DMATC(11) /*!< DMA transfer 12 times */
+#define TIMER_DMACFG_DMATC_13TRANSFER DMACFG_DMATC(12) /*!< DMA transfer 13 times */
+#define TIMER_DMACFG_DMATC_14TRANSFER DMACFG_DMATC(13) /*!< DMA transfer 14 times */
+#define TIMER_DMACFG_DMATC_15TRANSFER DMACFG_DMATC(14) /*!< DMA transfer 15 times */
+#define TIMER_DMACFG_DMATC_16TRANSFER DMACFG_DMATC(15) /*!< DMA transfer 16 times */
+#define TIMER_DMACFG_DMATC_17TRANSFER DMACFG_DMATC(16) /*!< DMA transfer 17 times */
+#define TIMER_DMACFG_DMATC_18TRANSFER DMACFG_DMATC(17) /*!< DMA transfer 18 times */
+
+/* TIMER software event generation source */
+#define TIMER_EVENT_SRC_UPG ((uint16_t)0x0001U) /*!< update event generation */
+#define TIMER_EVENT_SRC_CH0G ((uint16_t)0x0002U) /*!< channel 0 capture or compare event generation */
+#define TIMER_EVENT_SRC_CH1G ((uint16_t)0x0004U) /*!< channel 1 capture or compare event generation */
+#define TIMER_EVENT_SRC_CH2G ((uint16_t)0x0008U) /*!< channel 2 capture or compare event generation */
+#define TIMER_EVENT_SRC_CH3G ((uint16_t)0x0010U) /*!< channel 3 capture or compare event generation */
+#define TIMER_EVENT_SRC_CMTG ((uint16_t)0x0020U) /*!< channel commutation event generation */
+#define TIMER_EVENT_SRC_TRGG ((uint16_t)0x0040U) /*!< trigger event generation */
+#define TIMER_EVENT_SRC_BRKG ((uint16_t)0x0080U) /*!< break event generation */
+
+/* center-aligned mode selection */
+#define CTL0_CAM(regval) ((uint16_t)(BITS(5, 6) & ((uint32_t)(regval) << 5U)))
+#define TIMER_COUNTER_EDGE CTL0_CAM(0) /*!< edge-aligned mode */
+#define TIMER_COUNTER_CENTER_DOWN CTL0_CAM(1) /*!< center-aligned and counting down assert mode */
+#define TIMER_COUNTER_CENTER_UP CTL0_CAM(2) /*!< center-aligned and counting up assert mode */
+#define TIMER_COUNTER_CENTER_BOTH CTL0_CAM(3) /*!< center-aligned and counting up/down assert mode */
+
+/* TIMER prescaler reload mode */
+#define TIMER_PSC_RELOAD_NOW ((uint8_t)0x00U) /*!< the prescaler is loaded right now */
+#define TIMER_PSC_RELOAD_UPDATE ((uint8_t)0x01U) /*!< the prescaler is loaded at the next update event */
+
+/* count direction */
+#define TIMER_COUNTER_UP ((uint16_t)0x0000U) /*!< counter up direction */
+#define TIMER_COUNTER_DOWN ((uint16_t)0x0010U) /*!< counter down direction */
+
+/* specify division ratio between TIMER clock and dead-time and sampling clock */
+#define CTL0_CKDIV(regval) ((uint16_t)(BITS(8, 9) & ((uint32_t)(regval) << 8U)))
+#define TIMER_CKDIV_DIV1 CTL0_CKDIV(0) /*!< clock division value is 1, fDTS=fTIMER_CK */
+#define TIMER_CKDIV_DIV2 CTL0_CKDIV(1) /*!< clock division value is 2, fDTS= fTIMER_CK/2 */
+#define TIMER_CKDIV_DIV4 CTL0_CKDIV(2) /*!< clock division value is 4, fDTS= fTIMER_CK/4 */
+
+/* single pulse mode */
+#define TIMER_SP_MODE_SINGLE ((uint8_t)0x00U) /*!< single pulse mode */
+#define TIMER_SP_MODE_REPETITIVE ((uint8_t)0x01U) /*!< repetitive pulse mode */
+
+/* update source */
+#define TIMER_UPDATE_SRC_REGULAR ((uint8_t)0x00U) /*!< update generate only by counter overflow/underflow */
+#define TIMER_UPDATE_SRC_GLOBAL ((uint8_t)0x01U) /*!< update generate by setting of UPG bit or the counter overflow/underflow,or the slave mode controller trigger */
+
+/* run mode off-state configure */
+#define TIMER_ROS_STATE_ENABLE ((uint32_t)0x00000800U) /*!< when POEN bit is set, the channel output signals (CHx_O/CHx_ON) are enabled, with relationship to CHxEN/CHxNEN bits */
+#define TIMER_ROS_STATE_DISABLE ((uint32_t)0x00000000U) /*!< when POEN bit is set, the channel output signals (CHx_O/CHx_ON) are disabled */
+
+/* idle mode off-state configure */
+#define TIMER_IOS_STATE_ENABLE ((uint16_t)0x0400U) /*!< when POEN bit is reset, he channel output signals (CHx_O/CHx_ON) are enabled, with relationship to CHxEN/CHxNEN bits */
+#define TIMER_IOS_STATE_DISABLE ((uint16_t)0x0000U) /*!< when POEN bit is reset, the channel output signals (CHx_O/CHx_ON) are disabled */
+
+/* break input polarity */
+#define TIMER_BREAK_POLARITY_LOW ((uint16_t)0x0000U) /*!< break input polarity is low */
+#define TIMER_BREAK_POLARITY_HIGH ((uint16_t)0x2000U) /*!< break input polarity is high */
+
+/* output automatic enable */
+#define TIMER_OUTAUTO_ENABLE ((uint16_t)0x4000U) /*!< output automatic enable */
+#define TIMER_OUTAUTO_DISABLE ((uint16_t)0x0000U) /*!< output automatic disable */
+
+/* complementary register protect control */
+#define CCHP_PROT(regval) ((uint16_t)(BITS(8, 9) & ((uint32_t)(regval) << 8U)))
+#define TIMER_CCHP_PROT_OFF CCHP_PROT(0) /*!< protect disable */
+#define TIMER_CCHP_PROT_0 CCHP_PROT(1) /*!< PROT mode 0 */
+#define TIMER_CCHP_PROT_1 CCHP_PROT(2) /*!< PROT mode 1 */
+#define TIMER_CCHP_PROT_2 CCHP_PROT(3) /*!< PROT mode 2 */
+
+/* break input enable */
+#define TIMER_BREAK_ENABLE ((uint16_t)0x1000U) /*!< break input enable */
+#define TIMER_BREAK_DISABLE ((uint16_t)0x0000U) /*!< break input disable */
+
+/* TIMER channel n(n=0,1,2,3) */
+#define TIMER_CH_0 ((uint16_t)0x0000U) /*!< TIMER channel 0(TIMERx(x=0..2,13..16)) */
+#define TIMER_CH_1 ((uint16_t)0x0001U) /*!< TIMER channel 1(TIMERx(x=0..2,14)) */
+#define TIMER_CH_2 ((uint16_t)0x0002U) /*!< TIMER channel 2(TIMERx(x=0..2)) */
+#define TIMER_CH_3 ((uint16_t)0x0003U) /*!< TIMER channel 3(TIMERx(x=0..2)) */
+
+/* channel enable state*/
+#define TIMER_CCX_ENABLE ((uint32_t)0x00000001U) /*!< channel enable */
+#define TIMER_CCX_DISABLE ((uint32_t)0x00000000U) /*!< channel disable */
+
+/* channel complementary output enable state*/
+#define TIMER_CCXN_ENABLE ((uint16_t)0x0004U) /*!< channel complementary enable */
+#define TIMER_CCXN_DISABLE ((uint16_t)0x0000U) /*!< channel complementary disable */
+
+/* channel output polarity */
+#define TIMER_OC_POLARITY_HIGH ((uint16_t)0x0000U) /*!< channel output polarity is high */
+#define TIMER_OC_POLARITY_LOW ((uint16_t)0x0002U) /*!< channel output polarity is low */
+
+/* channel complementary output polarity */
+#define TIMER_OCN_POLARITY_HIGH ((uint16_t)0x0000U) /*!< channel complementary output polarity is high */
+#define TIMER_OCN_POLARITY_LOW ((uint16_t)0x0008U) /*!< channel complementary output polarity is low */
+
+/* idle state of channel output */
+#define TIMER_OC_IDLE_STATE_HIGH ((uint16_t)0x0100) /*!< idle state of channel output is high */
+#define TIMER_OC_IDLE_STATE_LOW ((uint16_t)0x0000) /*!< idle state of channel output is low */
+
+/* idle state of channel complementary output */
+#define TIMER_OCN_IDLE_STATE_HIGH ((uint16_t)0x0200U) /*!< idle state of channel complementary output is high */
+#define TIMER_OCN_IDLE_STATE_LOW ((uint16_t)0x0000U) /*!< idle state of channel complementary output is low */
+
+/* channel output compare mode */
+#define TIMER_OC_MODE_TIMING ((uint16_t)0x0000U) /*!< timing mode */
+#define TIMER_OC_MODE_ACTIVE ((uint16_t)0x0010U) /*!< active mode */
+#define TIMER_OC_MODE_INACTIVE ((uint16_t)0x0020U) /*!< inactive mode */
+#define TIMER_OC_MODE_TOGGLE ((uint16_t)0x0030U) /*!< toggle mode */
+#define TIMER_OC_MODE_LOW ((uint16_t)0x0040U) /*!< force low mode */
+#define TIMER_OC_MODE_HIGH ((uint16_t)0x0050U) /*!< force high mode */
+#define TIMER_OC_MODE_PWM0 ((uint16_t)0x0060U) /*!< PWM0 mode */
+#define TIMER_OC_MODE_PWM1 ((uint16_t)0x0070U) /*!< PWM1 mode*/
+
+/* channel output compare shadow enable */
+#define TIMER_OC_SHADOW_ENABLE ((uint16_t)0x0008U) /*!< channel output shadow state enable */
+#define TIMER_OC_SHADOW_DISABLE ((uint16_t)0x0000U) /*!< channel output shadow state disable */
+
+/* channel output compare fast enable */
+#define TIMER_OC_FAST_ENABLE ((uint16_t)0x0004) /*!< channel output fast function enable */
+#define TIMER_OC_FAST_DISABLE ((uint16_t)0x0000) /*!< channel output fast function disable */
+
+/* channel output compare clear enable */
+#define TIMER_OC_CLEAR_ENABLE ((uint16_t)0x0080U) /*!< channel output clear function enable */
+#define TIMER_OC_CLEAR_DISABLE ((uint16_t)0x0000U) /*!< channel output clear function disable */
+
+/* channel control shadow register update control */
+#define TIMER_UPDATECTL_CCU ((uint8_t)0x00U) /*!< the shadow registers update by when CMTG bit is set */
+#define TIMER_UPDATECTL_CCUTRI ((uint8_t)0x01U) /*!< the shadow registers update by when CMTG bit is set or an rising edge of TRGI occurs */
+
+/* channel input capture polarity */
+#define TIMER_IC_POLARITY_RISING ((uint16_t)0x0000U) /*!< input capture rising edge */
+#define TIMER_IC_POLARITY_FALLING ((uint16_t)0x0002U) /*!< input capture falling edge */
+#define TIMER_IC_POLARITY_BOTH_EDGE ((uint16_t)0x000AU) /*!< input capture both edge */
+
+/* timer input capture selection */
+#define TIMER_IC_SELECTION_DIRECTTI ((uint16_t)0x0001U) /*!< channel y is configured as input and icy is mapped on CIy */
+#define TIMER_IC_SELECTION_INDIRECTTI ((uint16_t)0x0002U) /*!< channel y is configured as input and icy is mapped on opposite input */
+#define TIMER_IC_SELECTION_ITS ((uint16_t)0x0003U) /*!< channel y is configured as input and icy is mapped on ITS */
+
+/* channel input capture prescaler */
+#define TIMER_IC_PSC_DIV1 ((uint16_t)0x0000U) /*!< no prescaler */
+#define TIMER_IC_PSC_DIV2 ((uint16_t)0x0004U) /*!< divided by 2 */
+#define TIMER_IC_PSC_DIV4 ((uint16_t)0x0008U) /*!< divided by 4*/
+#define TIMER_IC_PSC_DIV8 ((uint16_t)0x000CU) /*!< divided by 8 */
+
+/* trigger selection */
+#define SMCFG_TRGSEL(regval) (BITS(4, 6) & ((uint32_t)(regval) << 4U))
+#define TIMER_SMCFG_TRGSEL_ITI0 SMCFG_TRGSEL(0) /*!< internal trigger 0 */
+#define TIMER_SMCFG_TRGSEL_ITI1 SMCFG_TRGSEL(1) /*!< internal trigger 1 */
+#define TIMER_SMCFG_TRGSEL_ITI2 SMCFG_TRGSEL(2) /*!< internal trigger 2 */
+#define TIMER_SMCFG_TRGSEL_ITI3 SMCFG_TRGSEL(3) /*!< internal trigger 3 */
+#define TIMER_SMCFG_TRGSEL_CI0F_ED SMCFG_TRGSEL(4) /*!< TI0 Edge Detector */
+#define TIMER_SMCFG_TRGSEL_CI0FE0 SMCFG_TRGSEL(5) /*!< filtered TIMER input 0 */
+#define TIMER_SMCFG_TRGSEL_CI1FE1 SMCFG_TRGSEL(6) /*!< filtered TIMER input 1 */
+#define TIMER_SMCFG_TRGSEL_ETIFP SMCFG_TRGSEL(7) /*!< external trigger */
+
+/* master mode control */
+#define CTL1_MMC(regval) (BITS(4, 6) & ((uint32_t)(regval) << 4U))
+#define TIMER_TRI_OUT_SRC_RESET CTL1_MMC(0) /*!< the UPG bit as trigger output */
+#define TIMER_TRI_OUT_SRC_ENABLE CTL1_MMC(1) /*!< the counter enable signal TIMER_CTL0_CEN as trigger output */
+#define TIMER_TRI_OUT_SRC_UPDATE CTL1_MMC(2) /*!< update event as trigger output */
+#define TIMER_TRI_OUT_SRC_CH0 CTL1_MMC(3) /*!< a capture or a compare match occurred in channal0 as trigger output TRGO */
+#define TIMER_TRI_OUT_SRC_O0CPRE CTL1_MMC(4) /*!< O0CPRE as trigger output */
+#define TIMER_TRI_OUT_SRC_O1CPRE CTL1_MMC(5) /*!< O1CPRE as trigger output */
+#define TIMER_TRI_OUT_SRC_O2CPRE CTL1_MMC(6) /*!< O2CPRE as trigger output */
+#define TIMER_TRI_OUT_SRC_O3CPRE CTL1_MMC(7) /*!< O3CPRE as trigger output */
+
+/* slave mode control */
+#define SMCFG_SMC(regval) (BITS(0, 2) & ((uint32_t)(regval) << 0U))
+#define TIMER_SLAVE_MODE_DISABLE SMCFG_SMC(0) /*!< slave mode disable */
+#define TIMER_ENCODER_MODE0 SMCFG_SMC(1) /*!< encoder mode 0 */
+#define TIMER_ENCODER_MODE1 SMCFG_SMC(2) /*!< encoder mode 1 */
+#define TIMER_ENCODER_MODE2 SMCFG_SMC(3) /*!< encoder mode 2 */
+#define TIMER_SLAVE_MODE_RESTART SMCFG_SMC(4) /*!< restart mode */
+#define TIMER_SLAVE_MODE_PAUSE SMCFG_SMC(5) /*!< pause mode */
+#define TIMER_SLAVE_MODE_EVENT SMCFG_SMC(6) /*!< event mode */
+#define TIMER_SLAVE_MODE_EXTERNAL0 SMCFG_SMC(7) /*!< external clock mode 0 */
+
+/* OCPRE clear source selection */
+#define TIMER_OCPRE_CLEAR_SOURCE_CLR ((uint8_t)0x00U) /*!< OCPRE_CLR_INT is connected to the OCPRE_CLR input */
+#define TIMER_OCPRE_CLEAR_SOURCE_ETIF ((uint8_t)0x01U) /*!< OCPRE_CLR_INT is connected to ETIF */
+
+/* master slave mode selection */
+#define TIMER_MASTER_SLAVE_MODE_ENABLE ((uint8_t)0x00U) /*!< master slave mode enable */
+#define TIMER_MASTER_SLAVE_MODE_DISABLE ((uint8_t)0x01U) /*!< master slave mode disable */
+
+/* external trigger prescaler */
+#define SMCFG_ETPSC(regval) (BITS(12, 13) & ((uint32_t)(regval) << 12U))
+#define TIMER_EXT_TRI_PSC_OFF SMCFG_ETPSC(0) /*!< no divided */
+#define TIMER_EXT_TRI_PSC_DIV2 SMCFG_ETPSC(1) /*!< divided by 2 */
+#define TIMER_EXT_TRI_PSC_DIV4 SMCFG_ETPSC(2) /*!< divided by 4 */
+#define TIMER_EXT_TRI_PSC_DIV8 SMCFG_ETPSC(3) /*!< divided by 8 */
+
+/* external trigger polarity */
+#define TIMER_ETP_FALLING TIMER_SMCFG_ETP /*!< active low or falling edge active */
+#define TIMER_ETP_RISING ((uint32_t)0x00000000U) /*!< active high or rising edge active */
+
+/* channel 0 trigger input selection */
+#define TIMER_HALLINTERFACE_ENABLE ((uint8_t)0x00U) /*!< TIMER hall sensor mode enable */
+#define TIMER_HALLINTERFACE_DISABLE ((uint8_t)0x01U) /*!< TIMER hall sensor mode disable */
+
+/* timerx(x=0,1,2,13,14,15,16) write CHxVAL register selection */
+#define TIMER_CHVSEL_ENABLE ((uint16_t)0x0002U) /*!< write CHxVAL register selection enable */
+#define TIMER_CHVSEL_DISABLE ((uint16_t)0x0000U) /*!< write CHxVAL register selection disable */
+
+/* the output value selection */
+#define TIMER_OUTSEL_DISABLE ((uint16_t)0x0000U) /*!< output value selection disable */
+#define TIMER_OUTSEL_ENABLE ((uint16_t)0x0001U) /*!< output value selection enable */
+
+/* timer13 channel 0 input remap */
+#define TIMER13_IRMP(regval) (BITS(0, 1) & ((uint32_t)(regval) << 0U))
+#define TIMER13_CI0_RMP_GPIO TIMER13_IRMP(0) /*!< timer13 channel 0 input is connected to GPIO(TIMER13_CH0) */
+#define TIMER13_CI0_RMP_RTCCLK TIMER13_IRMP(1) /*!< timer13 channel 0 input is connected to the RTCCLK */
+#define TIMER13_CI0_RMP_HXTAL_DIV32 TIMER13_IRMP(2) /*!< timer13 channel 0 input is connected to HXTAL/32 clock */
+#define TIMER13_CI0_RMP_CKOUTSEL TIMER13_IRMP(3) /*!< timer13 channel 0 input is connected to CKOUTSEL */
+
+/* function declarations */
+/* TIMER timebase*/
+/* deinit a TIMER */
+void timer_deinit(uint32_t timer_periph);
+/* initialize TIMER init parameter struct */
+void timer_struct_para_init(timer_parameter_struct *initpara);
+/* initialize TIMER counter */
+void timer_init(uint32_t timer_periph, timer_parameter_struct *initpara);
+/* enable a TIMER */
+void timer_enable(uint32_t timer_periph);
+/* disable a TIMER */
+void timer_disable(uint32_t timer_periph);
+/* enable the auto reload shadow function */
+void timer_auto_reload_shadow_enable(uint32_t timer_periph);
+/* disable the auto reload shadow function */
+void timer_auto_reload_shadow_disable(uint32_t timer_periph);
+/* enable the update event */
+void timer_update_event_enable(uint32_t timer_periph);
+/* disable the update event */
+void timer_update_event_disable(uint32_t timer_periph);
+/* set TIMER counter alignment mode */
+void timer_counter_alignment(uint32_t timer_periph, uint16_t aligned);
+/* set TIMER counter up direction */
+void timer_counter_up_direction(uint32_t timer_periph);
+/* set TIMER counter down direction */
+void timer_counter_down_direction(uint32_t timer_periph);
+/* configure TIMER prescaler */
+void timer_prescaler_config(uint32_t timer_periph, uint16_t prescaler, uint8_t pscreload);
+/* configure TIMER repetition register value */
+void timer_repetition_value_config(uint32_t timer_periph, uint16_t repetition);
+/* configure TIMER autoreload register value */
+void timer_autoreload_value_config(uint32_t timer_periph, uint32_t autoreload);
+/* configure TIMER counter register value */
+void timer_counter_value_config(uint32_t timer_periph, uint32_t counter);
+/* read TIMER counter value */
+uint32_t timer_counter_read(uint32_t timer_periph);
+/* read TIMER prescaler value */
+uint16_t timer_prescaler_read(uint32_t timer_periph);
+/* configure TIMER single pulse mode */
+void timer_single_pulse_mode_config(uint32_t timer_periph, uint8_t spmode);
+/* configure TIMER update source */
+void timer_update_source_config(uint32_t timer_periph, uint8_t update);
+/* OCPRE clear source selection */
+void timer_ocpre_clear_source_config(uint32_t timer_periph, uint8_t ocpreclear);
+
+/* TIMER interrupt and flag*/
+/* get TIMER flags */
+FlagStatus timer_flag_get(uint32_t timer_periph, uint32_t flag);
+/* clear TIMER flags */
+void timer_flag_clear(uint32_t timer_periph, uint32_t flag);
+/* enable the TIMER interrupt */
+void timer_interrupt_enable(uint32_t timer_periph, uint32_t interrupt);
+/* disable the TIMER interrupt */
+void timer_interrupt_disable(uint32_t timer_periph, uint32_t interrupt);
+/* get TIMER interrupt flag */
+FlagStatus timer_interrupt_flag_get(uint32_t timer_periph, uint32_t interrupt);
+/* clear TIMER interrupt flag */
+void timer_interrupt_flag_clear(uint32_t timer_periph, uint32_t interrupt);
+
+/* TIMER DMA and event*/
+/* enable the TIMER DMA */
+void timer_dma_enable(uint32_t timer_periph, uint16_t dma);
+/* disable the TIMER DMA */
+void timer_dma_disable(uint32_t timer_periph, uint16_t dma);
+/* channel DMA request source selection */
+void timer_channel_dma_request_source_select(uint32_t timer_periph, uint8_t dma_request);
+/* configure the TIMER DMA transfer */
+void timer_dma_transfer_config(uint32_t timer_periph, uint32_t dma_baseaddr, uint32_t dma_lenth);
+/* software generate events */
+void timer_event_software_generate(uint32_t timer_periph, uint16_t event);
+
+/* TIMER channel complementary protection */
+/* initialize TIMER break parameter struct */
+void timer_break_struct_para_init(timer_break_parameter_struct *breakpara);
+/* configure TIMER break function */
+void timer_break_config(uint32_t timer_periph, timer_break_parameter_struct *breakpara);
+/* enable TIMER break function */
+void timer_break_enable(uint32_t timer_periph);
+/* disable TIMER break function */
+void timer_break_disable(uint32_t timer_periph);
+/* enable TIMER output automatic function */
+void timer_automatic_output_enable(uint32_t timer_periph);
+/* disable TIMER output automatic function */
+void timer_automatic_output_disable(uint32_t timer_periph);
+/* enable or disable TIMER primary output function */
+void timer_primary_output_config(uint32_t timer_periph, ControlStatus newvalue);
+/* enable or disable channel capture/compare control shadow register */
+void timer_channel_control_shadow_config(uint32_t timer_periph, ControlStatus newvalue);
+/* configure TIMER channel control shadow register update control */
+void timer_channel_control_shadow_update_config(uint32_t timer_periph, uint8_t ccuctl);
+
+/* TIMER channel output */
+/* initialize TIMER channel output parameter struct */
+void timer_channel_output_struct_para_init(timer_oc_parameter_struct *ocpara);
+/* configure TIMER channel output function */
+void timer_channel_output_config(uint32_t timer_periph, uint16_t channel, timer_oc_parameter_struct *ocpara);
+/* configure TIMER channel output compare mode */
+void timer_channel_output_mode_config(uint32_t timer_periph, uint16_t channel, uint16_t ocmode);
+/* configure TIMER channel output pulse value */
+void timer_channel_output_pulse_value_config(uint32_t timer_periph, uint16_t channel, uint32_t pulse);
+/* configure TIMER channel output shadow function */
+void timer_channel_output_shadow_config(uint32_t timer_periph, uint16_t channel, uint16_t ocshadow);
+/* configure TIMER channel output fast function */
+void timer_channel_output_fast_config(uint32_t timer_periph, uint16_t channel, uint16_t ocfast);
+/* configure TIMER channel output clear function */
+void timer_channel_output_clear_config(uint32_t timer_periph, uint16_t channel, uint16_t occlear);
+/* configure TIMER channel output polarity */
+void timer_channel_output_polarity_config(uint32_t timer_periph, uint16_t channel, uint16_t ocpolarity);
+/* configure TIMER channel complementary output polarity */
+void timer_channel_complementary_output_polarity_config(uint32_t timer_periph, uint16_t channel, uint16_t ocnpolarity);
+/* configure TIMER channel enable state */
+void timer_channel_output_state_config(uint32_t timer_periph, uint16_t channel, uint32_t state);
+/* configure TIMER channel complementary output enable state */
+void timer_channel_complementary_output_state_config(uint32_t timer_periph, uint16_t channel, uint16_t ocnstate);
+
+/* TIMER channel input */
+/* initialize TIMER channel input parameter struct */
+void timer_channel_input_struct_para_init(timer_ic_parameter_struct *icpara);
+/* configure TIMER input capture parameter */
+void timer_input_capture_config(uint32_t timer_periph, uint16_t channel, timer_ic_parameter_struct *icpara);
+/* configure TIMER channel input capture prescaler value */
+void timer_channel_input_capture_prescaler_config(uint32_t timer_periph, uint16_t channel, uint16_t prescaler);
+/* read TIMER channel capture compare register value */
+uint32_t timer_channel_capture_value_register_read(uint32_t timer_periph, uint16_t channel);
+/* configure TIMER input pwm capture function */
+void timer_input_pwm_capture_config(uint32_t timer_periph, uint16_t channel, timer_ic_parameter_struct *icpwm);
+/* configure TIMER hall sensor mode */
+void timer_hall_mode_config(uint32_t timer_periph, uint8_t hallmode);
+
+/* TIMER master and slave */
+/* select TIMER input trigger source */
+void timer_input_trigger_source_select(uint32_t timer_periph, uint32_t intrigger);
+/* select TIMER master mode output trigger source */
+void timer_master_output_trigger_source_select(uint32_t timer_periph, uint32_t outrigger);
+/* select TIMER slave mode */
+void timer_slave_mode_select(uint32_t timer_periph, uint32_t slavemode);
+/* configure TIMER master slave mode */
+void timer_master_slave_mode_config(uint32_t timer_periph, uint8_t masterslave);
+/* configure TIMER external trigger input */
+void timer_external_trigger_config(uint32_t timer_periph, uint32_t extprescaler, uint32_t extpolarity, uint32_t extfilter);
+/* configure TIMER quadrature decoder mode */
+void timer_quadrature_decoder_mode_config(uint32_t timer_periph, uint32_t decomode, uint16_t ic0polarity, uint16_t ic1polarity);
+/* configure TIMER internal clock mode */
+void timer_internal_clock_config(uint32_t timer_periph);
+/* configure TIMER the internal trigger as external clock input */
+void timer_internal_trigger_as_external_clock_config(uint32_t timer_periph, uint32_t intrigger);
+/* configure TIMER the external trigger as external clock input */
+void timer_external_trigger_as_external_clock_config(uint32_t timer_periph, uint32_t extrigger, uint16_t extpolarity, uint32_t extfilter);
+/* configure TIMER the external clock mode 0 */
+void timer_external_clock_mode0_config(uint32_t timer_periph, uint32_t extprescaler, uint32_t extpolarity, uint32_t extfilter);
+/* configure TIMER the external clock mode 1 */
+void timer_external_clock_mode1_config(uint32_t timer_periph, uint32_t extprescaler, uint32_t extpolarity, uint32_t extfilter);
+/* disable TIMER the external clock mode 1 */
+void timer_external_clock_mode1_disable(uint32_t timer_periph);
+/* configure TIMER channel remap function */
+void timer_channel_remap_config(uint32_t timer_periph, uint32_t remap);
+
+/* TIMER configure */
+/* configure TIMER write CHxVAL register selection */
+void timer_write_chxval_register_config(uint32_t timer_periph, uint16_t ccsel);
+/* configure TIMER output value selection */
+void timer_output_value_selection_config(uint32_t timer_periph, uint16_t outsel);
+
+#endif /* GD32F3X0_TIMER_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_tsi.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_tsi.h
new file mode 100644
index 00000000..b3429bf9
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_tsi.h
@@ -0,0 +1,390 @@
+/*!
+ \file gd32f3x0_tsi.h
+ \brief definitions for the TSI
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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 GD32F3X0_TSI_H
+#define GD32F3X0_TSI_H
+
+#include "gd32f3x0.h"
+
+/* TSI definitions */
+#define TSI TSI_BASE /*!< TSI base address */
+
+/* registers definitions */
+#define TSI_CTL0 REG32(TSI + 0x00000000U)/*!< TSI control register0 */
+#define TSI_INTEN REG32(TSI + 0x00000004U)/*!< TSI interrupt enable register */
+#define TSI_INTC REG32(TSI + 0x00000008U)/*!< TSI interrupt flag clear register */
+#define TSI_INTF REG32(TSI + 0x0000000CU)/*!< TSI interrupt flag register */
+#define TSI_PHM REG32(TSI + 0x00000010U)/*!< TSI pin hysteresis mode register */
+#define TSI_ASW REG32(TSI + 0x00000018U)/*!< TSI analog switch register */
+#define TSI_SAMPCFG REG32(TSI + 0x00000020U)/*!< TSI sample configuration register */
+#define TSI_CHCFG REG32(TSI + 0x00000028U)/*!< TSI channel configuration register */
+#define TSI_GCTL REG32(TSI + 0x00000030U)/*!< TSI group control register */
+#define TSI_G0CYCN REG32(TSI + 0x00000034U)/*!< TSI group 0 cycle number register */
+#define TSI_G1CYCN REG32(TSI + 0x00000038U)/*!< TSI group 1 cycle number register */
+#define TSI_G2CYCN REG32(TSI + 0x0000003CU)/*!< TSI group 2 cycle number register */
+#define TSI_G3CYCN REG32(TSI + 0x00000040U)/*!< TSI group 3 cycle number register */
+#define TSI_G4CYCN REG32(TSI + 0x00000044U)/*!< TSI group 4 cycle number register */
+#define TSI_G5CYCN REG32(TSI + 0x00000048U)/*!< TSI group 5 cycle number register */
+#define TSI_CTL1 REG32(TSI + 0x00000300U)/*!< TSI control registers1 */
+
+/* bits definitions */
+/* TSI_CTL0 */
+#define TSI_CTL0_TSIEN BIT(0) /*!< TSI enable */
+#define TSI_CTL0_TSIS BIT(1) /*!< TSI start */
+#define TSI_CTL0_TRGMOD BIT(2) /*!< trigger mode selection */
+#define TSI_CTL0_EGSEL BIT(3) /*!< edge selection */
+#define TSI_CTL0_PINMOD BIT(4) /*!< pin mode */
+#define TSI_CTL0_MCN BITS(5,7) /*!< max cycle number of a sequence */
+#define TSI_CTL0_CTCDIV BITS(12,14) /*!< CTCLK clock division factor */
+#define TSI_CTL0_ECDIV BIT(15) /*!< ECCLK clock division factor */
+#define TSI_CTL0_ECEN BIT(16) /*!< extend charge state enable */
+#define TSI_CTL0_ECDT BITS(17,23) /*!< extend charge State maximum duration time */
+#define TSI_CTL0_CTDT BITS(24,27) /*!< charge transfer state duration time */
+#define TSI_CTL0_CDT BITS(28,31) /*!< charge state duration time */
+
+/* TSI_INTEN */
+#define TSI_INTEN_CTCFIE BIT(0) /*!< charge transfer complete flag interrupt enable */
+#define TSI_INTEN_MNERRIE BIT(1) /*!< max cycle number error interrupt enable */
+
+/* TSI_INTC */
+#define TSI_INTC_CCTCF BIT(0) /*!< clear charge transfer complete flag */
+#define TSI_INTC_CMNERR BIT(1) /*!< clear max cycle number error */
+
+/* TSI_INTF */
+#define TSI_INTF_CTCF BIT(0) /*!< charge transfer complete flag */
+#define TSI_INTF_MNERR BIT(1) /*!< max cycle number error */
+
+/* TSI_PHM */
+#define TSI_PHM_G0P0 BIT(0) /*!< pin G0P0 Schmitt trigger hysteresis state */
+#define TSI_PHM_G0P1 BIT(1) /*!< pin G0P1 Schmitt trigger hysteresis state */
+#define TSI_PHM_G0P2 BIT(2) /*!< pin G0P2 Schmitt trigger hysteresis state */
+#define TSI_PHM_G0P3 BIT(3) /*!< pin G0P3 Schmitt trigger hysteresis state */
+#define TSI_PHM_G1P0 BIT(4) /*!< pin G1P0 Schmitt trigger hysteresis state */
+#define TSI_PHM_G1P1 BIT(5) /*!< pin G1P1 Schmitt trigger hysteresis state */
+#define TSI_PHM_G1P2 BIT(6) /*!< pin G1P2 Schmitt trigger hysteresis state */
+#define TSI_PHM_G1P3 BIT(7) /*!< pin G1P3 Schmitt trigger hysteresis state */
+#define TSI_PHM_G2P0 BIT(8) /*!< pin G2P0 Schmitt trigger hysteresis state */
+#define TSI_PHM_G2P1 BIT(9) /*!< pin G2P1 Schmitt trigger hysteresis state */
+#define TSI_PHM_G2P2 BIT(10) /*!< pin G2P2 Schmitt trigger hysteresis state */
+#define TSI_PHM_G2P3 BIT(11) /*!< pin G2P3 Schmitt trigger hysteresis state */
+#define TSI_PHM_G3P0 BIT(12) /*!< pin G3P0 Schmitt trigger hysteresis state */
+#define TSI_PHM_G3P1 BIT(13) /*!< pin G3P1 Schmitt trigger hysteresis state */
+#define TSI_PHM_G3P2 BIT(14) /*!< pin G3P2 Schmitt trigger hysteresis state */
+#define TSI_PHM_G3P3 BIT(15) /*!< pin G3P3 Schmitt trigger hysteresis state */
+#define TSI_PHM_G4P0 BIT(16) /*!< pin G4P0 Schmitt trigger hysteresis state */
+#define TSI_PHM_G4P1 BIT(17) /*!< pin G4P1 Schmitt trigger hysteresis state */
+#define TSI_PHM_G4P2 BIT(18) /*!< pin G4P2 Schmitt trigger hysteresis state */
+#define TSI_PHM_G4P3 BIT(19) /*!< pin G4P3 Schmitt trigger hysteresis state */
+#define TSI_PHM_G5P0 BIT(20) /*!< pin G5P0 Schmitt trigger hysteresis state */
+#define TSI_PHM_G5P1 BIT(21) /*!< pin G5P1 Schmitt trigger hysteresis state */
+#define TSI_PHM_G5P2 BIT(22) /*!< pin G5P2 Schmitt trigger hysteresis state */
+#define TSI_PHM_G5P3 BIT(23) /*!< pin G5P3 Schmitt trigger hysteresis state */
+
+/* TSI_ASW */
+#define TSI_ASW_G0P0 BIT(0) /*!< pin G0P0 analog switch state */
+#define TSI_ASW_G0P1 BIT(1) /*!< pin G0P1 analog switch state */
+#define TSI_ASW_G0P2 BIT(2) /*!< pin G0P2 analog switch state */
+#define TSI_ASW_G0P3 BIT(3) /*!< pin G0P3 analog switch state */
+#define TSI_ASW_G1P0 BIT(4) /*!< pin G1P0 analog switch state */
+#define TSI_ASW_G1P1 BIT(5) /*!< pin G1P1 analog switch state */
+#define TSI_ASW_G1P2 BIT(6) /*!< pin G1P2 analog switch state */
+#define TSI_ASW_G1P3 BIT(7) /*!< pin G1P3 analog switch state */
+#define TSI_ASW_G2P0 BIT(8) /*!< pin G2P0 analog switch state */
+#define TSI_ASW_G2P1 BIT(9) /*!< pin G2P1 analog switch state */
+#define TSI_ASW_G2P2 BIT(10) /*!< pin G2P2 analog switch state */
+#define TSI_ASW_G2P3 BIT(11) /*!< pin G2P3 analog switch state */
+#define TSI_ASW_G3P0 BIT(12) /*!< pin G3P0 analog switch state */
+#define TSI_ASW_G3P1 BIT(13) /*!< pin G3P1 analog switch state */
+#define TSI_ASW_G3P2 BIT(14) /*!< pin G3P2 analog switch state */
+#define TSI_ASW_G3P3 BIT(15) /*!< pin G3P3 analog switch state */
+#define TSI_ASW_G4P0 BIT(16) /*!< pin G4P0 analog switch state */
+#define TSI_ASW_G4P1 BIT(17) /*!< pin G4P1 analog switch state */
+#define TSI_ASW_G4P2 BIT(18) /*!< pin G4P2 analog switch state */
+#define TSI_ASW_G4P3 BIT(19) /*!< pin G4P3 analog switch state */
+#define TSI_ASW_G5P0 BIT(20) /*!< pin G5P0 analog switch state */
+#define TSI_ASW_G5P1 BIT(21) /*!< pin G5P1 analog switch state */
+#define TSI_ASW_G5P2 BIT(22) /*!< pin G5P2 analog switch state */
+#define TSI_ASW_G5P3 BIT(23) /*!< pin G5P3 analog switch state */
+
+/* TSI_SAMPCFG */
+#define TSI_SAMPCFG_G0P0 BIT(0) /*!< pin G0P0 sample pin mode */
+#define TSI_SAMPCFG_G0P1 BIT(1) /*!< pin G0P1 sample pin mode */
+#define TSI_SAMPCFG_G0P2 BIT(2) /*!< pin G0P2 sample pin mode */
+#define TSI_SAMPCFG_G0P3 BIT(3) /*!< pin G0P3 sample pin mode */
+#define TSI_SAMPCFG_G1P0 BIT(4) /*!< pin G1P0 sample pin mode */
+#define TSI_SAMPCFG_G1P1 BIT(5) /*!< pin G1P1 sample pin mode */
+#define TSI_SAMPCFG_G1P2 BIT(6) /*!< pin G1P2 sample pin mode */
+#define TSI_SAMPCFG_G1P3 BIT(7) /*!< pin G1P3 sample pin mode */
+#define TSI_SAMPCFG_G2P0 BIT(8) /*!< pin G2P0 sample pin mode */
+#define TSI_SAMPCFG_G2P1 BIT(9) /*!< pin G2P1 sample pin mode */
+#define TSI_SAMPCFG_G2P2 BIT(10) /*!< pin G2P2 sample pin mode */
+#define TSI_SAMPCFG_G2P3 BIT(11) /*!< pin G2P3 sample pin mode */
+#define TSI_SAMPCFG_G3P0 BIT(12) /*!< pin G3P0 sample pin mode */
+#define TSI_SAMPCFG_G3P1 BIT(13) /*!< pin G3P1 sample pin mode */
+#define TSI_SAMPCFG_G3P2 BIT(14) /*!< pin G3P2 sample pin mode */
+#define TSI_SAMPCFG_G3P3 BIT(15) /*!< pin G3P3 sample pin mode */
+#define TSI_SAMPCFG_G4P0 BIT(16) /*!< pin G4P0 sample pin mode */
+#define TSI_SAMPCFG_G4P1 BIT(17) /*!< pin G4P1 sample pin mode */
+#define TSI_SAMPCFG_G4P2 BIT(18) /*!< pin G4P2 sample pin mode */
+#define TSI_SAMPCFG_G4P3 BIT(19) /*!< pin G4P3 sample pin mode */
+#define TSI_SAMPCFG_G5P0 BIT(20) /*!< pin G5P0 sample pin mode */
+#define TSI_SAMPCFG_G5P1 BIT(21) /*!< pin G5P1 sample pin mode */
+#define TSI_SAMPCFG_G5P2 BIT(22) /*!< pin G5P2 sample pin mode */
+#define TSI_SAMPCFG_G5P3 BIT(23) /*!< pin G5P3 sample pin mode */
+
+/* TSI_CHCFG */
+#define TSI_CHCFG_G0P0 BIT(0) /*!< pin G0P0 channel pin mode */
+#define TSI_CHCFG_G0P1 BIT(1) /*!< pin G0P1 channel pin mode */
+#define TSI_CHCFG_G0P2 BIT(2) /*!< pin G0P2 channel pin mode */
+#define TSI_CHCFG_G0P3 BIT(3) /*!< pin G0P3 channel pin mode */
+#define TSI_CHCFG_G1P0 BIT(4) /*!< pin G1P0 channel pin mode */
+#define TSI_CHCFG_G1P1 BIT(5) /*!< pin G1P1 channel pin mode */
+#define TSI_CHCFG_G1P2 BIT(6) /*!< pin G1P2 channel pin mode */
+#define TSI_CHCFG_G1P3 BIT(7) /*!< pin G1P3 channel pin mode */
+#define TSI_CHCFG_G2P0 BIT(8) /*!< pin G2P0 channel pin mode */
+#define TSI_CHCFG_G2P1 BIT(9) /*!< pin G2P1 channel pin mode */
+#define TSI_CHCFG_G2P2 BIT(10) /*!< pin G2P2 channel pin mode */
+#define TSI_CHCFG_G2P3 BIT(11) /*!< pin G2P3 channel pin mode */
+#define TSI_CHCFG_G3P0 BIT(12) /*!< pin G3P0 channel pin mode */
+#define TSI_CHCFG_G3P1 BIT(13) /*!< pin G3P1 channel pin mode */
+#define TSI_CHCFG_G3P2 BIT(14) /*!< pin G3P2 channel pin mode */
+#define TSI_CHCFG_G3P3 BIT(15) /*!< pin G3P3 channel pin mode */
+#define TSI_CHCFG_G4P0 BIT(16) /*!< pin G4P0 channel pin mode */
+#define TSI_CHCFG_G4P1 BIT(17) /*!< pin G4P1 channel pin mode */
+#define TSI_CHCFG_G4P2 BIT(18) /*!< pin G4P2 channel pin mode */
+#define TSI_CHCFG_G4P3 BIT(19) /*!< pin G4P3 channel pin mode */
+#define TSI_CHCFG_G5P0 BIT(20) /*!< pin G5P0 channel pin mode */
+#define TSI_CHCFG_G5P1 BIT(21) /*!< pin G5P1 channel pin mode */
+#define TSI_CHCFG_G5P2 BIT(22) /*!< pin G5P2 channel pin mode */
+#define TSI_CHCFG_G5P3 BIT(23) /*!< pin G5P3 channel pin mode */
+
+/* TSI_GCTL */
+#define TSI_GCTL_GE0 BIT(0) /*!< group0 enable */
+#define TSI_GCTL_GE1 BIT(1) /*!< group1 enable */
+#define TSI_GCTL_GE2 BIT(2) /*!< group2 enable */
+#define TSI_GCTL_GE3 BIT(3) /*!< group3 enable */
+#define TSI_GCTL_GE4 BIT(4) /*!< group4 enable */
+#define TSI_GCTL_GE5 BIT(5) /*!< group5 enable */
+#define TSI_GCTL_GC0 BIT(16) /*!< group0 complete */
+#define TSI_GCTL_GC1 BIT(17) /*!< group1 complete */
+#define TSI_GCTL_GC2 BIT(18) /*!< group2 complete */
+#define TSI_GCTL_GC3 BIT(19) /*!< group3 complete */
+#define TSI_GCTL_GC4 BIT(20) /*!< group4 complete */
+#define TSI_GCTL_GC5 BIT(21) /*!< group5 complete */
+
+/* TSI_CTL1 */
+#define TSI_CTL1_CTCDIV BIT(24) /*!< CTCLK clock division factor */
+#define TSI_CTL1_ECDIV BITS(28,29) /*!< ECCLK clock division factor */
+
+/* constants definitions */
+/* TSI interrupt enable bit */
+#define TSI_INT_CCTCF TSI_INTEN_CTCFIE /*!< charge transfer complete flag interrupt enable */
+#define TSI_INT_MNERR TSI_INTEN_MNERRIE /*!< max cycle number error interrupt enable */
+
+/* TSI interrupt flags */
+#define TSI_INT_FLAG_CTCF TSI_INTF_CTCF /*!< charge transfer complete flag */
+#define TSI_INT_FLAG_MNERR TSI_INTF_MNERR /*!< max cycle number error */
+
+/* TSI flags */
+#define TSI_FLAG_CTCF TSI_INTF_CTCF /*!< charge transfer complete flag */
+#define TSI_FLAG_MNERR TSI_INTF_MNERR /*!< max cycle number error */
+
+/* CTCLK clock division factor */
+#define TSI_CTCDIV_DIV1 ((uint32_t)0x00000000U) /*!< fCTCLK = fHCLK */
+#define TSI_CTCDIV_DIV2 ((uint32_t)0x00000001U) /*!< fCTCLK = fHCLK/2 */
+#define TSI_CTCDIV_DIV4 ((uint32_t)0x00000002U) /*!< fCTCLK = fHCLK/4 */
+#define TSI_CTCDIV_DIV8 ((uint32_t)0x00000003U) /*!< fCTCLK = fHCLK/8 */
+#define TSI_CTCDIV_DIV16 ((uint32_t)0x00000004U) /*!< fCTCLK = fHCLK/16 */
+#define TSI_CTCDIV_DIV32 ((uint32_t)0x00000005U) /*!< fCTCLK = fHCLK/32 */
+#define TSI_CTCDIV_DIV64 ((uint32_t)0x00000006U) /*!< fCTCLK = fHCLK/64 */
+#define TSI_CTCDIV_DIV128 ((uint32_t)0x00000007U) /*!< fCTCLK = fHCLK/128 */
+#define TSI_CTCDIV_DIV256 ((uint32_t)0x00000008U) /*!< fCTCLK = fHCLK/256 */
+#define TSI_CTCDIV_DIV512 ((uint32_t)0x00000009U) /*!< fCTCLK = fHCLK/512 */
+#define TSI_CTCDIV_DIV1024 ((uint32_t)0x0000000AU) /*!< fCTCLK = fHCLK/1024 */
+#define TSI_CTCDIV_DIV2048 ((uint32_t)0x0000000BU) /*!< fCTCLK = fHCLK/2048 */
+#define TSI_CTCDIV_DIV4096 ((uint32_t)0x0000000CU) /*!< fCTCLK = fHCLK/4096 */
+#define TSI_CTCDIV_DIV8192 ((uint32_t)0x0000000DU) /*!< fCTCLK = fHCLK/8192 */
+#define TSI_CTCDIV_DIV16384 ((uint32_t)0x0000000EU) /*!< fCTCLK = fHCLK/16384 */
+#define TSI_CTCDIV_DIV32768 ((uint32_t)0x0000000FU) /*!< fCTCLK = fHCLK/32768 */
+
+/* charge transfer state duration Time */
+#define CTL_CTDT(regval) (BITS(24,27) & ((uint32_t)(regval) << 24U))
+#define TSI_TRANSFER_1CTCLK CTL_CTDT(0) /*!< the duration time of transfer state is 1 CTCLK */
+#define TSI_TRANSFER_2CTCLK CTL_CTDT(1) /*!< the duration time of transfer state is 2 CTCLK */
+#define TSI_TRANSFER_3CTCLK CTL_CTDT(2) /*!< the duration time of transfer state is 3 CTCLK */
+#define TSI_TRANSFER_4CTCLK CTL_CTDT(3) /*!< the duration time of transfer state is 4 CTCLK */
+#define TSI_TRANSFER_5CTCLK CTL_CTDT(4) /*!< the duration time of transfer state is 5 CTCLK */
+#define TSI_TRANSFER_6CTCLK CTL_CTDT(5) /*!< the duration time of transfer state is 6 CTCLK */
+#define TSI_TRANSFER_7CTCLK CTL_CTDT(6) /*!< the duration time of transfer state is 7 CTCLK */
+#define TSI_TRANSFER_8CTCLK CTL_CTDT(7) /*!< the duration time of transfer state is 8 CTCLK */
+#define TSI_TRANSFER_9CTCLK CTL_CTDT(8) /*!< the duration time of transfer state is 9 CTCLK */
+#define TSI_TRANSFER_10CTCLK CTL_CTDT(9) /*!< the duration time of transfer state is 10 CTCLK */
+#define TSI_TRANSFER_11CTCLK CTL_CTDT(10) /*!< the duration time of transfer state is 11 CTCLK */
+#define TSI_TRANSFER_12CTCLK CTL_CTDT(11) /*!< the duration time of transfer state is 12 CTCLK */
+#define TSI_TRANSFER_13CTCLK CTL_CTDT(12) /*!< the duration time of transfer state is 13 CTCLK */
+#define TSI_TRANSFER_14CTCLK CTL_CTDT(13) /*!< the duration time of transfer state is 14 CTCLK */
+#define TSI_TRANSFER_15CTCLK CTL_CTDT(14) /*!< the duration time of transfer state is 15 CTCLK */
+#define TSI_TRANSFER_16CTCLK CTL_CTDT(15) /*!< the duration time of transfer state is 16 CTCLK */
+
+/* charge state duration time */
+#define CTL_CDT(regval) (BITS(28,31) & ((uint32_t)(regval) << 28U))
+#define TSI_CHARGE_1CTCLK CTL_CDT(0) /*!< the duration time of charge state is 1 CTCLK */
+#define TSI_CHARGE_2CTCLK CTL_CDT(1) /*!< the duration time of charge state is 2 CTCLK */
+#define TSI_CHARGE_3CTCLK CTL_CDT(2) /*!< the duration time of charge state is 3 CTCLK */
+#define TSI_CHARGE_4CTCLK CTL_CDT(3) /*!< the duration time of charge state is 4 CTCLK */
+#define TSI_CHARGE_5CTCLK CTL_CDT(4) /*!< the duration time of charge state is 5 CTCLK */
+#define TSI_CHARGE_6CTCLK CTL_CDT(5) /*!< the duration time of charge state is 6 CTCLK */
+#define TSI_CHARGE_7CTCLK CTL_CDT(6) /*!< the duration time of charge state is 7 CTCLK */
+#define TSI_CHARGE_8CTCLK CTL_CDT(7) /*!< the duration time of charge state is 8 CTCLK */
+#define TSI_CHARGE_9CTCLK CTL_CDT(8) /*!< the duration time of charge state is 9 CTCLK */
+#define TSI_CHARGE_10CTCLK CTL_CDT(9) /*!< the duration time of charge state is 10 CTCLK */
+#define TSI_CHARGE_11CTCLK CTL_CDT(10) /*!< the duration time of charge state is 11 CTCLK */
+#define TSI_CHARGE_12CTCLK CTL_CDT(11) /*!< the duration time of charge state is 12 CTCLK */
+#define TSI_CHARGE_13CTCLK CTL_CDT(12) /*!< the duration time of charge state is 13 CTCLK */
+#define TSI_CHARGE_14CTCLK CTL_CDT(13) /*!< the duration time of charge state is 14 CTCLK */
+#define TSI_CHARGE_15CTCLK CTL_CDT(14) /*!< the duration time of charge state is 15 CTCLK */
+#define TSI_CHARGE_16CTCLK CTL_CDT(15) /*!< the duration time of charge state is 16 CTCLK */
+
+/* max cycle number of a sequence */
+#define CTL_MCN(regval) (BITS(5,7) & ((uint32_t)(regval) << 5U))
+#define TSI_MAXNUM255 CTL_MCN(0) /*!< the max cycle number of a sequence is 255 */
+#define TSI_MAXNUM511 CTL_MCN(1) /*!< the max cycle number of a sequence is 511 */
+#define TSI_MAXNUM1023 CTL_MCN(2) /*!< the max cycle number of a sequence is 1023 */
+#define TSI_MAXNUM2047 CTL_MCN(3) /*!< the max cycle number of a sequence is 2047 */
+#define TSI_MAXNUM4095 CTL_MCN(4) /*!< the max cycle number of a sequence is 4095 */
+#define TSI_MAXNUM8191 CTL_MCN(5) /*!< the max cycle number of a sequence is 8191 */
+#define TSI_MAXNUM16383 CTL_MCN(6) /*!< the max cycle number of a sequence is 16383 */
+
+/* ECCLK clock division factor */
+#define TSI_EXTEND_DIV1 ((uint32_t)0x00000000U) /*!< fECCLK = fHCLK */
+#define TSI_EXTEND_DIV2 ((uint32_t)0x00000001U) /*!< fECCLK = fHCLK/2 */
+#define TSI_EXTEND_DIV3 ((uint32_t)0x00000002U) /*!< fECCLK = fHCLK/3 */
+#define TSI_EXTEND_DIV4 ((uint32_t)0x00000003U) /*!< fECCLK = fHCLK/4 */
+#define TSI_EXTEND_DIV5 ((uint32_t)0x00000004U) /*!< fECCLK = fHCLK/5 */
+#define TSI_EXTEND_DIV6 ((uint32_t)0x00000005U) /*!< fECCLK = fHCLK/6 */
+#define TSI_EXTEND_DIV7 ((uint32_t)0x00000006U) /*!< fECCLK = fHCLK/7 */
+#define TSI_EXTEND_DIV8 ((uint32_t)0x00000007U) /*!< fECCLK = fHCLK/8 */
+
+/* extend charge state maximum duration time */
+#define TSI_EXTENDMAX(regval) (BITS(17,23) & ((uint32_t)(regval) << 17U)) /* value range 1..128,extend charge state maximum duration time */
+
+/* hardware trigger mode */
+#define TSI_FALLING_TRIGGER 0x00U /*!< falling edge trigger TSI charge transfer sequence */
+#define TSI_RISING_TRIGGER 0x01U /*!< rising edge trigger TSI charge transfer sequence */
+
+/* pin mode */
+#define TSI_OUTPUT_LOW 0x00U /*!< TSI pin will output low when IDLE */
+#define TSI_INPUT_FLOATING 0x01U /*!< TSI pin will keep input_floating when IDLE */
+
+/* function declarations */
+/* reset TSI peripheral */
+void tsi_deinit(void);
+/* initialize TSI plus prescaler,charge plus,transfer plus,max cycle number */
+void tsi_init(uint32_t prescaler, uint32_t charge_duration, uint32_t transfer_duration, uint32_t max_number);
+/* enable TSI module */
+void tsi_enable(void);
+/* disable TSI module */
+void tsi_disable(void);
+/* enable sample pin */
+void tsi_sample_pin_enable(uint32_t sample);
+/* disable sample pin */
+void tsi_sample_pin_disable(uint32_t sample);
+/* enable channel pin */
+void tsi_channel_pin_enable(uint32_t channel);
+/* disable channel pin */
+void tsi_channel_pin_disable(uint32_t channel);
+
+/* configure TSI triggering by software */
+void tsi_software_mode_config(void);
+/* start a charge-transfer sequence when TSI is in software trigger mode */
+void tsi_software_start(void);
+/* stop a charge-transfer sequence when TSI is in software trigger mode */
+void tsi_software_stop(void);
+/* configure TSI triggering by hardware */
+void tsi_hardware_mode_config(uint8_t trigger_edge);
+/* configure TSI pin mode when charge-transfer sequence is IDLE */
+void tsi_pin_mode_config(uint8_t pin_mode);
+/* configure extend charge state */
+void tsi_extend_charge_config(ControlStatus extend, uint8_t prescaler, uint32_t max_duration);
+
+/* configure charge plus and transfer plus */
+void tsi_plus_config(uint32_t prescaler, uint32_t charge_duration, uint32_t transfer_duration);
+/* configure the max cycle number of a charge-transfer sequence */
+void tsi_max_number_config(uint32_t max_number);
+/* switch on hysteresis pin */
+void tsi_hysteresis_on(uint32_t group_pin);
+/* switch off hysteresis pin */
+void tsi_hysteresis_off(uint32_t group_pin);
+/* switch on analog pin */
+void tsi_analog_on(uint32_t group_pin);
+/* switch off analog pin */
+void tsi_analog_off(uint32_t group_pin);
+
+/* enbale group */
+void tsi_group_enable(uint32_t group);
+/* disbale group */
+void tsi_group_disable(uint32_t group);
+/* get group complete status */
+FlagStatus tsi_group_status_get(uint32_t group);
+/* get the cycle number for group0 as soon as a charge-transfer sequence completes */
+uint16_t tsi_group0_cycle_get(void);
+/* get the cycle number for group1 as soon as a charge-transfer sequence completes */
+uint16_t tsi_group1_cycle_get(void);
+/* get the cycle number for group2 as soon as a charge-transfer sequence completes */
+uint16_t tsi_group2_cycle_get(void);
+/* get the cycle number for group3 as soon as a charge-transfer sequence completes */
+uint16_t tsi_group3_cycle_get(void);
+/* get the cycle number for group4 as soon as a charge-transfer sequence completes */
+uint16_t tsi_group4_cycle_get(void);
+/* get the cycle number for group5 as soon as a charge-transfer sequence completes */
+uint16_t tsi_group5_cycle_get(void);
+
+/* clear flag */
+void tsi_flag_clear(uint32_t flag);
+/* get flag */
+FlagStatus tsi_flag_get(uint32_t flag);
+
+/* enable TSI interrupt */
+void tsi_interrupt_enable(uint32_t source);
+/* disable TSI interrupt */
+void tsi_interrupt_disable(uint32_t source);
+/* clear interrupt flag */
+void tsi_interrupt_flag_clear(uint32_t flag);
+/* get TSI interrupt flag */
+FlagStatus tsi_interrupt_flag_get(uint32_t flag);
+
+#endif /* GD32F3X0_TSI_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_usart.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_usart.h
new file mode 100644
index 00000000..c471a814
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_usart.h
@@ -0,0 +1,595 @@
+/*!
+ \file gd32f3x0_usart.h
+ \brief definitions for the USART
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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 GD32F3X0_USART_H
+#define GD32F3X0_USART_H
+
+#include "gd32f3x0.h"
+
+/* USARTx(x=0,1) definitions */
+#define USART0 (USART_BASE + 0x0000F400U)
+#define USART1 USART_BASE
+
+/* registers definitions */
+#define USART_CTL0(usartx) REG32((usartx) + 0x00000000U) /*!< USART control register 0 */
+#define USART_CTL1(usartx) REG32((usartx) + 0x00000004U) /*!< USART control register 1 */
+#define USART_CTL2(usartx) REG32((usartx) + 0x00000008U) /*!< USART control register 2 */
+#define USART_BAUD(usartx) REG32((usartx) + 0x0000000CU) /*!< USART baud rate register */
+#define USART_GP(usartx) REG32((usartx) + 0x00000010U) /*!< USART guard time and prescaler register */
+#define USART_RT(usartx) REG32((usartx) + 0x00000014U) /*!< USART receiver timeout register */
+#define USART_CMD(usartx) REG32((usartx) + 0x00000018U) /*!< USART command register */
+#define USART_STAT(usartx) REG32((usartx) + 0x0000001CU) /*!< USART status register */
+#define USART_INTC(usartx) REG32((usartx) + 0x00000020U) /*!< USART status clear register */
+#define USART_RDATA(usartx) REG32((usartx) + 0x00000024U) /*!< USART receive data register */
+#define USART_TDATA(usartx) REG32((usartx) + 0x00000028U) /*!< USART transmit data register */
+#define USART_RFCS(usartx) REG32((usartx) + 0x000000D0U) /*!< USART receive FIFO control and status register */
+
+/* bits definitions */
+/* USARTx_CTL0 */
+#define USART_CTL0_UEN BIT(0) /*!< USART enable */
+#define USART_CTL0_UESM BIT(1) /*!< USART enable in deep-sleep mode */
+#define USART_CTL0_REN BIT(2) /*!< receiver enable */
+#define USART_CTL0_TEN BIT(3) /*!< transmitter enable */
+#define USART_CTL0_IDLEIE BIT(4) /*!< idle line detected interrupt enable */
+#define USART_CTL0_RBNEIE BIT(5) /*!< read data buffer not empty interrupt and overrun error interrupt enable */
+#define USART_CTL0_TCIE BIT(6) /*!< transmission complete interrupt enable */
+#define USART_CTL0_TBEIE BIT(7) /*!< transmitter register empty interrupt enable */
+#define USART_CTL0_PERRIE BIT(8) /*!< parity error interrupt enable */
+#define USART_CTL0_PM BIT(9) /*!< parity mode */
+#define USART_CTL0_PCEN BIT(10) /*!< parity control enable */
+#define USART_CTL0_WM BIT(11) /*!< wakeup method in mute mode */
+#define USART_CTL0_WL BIT(12) /*!< word length */
+#define USART_CTL0_MEN BIT(13) /*!< mute mode enable */
+#define USART_CTL0_AMIE BIT(14) /*!< address match interrupt enable */
+#define USART_CTL0_OVSMOD BIT(15) /*!< oversample mode */
+#define USART_CTL0_DED BITS(16,20) /*!< driver enable deassertion time */
+#define USART_CTL0_DEA BITS(21,25) /*!< driver enable assertion time */
+#define USART_CTL0_RTIE BIT(26) /*!< receiver timeout interrupt enable */
+#define USART_CTL0_EBIE BIT(27) /*!< end of block interrupt enable */
+
+/* USARTx_CTL1 */
+#define USART_CTL1_ADDM BIT(4) /*!< address detection mode */
+#define USART_CTL1_LBLEN BIT(5) /*!< LIN break frame length */
+#define USART_CTL1_LBDIE BIT(6) /*!< LIN break detection interrupt enable */
+#define USART_CTL1_CLEN BIT(8) /*!< last bit clock pulse */
+#define USART_CTL1_CPH BIT(9) /*!< clock phase */
+#define USART_CTL1_CPL BIT(10) /*!< clock polarity */
+#define USART_CTL1_CKEN BIT(11) /*!< ck pin enable */
+#define USART_CTL1_STB BITS(12,13) /*!< stop bits length */
+#define USART_CTL1_LMEN BIT(14) /*!< LIN mode enable */
+#define USART_CTL1_STRP BIT(15) /*!< swap TX/RX pins */
+#define USART_CTL1_RINV BIT(16) /*!< RX pin level inversion */
+#define USART_CTL1_TINV BIT(17) /*!< TX pin level inversion */
+#define USART_CTL1_DINV BIT(18) /*!< data bit level inversion */
+#define USART_CTL1_MSBF BIT(19) /*!< most significant bit first */
+#define USART_CTL1_ABDEN BIT(20) /*!< auto baud rate enable */
+#define USART_CTL1_ABDM BITS(21,22) /*!< auto baud rate mode */
+#define USART_CTL1_RTEN BIT(23) /*!< receiver timeout enable */
+#define USART_CTL1_ADDR BITS(24,31) /*!< address of the USART terminal */
+
+/* USARTx_CTL2 */
+#define USART_CTL2_ERRIE BIT(0) /*!< error interrupt enable in multibuffer communication */
+#define USART_CTL2_IREN BIT(1) /*!< IrDA mode enable */
+#define USART_CTL2_IRLP BIT(2) /*!< IrDA low-power */
+#define USART_CTL2_HDEN BIT(3) /*!< half-duplex enable */
+#define USART_CTL2_NKEN BIT(4) /*!< NACK enable in smartcard mode */
+#define USART_CTL2_SCEN BIT(5) /*!< smartcard mode enable */
+#define USART_CTL2_DENR BIT(6) /*!< DMA enable for reception */
+#define USART_CTL2_DENT BIT(7) /*!< DMA enable for transmission */
+#define USART_CTL2_RTSEN BIT(8) /*!< RTS enable */
+#define USART_CTL2_CTSEN BIT(9) /*!< CTS enable */
+#define USART_CTL2_CTSIE BIT(10) /*!< CTS interrupt enable */
+#define USART_CTL2_OSB BIT(11) /*!< one sample bit mode */
+#define USART_CTL2_OVRD BIT(12) /*!< overrun disable */
+#define USART_CTL2_DDRE BIT(13) /*!< disable DMA on reception error */
+#define USART_CTL2_DEM BIT(14) /*!< driver enable mode */
+#define USART_CTL2_DEP BIT(15) /*!< driver enable polarity mode */
+#define USART_CTL2_SCRTNUM BITS(17,19) /*!< smartcard auto-retry number */
+#define USART_CTL2_WUM BITS(20,21) /*!< wakeup mode from deep-sleep mode */
+#define USART_CTL2_WUIE BIT(22) /*!< wakeup from deep-sleep mode interrupt enable */
+
+/* USARTx_BAUD */
+#define USART_BAUD_FRADIV BITS(0,3) /*!< fraction of baud-rate divider */
+#define USART_BAUD_INTDIV BITS(4,15) /*!< integer of baud-rate divider */
+
+/* USARTx_GP */
+#define USART_GP_PSC BITS(0,7) /*!< prescaler value for dividing the system clock */
+#define USART_GP_GUAT BITS(8,15) /*!< guard time value in smartcard mode */
+
+/* USARTx_RT */
+#define USART_RT_RT BITS(0,23) /*!< receiver timeout threshold */
+#define USART_RT_BL BITS(24,31) /*!< block length */
+
+/* USARTx_CMD */
+#define USART_CMD_ABDCMD BIT(0) /*!< auto baudrate detection command */
+#define USART_CMD_SBKCMD BIT(1) /*!< send break command */
+#define USART_CMD_MMCMD BIT(2) /*!< mute mode command */
+#define USART_CMD_RXFCMD BIT(3) /*!< receive data flush command */
+#define USART_CMD_TXFCMD BIT(4) /*!< transmit data flush request */
+
+/* USARTx_STAT */
+#define USART_STAT_PERR BIT(0) /*!< parity error flag */
+#define USART_STAT_FERR BIT(1) /*!< frame error flag */
+#define USART_STAT_NERR BIT(2) /*!< noise error flag */
+#define USART_STAT_ORERR BIT(3) /*!< overrun error */
+#define USART_STAT_IDLEF BIT(4) /*!< idle line detected flag */
+#define USART_STAT_RBNE BIT(5) /*!< read data buffer not empty */
+#define USART_STAT_TC BIT(6) /*!< transmission completed */
+#define USART_STAT_TBE BIT(7) /*!< transmit data register empty */
+#define USART_STAT_LBDF BIT(8) /*!< LIN break detected flag */
+#define USART_STAT_CTSF BIT(9) /*!< CTS change flag */
+#define USART_STAT_CTS BIT(10) /*!< CTS level */
+#define USART_STAT_RTF BIT(11) /*!< receiver timeout flag */
+#define USART_STAT_EBF BIT(12) /*!< end of block flag */
+#define USART_STAT_ABDE BIT(14) /*!< auto baudrate detection error */
+#define USART_STAT_ABDF BIT(15) /*!< auto baudrate detection flag */
+#define USART_STAT_BSY BIT(16) /*!< busy flag */
+#define USART_STAT_AMF BIT(17) /*!< address match flag */
+#define USART_STAT_SBF BIT(18) /*!< send break flag */
+#define USART_STAT_RWU BIT(19) /*!< receiver wakeup from mute mode */
+#define USART_STAT_WUF BIT(20) /*!< wakeup from deep-sleep mode flag */
+#define USART_STAT_TEA BIT(21) /*!< transmit enable acknowledge flag */
+#define USART_STAT_REA BIT(22) /*!< receive enable acknowledge flag */
+
+/* USARTx_INTC */
+#define USART_INTC_PEC BIT(0) /*!< parity error clear */
+#define USART_INTC_FEC BIT(1) /*!< frame error flag clear */
+#define USART_INTC_NEC BIT(2) /*!< noise detected clear */
+#define USART_INTC_OREC BIT(3) /*!< overrun error clear */
+#define USART_INTC_IDLEC BIT(4) /*!< idle line detected clear */
+#define USART_INTC_TCC BIT(6) /*!< transmission complete clear */
+#define USART_INTC_LBDC BIT(8) /*!< LIN break detected clear */
+#define USART_INTC_CTSC BIT(9) /*!< CTS change clear */
+#define USART_INTC_RTC BIT(11) /*!< receiver timeout clear */
+#define USART_INTC_EBC BIT(12) /*!< end of timeout clear */
+#define USART_INTC_AMC BIT(17) /*!< address match clear */
+#define USART_INTC_WUC BIT(20) /*!< wakeup from deep-sleep mode clear */
+
+/* USARTx_RDATA */
+#define USART_RDATA_RDATA BITS(0,8) /*!< receive data value */
+
+/* USARTx_TDATA */
+#define USART_TDATA_TDATA BITS(0,8) /*!< transmit data value */
+
+/* USARTx_RFCS */
+#define USART_RFCS_ELNACK BIT(0) /*!< early NACK */
+#define USART_RFCS_RFEN BIT(8) /*!< receive FIFO enable */
+#define USART_RFCS_RFFIE BIT(9) /*!< receive FIFO full interrupt enable */
+#define USART_RFCS_RFE BIT(10) /*!< receive FIFO empty flag */
+#define USART_RFCS_RFF BIT(11) /*!< receive FIFO full flag */
+#define USART_RFCS_RFCNT BITS(12,14) /*!< receive FIFO counter number */
+#define USART_RFCS_RFFINT BIT(15) /*!< receive FIFO full interrupt flag */
+
+/* constants definitions */
+
+/* define the USART bit position and its register index offset */
+#define USART_REGIDX_BIT(regidx, bitpos) (((uint32_t)(regidx) << 6) | (uint32_t)(bitpos))
+#define USART_REG_VAL(usartx, offset) (REG32((usartx) + (((uint32_t)(offset) & 0x0000FFFFU) >> 6)))
+#define USART_BIT_POS(val) ((uint32_t)(val) & 0x0000001FU)
+#define USART_REGIDX_BIT2(regidx, bitpos, regidx2, bitpos2) (((uint32_t)(regidx2) << 22) | (uint32_t)((bitpos2) << 16)\
+ | (((uint32_t)(regidx) << 6) | (uint32_t)(bitpos)))
+#define USART_REG_VAL2(usartx, offset) (REG32((usartx) + ((uint32_t)(offset) >> 22)))
+#define USART_BIT_POS2(val) (((uint32_t)(val) & 0x001F0000U) >> 16)
+
+/* register offset */
+#define USART_CTL0_REG_OFFSET (0x00000000U) /*!< CTL0 register offset */
+#define USART_CTL1_REG_OFFSET (0x00000004U) /*!< CTL1 register offset */
+#define USART_CTL2_REG_OFFSET (0x00000008U) /*!< CTL2 register offset */
+#define USART_STAT_REG_OFFSET (0x0000001CU) /*!< STAT register offset */
+#define USART_RFCS_REG_OFFSET (0x000000D0U) /*!< RFCS register offset */
+
+/* USART flags */
+typedef enum {
+ /* flags in STAT register */
+ USART_FLAG_REA = USART_REGIDX_BIT(USART_STAT_REG_OFFSET, 22U), /*!< receive enable acknowledge flag */
+ USART_FLAG_TEA = USART_REGIDX_BIT(USART_STAT_REG_OFFSET, 21U), /*!< transmit enable acknowledge flag */
+ USART_FLAG_WU = USART_REGIDX_BIT(USART_STAT_REG_OFFSET, 20U), /*!< wakeup from deep-sleep mode flag */
+ USART_FLAG_RWU = USART_REGIDX_BIT(USART_STAT_REG_OFFSET, 19U), /*!< receiver wakeup from mute mode */
+ USART_FLAG_SB = USART_REGIDX_BIT(USART_STAT_REG_OFFSET, 18U), /*!< send break flag */
+ USART_FLAG_AM = USART_REGIDX_BIT(USART_STAT_REG_OFFSET, 17U), /*!< ADDR match flag */
+ USART_FLAG_BSY = USART_REGIDX_BIT(USART_STAT_REG_OFFSET, 16U), /*!< busy flag */
+ USART_FLAG_ABD = USART_REGIDX_BIT(USART_STAT_REG_OFFSET, 15U), /*!< auto baudrate detection flag */
+ USART_FLAG_ABDE = USART_REGIDX_BIT(USART_STAT_REG_OFFSET, 14U), /*!< auto baudrate detection error */
+ USART_FLAG_EB = USART_REGIDX_BIT(USART_STAT_REG_OFFSET, 12U), /*!< end of block flag */
+ USART_FLAG_RT = USART_REGIDX_BIT(USART_STAT_REG_OFFSET, 11U), /*!< receiver timeout flag */
+ USART_FLAG_CTS = USART_REGIDX_BIT(USART_STAT_REG_OFFSET, 10U), /*!< CTS level */
+ USART_FLAG_CTSF = USART_REGIDX_BIT(USART_STAT_REG_OFFSET, 9U), /*!< CTS change flag */
+ USART_FLAG_LBD = USART_REGIDX_BIT(USART_STAT_REG_OFFSET, 8U), /*!< LIN break detected flag */
+ USART_FLAG_TBE = USART_REGIDX_BIT(USART_STAT_REG_OFFSET, 7U), /*!< transmit data buffer empty */
+ USART_FLAG_TC = USART_REGIDX_BIT(USART_STAT_REG_OFFSET, 6U), /*!< transmission complete */
+ USART_FLAG_RBNE = USART_REGIDX_BIT(USART_STAT_REG_OFFSET, 5U), /*!< read data buffer not empty */
+ USART_FLAG_IDLE = USART_REGIDX_BIT(USART_STAT_REG_OFFSET, 4U), /*!< IDLE line detected flag */
+ USART_FLAG_ORERR = USART_REGIDX_BIT(USART_STAT_REG_OFFSET, 3U), /*!< overrun error */
+ USART_FLAG_NERR = USART_REGIDX_BIT(USART_STAT_REG_OFFSET, 2U), /*!< noise error flag */
+ USART_FLAG_FERR = USART_REGIDX_BIT(USART_STAT_REG_OFFSET, 1U), /*!< frame error flag */
+ USART_FLAG_PERR = USART_REGIDX_BIT(USART_STAT_REG_OFFSET, 0U), /*!< parity error flag */
+ /* flags in RFCS register */
+ USART_FLAG_RFF = USART_REGIDX_BIT(USART_RFCS_REG_OFFSET, 11U), /*!< receive FIFO full flag */
+ USART_FLAG_RFE = USART_REGIDX_BIT(USART_RFCS_REG_OFFSET, 10U), /*!< receive FIFO empty flag */
+} usart_flag_enum;
+
+/* USART interrupt flags */
+typedef enum {
+ /* interrupt flags in CTL0 register */
+ USART_INT_FLAG_EB = USART_REGIDX_BIT2(USART_CTL0_REG_OFFSET, 27U, USART_STAT_REG_OFFSET, 12U), /*!< end of block interrupt flag */
+ USART_INT_FLAG_RT = USART_REGIDX_BIT2(USART_CTL0_REG_OFFSET, 26U, USART_STAT_REG_OFFSET, 11U), /*!< receiver timeout interrupt flag */
+ USART_INT_FLAG_AM = USART_REGIDX_BIT2(USART_CTL0_REG_OFFSET, 14U, USART_STAT_REG_OFFSET, 17U), /*!< address match interrupt flag */
+ USART_INT_FLAG_PERR = USART_REGIDX_BIT2(USART_CTL0_REG_OFFSET, 8U, USART_STAT_REG_OFFSET, 0U), /*!< parity error interrupt flag */
+ USART_INT_FLAG_TBE = USART_REGIDX_BIT2(USART_CTL0_REG_OFFSET, 7U, USART_STAT_REG_OFFSET, 7U), /*!< transmitter buffer empty interrupt flag */
+ USART_INT_FLAG_TC = USART_REGIDX_BIT2(USART_CTL0_REG_OFFSET, 6U, USART_STAT_REG_OFFSET, 6U), /*!< transmission complete interrupt flag */
+ USART_INT_FLAG_RBNE = USART_REGIDX_BIT2(USART_CTL0_REG_OFFSET, 5U, USART_STAT_REG_OFFSET, 5U), /*!< read data buffer not empty interrupt flag */
+ USART_INT_FLAG_RBNE_ORERR = USART_REGIDX_BIT2(USART_CTL0_REG_OFFSET, 5U, USART_STAT_REG_OFFSET, 3U), /*!< overrun error interrupt flag */
+ USART_INT_FLAG_IDLE = USART_REGIDX_BIT2(USART_CTL0_REG_OFFSET, 4U, USART_STAT_REG_OFFSET, 4U), /*!< IDLE line detected interrupt flag */
+ /* interrupt flags in CTL1 register */
+ USART_INT_FLAG_LBD = USART_REGIDX_BIT2(USART_CTL1_REG_OFFSET, 6U, USART_STAT_REG_OFFSET, 8U), /*!< LIN break detected interrupt flag */
+ /* interrupt flags in CTL2 register */
+ USART_INT_FLAG_WU = USART_REGIDX_BIT2(USART_CTL2_REG_OFFSET, 22U, USART_STAT_REG_OFFSET, 20U), /*!< wakeup from deep-sleep mode interrupt flag */
+ USART_INT_FLAG_CTS = USART_REGIDX_BIT2(USART_CTL2_REG_OFFSET, 10U, USART_STAT_REG_OFFSET, 9U), /*!< CTS interrupt flag */
+ USART_INT_FLAG_ERR_NERR = USART_REGIDX_BIT2(USART_CTL2_REG_OFFSET, 0U, USART_STAT_REG_OFFSET, 2U), /*!< noise error interrupt flag */
+ USART_INT_FLAG_ERR_ORERR = USART_REGIDX_BIT2(USART_CTL2_REG_OFFSET, 0U, USART_STAT_REG_OFFSET, 3U), /*!< overrun error interrupt flag */
+ USART_INT_FLAG_ERR_FERR = USART_REGIDX_BIT2(USART_CTL2_REG_OFFSET, 0U, USART_STAT_REG_OFFSET, 1U), /*!< frame error interrupt flag */
+ /* interrupt flags in RFCS register */
+ USART_INT_FLAG_RFFINT = USART_REGIDX_BIT2(USART_RFCS_REG_OFFSET, 9U, USART_RFCS_REG_OFFSET, 15U), /*!< receive FIFO full interrupt flag */
+} usart_interrupt_flag_enum;
+
+/* USART interrupt enable or disable */
+typedef enum {
+ /* interrupt in CTL0 register */
+ USART_INT_EB = USART_REGIDX_BIT(USART_CTL0_REG_OFFSET, 27U), /*!< end of block interrupt */
+ USART_INT_RT = USART_REGIDX_BIT(USART_CTL0_REG_OFFSET, 26U), /*!< receiver timeout interrupt */
+ USART_INT_AM = USART_REGIDX_BIT(USART_CTL0_REG_OFFSET, 14U), /*!< address match interrupt */
+ USART_INT_PERR = USART_REGIDX_BIT(USART_CTL0_REG_OFFSET, 8U), /*!< parity error interrupt */
+ USART_INT_TBE = USART_REGIDX_BIT(USART_CTL0_REG_OFFSET, 7U), /*!< transmitter buffer empty interrupt */
+ USART_INT_TC = USART_REGIDX_BIT(USART_CTL0_REG_OFFSET, 6U), /*!< transmission complete interrupt */
+ USART_INT_RBNE = USART_REGIDX_BIT(USART_CTL0_REG_OFFSET, 5U), /*!< read data buffer not empty interrupt and overrun error interrupt */
+ USART_INT_IDLE = USART_REGIDX_BIT(USART_CTL0_REG_OFFSET, 4U), /*!< IDLE line detected interrupt */
+ /* interrupt in CTL1 register */
+ USART_INT_LBD = USART_REGIDX_BIT(USART_CTL1_REG_OFFSET, 6U), /*!< LIN break detected interrupt */
+ /* interrupt in CTL2 register */
+ USART_INT_WU = USART_REGIDX_BIT(USART_CTL2_REG_OFFSET, 22U), /*!< wakeup from deep-sleep mode interrupt */
+ USART_INT_CTS = USART_REGIDX_BIT(USART_CTL2_REG_OFFSET, 10U), /*!< CTS interrupt */
+ USART_INT_ERR = USART_REGIDX_BIT(USART_CTL2_REG_OFFSET, 0U), /*!< error interrupt */
+ /* interrupt in RFCS register */
+ USART_INT_RFF = USART_REGIDX_BIT(USART_RFCS_REG_OFFSET, 9U), /*!< receive FIFO full interrupt */
+} usart_interrupt_enum;
+
+/* USART invert configure */
+typedef enum {
+ /* data bit level inversion */
+ USART_DINV_ENABLE, /*!< data bit level inversion */
+ USART_DINV_DISABLE, /*!< data bit level not inversion */
+ /* TX pin level inversion */
+ USART_TXPIN_ENABLE, /*!< TX pin level inversion */
+ USART_TXPIN_DISABLE, /*!< TX pin level not inversion */
+ /* RX pin level inversion */
+ USART_RXPIN_ENABLE, /*!< RX pin level inversion */
+ USART_RXPIN_DISABLE, /*!< RX pin level not inversion */
+ /* swap TX/RX pins */
+ USART_SWAP_ENABLE, /*!< swap TX/RX pins */
+ USART_SWAP_DISABLE, /*!< not swap TX/RX pins */
+} usart_invert_enum;
+
+/* USART receiver configure */
+#define CTL0_REN(regval) (BIT(2) & ((uint32_t)(regval) << 2))
+#define USART_RECEIVE_ENABLE CTL0_REN(1) /*!< enable receiver */
+#define USART_RECEIVE_DISABLE CTL0_REN(0) /*!< disable receiver */
+
+/* USART transmitter configure */
+#define CTL0_TEN(regval) (BIT(3) & ((uint32_t)(regval) << 3))
+#define USART_TRANSMIT_ENABLE CTL0_TEN(1) /*!< enable transmitter */
+#define USART_TRANSMIT_DISABLE CTL0_TEN(0) /*!< disable transmitter */
+
+/* USART parity bits definitions */
+#define CTL0_PM(regval) (BITS(9,10) & ((uint32_t)(regval) << 9))
+#define USART_PM_NONE CTL0_PM(0) /*!< no parity */
+#define USART_PM_EVEN CTL0_PM(2) /*!< even parity */
+#define USART_PM_ODD CTL0_PM(3) /*!< odd parity */
+
+/* USART wakeup method in mute mode */
+#define CTL0_WM(regval) (BIT(11) & ((uint32_t)(regval) << 11))
+#define USART_WM_IDLE CTL0_WM(0) /*!< idle line */
+#define USART_WM_ADDR CTL0_WM(1) /*!< address match */
+
+/* USART word length definitions */
+#define CTL0_WL(regval) (BIT(12) & ((uint32_t)(regval) << 12))
+#define USART_WL_8BIT CTL0_WL(0) /*!< 8 bits */
+#define USART_WL_9BIT CTL0_WL(1) /*!< 9 bits */
+
+/* USART oversample mode */
+#define CTL0_OVSMOD(regval) (BIT(15) & ((uint32_t)(regval) << 15))
+#define USART_OVSMOD_8 CTL0_OVSMOD(1) /*!< oversampling by 8 */
+#define USART_OVSMOD_16 CTL0_OVSMOD(0) /*!< oversampling by 16 */
+
+/* USART address detection mode */
+#define CTL1_ADDM(regval) (BIT(4) & ((uint32_t)(regval) << 4))
+#define USART_ADDM_4BIT CTL1_ADDM(0) /*!< 4-bit address detection */
+#define USART_ADDM_FULLBIT CTL1_ADDM(1) /*!< full-bit address detection */
+
+/* USART LIN break frame length */
+#define CTL1_LBLEN(regval) (BIT(5) & ((uint32_t)(regval) << 5))
+#define USART_LBLEN_10B CTL1_LBLEN(0) /*!< 10 bits break detection */
+#define USART_LBLEN_11B CTL1_LBLEN(1) /*!< 11 bits break detection */
+
+/* USART last bit clock pulse */
+#define CTL1_CLEN(regval) (BIT(8) & ((uint32_t)(regval) << 8))
+#define USART_CLEN_NONE CTL1_CLEN(0) /*!< clock pulse of the last data bit (MSB) is not output to the CK pin */
+#define USART_CLEN_EN CTL1_CLEN(1) /*!< clock pulse of the last data bit (MSB) is output to the CK pin */
+
+/* USART clock phase */
+#define CTL1_CPH(regval) (BIT(9) & ((uint32_t)(regval) << 9))
+#define USART_CPH_1CK CTL1_CPH(0) /*!< first clock transition is the first data capture edge */
+#define USART_CPH_2CK CTL1_CPH(1) /*!< second clock transition is the first data capture edge */
+
+/* USART clock polarity */
+#define CTL1_CPL(regval) (BIT(10) & ((uint32_t)(regval) << 10))
+#define USART_CPL_LOW CTL1_CPL(0) /*!< steady low value on CK pin */
+#define USART_CPL_HIGH CTL1_CPL(1) /*!< steady high value on CK pin */
+
+/* USART stop bits definitions */
+#define CTL1_STB(regval) (BITS(12,13) & ((uint32_t)(regval) << 12))
+#define USART_STB_1BIT CTL1_STB(0) /*!< 1 bit */
+#define USART_STB_0_5BIT CTL1_STB(1) /*!< 0.5 bit */
+#define USART_STB_2BIT CTL1_STB(2) /*!< 2 bits */
+#define USART_STB_1_5BIT CTL1_STB(3) /*!< 1.5 bits */
+
+/* USART data is transmitted/received with the LSB/MSB first */
+#define CTL1_MSBF(regval) (BIT(19) & ((uint32_t)(regval) << 19))
+#define USART_MSBF_LSB CTL1_MSBF(0) /*!< LSB first */
+#define USART_MSBF_MSB CTL1_MSBF(1) /*!< MSB first */
+
+/* USART auto baud rate detection mode bits definitions */
+#define CTL1_ABDM(regval) (BITS(21,22) & ((uint32_t)(regval) << 21))
+#define USART_ABDM_FTOR CTL1_ABDM(0) /*!< falling edge to rising edge measurement */
+#define USART_ABDM_FTOF CTL1_ABDM(1) /*!< falling edge to falling edge measurement */
+
+/* USART IrDA low-power enable */
+#define CTL2_IRLP(regval) (BIT(2) & ((uint32_t)(regval) << 2))
+#define USART_IRLP_LOW CTL2_IRLP(1) /*!< low-power */
+#define USART_IRLP_NORMAL CTL2_IRLP(0) /*!< normal */
+
+/* DMA enable for reception */
+#define CTL2_DENR(regval) (BIT(6) & ((uint32_t)(regval) << 6))
+#define USART_DENR_ENABLE CTL2_DENR(1) /*!< enable for reception */
+#define USART_DENR_DISABLE CTL2_DENR(0) /*!< disable for reception */
+
+/* DMA enable for transmission */
+#define CTL2_DENT(regval) (BIT(7) & ((uint32_t)(regval) << 7))
+#define USART_DENT_ENABLE CTL2_DENT(1) /*!< enable for transmission */
+#define USART_DENT_DISABLE CTL2_DENT(0) /*!< disable for transmission */
+
+/* USART RTS hardware flow control configure */
+#define CTL2_RTSEN(regval) (BIT(8) & ((uint32_t)(regval) << 8))
+#define USART_RTS_ENABLE CTL2_RTSEN(1) /*!< RTS hardware flow control enabled */
+#define USART_RTS_DISABLE CTL2_RTSEN(0) /*!< RTS hardware flow control disabled */
+
+/* USART CTS hardware flow control configure */
+#define CTL2_CTSEN(regval) (BIT(9) & ((uint32_t)(regval) << 9))
+#define USART_CTS_ENABLE CTL2_CTSEN(1) /*!< CTS hardware flow control enabled */
+#define USART_CTS_DISABLE CTL2_CTSEN(0) /*!< CTS hardware flow control disabled */
+
+/* USART one sample bit method configure */
+#define CTL2_OSB(regval) (BIT(11) & ((uint32_t)(regval) << 11))
+#define USART_OSB_1BIT CTL2_OSB(1) /*!< 1 sample bit */
+#define USART_OSB_3BIT CTL2_OSB(0) /*!< 3 sample bits */
+
+/* USART driver enable polarity mode */
+#define CTL2_DEP(regval) (BIT(15) & ((uint32_t)(regval) << 15))
+#define USART_DEP_HIGH CTL2_DEP(0) /*!< DE signal is active high */
+#define USART_DEP_LOW CTL2_DEP(1) /*!< DE signal is active low */
+
+/* USART wakeup mode from deep-sleep mode */
+#define CTL2_WUM(regval) (BITS(20,21) & ((uint32_t)(regval) << 20))
+#define USART_WUM_ADDR CTL2_WUM(0) /*!< WUF active on address match */
+#define USART_WUM_STARTB CTL2_WUM(2) /*!< WUF active on start bit */
+#define USART_WUM_RBNE CTL2_WUM(3) /*!< WUF active on RBNE */
+
+/* function declarations */
+/* initialization functions */
+/* reset USART */
+void usart_deinit(uint32_t usart_periph);
+/* configure USART baud rate value */
+void usart_baudrate_set(uint32_t usart_periph, uint32_t baudval);
+/* configure USART parity function */
+void usart_parity_config(uint32_t usart_periph, uint32_t paritycfg);
+/* configure USART word length */
+void usart_word_length_set(uint32_t usart_periph, uint32_t wlen);
+/* configure USART stop bit length */
+void usart_stop_bit_set(uint32_t usart_periph, uint32_t stblen);
+/* enable USART */
+void usart_enable(uint32_t usart_periph);
+/* disable USART */
+void usart_disable(uint32_t usart_periph);
+/* configure USART transmitter */
+void usart_transmit_config(uint32_t usart_periph, uint32_t txconfig);
+/* configure USART receiver */
+void usart_receive_config(uint32_t usart_periph, uint32_t rxconfig);
+
+/* USART normal mode communication */
+/* data is transmitted/received with the LSB/MSB first */
+void usart_data_first_config(uint32_t usart_periph, uint32_t msbf);
+/* configure USART inverted */
+void usart_invert_config(uint32_t usart_periph, usart_invert_enum invertpara);
+/* enable the USART overrun function */
+void usart_overrun_enable(uint32_t usart_periph);
+/* disable the USART overrun function */
+void usart_overrun_disable(uint32_t usart_periph);
+/* configure the USART oversample mode */
+void usart_oversample_config(uint32_t usart_periph, uint32_t oversamp);
+/* configure sample bit method */
+void usart_sample_bit_config(uint32_t usart_periph, uint32_t osb);
+/* enable receiver timeout */
+void usart_receiver_timeout_enable(uint32_t usart_periph);
+/* disable receiver timeout */
+void usart_receiver_timeout_disable(uint32_t usart_periph);
+/* configure receiver timeout threshold */
+void usart_receiver_timeout_threshold_config(uint32_t usart_periph, uint32_t rtimeout);
+/* USART transmit data function */
+void usart_data_transmit(uint32_t usart_periph, uint32_t data);
+/* USART receive data function */
+uint16_t usart_data_receive(uint32_t usart_periph);
+
+/* auto baud rate detection */
+/* enable auto baud rate detection */
+void usart_autobaud_detection_enable(uint32_t usart_periph);
+/* disable auto baud rate detection */
+void usart_autobaud_detection_disable(uint32_t usart_periph);
+/* configure auto baud rate detection mode */
+void usart_autobaud_detection_mode_config(uint32_t usart_periph, uint32_t abdmod);
+
+/* multi-processor communication */
+/* configure the address of the USART in wake up by address match mode */
+void usart_address_config(uint32_t usart_periph, uint8_t addr);
+/* configure address detection mode */
+void usart_address_detection_mode_config(uint32_t usart_periph, uint32_t addmod);
+/* enable mute mode */
+void usart_mute_mode_enable(uint32_t usart_periph);
+/* disable mute mode */
+void usart_mute_mode_disable(uint32_t usart_periph);
+/* configure wakeup method in mute mode */
+void usart_mute_mode_wakeup_config(uint32_t usart_periph, uint32_t wmethod);
+
+/* LIN mode communication */
+/* enable LIN mode */
+void usart_lin_mode_enable(uint32_t usart_periph);
+/* disable LIN mode */
+void usart_lin_mode_disable(uint32_t usart_periph);
+/* configure LIN break frame length */
+void usart_lin_break_detection_length_config(uint32_t usart_periph, uint32_t lblen);
+
+/* half-duplex communication */
+/* enable half-duplex mode */
+void usart_halfduplex_enable(uint32_t usart_periph);
+/* disable half-duplex mode */
+void usart_halfduplex_disable(uint32_t usart_periph);
+
+/* synchronous communication */
+/* enable USART clock */
+void usart_clock_enable(uint32_t usart_periph);
+/* disable USART clock */
+void usart_clock_disable(uint32_t usart_periph);
+/* configure USART synchronous mode parameters */
+void usart_synchronous_clock_config(uint32_t usart_periph, uint32_t clen, uint32_t cph, uint32_t cpl);
+
+/* smartcard communication */
+/* configure guard time value in smartcard mode */
+void usart_guard_time_config(uint32_t usart_periph, uint32_t guat);
+/* enable smartcard mode */
+void usart_smartcard_mode_enable(uint32_t usart_periph);
+/* disable smartcard mode */
+void usart_smartcard_mode_disable(uint32_t usart_periph);
+/* enable NACK in smartcard mode */
+void usart_smartcard_mode_nack_enable(uint32_t usart_periph);
+/* disable NACK in smartcard mode */
+void usart_smartcard_mode_nack_disable(uint32_t usart_periph);
+/* enable early NACK in smartcard mode */
+void usart_smartcard_mode_early_nack_enable(uint32_t usart_periph);
+/* disable early NACK in smartcard mode */
+void usart_smartcard_mode_early_nack_disable(uint32_t usart_periph);
+/* configure smartcard auto-retry number */
+void usart_smartcard_autoretry_config(uint32_t usart_periph, uint32_t scrtnum);
+/* configure block length */
+void usart_block_length_config(uint32_t usart_periph, uint32_t bl);
+
+/* IrDA communication */
+/* enable IrDA mode */
+void usart_irda_mode_enable(uint32_t usart_periph);
+/* disable IrDA mode */
+void usart_irda_mode_disable(uint32_t usart_periph);
+/* configure the peripheral clock prescaler in USART IrDA low-power mode or SmartCard mode */
+void usart_prescaler_config(uint32_t usart_periph, uint32_t psc);
+/* configure IrDA low-power */
+void usart_irda_lowpower_config(uint32_t usart_periph, uint32_t irlp);
+
+/* hardware flow communication */
+/* configure hardware flow control RTS */
+void usart_hardware_flow_rts_config(uint32_t usart_periph, uint32_t rtsconfig);
+/* configure hardware flow control CTS */
+void usart_hardware_flow_cts_config(uint32_t usart_periph, uint32_t ctsconfig);
+
+/* enable RS485 driver */
+void usart_rs485_driver_enable(uint32_t usart_periph);
+/* disable RS485 driver */
+void usart_rs485_driver_disable(uint32_t usart_periph);
+/* configure driver enable assertion time */
+void usart_driver_assertime_config(uint32_t usart_periph, uint32_t deatime);
+/* configure driver enable de-assertion time */
+void usart_driver_deassertime_config(uint32_t usart_periph, uint32_t dedtime);
+/* configure driver enable polarity mode */
+void usart_depolarity_config(uint32_t usart_periph, uint32_t dep);
+
+/* USART DMA */
+/* configure USART DMA for reception */
+void usart_dma_receive_config(uint32_t usart_periph, uint32_t dmacmd);
+/* configure USART DMA for transmission */
+void usart_dma_transmit_config(uint32_t usart_periph, uint32_t dmacmd);
+/* disable DMA on reception error */
+void usart_reception_error_dma_disable(uint32_t usart_periph);
+/* enable DMA on reception error */
+void usart_reception_error_dma_enable(uint32_t usart_periph);
+
+/* enable USART to wakeup the mcu from deep-sleep mode */
+void usart_wakeup_enable(uint32_t usart_periph);
+/* disable USART to wakeup the mcu from deep-sleep mode */
+void usart_wakeup_disable(uint32_t usart_periph);
+/* configure the USART wakeup mode from deep-sleep mode */
+void usart_wakeup_mode_config(uint32_t usart_periph, uint32_t wum);
+/* enable USART command */
+void usart_command_enable(uint32_t usart_periph, uint32_t cmdtype);
+
+/* USART receive FIFO */
+/* enable receive FIFO */
+void usart_receive_fifo_enable(uint32_t usart_periph);
+/* disable receive FIFO */
+void usart_receive_fifo_disable(uint32_t usart_periph);
+/* read receive FIFO counter number */
+uint8_t usart_receive_fifo_counter_number(uint32_t usart_periph);
+
+/* flag & interrupt functions */
+/* get flag in STAT/RFCS register */
+FlagStatus usart_flag_get(uint32_t usart_periph, usart_flag_enum flag);
+/* clear flag in STAT register */
+void usart_flag_clear(uint32_t usart_periph, usart_flag_enum flag);
+/* enable USART interrupt */
+void usart_interrupt_enable(uint32_t usart_periph, usart_interrupt_enum interrupt);
+/* disable USART interrupt */
+void usart_interrupt_disable(uint32_t usart_periph, usart_interrupt_enum interrupt);
+/* get USART interrupt and flag status */
+FlagStatus usart_interrupt_flag_get(uint32_t usart_periph, usart_interrupt_flag_enum int_flag);
+/* clear USART interrupt flag */
+void usart_interrupt_flag_clear(uint32_t usart_periph, usart_interrupt_flag_enum int_flag);
+
+#endif /* GD32F3X0_USART_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_wwdgt.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_wwdgt.h
new file mode 100644
index 00000000..5fe0161f
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Include/gd32f3x0_wwdgt.h
@@ -0,0 +1,95 @@
+/*!
+ \file gd32f3x0_wwdgt.h
+ \brief definitions for the WWDGT
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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 GD32F3X0_WWDGT_H
+#define GD32F3X0_WWDGT_H
+
+#include "gd32f3x0.h"
+
+/* WWDGT definitions */
+#define WWDGT WWDGT_BASE
+
+/* registers definitions */
+#define WWDGT_CTL REG32(WWDGT + 0x00000000U) /*!< WWDGT control register */
+#define WWDGT_CFG REG32(WWDGT + 0x00000004U) /*!< WWDGT configuration register */
+#define WWDGT_STAT REG32(WWDGT + 0x00000008U) /*!< WWDGT status register */
+
+/* bits definitions */
+/* WWDGT_CTL */
+#define WWDGT_CTL_CNT BITS(0,6) /*!< WWDGT counter value */
+#define WWDGT_CTL_WDGTEN BIT(7) /*!< WWDGT counter enable */
+
+/* WWDGT_CFG */
+#define WWDGT_CFG_WIN BITS(0,6) /*!< WWDGT counter window value */
+#define WWDGT_CFG_PSC BITS(7,8) /*!< WWDGT prescaler divider value */
+#define WWDGT_CFG_EWIE BIT(9) /*!< WWDGT early wakeup interrupt enable */
+
+/* WWDGT_STAT */
+#define WWDGT_STAT_EWIF BIT(0) /*!< WWDGT early wakeup interrupt flag */
+
+/* constants definitions */
+/* WWDGT_CTL register value */
+#define CTL_CNT(regval) (BITS(0,6) & ((uint32_t)(regval) << 0U)) /*!< write value to WWDGT_CTL_CNT bit field */
+
+/* WWDGT_CFG register value */
+#define CFG_WIN(regval) (BITS(0,6) & ((uint32_t)(regval) << 0U)) /*!< write value to WWDGT_CFG_WIN bit field */
+
+#define CFG_PSC(regval) (BITS(7,8) & ((uint32_t)(regval) << 7U)) /*!< write value to WWDGT_CFG_PSC bit field */
+#define WWDGT_CFG_PSC_DIV1 ((uint32_t)CFG_PSC(0)) /*!< the time base of WWDGT = (PCLK1/4096)/1 */
+#define WWDGT_CFG_PSC_DIV2 ((uint32_t)CFG_PSC(1)) /*!< the time base of WWDGT = (PCLK1/4096)/2 */
+#define WWDGT_CFG_PSC_DIV4 ((uint32_t)CFG_PSC(2)) /*!< the time base of WWDGT = (PCLK1/4096)/4 */
+#define WWDGT_CFG_PSC_DIV8 ((uint32_t)CFG_PSC(3)) /*!< the time base of WWDGT = (PCLK1/4096)/8 */
+
+/* function declarations */
+/* reset the window watchdog timer configuration */
+void wwdgt_deinit(void);
+/* start the window watchdog timer counter */
+void wwdgt_enable(void);
+
+/* configure the window watchdog timer counter value */
+void wwdgt_counter_update(uint16_t counter_value);
+/* configure counter value, window value, and prescaler divider value */
+void wwdgt_config(uint16_t counter, uint16_t window, uint32_t prescaler);
+
+/* enable early wakeup interrupt of WWDGT */
+void wwdgt_interrupt_enable(void);
+/* check early wakeup interrupt state of WWDGT */
+FlagStatus wwdgt_flag_get(void);
+/* clear early wakeup interrupt state of WWDGT */
+void wwdgt_flag_clear(void);
+
+#endif /* GD32F3X0_WWDGT_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_adc.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_adc.c
new file mode 100644
index 00000000..c8ad5cde
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_adc.c
@@ -0,0 +1,871 @@
+/*!
+ \file gd32f3x0_adc.c
+ \brief ADC driver
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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.
+*/
+
+#include "gd32f3x0_adc.h"
+
+/*!
+ \brief reset ADC
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void adc_deinit(void)
+{
+ rcu_periph_reset_enable(RCU_ADCRST);
+ rcu_periph_reset_disable(RCU_ADCRST);
+}
+
+/*!
+ \brief enable ADC interface
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void adc_enable(void)
+{
+ if(RESET == (ADC_CTL1 & ADC_CTL1_ADCON)) {
+ ADC_CTL1 |= (uint32_t)ADC_CTL1_ADCON;
+ }
+}
+
+/*!
+ \brief disable ADC interface
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void adc_disable(void)
+{
+ ADC_CTL1 &= ~((uint32_t)ADC_CTL1_ADCON);
+}
+
+/*!
+ \brief ADC calibration and reset calibration
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void adc_calibration_enable(void)
+{
+ /* reset the selected ADC calibration register */
+ ADC_CTL1 |= (uint32_t) ADC_CTL1_RSTCLB;
+ /* check the RSTCLB bit state */
+ while((ADC_CTL1 & ADC_CTL1_RSTCLB)) {
+ }
+
+ /* enable ADC calibration process */
+ ADC_CTL1 |= ADC_CTL1_CLB;
+ /* check the CLB bit state */
+ while((ADC_CTL1 & ADC_CTL1_CLB)) {
+ }
+}
+
+/*!
+ \brief enable DMA request
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void adc_dma_mode_enable(void)
+{
+ ADC_CTL1 |= (uint32_t)(ADC_CTL1_DMA);
+}
+
+/*!
+ \brief disable DMA request
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void adc_dma_mode_disable(void)
+{
+ ADC_CTL1 &= ~((uint32_t)ADC_CTL1_DMA);
+}
+
+/*!
+ \brief enable the temperature sensor and Vrefint channel
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void adc_tempsensor_vrefint_enable(void)
+{
+ /* enable the temperature sensor and Vrefint channel */
+ ADC_CTL1 |= ADC_CTL1_TSVREN;
+}
+
+/*!
+ \brief disable the temperature sensor and Vrefint channel
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void adc_tempsensor_vrefint_disable(void)
+{
+ /* disable the temperature sensor and Vrefint channel */
+ ADC_CTL1 &= ~ADC_CTL1_TSVREN;
+}
+
+/*!
+ \brief enable the Vbat channel
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void adc_vbat_enable(void)
+{
+ /* enable the vbat channel */
+ ADC_CTL1 |= ADC_CTL1_VBETEN;
+}
+
+/*!
+ \brief disable the Vbat channel
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void adc_vbat_disable(void)
+{
+ /* disable the vbat channel */
+ ADC_CTL1 &= ~ADC_CTL1_VBETEN;
+}
+
+/*!
+ \brief configure ADC discontinuous mode
+ \param[in] channel_group: select the channel group
+ only one parameter can be selected which is shown as below:
+ \arg ADC_REGULAR_CHANNEL: regular channel group
+ \arg ADC_INSERTED_CHANNEL: inserted channel group
+ \arg ADC_CHANNEL_DISCON_DISABLE: disable discontinuous mode of regular and inserted channel
+ \param[in] length: number of conversions in discontinuous mode,the number can be 1..8
+ for regular channel, the number has no effect for inserted channel
+ \param[out] none
+ \retval none
+*/
+void adc_discontinuous_mode_config(uint8_t channel_group, uint8_t length)
+{
+ ADC_CTL0 &= ~((uint32_t)(ADC_CTL0_DISRC | ADC_CTL0_DISIC));
+
+ switch(channel_group) {
+ case ADC_REGULAR_CHANNEL:
+ /* configure the number of conversions in discontinuous mode */
+ ADC_CTL0 &= ~((uint32_t)ADC_CTL0_DISNUM);
+ ADC_CTL0 |= CTL0_DISNUM(((uint32_t)length - 1U));
+ ADC_CTL0 |= (uint32_t)ADC_CTL0_DISRC;
+ break;
+ case ADC_INSERTED_CHANNEL:
+ ADC_CTL0 |= (uint32_t)ADC_CTL0_DISIC;
+ break;
+ case ADC_CHANNEL_DISCON_DISABLE:
+ default:
+ break;
+ }
+}
+
+/*!
+ \brief enable or disable ADC special function
+ \param[in] function: the function to configure
+ one or more parameters can be selected which is shown as below:
+ \arg ADC_SCAN_MODE: scan mode select
+ \arg ADC_INSERTED_CHANNEL_AUTO: inserted channel group convert automatically
+ \arg ADC_CONTINUOUS_MODE: continuous mode select
+ \param[in] newvalue: ENABLE or DISABLE
+ \param[out] none
+ \retval none
+*/
+void adc_special_function_config(uint32_t function, ControlStatus newvalue)
+{
+ if(newvalue) {
+ /* enable ADC scan mode */
+ if(RESET != (function & ADC_SCAN_MODE)) {
+ ADC_CTL0 |= ADC_SCAN_MODE;
+ }
+ /* enable ADC inserted channel group convert automatically */
+ if(RESET != (function & ADC_INSERTED_CHANNEL_AUTO)) {
+ ADC_CTL0 |= ADC_INSERTED_CHANNEL_AUTO;
+ }
+ /* enable ADC continuous mode */
+ if(RESET != (function & ADC_CONTINUOUS_MODE)) {
+ ADC_CTL1 |= ADC_CONTINUOUS_MODE;
+ }
+ } else {
+ /* disable ADC scan mode */
+ if(RESET != (function & ADC_SCAN_MODE)) {
+ ADC_CTL0 &= ~ADC_SCAN_MODE;
+ }
+ /* disable ADC inserted channel group convert automatically */
+ if(RESET != (function & ADC_INSERTED_CHANNEL_AUTO)) {
+ ADC_CTL0 &= ~ADC_INSERTED_CHANNEL_AUTO;
+ }
+ /* disable ADC continuous mode */
+ if(RESET != (function & ADC_CONTINUOUS_MODE)) {
+ ADC_CTL1 &= ~ADC_CONTINUOUS_MODE;
+ }
+ }
+}
+
+/*!
+ \brief configure ADC data alignment
+ \param[in] data_alignment: data alignment select
+ only one parameter can be selected which is shown as below:
+ \arg ADC_DATAALIGN_RIGHT: right alignment
+ \arg ADC_DATAALIGN_LEFT: left alignment
+ \param[out] none
+ \retval none
+*/
+void adc_data_alignment_config(uint32_t data_alignment)
+{
+ if(ADC_DATAALIGN_RIGHT != data_alignment) {
+ ADC_CTL1 |= ADC_CTL1_DAL;
+ } else {
+ ADC_CTL1 &= ~((uint32_t)ADC_CTL1_DAL);
+ }
+}
+
+/*!
+ \brief configure the length of regular channel group or inserted channel group
+ \param[in] channel_group: select the channel group
+ only one parameter can be selected which is shown as below:
+ \arg ADC_REGULAR_CHANNEL: regular channel group
+ \arg ADC_INSERTED_CHANNEL: inserted channel group
+ \param[in] length: the length of the channel
+ regular channel 1-16
+ inserted channel 1-4
+ \param[out] none
+ \retval none
+*/
+void adc_channel_length_config(uint8_t channel_group, uint32_t length)
+{
+ switch(channel_group) {
+ case ADC_REGULAR_CHANNEL:
+ /* configure the length of regular channel group */
+ ADC_RSQ0 &= ~((uint32_t)ADC_RSQ0_RL);
+ ADC_RSQ0 |= RSQ0_RL((uint32_t)(length - 1U));
+ break;
+ case ADC_INSERTED_CHANNEL:
+ /* configure the length of inserted channel group */
+ ADC_ISQ &= ~((uint32_t)ADC_ISQ_IL);
+ ADC_ISQ |= ISQ_IL((uint32_t)(length - 1U));
+ break;
+ default:
+ break;
+ }
+}
+
+/*!
+ \brief configure ADC regular channel
+ \param[in] rank: the regular group sequence rank, this parameter must be between 0 to 15
+ \param[in] channel: the selected ADC channel
+ only one parameter can be selected which is shown as below:
+ \arg ADC_CHANNEL_x(x=0..18): ADC Channelx
+ \param[in] sample_time: the sample time value
+ only one parameter can be selected which is shown as below:
+ \arg ADC_SAMPLETIME_1POINT5: 1.5 cycles
+ \arg ADC_SAMPLETIME_7POINT5: 7.5 cycles
+ \arg ADC_SAMPLETIME_13POINT5: 13.5 cycles
+ \arg ADC_SAMPLETIME_28POINT5: 28.5 cycles
+ \arg ADC_SAMPLETIME_41POINT5: 41.5 cycles
+ \arg ADC_SAMPLETIME_55POINT5: 55.5 cycles
+ \arg ADC_SAMPLETIME_71POINT5: 71.5 cycles
+ \arg ADC_SAMPLETIME_239POINT5: 239.5 cycles
+ \param[out] none
+ \retval none
+*/
+void adc_regular_channel_config(uint8_t rank, uint8_t channel, uint32_t sample_time)
+{
+ uint32_t rsq, sampt;
+
+ /* configure ADC regular sequence */
+ if(rank < 6U) {
+ rsq = ADC_RSQ2;
+ rsq &= ~((uint32_t)(ADC_RSQX_RSQN << (5U * rank)));
+ rsq |= ((uint32_t)channel << (5U * rank));
+ ADC_RSQ2 = rsq;
+ } else if(rank < 12U) {
+ rsq = ADC_RSQ1;
+ rsq &= ~((uint32_t)(ADC_RSQX_RSQN << (5U * (rank - 6U))));
+ rsq |= ((uint32_t)channel << (5U * (rank - 6U)));
+ ADC_RSQ1 = rsq;
+ } else if(rank < 16U) {
+ rsq = ADC_RSQ0;
+ rsq &= ~((uint32_t)(ADC_RSQX_RSQN << (5U * (rank - 12U))));
+ rsq |= ((uint32_t)channel << (5U * (rank - 12U)));
+ ADC_RSQ0 = rsq;
+ } else {
+ }
+
+ /* configure ADC sampling time */
+ if(channel < 10U) {
+ sampt = ADC_SAMPT1;
+ sampt &= ~((uint32_t)(ADC_SAMPTX_SPTN << (3U * channel)));
+ sampt |= (uint32_t)(sample_time << (3U * channel));
+ ADC_SAMPT1 = sampt;
+ } else if(channel < 19U) {
+ sampt = ADC_SAMPT0;
+ sampt &= ~((uint32_t)(ADC_SAMPTX_SPTN << (3U * (channel - 10U))));
+ sampt |= (uint32_t)(sample_time << (3U * (channel - 10U)));
+ ADC_SAMPT0 = sampt;
+ } else {
+ /* illegal parameters */
+ }
+}
+
+/*!
+ \brief configure ADC inserted channel
+ \param[in] rank: the inserted group sequencer rank,this parameter must be between 0 to 3
+ \param[in] channel: the selected ADC channel
+ only one parameter can be selected which is shown as below:
+ \arg ADC_CHANNEL_x(x=0..18): ADC Channelx
+ \param[in] sample_time: The sample time value
+ only one parameter can be selected which is shown as below:
+ \arg ADC_SAMPLETIME_1POINT5: 1.5 cycles
+ \arg ADC_SAMPLETIME_7POINT5: 7.5 cycles
+ \arg ADC_SAMPLETIME_13POINT5: 13.5 cycles
+ \arg ADC_SAMPLETIME_28POINT5: 28.5 cycles
+ \arg ADC_SAMPLETIME_41POINT5: 41.5 cycles
+ \arg ADC_SAMPLETIME_55POINT5: 55.5 cycles
+ \arg ADC_SAMPLETIME_71POINT5: 71.5 cycles
+ \arg ADC_SAMPLETIME_239POINT5: 239.5 cycles
+ \param[out] none
+ \retval none
+*/
+void adc_inserted_channel_config(uint8_t rank, uint8_t channel, uint32_t sample_time)
+{
+ uint8_t inserted_length;
+ uint32_t isq, sampt;
+
+ inserted_length = (uint8_t)GET_BITS(ADC_ISQ, 20U, 21U);
+
+ isq = ADC_ISQ;
+ isq &= ~((uint32_t)(ADC_ISQ_ISQN << (15U - (inserted_length - rank) * 5U)));
+ isq |= ((uint32_t)channel << (15U - (inserted_length - rank) * 5U));
+ ADC_ISQ = isq;
+
+ /* configure ADC sampling time */
+ if(channel < 10U) {
+ sampt = ADC_SAMPT1;
+ sampt &= ~((uint32_t)(ADC_SAMPTX_SPTN << (3U * channel)));
+ sampt |= (uint32_t) sample_time << (3U * channel);
+ ADC_SAMPT1 = sampt;
+ } else if(channel < 19U) {
+ sampt = ADC_SAMPT0;
+ sampt &= ~((uint32_t)(ADC_SAMPTX_SPTN << (3U * (channel - 10U))));
+ sampt |= ((uint32_t)sample_time << (3U * (channel - 10U)));
+ ADC_SAMPT0 = sampt;
+ } else {
+ /* illegal parameters */
+ }
+}
+
+/*!
+ \brief configure ADC inserted channel offset
+ \param[in] inserted_channel: insert channel select
+ only one parameter can be selected which is shown as below:
+ \arg ADC_INSERTED_CHANNEL_0: ADC inserted channel 0
+ \arg ADC_INSERTED_CHANNEL_1: ADC inserted channel 1
+ \arg ADC_INSERTED_CHANNEL_2: ADC inserted channel 2
+ \arg ADC_INSERTED_CHANNEL_3: ADC inserted channel 3
+ \param[in] offset: the offset data
+ \param[out] none
+ \retval none
+*/
+void adc_inserted_channel_offset_config(uint8_t inserted_channel, uint16_t offset)
+{
+ uint8_t inserted_length;
+ uint32_t num = 0U;
+
+ inserted_length = (uint8_t)GET_BITS(ADC_ISQ, 20U, 21U);
+ num = 3U - (inserted_length - inserted_channel);
+
+ if(num <= 3U) {
+ /* calculate the offset of the register */
+ num = num * 4U;
+ /* configure the offset of the selected channels */
+ REG32((ADC) + 0x14U + num) = IOFFX_IOFF((uint32_t)offset);
+ }
+}
+
+/*!
+ \brief enable or disable ADC external trigger
+ \param[in] channel_group: select the channel group
+ one or more parameters can be selected which is shown as below:
+ \arg ADC_REGULAR_CHANNEL: regular channel group
+ \arg ADC_INSERTED_CHANNEL: inserted channel group
+ \param[in] newvalue: ENABLE or DISABLE
+ \param[out] none
+ \retval none
+*/
+void adc_external_trigger_config(uint8_t channel_group, ControlStatus newvalue)
+{
+ if(newvalue) {
+ /* external trigger enable for regular channel */
+ if(RESET != (channel_group & ADC_REGULAR_CHANNEL)) {
+ ADC_CTL1 |= ADC_CTL1_ETERC;
+ }
+ /* external trigger enable for inserted channel */
+ if(RESET != (channel_group & ADC_INSERTED_CHANNEL)) {
+ ADC_CTL1 |= ADC_CTL1_ETEIC;
+ }
+ } else {
+ /* external trigger disable for regular channel */
+ if(RESET != (channel_group & ADC_REGULAR_CHANNEL)) {
+ ADC_CTL1 &= ~ADC_CTL1_ETERC;
+ }
+ /* external trigger disable for inserted channel */
+ if(RESET != (channel_group & ADC_INSERTED_CHANNEL)) {
+ ADC_CTL1 &= ~ADC_CTL1_ETEIC;
+ }
+ }
+}
+
+/*!
+ \brief configure ADC external trigger source
+ \param[in] channel_group: select the channel group
+ only one parameter can be selected which is shown as below:
+ \arg ADC_REGULAR_CHANNEL: regular channel group
+ \arg ADC_INSERTED_CHANNEL: inserted channel group
+ \param[in] external_trigger_source: regular or inserted group trigger source
+ only one parameter can be selected which is shown as below:
+ for regular channel:
+ \arg ADC_EXTTRIG_REGULAR_T0_CH0: TIMER0 CH0 event select
+ \arg ADC_EXTTRIG_REGULAR_T0_CH1: TIMER0 CH1 event select
+ \arg ADC_EXTTRIG_REGULAR_T0_CH2: TIMER0 CH2 event select
+ \arg ADC_EXTTRIG_REGULAR_T1_CH1: TIMER1 CH1 event select
+ \arg ADC_EXTTRIG_REGULAR_T2_TRGO: TIMER2 TRGO event select
+ \arg ADC_EXTTRIG_REGULAR_T14_CH0: TIMER14 CH0 event select
+ \arg ADC_EXTTRIG_REGULAR_EXTI_11: external interrupt line 11
+ \arg ADC_EXTTRIG_REGULAR_NONE: software trigger
+ for inserted channel:
+ \arg ADC_EXTTRIG_INSERTED_T0_TRGO: TIMER0 TRGO event select
+ \arg ADC_EXTTRIG_INSERTED_T0_CH3: TIMER0 CH3 event select
+ \arg ADC_EXTTRIG_INSERTED_T1_TRGO: TIMER1 TRGO event select
+ \arg ADC_EXTTRIG_INSERTED_T1_CH0: TIMER1 CH0 event select
+ \arg ADC_EXTTRIG_INSERTED_T2_CH3: TIMER2 CH3 event select
+ \arg ADC_EXTTRIG_INSERTED_T14_TRGO: TIMER14 TRGO event select
+ \arg ADC_EXTTRIG_INSERTED_EXTI_15: external interrupt line 15
+ \arg ADC_EXTTRIG_INSERTED_NONE: software trigger
+ \param[out] none
+ \retval none
+*/
+void adc_external_trigger_source_config(uint8_t channel_group, uint32_t external_trigger_source)
+{
+ switch(channel_group) {
+ case ADC_REGULAR_CHANNEL:
+ /* external trigger select for regular channel */
+ ADC_CTL1 &= ~((uint32_t)ADC_CTL1_ETSRC);
+ ADC_CTL1 |= (uint32_t)external_trigger_source;
+ break;
+ case ADC_INSERTED_CHANNEL:
+ /* external trigger select for inserted channel */
+ ADC_CTL1 &= ~((uint32_t)ADC_CTL1_ETSIC);
+ ADC_CTL1 |= (uint32_t)external_trigger_source;
+ break;
+ default:
+ break;
+ }
+}
+
+/*!
+ \brief enable ADC software trigger
+ \param[in] channel_group: select the channel group
+ one or more parameters can be selected which is shown as below:
+ \arg ADC_REGULAR_CHANNEL: regular channel group
+ \arg ADC_INSERTED_CHANNEL: inserted channel group
+ \param[out] none
+ \retval none
+*/
+void adc_software_trigger_enable(uint8_t channel_group)
+{
+ /* enable regular group channel software trigger */
+ if(RESET != (channel_group & ADC_REGULAR_CHANNEL)) {
+ ADC_CTL1 |= ADC_CTL1_SWRCST;
+ }
+ /* enable inserted channel group software trigger */
+ if(RESET != (channel_group & ADC_INSERTED_CHANNEL)) {
+ ADC_CTL1 |= ADC_CTL1_SWICST;
+ }
+}
+
+/*!
+ \brief read ADC regular group data register
+ \param[in] none
+ \param[out] none
+ \retval the conversion value
+*/
+uint16_t adc_regular_data_read(void)
+{
+ return ((uint16_t)ADC_RDATA);
+}
+
+/*!
+ \brief read ADC inserted group data register
+ \param[in] inserted_channel: inserted channel select
+ only one parameter can be selected which is shown as below:
+ \arg ADC_INSERTED_CHANNEL_0: ADC inserted channel 0
+ \arg ADC_INSERTED_CHANNEL_1: ADC inserted channel 1
+ \arg ADC_INSERTED_CHANNEL_2: ADC inserted channel 2
+ \arg ADC_INSERTED_CHANNEL_3: ADC inserted channel 3
+ \param[out] none
+ \retval the conversion value
+*/
+uint16_t adc_inserted_data_read(uint8_t inserted_channel)
+{
+ uint32_t idata;
+ /* read the data of the selected channel */
+ switch(inserted_channel) {
+ case ADC_INSERTED_CHANNEL_0:
+ idata = ADC_IDATA0;
+ break;
+ case ADC_INSERTED_CHANNEL_1:
+ idata = ADC_IDATA1;
+ break;
+ case ADC_INSERTED_CHANNEL_2:
+ idata = ADC_IDATA2;
+ break;
+ case ADC_INSERTED_CHANNEL_3:
+ idata = ADC_IDATA3;
+ break;
+ default:
+ idata = 0U;
+ break;
+ }
+ return (uint16_t)idata;
+}
+
+/*!
+ \brief configure ADC analog watchdog single channel
+ \param[in] channel: the selected ADC channel
+ only one parameter can be selected which is shown as below:
+ \arg ADC_CHANNEL_x(x=0..18): ADC Channelx
+ \param[out] none
+ \retval none
+*/
+void adc_watchdog_single_channel_enable(uint8_t channel)
+{
+ ADC_CTL0 &= (uint32_t)~(ADC_CTL0_RWDEN | ADC_CTL0_IWDEN | ADC_CTL0_WDSC | ADC_CTL0_WDCHSEL);
+
+ ADC_CTL0 |= (uint32_t)channel;
+ ADC_CTL0 |= (uint32_t)(ADC_CTL0_RWDEN | ADC_CTL0_IWDEN | ADC_CTL0_WDSC);
+}
+
+/*!
+ \brief configure ADC analog watchdog group channel
+ \param[in] channel_group: the channel group use analog watchdog
+ only one parameter can be selected which is shown as below:
+ \arg ADC_REGULAR_CHANNEL: regular channel group
+ \arg ADC_INSERTED_CHANNEL: inserted channel group
+ \arg ADC_REGULAR_INSERTED_CHANNEL: both regular and inserted group
+ \param[out] none
+ \retval none
+*/
+void adc_watchdog_group_channel_enable(uint8_t channel_group)
+{
+ ADC_CTL0 &= (uint32_t)~(ADC_CTL0_RWDEN | ADC_CTL0_IWDEN | ADC_CTL0_WDSC);
+
+ /* select the group */
+ switch(channel_group) {
+ case ADC_REGULAR_CHANNEL:
+ ADC_CTL0 |= (uint32_t)ADC_CTL0_RWDEN;
+ break;
+ case ADC_INSERTED_CHANNEL:
+ ADC_CTL0 |= (uint32_t)ADC_CTL0_IWDEN;
+ break;
+ case ADC_REGULAR_INSERTED_CHANNEL:
+ ADC_CTL0 |= (uint32_t)(ADC_CTL0_RWDEN | ADC_CTL0_IWDEN);
+ break;
+ default:
+ break;
+ }
+}
+
+/*!
+ \brief disable ADC analog watchdog
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void adc_watchdog_disable(void)
+{
+ ADC_CTL0 &= (uint32_t)~(ADC_CTL0_RWDEN | ADC_CTL0_IWDEN | ADC_CTL0_WDSC | ADC_CTL0_WDCHSEL);
+}
+
+/*!
+ \brief configure ADC analog watchdog threshold
+ \param[in] low_threshold: analog watchdog low threshold,0..4095
+ \param[in] high_threshold: analog watchdog high threshold,0..4095
+ \param[out] none
+ \retval none
+*/
+void adc_watchdog_threshold_config(uint16_t low_threshold, uint16_t high_threshold)
+{
+ ADC_WDLT = (uint32_t)WDLT_WDLT(low_threshold);
+ ADC_WDHT = (uint32_t)WDHT_WDHT(high_threshold);
+}
+
+/*!
+ \brief configure ADC resolution
+ \param[in] resolution: ADC resolution
+ only one parameter can be selected which is shown as below:
+ \arg ADC_RESOLUTION_12B: 12-bit ADC resolution
+ \arg ADC_RESOLUTION_10B: 10-bit ADC resolution
+ \arg ADC_RESOLUTION_8B: 8-bit ADC resolution
+ \arg ADC_RESOLUTION_6B: 6-bit ADC resolution
+ \param[out] none
+ \retval none
+*/
+void adc_resolution_config(uint32_t resolution)
+{
+ ADC_CTL0 &= ~((uint32_t)ADC_CTL0_DRES);
+ ADC_CTL0 |= (uint32_t)resolution;
+}
+
+/*!
+ \brief configure ADC oversample mode
+ \param[in] mode: ADC oversampling mode
+ only one parameter can be selected which is shown as below:
+ \arg ADC_OVERSAMPLING_ALL_CONVERT: all oversampled conversions for a channel are done consecutively after a trigger
+ \arg ADC_OVERSAMPLING_ONE_CONVERT: each oversampled conversion for a channel needs a trigger
+ \param[in] shift: ADC oversampling shift
+ only one parameter can be selected which is shown as below:
+ \arg ADC_OVERSAMPLING_SHIFT_NONE: no oversampling shift
+ \arg ADC_OVERSAMPLING_SHIFT_1B: 1-bit oversampling shift
+ \arg ADC_OVERSAMPLING_SHIFT_2B: 2-bit oversampling shift
+ \arg ADC_OVERSAMPLING_SHIFT_3B: 3-bit oversampling shift
+ \arg ADC_OVERSAMPLING_SHIFT_4B: 3-bit oversampling shift
+ \arg ADC_OVERSAMPLING_SHIFT_5B: 5-bit oversampling shift
+ \arg ADC_OVERSAMPLING_SHIFT_6B: 6-bit oversampling shift
+ \arg ADC_OVERSAMPLING_SHIFT_7B: 7-bit oversampling shift
+ \arg ADC_OVERSAMPLING_SHIFT_8B: 8-bit oversampling shift
+ \param[in] ratio: ADC oversampling ratio
+ only one parameter can be selected which is shown as below:
+ \arg ADC_OVERSAMPLING_RATIO_MUL2: oversampling ratio multiple 2
+ \arg ADC_OVERSAMPLING_RATIO_MUL4: oversampling ratio multiple 4
+ \arg ADC_OVERSAMPLING_RATIO_MUL8: oversampling ratio multiple 8
+ \arg ADC_OVERSAMPLING_RATIO_MUL16: oversampling ratio multiple 16
+ \arg ADC_OVERSAMPLING_RATIO_MUL32: oversampling ratio multiple 32
+ \arg ADC_OVERSAMPLING_RATIO_MUL64: oversampling ratio multiple 64
+ \arg ADC_OVERSAMPLING_RATIO_MUL128: oversampling ratio multiple 128
+ \arg ADC_OVERSAMPLING_RATIO_MUL256: oversampling ratio multiple 256
+ \param[out] none
+ \retval none
+*/
+void adc_oversample_mode_config(uint8_t mode, uint16_t shift, uint8_t ratio)
+{
+ /* configure ADC oversampling mode */
+ if(ADC_OVERSAMPLING_ONE_CONVERT == mode) {
+ ADC_OVSAMPCTL |= (uint32_t)ADC_OVSAMPCTL_TOVS;
+ } else {
+ ADC_OVSAMPCTL &= ~((uint32_t)ADC_OVSAMPCTL_TOVS);
+ }
+
+ /* configure the shift and ratio */
+ ADC_OVSAMPCTL &= ~((uint32_t)(ADC_OVSAMPCTL_OVSR | ADC_OVSAMPCTL_OVSS));
+ ADC_OVSAMPCTL |= ((uint32_t)shift | (uint32_t)ratio);
+}
+
+/*!
+ \brief enable ADC oversample mode
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void adc_oversample_mode_enable(void)
+{
+ ADC_OVSAMPCTL |= ADC_OVSAMPCTL_OVSEN;
+}
+
+/*!
+ \brief disable ADC oversample mode
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void adc_oversample_mode_disable(void)
+{
+ ADC_OVSAMPCTL &= ~((uint32_t)ADC_OVSAMPCTL_OVSEN);
+}
+
+/*!
+ \brief get the ADC flag bits
+ \param[in] flag: the adc flag bits
+ only one parameter can be selected which is shown as below:
+ \arg ADC_FLAG_WDE: analog watchdog event flag
+ \arg ADC_FLAG_EOC: end of group conversion flag
+ \arg ADC_FLAG_EOIC: end of inserted group conversion flag
+ \arg ADC_FLAG_STIC: start flag of inserted channel group
+ \arg ADC_FLAG_STRC: start flag of regular channel group
+ \param[out] none
+ \retval FlagStatus: SET or RESET
+*/
+FlagStatus adc_flag_get(uint32_t flag)
+{
+ FlagStatus reval = RESET;
+
+ if(ADC_STAT & flag) {
+ reval = SET;
+ }
+ return reval;
+}
+
+/*!
+ \brief clear the ADC flag
+ \param[in] flag: the adc flag
+ one or more parameters can be selected which is shown as below:
+ \arg ADC_FLAG_WDE: analog watchdog event flag
+ \arg ADC_FLAG_EOC: end of group conversion flag
+ \arg ADC_FLAG_EOIC: end of inserted group conversion flag
+ \arg ADC_FLAG_STIC: start flag of inserted channel group
+ \arg ADC_FLAG_STRC: start flag of regular channel group
+ \param[out] none
+ \retval none
+*/
+void adc_flag_clear(uint32_t flag)
+{
+ ADC_STAT &= ~((uint32_t)flag);
+}
+
+/*!
+ \brief enable ADC interrupt
+ \param[in] interrupt: the adc interrupt
+ one or more parameters can be selected which is shown as below:
+ \arg ADC_INT_WDE: analog watchdog interrupt
+ \arg ADC_INT_EOC: end of group conversion interrupt
+ \arg ADC_INT_EOIC: end of inserted group conversion interrupt
+ \param[out] none
+ \retval none
+*/
+void adc_interrupt_enable(uint32_t interrupt)
+{
+ /* enable analog watchdog interrupt */
+ if(RESET != (interrupt & ADC_INT_WDE)) {
+ ADC_CTL0 |= (uint32_t)ADC_CTL0_WDEIE;
+ }
+
+ /* enable end of group conversion interrupt */
+ if(RESET != (interrupt & ADC_INT_EOC)) {
+ ADC_CTL0 |= (uint32_t)ADC_CTL0_EOCIE;
+ }
+
+ /* enable end of inserted group conversion interrupt */
+ if(RESET != (interrupt & ADC_INT_EOIC)) {
+ ADC_CTL0 |= (uint32_t)ADC_CTL0_EOICIE;
+ }
+}
+
+/*!
+ \brief disable ADC interrupt
+ \param[in] interrupt: the adc interrupt flag
+ one or more parameters can be selected which is shown as below:
+ \arg ADC_INT_WDE: analog watchdog interrupt
+ \arg ADC_INT_EOC: end of group conversion interrupt
+ \arg ADC_INT_EOIC: end of inserted group conversion interrupt
+ \param[out] none
+ \retval none
+*/
+void adc_interrupt_disable(uint32_t interrupt)
+{
+ /* disable analog watchdog interrupt */
+ if(RESET != (interrupt & ADC_INT_WDE)) {
+ ADC_CTL0 &= ~(uint32_t)ADC_CTL0_WDEIE;
+ }
+
+ /* disable end of group conversion interrupt */
+ if(RESET != (interrupt & ADC_INT_EOC)) {
+ ADC_CTL0 &= ~(uint32_t)ADC_CTL0_EOCIE;
+ }
+
+ /* disable end of inserted group conversion interrupt */
+ if(RESET != (interrupt & ADC_INT_EOIC)) {
+ ADC_CTL0 &= ~(uint32_t)ADC_CTL0_EOICIE;
+ }
+}
+
+/*!
+ \brief get the ADC interrupt flag
+ \param[in] flag: the adc interrupt flag
+ only one parameter can be selected which is shown as below:
+ \arg ADC_INT_FLAG_WDE: analog watchdog interrupt flag
+ \arg ADC_INT_FLAG_EOC: end of group conversion interrupt flag
+ \arg ADC_INT_FLAG_EOIC: end of inserted group conversion interrupt flag
+ \param[out] none
+ \retval FlagStatus: SET or RESET
+*/
+FlagStatus adc_interrupt_flag_get(uint32_t flag)
+{
+ FlagStatus interrupt_flag = RESET;
+ uint32_t state;
+
+ /* check the interrupt bits */
+ switch(flag) {
+ case ADC_INT_FLAG_WDE:
+ state = ADC_STAT & ADC_STAT_WDE;
+ if((ADC_CTL0 & ADC_CTL0_WDEIE) && state) {
+ interrupt_flag = SET;
+ }
+ break;
+ case ADC_INT_FLAG_EOC:
+ state = ADC_STAT & ADC_STAT_EOC;
+ if((ADC_CTL0 & ADC_CTL0_EOCIE) && state) {
+ interrupt_flag = SET;
+ }
+ break;
+ case ADC_INT_FLAG_EOIC:
+ state = ADC_STAT & ADC_STAT_EOIC;
+ if((ADC_CTL0 & ADC_CTL0_EOICIE) && state) {
+ interrupt_flag = SET;
+ }
+ break;
+ default:
+ break;
+ }
+ return interrupt_flag;
+}
+
+/*!
+ \brief clear ADC interrupt flag
+ \param[in] flag: the adc interrupt flag
+ only one parameter can be selected which is shown as below:
+ \arg ADC_INT_FLAG_WDE: analog watchdog interrupt flag
+ \arg ADC_INT_FLAG_EOC: end of group conversion interrupt flag
+ \arg ADC_INT_FLAG_EOIC: end of inserted group conversion interrupt flag
+ \param[out] none
+ \retval none
+*/
+void adc_interrupt_flag_clear(uint32_t flag)
+{
+ ADC_STAT &= ~((uint32_t)flag);
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_cec.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_cec.c
new file mode 100644
index 00000000..b2d4f914
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_cec.c
@@ -0,0 +1,500 @@
+/*!
+ \file gd32f3x0_cec.c
+ \brief CEC driver
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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.
+*/
+
+#ifdef GD32F350
+
+#include "gd32f3x0_cec.h"
+
+/*!
+ \brief reset HDMI-CEC controller
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void cec_deinit(void)
+{
+ rcu_periph_reset_enable(RCU_CECRST);
+ rcu_periph_reset_disable(RCU_CECRST);
+}
+
+/*!
+ \brief configure signal free time,the signal free time counter start option,own address
+ \param[in] sftmopt: signal free time counter start option
+ only one parameter can be selected which is shown as below:
+ \arg CEC_SFT_START_STAOM: signal free time counter starts counting when STAOM is asserted
+ \arg CEC_SFT_START_LAST: signal free time counter starts automatically after transmission/reception end
+ \param[in] sft: signal free time
+ only one parameter can be selected which is shown as below:
+ \arg CEC_SFT_PROTOCOL_PERIOD: the signal free time will perform as HDMI-CEC protocol description
+ \arg CEC_SFT_1POINT5_PERIOD: 1.5 nominal data bit periods
+ \arg CEC_SFT_2POINT5_PERIOD: 2.5 nominal data bit periods
+ \arg CEC_SFT_3POINT5_PERIOD: 3.5 nominal data bit periods
+ \arg CEC_SFT_4POINT5_PERIOD: 4.5 nominal data bit periods
+ \arg CEC_SFT_5POINT5_PERIOD: 5.5 nominal data bit periods
+ \arg CEC_SFT_6POINT5_PERIOD: 6.5 nominal data bit periods
+ \arg CEC_SFT_7POINT5_PERIOD: 7.5 nominal data bit periods
+ \param[in] address: own address
+ only one parameter can be selected which is shown as below:
+ \arg CEC_OWN_ADDRESS_CLEAR: own address is cleared
+ \arg CEC_OWN_ADDRESSx(x=0..14): own address is x
+ \param[out] none
+ \retval none
+*/
+void cec_init(uint32_t sftmopt, uint32_t sft, uint32_t address)
+{
+ uint32_t cfg;
+ cfg = CEC_CFG;
+ /* clear SFTMOPT bit,SFT[2:0] */
+ cfg &= ~(CEC_CFG_SFTOPT | CEC_CFG_SFT);
+ /* assign SFTMOPT bit,SFT[2:0] */
+ cfg |= (sftmopt | sft);
+ CEC_CFG = cfg;
+ if(CEC_OWN_ADDRESS_CLEAR == address){
+ CEC_CFG &= ~CEC_CFG_OAD;
+ }else{
+ CEC_CFG |= address;
+ }
+}
+
+/*!
+ \brief configure generate Error-bit when detected some abnormal situation or not,
+ whether stop receive message when detected bit rising error
+ \param[in] broadcast:
+ only one parameter can be selected which is shown as below:
+ \arg CEC_BROADCAST_ERROR_BIT_ON:generate Error-bit in broadcast
+ \arg CEC_BROADCAST_ERROR_BIT_OFF:do not generate Error-bit in broadcast
+ \param[in] singlecast_lbpe:
+ only one parameter can be selected which is shown as below:
+ \arg CEC_LONG_PERIOD_ERROR_BIT_ON:generate Error-bit on long bit period error
+ \arg CEC_LONG_PERIOD_ERROR_BIT_OFF:do not generate Error-bit on long bit period error
+ \param[in] singlecast_bre:
+ only one parameter can be selected which is shown as below:
+ \arg CEC_RISING_PERIOD_ERROR_BIT_ON:generate Error-bit on bit rising error
+ \arg CEC_RISING_PERIOD_ERROR_BIT_OFF:do not generate Error-bit on bit rising error
+ \param[in] rxbrestp:
+ only one parameter can be selected which is shown as below:
+ \arg CEC_STOP_RISING_ERROR_BIT_ON: stop reception when detected bit rising error
+ \arg CEC_STOP_RISING_ERROR_BIT_OFF: do not stop reception when detected bit rising error
+ \param[out] none
+ \retval none
+*/
+void cec_error_config(uint32_t broadcast, uint32_t singlecast_lbpe, uint32_t singlecast_bre, uint32_t rxbrestp)
+{
+ uint32_t cfg;
+ cfg = CEC_CFG;
+ /* clear BCNG bit, BPLEG bit, BREG bit */
+ cfg &= ~(CEC_CFG_BCNG | CEC_CFG_BPLEG | CEC_CFG_BREG);
+ /* assign BCNG bit, BPLEG bit, BREG bit */
+ cfg |= (broadcast | singlecast_lbpe | singlecast_bre);
+ CEC_CFG = cfg;
+ if(CEC_STOP_RISING_ERROR_BIT_ON == rxbrestp){
+ CEC_CFG |= CEC_CFG_BRES;
+ }else{
+ CEC_CFG &= ~CEC_CFG_BRES;
+ }
+}
+
+/*!
+ \brief enable HDMI-CEC controller
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void cec_enable(void)
+{
+ CEC_CTL |= CEC_CTL_CECEN;
+}
+
+/*!
+ \brief disable HDMI-CEC controller
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void cec_disable(void)
+{
+ CEC_CTL &= ~CEC_CTL_CECEN;
+}
+
+/*!
+ \brief start CEC message transmission
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void cec_transmission_start(void)
+{
+ CEC_CTL |= CEC_CTL_STAOM;
+}
+
+/*!
+ \brief end CEC message transmission
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void cec_transmission_end(void)
+{
+ CEC_CTL |= CEC_CTL_ENDOM;
+}
+
+/*!
+ \brief enable CEC listen mode.
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void cec_listen_mode_enable(void)
+{
+ CEC_CFG |= CEC_CFG_LMEN;
+}
+
+/*!
+ \brief disable CEC listen mode.
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void cec_listen_mode_disable(void)
+{
+ CEC_CFG &= ~CEC_CFG_LMEN;
+}
+
+/*!
+ \brief configure and clear own address.the controller can be configured to multiple own address
+ \param[in] address: own address
+ one or more parameters can be selected which are shown as below:
+ \arg CEC_OWN_ADDRESS_CLEAR: own address is cleared
+ \arg CEC_OWN_ADDRESSx(x=0..14): own address is x
+ \param[out] none
+ \retval none
+*/
+void cec_own_address_config(uint32_t address)
+{
+ if(CEC_OWN_ADDRESS_CLEAR == address){
+ CEC_CFG &= ~CEC_CFG_OAD;
+ }else{
+ CEC_CFG |= address;
+ }
+}
+
+/*!
+ \brief configure signal free time and the signal free time counter start option
+ \param[in] sftmopt: signal free time counter start option
+ only one parameter can be selected which is shown as below:
+ \arg CEC_SFT_START_STAOM: signal free time counter starts counting when STAOM is asserted
+ \arg CEC_SFT_START_LAST: signal free time counter starts automatically after transmission/reception end
+ \param[in] sft: signal free time
+ only one parameter can be selected which is shown as below:
+ \arg CEC_SFT_PROTOCOL_PERIOD: the signal free time will perform as HDMI-CEC protocol description
+ \arg CEC_SFT_1POINT5_PERIOD: 1.5 nominal data bit periods
+ \arg CEC_SFT_2POINT5_PERIOD: 2.5 nominal data bit periods
+ \arg CEC_SFT_3POINT5_PERIOD: 3.5 nominal data bit periods
+ \arg CEC_SFT_4POINT5_PERIOD: 4.5 nominal data bit periods
+ \arg CEC_SFT_5POINT5_PERIOD: 5.5 nominal data bit periods
+ \arg CEC_SFT_6POINT5_PERIOD: 6.5 nominal data bit periods
+ \arg CEC_SFT_7POINT5_PERIOD: 7.5 nominal data bit periods
+ \param[out] none
+ \retval none
+*/
+void cec_sft_config(uint32_t sftmopt, uint32_t sft)
+{
+ uint32_t cfg;
+ cfg = CEC_CFG;
+ /* clear SFTMOPT bit,SFT[2:0] */
+ cfg &= ~(CEC_CFG_SFTOPT | CEC_CFG_SFT);
+ /* assign SFTMOPT bit,SFT[2:0] */
+ cfg |= (sftmopt | sft);
+ CEC_CFG = cfg;
+}
+
+/*!
+ \brief configure generate Error-bit when detected some abnormal situation or not
+ \param[in] broadcast:
+ only one parameter can be selected which is shown as below:
+ \arg CEC_BROADCAST_ERROR_BIT_ON:generate Error-bit in broadcast
+ \arg CEC_BROADCAST_ERROR_BIT_OFF:do not generate Error-bit in broadcast
+ \param[in] singlecast_lbpe:
+ only one parameter can be selected which is shown as below:
+ \arg CEC_LONG_PERIOD_ERROR_BIT_ON:generate Error-bit on long bit period error
+ \arg CEC_LONG_PERIOD_ERROR_BIT_OFF:do not generate Error-bit on long bit period error
+ \param[in] singlecast_bre:
+ only one parameter can be selected which is shown as below:
+ \arg CEC_RISING_PERIOD_ERROR_BIT_ON:generate Error-bit on bit rising error
+ \arg CEC_RISING_PERIOD_ERROR_BIT_OFF:do not generate Error-bit on bit rising error
+ \param[out] none
+ \retval none
+*/
+void cec_generate_errorbit_config(uint32_t broadcast, uint32_t singlecast_lbpe, uint32_t singlecast_bre)
+{
+ uint32_t cfg;
+ cfg = CEC_CFG;
+ /* clear BCNG bit, RLBPEGEN bit, RBREGEN bit */
+ cfg &= ~(CEC_CFG_BCNG | CEC_CFG_BPLEG | CEC_CFG_BREG);
+ /* assign BCNG bit, RLBPEGEN bit, RBREGEN bit */
+ cfg |= (broadcast | singlecast_lbpe | singlecast_bre);
+ CEC_CFG = cfg;
+}
+
+/*!
+ \brief whether stop receive message when detected bit rising error
+ \param[in] rxbrestp:
+ only one parameter can be selected which is shown as below:
+ \arg CEC_STOP_RISING_ERROR_BIT_ON: stop reception when detected bit rising error
+ \arg CEC_STOP_RISING_ERROR_BIT_OFF: do not stop reception when detected bit rising error
+ \param[out] none
+ \retval none
+*/
+void cec_stop_receive_bre_config(uint32_t rxbrestp)
+{
+ if(CEC_STOP_RISING_ERROR_BIT_ON == rxbrestp){
+ CEC_CFG |= CEC_CFG_BRES;
+ }else{
+ CEC_CFG &= ~CEC_CFG_BRES;
+ }
+}
+
+/*!
+ \brief enable reception bit timing tolerance
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void cec_reception_tolerance_enable(void)
+{
+ CEC_CFG |= CEC_CFG_RTOL;
+}
+
+/*!
+ \brief disable reception bit timing tolerance
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void cec_reception_tolerance_disable(void)
+{
+ CEC_CFG &= ~CEC_CFG_RTOL;
+}
+
+/*!
+ \brief send a data by the CEC peripheral
+ \param[in] data: the data to transmit
+ \param[out] none
+ \retval none
+*/
+void cec_data_send(uint8_t data)
+{
+ CEC_TDATA = (uint32_t)data;
+}
+
+/*!
+ \brief receive a data by the CEC peripheral
+ \param[in] data: the data to receive
+ \param[out] none
+ \retval none
+*/
+uint8_t cec_data_receive(void)
+{
+ return (uint8_t)CEC_RDATA;
+}
+
+
+/*!
+ \brief enable interrupt
+ \param[in] flag: specify which flag
+ one or more parameters can be selected which are shown as below:
+ \arg CEC_INT_BR: enable Rx-byte data received interrupt
+ \arg CEC_INT_REND: enable end of reception interrupt
+ \arg CEC_INT_RO: enable RX overrun interrupt
+ \arg CEC_INT_BRE: enable bit rising error interrupt
+ \arg CEC_INT_BPSE: enable short bit period error interrupt
+ \arg CEC_INT_BPLE: enable long bit period error interrupt
+ \arg CEC_INT_RAE: enable Rx ACK error interrupt
+ \arg CEC_INT_ARBF: enable arbitration lost interrupt
+ \arg CEC_INT_TBR: enable Tx-byte data request interrupt
+ \arg CEC_INT_TEND: enable transmission successfully end interrupt
+ \arg CEC_INT_TU: enable Tx data buffer underrun interrupt
+ \arg CEC_INT_TERR: enable Tx-error interrupt
+ \arg CEC_INT_TAERR: enable Tx ACK error interrupt
+ \param[out] none
+ \retval none
+*/
+void cec_interrupt_enable(uint32_t flag)
+{
+ CEC_INTEN |= flag;
+}
+
+/*!
+ \brief disable interrupt
+ \param[in] flag: specify which flag
+ one or more parameters can be selected which are shown as below:
+ \arg CEC_INT_BR: disable Rx-byte data received interrupt
+ \arg CEC_INT_REND: disable end of reception interrupt
+ \arg CEC_INT_RO: disable RX overrun interrupt
+ \arg CEC_INT_BRE: disable bit rising error interrupt
+ \arg CEC_INT_BPSE: disable short bit period error interrupt
+ \arg CEC_INT_BPLE: disable long bit period error interrupt
+ \arg CEC_INT_RAE: disable Rx ACK error interrupt
+ \arg CEC_INT_ARBF: disable arbitration lost interrupt
+ \arg CEC_INT_TBR: disable Tx-byte data request interrupt
+ \arg CEC_INT_TEND: disable transmission successfully end interrupt
+ \arg CEC_INT_TU: disable Tx data buffer underrun interrupt
+ \arg CEC_INT_TERR: disable Tx-error interrupt
+ \arg CEC_INT_TAERR: disable Tx ACK error interrupt
+
+ \param[out] none
+ \retval none
+*/
+void cec_interrupt_disable(uint32_t flag)
+{
+ CEC_INTEN &= ~flag;
+}
+
+
+/*!
+ \brief get CEC status
+ \param[in] flag: specify which flag
+ one or more parameters can be selected which are shown as below:
+ \arg CEC_FLAG_BR: Rx-byte data received
+ \arg CEC_FLAG_REND: end of reception
+ \arg CEC_FLAG_RO: RX overrun
+ \arg CEC_FLAG_BRE: bit rising error
+ \arg CEC_FLAG_BPSE: short bit period error
+ \arg CEC_FLAG_BPLE: long bit period error
+ \arg CEC_FLAG_RAE: Rx ACK error
+ \arg CEC_FLAG_ARBF: arbitration lost
+ \arg CEC_FLAG_TBR: Tx-byte data request
+ \arg CEC_FLAG_TEND: transmission successfully end
+ \arg CEC_FLAG_TU: Tx data buffer underrun
+ \arg CEC_FLAG_TERR: Tx-error
+ \arg CEC_FLAG_TAERR Tx ACK error flag
+ \param[out] none
+ \retval FlagStatus: SET or RESET
+*/
+FlagStatus cec_flag_get(uint32_t flag)
+{
+ if(CEC_INTF & flag){
+ return SET;
+ }else{
+ return RESET;
+ }
+}
+
+/*!
+ \brief clear CEC status
+ \param[in] flag: specify which flag
+ one or more parameters can be selected which are shown as below:
+ \arg CEC_FLAG_BR: Rx-byte data received
+ \arg CEC_FLAG_REND: end of reception
+ \arg CEC_FLAG_RO: RX overrun
+ \arg CEC_FLAG_BRE: bit rising error
+ \arg CEC_FLAG_BPSE: short bit period error
+ \arg CEC_FLAG_BPLE: long bit period error
+ \arg CEC_FLAG_RAE: Rx ACK error
+ \arg CEC_FLAG_ARBF: arbitration lost
+ \arg CEC_FLAG_TBR: Tx-byte data request
+ \arg CEC_FLAG_TEND: transmission successfully end
+ \arg CEC_FLAG_TU: Tx data buffer underrun
+ \arg CEC_FLAG_TERR: Tx-error
+ \arg CEC_FLAG_TAERR: Tx ACK error flag
+
+ \param[out] none
+ \retval FlagStatus: SET or RESET
+*/
+void cec_flag_clear(uint32_t flag)
+{
+ CEC_INTF |= flag;
+}
+
+/*!
+ \brief get CEC int flag and status
+ \param[in] flag: specify which flag
+ one or more parameters can be selected which are shown as below:
+ \arg CEC_INT_FLAG_BR: Rx-byte data received
+ \arg CEC_INT_FLAG_REND: end of reception
+ \arg CEC_INT_FLAG_RO: RX overrun
+ \arg CEC_INT_FLAG_BRE: bit rising error
+ \arg CEC_INT_FLAG_BPSE: short bit period error
+ \arg CEC_INT_FLAG_BPLE: long bit period error
+ \arg CEC_INT_FLAG_RAE: Rx ACK error
+ \arg CEC_INT_FLAG_ARBF: arbitration lost
+ \arg CEC_INT_FLAG_TBR: Tx-byte data request
+ \arg CEC_INT_FLAG_TEND: transmission successfully end
+ \arg CEC_INT_FLAG_TU: Tx data buffer underrun
+ \arg CEC_INT_FLAG_TERR: Tx-error
+ \arg CEC_INT_FLAG_TAERR: Tx ACK error flag
+ \param[out] none
+ \retval FlagStatus: SET or RESET
+*/
+FlagStatus cec_interrupt_flag_get(uint32_t flag)
+{
+ uint32_t interrupt_enable = 0U, interrupt_flag = 0U;
+ interrupt_flag = (CEC_INTF & flag);
+ interrupt_enable = (CEC_INTEN & flag);
+ if(interrupt_flag && interrupt_enable){
+ return SET;
+ }else{
+ return RESET;
+ }
+}
+
+/*!
+ \brief clear CEC int flag and status
+ \param[in] flag: specify which flag
+ one or more parameters can be selected which are shown as below:
+ \arg CEC_INT_FLAG_BR: Rx-byte data received
+ \arg CEC_INT_FLAG_REND: end of reception
+ \arg CEC_INT_FLAG_RO: RX overrun
+ \arg CEC_INT_FLAG_BRE: bit rising error
+ \arg CEC_INT_FLAG_BPSE: short bit period error
+ \arg CEC_INT_FLAG_BPLE: long bit period error
+ \arg CEC_INT_FLAG_RAE: Rx ACK error
+ \arg CEC_INT_FLAG_ARBF: arbitration lost
+ \arg CEC_INT_FLAG_TBR: Tx-byte data request
+ \arg CEC_INT_FLAG_TEND: transmission successfully end
+ \arg CEC_INT_FLAG_TU: Tx data buffer underrun
+ \arg CEC_INT_FLAG_TERR: Tx-error
+ \arg CEC_INT_FLAG_TAERR: Tx ACK error flag
+ \param[out] none
+ \retval none
+*/
+void cec_interrupt_flag_clear(uint32_t flag)
+{
+ CEC_INTF = flag;
+}
+
+#endif
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_cmp.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_cmp.c
new file mode 100644
index 00000000..767221fa
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_cmp.c
@@ -0,0 +1,269 @@
+/*!
+ \file gd32f3x0_cmp.c
+ \brief CMP driver
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2021-05-19, V2.1.1, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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.
+*/
+
+#include "gd32f3x0_cmp.h"
+
+/*!
+ \brief deinitialize comparator
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void cmp_deinit(void)
+{
+ CMP_CS = ((uint32_t)0x00000000U);
+}
+
+/*!
+ \brief initialize comparator mode
+ \param[in] cmp_periph
+ \arg CMP0: comparator 0
+ \arg CMP1: comparator 1
+ \param[in] operating_mode
+ \arg CMP_HIGHSPEED: high speed mode
+ \arg CMP_MIDDLESPEED: medium speed mode
+ \arg CMP_LOWSPEED: low speed mode
+ \arg CMP_VERYLOWSPEED: very-low speed mode
+ \param[in] inverting_input
+ \arg CMP_1_4VREFINT: VREFINT *1/4 input
+ \arg CMP_1_2VREFINT: VREFINT *1/2 input
+ \arg CMP_3_4VREFINT: VREFINT *3/4 input
+ \arg CMP_VREFINT: VREFINT input
+ \arg CMP_DAC: PA4 (DAC) input
+ \arg CMP_PA5: PA5 input
+ \arg CMP_PA_0_2: PA0 or PA2 input
+ \param[in] hysteresis
+ \arg CMP_HYSTERESIS_NO: output no hysteresis
+ \arg CMP_HYSTERESIS_LOW: output low hysteresis
+ \arg CMP_HYSTERESIS_MIDDLE: output middle hysteresis
+ \arg CMP_HYSTERESIS_HIGH: output high hysteresis
+ \param[out] none
+ \retval none
+*/
+void cmp_mode_init(uint32_t cmp_periph, operating_mode_enum operating_mode, inverting_input_enum inverting_input,
+ cmp_hysteresis_enum output_hysteresis)
+{
+ uint32_t CMPx_CS = 0;
+ if(CMP0 == cmp_periph) {
+ /* initialize comparator 0 mode */
+ CMPx_CS = CMP_CS;
+ CMPx_CS &= ~(uint32_t)(CMP_CS_CMP0M | CMP_CS_CMP0MSEL | CMP_CS_CMP0HST);
+ CMPx_CS |= CS_CMP0M(operating_mode) | CS_CMP0MSEL(inverting_input) | CS_CMP0HST(output_hysteresis);
+ CMP_CS = CMPx_CS;
+ } else {
+ /* initialize comparator 1 mode */
+ CMPx_CS = CMP_CS;
+ CMPx_CS &= ~(uint32_t)(CMP_CS_CMP1M | CMP_CS_CMP1MSEL | CMP_CS_CMP1HST);
+ CMPx_CS |= CS_CMP1M(operating_mode) | CS_CMP1MSEL(inverting_input) | CS_CMP1HST(output_hysteresis);
+ CMP_CS = CMPx_CS;
+ }
+}
+
+/*!
+ \brief initialize comparator output
+ \param[in] cmp_periph
+ \arg CMP0: comparator 0
+ \arg CMP1: comparator 1
+ \param[in] output_slection
+ \arg CMP_OUTPUT_NONE: output no selection
+ \arg CMP_OUTPUT_TIMER0BKIN: TIMER 0 break input
+ \arg CMP_OUTPUT_TIMER0IC0: TIMER 0 channel0 input capture
+ \arg CMP_OUTPUT_TIMER0OCPRECLR: TIMER 0 OCPRE_CLR input
+ \arg CMP_OUTPUT_TIMER1IC3: TIMER 1 channel3 input capture
+ \arg CMP_OUTPUT_TIMER1OCPRECLR: TIMER 1 OCPRE_CLR input
+ \arg CMP_OUTPUT_TIMER2IC0: TIMER 2 channel0 input capture
+ \arg CMP_OUTPUT_TIMER2OCPRECLR: TIMER 2 OCPRE_CLR input
+ \param[in] output_polarity
+ \arg CMP_OUTPUT_POLARITY_INVERTED: output is inverted
+ \arg CMP_OUTPUT_POLARITY_NOINVERTED: output is not inverted
+ \param[out] none
+ \retval none
+*/
+void cmp_output_init(uint32_t cmp_periph, cmp_output_enum output_slection, uint32_t output_polarity)
+{
+ uint32_t CMPx_CS = 0;
+ /* initialize comparator 0 output */
+ if(CMP0 == cmp_periph) {
+ CMPx_CS = CMP_CS;
+ CMPx_CS &= ~(uint32_t)CMP_CS_CMP0OSEL;
+ CMPx_CS |= CS_CMP0OSEL(output_slection);
+ /* output polarity */
+ if(CMP_OUTPUT_POLARITY_INVERTED == output_polarity) {
+ CMPx_CS |= CMP_CS_CMP0PL;
+ } else {
+ CMPx_CS &= ~CMP_CS_CMP0PL;
+ }
+ CMP_CS = CMPx_CS;
+ } else if(CMP1 == cmp_periph) {
+ /* initialize comparator 1 output */
+ CMPx_CS = CMP_CS;
+ CMPx_CS &= ~(uint32_t)CMP_CS_CMP1OSEL;
+ CMPx_CS |= CS_CMP1OSEL(output_slection);
+ /* output polarity */
+ if(CMP_OUTPUT_POLARITY_INVERTED == output_polarity) {
+ CMPx_CS |= CMP_CS_CMP1PL;
+ } else {
+ CMPx_CS &= ~CMP_CS_CMP1PL;
+ }
+ CMP_CS = CMPx_CS;
+ }
+}
+
+/*!
+ \brief enable comparator
+ \param[in] cmp_periph
+ \arg CMP0: comparator 0
+ \arg CMP1: comparator 1
+ \param[out] none
+ \retval none
+*/
+void cmp_enable(uint32_t cmp_periph)
+{
+ if(CMP0 == cmp_periph) {
+ CMP_CS |= CMP_CS_CMP0EN;
+ } else {
+ CMP_CS |= CMP_CS_CMP1EN;
+ }
+}
+
+/*!
+ \brief disable comparator
+ \param[in] cmp_periph
+ \arg CMP0: comparator 0
+ \arg CMP1: comparator 1
+ \param[out] none
+ \retval none
+*/
+void cmp_disable(uint32_t cmp_periph)
+{
+ if(CMP0 == cmp_periph) {
+ CMP_CS &= ~CMP_CS_CMP0EN;
+ } else {
+ CMP_CS &= ~CMP_CS_CMP1EN;
+ }
+}
+
+/*!
+ \brief enable comparator switch
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void cmp_switch_enable(void)
+{
+ CMP_CS |= CMP_CS_CMP0SW;
+}
+
+/*!
+ \brief disable comparator switch
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void cmp_switch_disable(void)
+{
+ CMP_CS &= ~CMP_CS_CMP0SW;
+}
+
+/*!
+ \brief enable the window mode
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void cmp_window_enable(void)
+{
+ CMP_CS |= CMP_CS_WNDEN;
+}
+
+/*!
+ \brief disable the window mode
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void cmp_window_disable(void)
+{
+ CMP_CS &= ~CMP_CS_WNDEN;
+}
+
+/*!
+ \brief lock the comparator
+ \param[in] cmp_periph
+ \arg CMP0: comparator 0
+ \arg CMP1: comparator 1
+ \param[out] none
+ \retval none
+*/
+void cmp_lock_enable(uint32_t cmp_periph)
+{
+ if(CMP0 == cmp_periph) {
+ /* lock CMP0 */
+ CMP_CS |= CMP_CS_CMP0LK;
+ } else {
+ /* lock CMP1 */
+ CMP_CS |= CMP_CS_CMP1LK;
+ }
+}
+
+/*!
+ \brief get output level
+ \param[in] cmp_periph
+ \arg CMP0: comparator 0
+ \arg CMP1: comparator 1
+ \param[out] none
+ \retval the output level
+*/
+uint32_t cmp_output_level_get(uint32_t cmp_periph)
+{
+ if(CMP0 == cmp_periph) {
+ /* get output level of CMP0 */
+ if(CMP_CS & CMP_CS_CMP0O) {
+ return CMP_OUTPUTLEVEL_HIGH;
+ } else {
+ return CMP_OUTPUTLEVEL_LOW;
+ }
+ } else {
+ /* get output level of CMP1 */
+ if(CMP_CS & CMP_CS_CMP1O) {
+ return CMP_OUTPUTLEVEL_HIGH;
+ } else {
+ return CMP_OUTPUTLEVEL_LOW;
+ }
+ }
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_crc.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_crc.c
new file mode 100644
index 00000000..87a5e5ff
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_crc.c
@@ -0,0 +1,244 @@
+/*!
+ \file gd32f3x0_crc.c
+ \brief CRC driver
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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.
+*/
+
+#include "gd32f3x0_crc.h"
+
+/*!
+ \brief deinit CRC calculation unit
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void crc_deinit(void)
+{
+ CRC_IDATA = (uint32_t)0xFFFFFFFFU;
+ CRC_DATA = (uint32_t)0xFFFFFFFFU;
+ CRC_FDATA = (uint32_t)0x00000000U;
+ CRC_POLY = (uint32_t)0x04C11DB7U;
+ CRC_CTL = CRC_CTL_RST;
+}
+
+/*!
+ \brief enable the reverse operation of output data
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void crc_reverse_output_data_enable(void)
+{
+ CRC_CTL &= (uint32_t)(~ CRC_CTL_REV_O);
+ CRC_CTL |= (uint32_t)CRC_CTL_REV_O;
+}
+
+/*!
+ \brief disable the reverse operation of output data
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void crc_reverse_output_data_disable(void)
+{
+ CRC_CTL &= (uint32_t)(~ CRC_CTL_REV_O);
+}
+
+/*!
+ \brief reset data register to the value of initializaiton data register
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void crc_data_register_reset(void)
+{
+ CRC_CTL |= (uint32_t)CRC_CTL_RST;
+}
+
+/*!
+ \brief read the data register
+ \param[in] none
+ \param[out] none
+ \retval 32-bit value of the data register
+*/
+uint32_t crc_data_register_read(void)
+{
+ uint32_t data;
+ data = CRC_DATA;
+ return (data);
+}
+
+/*!
+ \brief read the free data register
+ \param[in] none
+ \param[out] none
+ \retval 8-bit value of the free data register
+*/
+uint8_t crc_free_data_register_read(void)
+{
+ uint8_t fdata;
+ fdata = (uint8_t)CRC_FDATA;
+ return (fdata);
+}
+
+/*!
+ \brief write the free data register
+ \param[in] free_data: specify 8-bit data
+ \param[out] none
+ \retval none
+*/
+void crc_free_data_register_write(uint8_t free_data)
+{
+ CRC_FDATA = (uint32_t)free_data;
+}
+
+/*!
+ \brief write the initializaiton data register
+ \param[in] init_data:specify 32-bit data
+ \param[out] none
+ \retval none
+*/
+void crc_init_data_register_write(uint32_t init_data)
+{
+ CRC_IDATA = (uint32_t)init_data;
+}
+
+/*!
+ \brief configure the CRC input data function
+ \param[in] data_reverse: specify input data reverse function
+ only one parameter can be selected which is shown as below:
+ \arg CRC_INPUT_DATA_NOT: input data is not reversed
+ \arg CRC_INPUT_DATA_BYTE: input data is reversed on 8 bits
+ \arg CRC_INPUT_DATA_HALFWORD: input data is reversed on 16 bits
+ \arg CRC_INPUT_DATA_WORD: input data is reversed on 32 bits
+ \param[out] none
+ \retval none
+*/
+void crc_input_data_reverse_config(uint32_t data_reverse)
+{
+ CRC_CTL &= (uint32_t)(~CRC_CTL_REV_I);
+ CRC_CTL |= (uint32_t)data_reverse;
+}
+
+/*!
+ \brief configure the CRC size of polynomial function
+ \param[in] poly_size: size of polynomial
+ only one parameter can be selected which is shown as below:
+ \arg CRC_CTL_PS_32: 32-bit polynomial for CRC calculation
+ \arg CRC_CTL_PS_16: 16-bit polynomial for CRC calculation
+ \arg CRC_CTL_PS_8: 8-bit polynomial for CRC calculation
+ \arg CRC_CTL_PS_7: 7-bit polynomial for CRC calculation
+ \param[out] none
+ \retval none
+*/
+void crc_polynomial_size_set(uint32_t poly_size)
+{
+ CRC_CTL &= (uint32_t)(~(CRC_CTL_PS));
+ CRC_CTL |= (uint32_t)poly_size;
+}
+
+/*!
+ \brief configure the CRC polynomial value function
+ \param[in] poly: configurable polynomial value
+ \param[out] none
+ \retval none
+*/
+void crc_polynomial_set(uint32_t poly)
+{
+ CRC_POLY &= (uint32_t)(~CRC_POLY_POLY);
+ CRC_POLY = poly;
+}
+
+/*!
+ \brief CRC calculate single data
+ \param[in] sdata: specify input data data
+ \param[in] data_format: input data format
+ only one parameter can be selected which is shown as below:
+ \arg INPUT_FORMAT_WORD: input data in word format
+ \arg INPUT_FORMAT_HALFWORD: input data in half-word format
+ \arg INPUT_FORMAT_BYTE: input data in byte format
+ \param[out] none
+ \retval CRC calculate value
+*/
+uint32_t crc_single_data_calculate(uint32_t sdata, uint8_t data_format)
+{
+ if(INPUT_FORMAT_WORD == data_format) {
+ REG32(CRC) = sdata;
+ } else if(INPUT_FORMAT_HALFWORD == data_format) {
+ REG16(CRC) = (uint16_t)sdata;
+ } else {
+ REG8(CRC) = (uint8_t)sdata;
+ }
+
+ return(CRC_DATA);
+}
+
+/*!
+ \brief CRC calculate a data array
+ \param[in] array: pointer to the input data array
+ \param[in] size: size of the array
+ \param[in] data_format: input data format
+ only one parameter can be selected which is shown as below:
+ \arg INPUT_FORMAT_WORD: input data in word format
+ \arg INPUT_FORMAT_HALFWORD: input data in half-word format
+ \arg INPUT_FORMAT_BYTE: input data in byte format
+ \param[out] none
+ \retval CRC calculate value
+*/
+uint32_t crc_block_data_calculate(void *array, uint32_t size, uint8_t data_format)
+{
+ uint8_t *data8;
+ uint16_t *data16;
+ uint32_t *data32;
+ uint32_t index;
+
+ if(INPUT_FORMAT_WORD == data_format) {
+ data32 = (uint32_t *)array;
+ for(index = 0U; index < size; index++) {
+ REG32(CRC) = data32[index];
+ }
+ } else if(INPUT_FORMAT_HALFWORD == data_format) {
+ data16 = (uint16_t *)array;
+ for(index = 0U; index < size; index++) {
+ REG16(CRC) = data16[index];
+ }
+ } else {
+ data8 = (uint8_t *)array;
+ for(index = 0U; index < size; index++) {
+ REG8(CRC) = data8[index];
+ }
+ }
+
+ return (CRC_DATA);
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_ctc.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_ctc.c
new file mode 100644
index 00000000..21598498
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_ctc.c
@@ -0,0 +1,384 @@
+/*!
+ \file gd32f3x0_ctc.c
+ \brief CTC driver
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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.
+*/
+
+#include "gd32f3x0_ctc.h"
+
+#define CTC_FLAG_MASK ((uint32_t)0x00000700U)
+
+/*!
+ \brief reset CTC clock trim controller
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void ctc_deinit(void)
+{
+ /* reset CTC */
+ rcu_periph_reset_enable(RCU_CTCRST);
+ rcu_periph_reset_disable(RCU_CTCRST);
+}
+
+/*!
+ \brief configure reference signal source polarity
+ \param[in] polarity:
+ only one parameter can be selected which is shown as below:
+ \arg CTC_REFSOURCE_POLARITY_FALLING: reference signal source polarity is falling edge
+ \arg CTC_REFSOURCE_POLARITY_RISING: reference signal source polarity is rising edge
+ \param[out] none
+ \retval none
+*/
+void ctc_refsource_polarity_config(uint32_t polarity)
+{
+ CTC_CTL1 &= (uint32_t)(~CTC_CTL1_REFPOL);
+ CTC_CTL1 |= (uint32_t)polarity;
+}
+
+/*!
+ \brief select reference signal source
+ \param[in] refs:
+ only one parameter can be selected which is shown as below:
+ \arg CTC_REFSOURCE_GPIO: GPIO is selected
+ \arg CTC_REFSOURCE_LXTAL: LXTAL is clock selected
+ \arg CTC_REFSOURCE_USBSOF: USBSOF is selected
+ \param[out] none
+ \retval none
+*/
+void ctc_refsource_signal_select(uint32_t refs)
+{
+ CTC_CTL1 &= (uint32_t)(~CTC_CTL1_REFSEL);
+ CTC_CTL1 |= (uint32_t)refs;
+}
+
+/*!
+ \brief configure reference signal source prescaler
+ \param[in] prescaler:
+ only one parameter can be selected which is shown as below:
+ \arg CTC_REFSOURCE_PSC_OFF: reference signal not divided
+ \arg CTC_REFSOURCE_PSC_DIV2: reference signal divided by 2
+ \arg CTC_REFSOURCE_PSC_DIV4: reference signal divided by 4
+ \arg CTC_REFSOURCE_PSC_DIV8: reference signal divided by 8
+ \arg CTC_REFSOURCE_PSC_DIV16: reference signal divided by 16
+ \arg CTC_REFSOURCE_PSC_DIV32: reference signal divided by 32
+ \arg CTC_REFSOURCE_PSC_DIV64: reference signal divided by 64
+ \arg CTC_REFSOURCE_PSC_DIV128: reference signal divided by 128
+ \param[out] none
+ \retval none
+*/
+void ctc_refsource_prescaler_config(uint32_t prescaler)
+{
+ CTC_CTL1 &= (uint32_t)(~CTC_CTL1_REFPSC);
+ CTC_CTL1 |= (uint32_t)prescaler;
+}
+
+/*!
+ \brief configure clock trim base limit value
+ \param[in] limit_value: 8-bit clock trim base limit value
+ \arg 0x00-0xFF
+ \param[out] none
+ \retval none
+*/
+void ctc_clock_limit_value_config(uint8_t limit_value)
+{
+ CTC_CTL1 &= (uint32_t)(~CTC_CTL1_CKLIM);
+ CTC_CTL1 |= CTL1_CKLIM(limit_value);
+}
+
+/*!
+ \brief configure CTC counter reload value
+ \param[in] reload_value: 16-bit CTC counter reload value
+ \arg 0x0000-0xFFFF
+ \param[out] none
+ \retval none
+*/
+void ctc_counter_reload_value_config(uint16_t reload_value)
+{
+ CTC_CTL1 &= (uint32_t)(~CTC_CTL1_RLVALUE);
+ CTC_CTL1 |= (uint32_t)reload_value;
+}
+
+/*!
+ \brief enable CTC trim counter
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void ctc_counter_enable(void)
+{
+ CTC_CTL0 |= (uint32_t)CTC_CTL0_CNTEN;
+}
+
+/*!
+ \brief disable CTC trim counter
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void ctc_counter_disable(void)
+{
+ CTC_CTL0 &= (uint32_t)(~CTC_CTL0_CNTEN);
+}
+
+/*!
+ \brief configure the IRC48M trim value
+ \param[in] trim_value: 8-bit IRC48M trim value
+ \arg 0x00-0x3F
+ \param[out] none
+ \retval none
+*/
+void ctc_irc48m_trim_value_config(uint8_t trim_value)
+{
+ /* clear TRIMVALUE bits */
+ CTC_CTL0 &= (~(uint32_t)CTC_CTL0_TRIMVALUE);
+ /* set TRIMVALUE bits */
+ CTC_CTL0 |= CTL0_TRIMVALUE(trim_value);
+}
+
+/*!
+ \brief generate software reference source sync pulse
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void ctc_software_refsource_pulse_generate(void)
+{
+ CTC_CTL0 |= (uint32_t)CTC_CTL0_SWREFPUL;
+}
+
+/*!
+ \brief configure hardware automatically trim mode
+ \param[in] hardmode:
+ only one parameter can be selected which is shown as below:
+ \arg CTC_HARDWARE_TRIM_MODE_ENABLE: hardware automatically trim mode enable
+ \arg CTC_HARDWARE_TRIM_MODE_DISABLE: hardware automatically trim mode disable
+ \param[out] none
+ \retval none
+*/
+void ctc_hardware_trim_mode_config(uint32_t hardmode)
+{
+ CTC_CTL0 &= (uint32_t)(~CTC_CTL0_AUTOTRIM);
+ CTC_CTL0 |= (uint32_t)hardmode;
+}
+
+/*!
+ \brief read CTC counter capture value when reference sync pulse occurred
+ \param[in] none
+ \param[out] none
+ \retval the 16-bit CTC counter capture value
+*/
+uint16_t ctc_counter_capture_value_read(void)
+{
+ uint16_t capture_value = 0U;
+ capture_value = (uint16_t)GET_STAT_REFCAP(CTC_STAT);
+ return (capture_value);
+}
+
+/*!
+ \brief read CTC trim counter direction when reference sync pulse occurred
+ \param[in] none
+ \param[out] none
+ \retval FlagStatus: SET or RESET
+ \arg SET: CTC trim counter direction is down-counting
+ \arg RESET: CTC trim counter direction is up-counting
+*/
+FlagStatus ctc_counter_direction_read(void)
+{
+ FlagStatus ret_status = RESET;
+ if(RESET != (CTC_STAT & CTC_STAT_REFDIR)) {
+ ret_status = SET;
+ }
+ return ret_status;
+}
+
+/*!
+ \brief read CTC counter reload value
+ \param[in] none
+ \param[out] none
+ \retval the 16-bit CTC counter reload value
+*/
+uint16_t ctc_counter_reload_value_read(void)
+{
+ uint16_t reload_value = 0U;
+ reload_value = (uint16_t)(CTC_CTL1 & CTC_CTL1_RLVALUE);
+ return (reload_value);
+}
+
+/*!
+ \brief read the IRC48M trim value
+ \param[in] none
+ \param[out] none
+ \retval the 8-bit IRC48M trim value
+*/
+uint8_t ctc_irc48m_trim_value_read(void)
+{
+ uint8_t trim_value = 0U;
+ trim_value = (uint8_t)GET_CTL0_TRIMVALUE(CTC_CTL0);
+ return (trim_value);
+}
+
+/*!
+ \brief enable the CTC interrupt
+ \param[in] interrupt: CTC interrupt enable
+ one or more parameters can be selected which are shown as below:
+ \arg CTC_INT_CKOK: clock trim OK interrupt enable
+ \arg CTC_INT_CKWARN: clock trim warning interrupt enable
+ \arg CTC_INT_ERR: error interrupt enable
+ \arg CTC_INT_EREF: expect reference interrupt enable
+ \param[out] none
+ \retval none
+*/
+void ctc_interrupt_enable(uint32_t interrupt)
+{
+ CTC_CTL0 |= (uint32_t)interrupt;
+}
+
+/*!
+ \brief disable the CTC interrupt
+ \param[in] interrupt: CTC interrupt enable source
+ one or more parameters can be selected which are shown as below:
+ \arg CTC_INT_CKOK: clock trim OK interrupt enable
+ \arg CTC_INT_CKWARN: clock trim warning interrupt enable
+ \arg CTC_INT_ERR: error interrupt enable
+ \arg CTC_INT_EREF: expect reference interrupt enable
+ \param[out] none
+ \retval none
+*/
+void ctc_interrupt_disable(uint32_t interrupt)
+{
+ CTC_CTL0 &= (uint32_t)(~(interrupt));
+}
+
+/*!
+ \brief get CTC flag
+ \param[in] flag: the CTC flag
+ only one parameter can be selected which is shown as below:
+ \arg CTC_FLAG_CKOK: clock trim OK flag
+ \arg CTC_FLAG_CKWARN: clock trim warning flag
+ \arg CTC_FLAG_ERR: error flag
+ \arg CTC_FLAG_EREF: expect reference flag
+ \arg CTC_FLAG_CKERR: clock trim error bit
+ \arg CTC_FLAG_REFMISS: reference sync pulse miss
+ \arg CTC_FLAG_TRIMERR: trim value error bit
+ \param[out] none
+ \retval FlagStatus: SET or RESET
+*/
+FlagStatus ctc_flag_get(uint32_t flag)
+{
+ FlagStatus ret_status = RESET;
+
+ if(RESET != (CTC_STAT & flag)) {
+ ret_status = SET;
+ }
+ return ret_status;
+}
+
+/*!
+ \brief clear CTC flag
+ \param[in] flag: the CTC flag
+ only one parameter can be selected which is shown as below:
+ \arg CTC_FLAG_CKOK: clock trim OK flag
+ \arg CTC_FLAG_CKWARN: clock trim warning flag
+ \arg CTC_FLAG_ERR: error flag
+ \arg CTC_FLAG_EREF: expect reference flag
+ \arg CTC_FLAG_CKERR: clock trim error bit
+ \arg CTC_FLAG_REFMISS: reference sync pulse miss
+ \arg CTC_FLAG_TRIMERR: trim value error bit
+ \param[out] none
+ \retval none
+*/
+void ctc_flag_clear(uint32_t flag)
+{
+ if(flag & CTC_FLAG_MASK) {
+ CTC_INTC |= CTC_INTC_ERRIC;
+ } else {
+ CTC_INTC |= flag;
+ }
+}
+
+/*!
+ \brief get CTC interrupt flag
+ \param[in] interrupt: the CTC interrupt flag
+ only one parameter can be selected which is shown as below:
+ \arg CTC_INT_FLAG_CKOK: clock trim OK interrupt
+ \arg CTC_INT_FLAG_CKWARN: clock trim warning interrupt
+ \arg CTC_INT_FLAG_ERR: error interrupt
+ \arg CTC_INT_FLAG_EREF: expect reference interrupt
+ \arg CTC_INT_FLAG_CKERR: clock trim error bit interrupt
+ \arg CTC_INT_FLAG_REFMISS: reference sync pulse miss interrupt
+ \arg CTC_INT_FLAG_TRIMERR: trim value error interrupt
+ \param[out] none
+ \retval FlagStatus: SET or RESET
+*/
+FlagStatus ctc_interrupt_flag_get(uint32_t interrupt)
+{
+ uint32_t ctc_int = 0U, intenable = 0U;
+ FlagStatus ret_status = RESET;
+
+ if(interrupt & CTC_FLAG_MASK) {
+ intenable = CTC_CTL0 & CTC_INT_ERR;
+ } else {
+ intenable = CTC_CTL0 & interrupt;
+ }
+ ctc_int = CTC_STAT & interrupt;
+
+ if(ctc_int && intenable) {
+ ret_status = SET;
+ }
+ return ret_status;
+}
+
+/*!
+ \brief clear CTC interrupt flag
+ \param[in] interrupt: the CTC interrupt flag
+ only one parameter can be selected which is shown as below:
+ \arg CTC_INT_FLAG_CKOK: clock trim OK interrupt
+ \arg CTC_INT_FLAG_CKWARN: clock trim warning interrupt
+ \arg CTC_INT_FLAG_ERR: error interrupt
+ \arg CTC_INT_FLAG_EREF: expect reference interrupt
+ \arg CTC_INT_FLAG_CKERR: clock trim error bit interrupt
+ \arg CTC_INT_FLAG_REFMISS: reference sync pulse miss interrupt
+ \arg CTC_INT_FLAG_TRIMERR: trim value error interrupt
+ \param[out] none
+ \retval none
+*/
+void ctc_interrupt_flag_clear(uint32_t interrupt)
+{
+ if(interrupt & CTC_FLAG_MASK) {
+ CTC_INTC |= CTC_INTC_ERRIC;
+ } else {
+ CTC_INTC |= interrupt;
+ }
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_dac.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_dac.c
new file mode 100644
index 00000000..8b16fcf7
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_dac.c
@@ -0,0 +1,389 @@
+/*!
+ \file gd32f3x0_dac.c
+ \brief DAC driver
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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.
+*/
+
+#ifdef GD32F350
+#include "gd32f3x0_dac.h"
+
+/*!
+ \brief deinitialize DAC
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void dac_deinit(void)
+{
+ rcu_periph_reset_enable(RCU_DACRST);
+ rcu_periph_reset_disable(RCU_DACRST);
+}
+
+/*!
+ \brief enable DAC
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void dac_enable(void)
+{
+ DAC_CTL |= DAC_CTL_DEN;
+}
+
+/*!
+ \brief disable DAC
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void dac_disable(void)
+{
+ DAC_CTL &= ~DAC_CTL_DEN;
+}
+
+/*!
+ \brief enable DAC DMA
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void dac_dma_enable(void)
+{
+ DAC_CTL |= DAC_CTL_DDMAEN;
+}
+
+/*!
+ \brief disable DAC DMA
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void dac_dma_disable(void)
+{
+ DAC_CTL &= ~DAC_CTL_DDMAEN;
+}
+
+/*!
+ \brief enable DAC output buffer
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void dac_output_buffer_enable(void)
+{
+ DAC_CTL &= ~DAC_CTL_DBOFF;
+}
+
+/*!
+ \brief disable DAC output buffer
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void dac_output_buffer_disable(void)
+{
+ DAC_CTL |= DAC_CTL_DBOFF;
+}
+
+/*!
+ \brief enable DAC trigger
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void dac_trigger_enable(void)
+{
+ DAC_CTL |= DAC_CTL_DTEN;
+}
+
+/*!
+ \brief disable DAC trigger
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void dac_trigger_disable(void)
+{
+ DAC_CTL &= ~DAC_CTL_DTEN;
+}
+
+/*!
+ \brief enable DAC software trigger
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void dac_software_trigger_enable(void)
+{
+ DAC_SWT |= DAC_SWT_SWTR;
+}
+
+/*!
+ \brief disable DAC software trigger
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void dac_software_trigger_disable(void)
+{
+ DAC_SWT &= ~DAC_SWT_SWTR;
+}
+
+/*!
+ \brief configure DAC trigger source
+ \param[in] triggersource: external triggers of DAC
+ \arg DAC_TRIGGER_T1_TRGO: trigger source is TIMER1 TRGO
+ \arg DAC_TRIGGER_T2_TRGO: trigger source is TIMER2 TRGO
+ \arg DAC_TRIGGER_T5_TRGO: trigger source is TIMER5 TRGO
+ \arg DAC_TRIGGER_T14_TRGO: trigger source is TIMER14 TRGO
+ \arg DAC_TRIGGER_EXTI_9: trigger source is EXTI interrupt line9 event
+ \arg DAC_TRIGGER_SOFTWARE: software trigger
+ \param[out] none
+ \retval none
+*/
+void dac_trigger_source_config(uint32_t triggersource)
+{
+ DAC_CTL &= ~DAC_CTL_DTSEL;
+ DAC_CTL |= triggersource;
+}
+
+/*!
+ \brief configure DAC wave mode
+ \param[in] wave_mode
+ \arg DAC_WAVE_DISABLE: wave disable
+ \arg DAC_WAVE_MODE_LFSR: LFSR noise mode
+ \arg DAC_WAVE_MODE_TRIANGLE: triangle noise mode
+ \param[out] none
+ \retval none
+*/
+void dac_wave_mode_config(uint32_t wave_mode)
+{
+ DAC_CTL &= ~DAC_CTL_DWM;
+ DAC_CTL |= wave_mode;
+}
+
+/*!
+ \brief configure DAC wave bit width
+ \param[in] bit_width
+ \arg DAC_WAVE_BIT_WIDTH_1: bit width of the wave signal is 1
+ \arg DAC_WAVE_BIT_WIDTH_2: bit width of the wave signal is 2
+ \arg DAC_WAVE_BIT_WIDTH_3: bit width of the wave signal is 3
+ \arg DAC_WAVE_BIT_WIDTH_4: bit width of the wave signal is 4
+ \arg DAC_WAVE_BIT_WIDTH_5: bit width of the wave signal is 5
+ \arg DAC_WAVE_BIT_WIDTH_6: bit width of the wave signal is 6
+ \arg DAC_WAVE_BIT_WIDTH_7: bit width of the wave signal is 7
+ \arg DAC_WAVE_BIT_WIDTH_8: bit width of the wave signal is 8
+ \arg DAC_WAVE_BIT_WIDTH_9: bit width of the wave signal is 9
+ \arg DAC_WAVE_BIT_WIDTH_10: bit width of the wave signal is 10
+ \arg DAC_WAVE_BIT_WIDTH_11: bit width of the wave signal is 11
+ \arg DAC_WAVE_BIT_WIDTH_12: bit width of the wave signal is 12
+ \param[out] none
+ \retval none
+*/
+void dac_wave_bit_width_config(uint32_t bit_width)
+{
+ DAC_CTL &= ~DAC_CTL_DWBW;
+ DAC_CTL |= bit_width;
+}
+
+/*!
+ \brief configure DAC LFSR noise mode
+ \param[in] unmask_bits
+ \arg DAC_LFSR_BIT0: unmask the LFSR bit0
+ \arg DAC_LFSR_BITS1_0: unmask the LFSR bits[1:0]
+ \arg DAC_LFSR_BITS2_0: unmask the LFSR bits[2:0]
+ \arg DAC_LFSR_BITS3_0: unmask the LFSR bits[3:0]
+ \arg DAC_LFSR_BITS4_0: unmask the LFSR bits[4:0]
+ \arg DAC_LFSR_BITS5_0: unmask the LFSR bits[5:0]
+ \arg DAC_LFSR_BITS6_0: unmask the LFSR bits[6:0]
+ \arg DAC_LFSR_BITS7_0: unmask the LFSR bits[7:0]
+ \arg DAC_LFSR_BITS8_0: unmask the LFSR bits[8:0]
+ \arg DAC_LFSR_BITS9_0: unmask the LFSR bits[9:0]
+ \arg DAC_LFSR_BITS10_0: unmask the LFSR bits[10:0]
+ \arg DAC_LFSR_BITS11_0: unmask the LFSR bits[11:0]
+ \param[out] none
+ \retval none
+*/
+void dac_lfsr_noise_config(uint32_t unmask_bits)
+{
+ DAC_CTL &= ~DAC_CTL_DWBW;
+ DAC_CTL |= unmask_bits;
+}
+
+/*!
+ \brief configure DAC triangle noise mode
+ \param[in] amplitude
+ \arg DAC_TRIANGLE_AMPLITUDE_1: triangle amplitude is 1
+ \arg DAC_TRIANGLE_AMPLITUDE_3: triangle amplitude is 3
+ \arg DAC_TRIANGLE_AMPLITUDE_7: triangle amplitude is 7
+ \arg DAC_TRIANGLE_AMPLITUDE_15: triangle amplitude is 15
+ \arg DAC_TRIANGLE_AMPLITUDE_31: triangle amplitude is 31
+ \arg DAC_TRIANGLE_AMPLITUDE_63: triangle amplitude is 63
+ \arg DAC_TRIANGLE_AMPLITUDE_127: triangle amplitude is 127
+ \arg DAC_TRIANGLE_AMPLITUDE_255: triangle amplitude is 255
+ \arg DAC_TRIANGLE_AMPLITUDE_511: triangle amplitude is 511
+ \arg DAC_TRIANGLE_AMPLITUDE_1023: triangle amplitude is 1023
+ \arg DAC_TRIANGLE_AMPLITUDE_2047: triangle amplitude is 2047
+ \arg DAC_TRIANGLE_AMPLITUDE_4095: triangle amplitude is 4095
+ \param[out] none
+ \retval none
+*/
+void dac_triangle_noise_config(uint32_t amplitude)
+{
+ DAC_CTL &= ~DAC_CTL_DWBW;
+ DAC_CTL |= amplitude;
+}
+
+/*!
+ \brief get DAC output value
+ \param[in] none
+ \param[out] none
+ \retval DAC output data
+*/
+uint16_t dac_output_value_get(void)
+{
+ uint16_t data = 0U;
+ data = (uint16_t)DAC_DO;
+ return data;
+}
+
+/*!
+ \brief set DAC data holding register value
+ \param[in] dac_align
+ \arg DAC_ALIGN_8B_R: data right 8b alignment
+ \arg DAC_ALIGN_12B_R: data right 12b alignment
+ \arg DAC_ALIGN_12B_L: data left 12b alignment
+ \param[in] data: data to be loaded
+ \param[out] none
+ \retval none
+*/
+void dac_data_set(uint32_t dac_align, uint16_t data)
+{
+ switch(dac_align) {
+ /* data right 12b alignment */
+ case DAC_ALIGN_12B_R:
+ DAC_R12DH = data;
+ break;
+ /* data left 12b alignment */
+ case DAC_ALIGN_12B_L:
+ DAC_L12DH = data;
+ break;
+ /* data right 8b alignment */
+ case DAC_ALIGN_8B_R:
+ DAC_R8DH = data;
+ break;
+ default:
+ break;
+ }
+}
+
+/*!
+ \brief get the specified DAC flag(DAC DMA underrun flag)
+ \param[in] none
+ \param[out] none
+ \retval the state of dac bit(SET or RESET)
+*/
+FlagStatus dac_flag_get(void)
+{
+ /* check the DMA underrun flag */
+ if((uint8_t)RESET != (DAC_STAT & DAC_STAT_DDUDR)) {
+ return SET;
+ } else {
+ return RESET;
+ }
+}
+
+/*!
+ \brief clear the specified DAC flag(DAC DMA underrun flag)
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void dac_flag_clear(void)
+{
+ DAC_STAT |= DAC_STAT_DDUDR;
+}
+
+/*!
+ \brief enable DAC interrupt(DAC DMA underrun interrupt)
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void dac_interrupt_enable(void)
+{
+ DAC_CTL |= DAC_CTL_DDUDRIE;
+}
+
+/*!
+ \brief disable DAC interrupt(DAC DMA underrun interrupt)
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void dac_interrupt_disable(void)
+{
+ DAC_CTL &= ~DAC_CTL_DDUDRIE;
+}
+/*!
+ \brief get the specified DAC interrupt flag(DAC DMA underrun interrupt flag)
+ \param[in] none
+ \param[out] none
+ \retval the state of DAC interrupt flag(SET or RESET)
+*/
+FlagStatus dac_interrupt_flag_get(void)
+{
+ FlagStatus temp_flag = RESET;
+ uint32_t ddudr_flag = 0U, ddudrie_flag = 0U;
+ /* check the DMA underrun flag and DAC DMA underrun interrupt enable flag */
+ ddudr_flag = DAC_STAT & DAC_STAT_DDUDR;
+ ddudrie_flag = DAC_CTL & DAC_CTL_DDUDRIE;
+ if((RESET != ddudr_flag) && (RESET != ddudrie_flag)) {
+ temp_flag = SET;
+ }
+ return temp_flag;
+}
+
+/*!
+ \brief clear the specified DAC interrupt flag(DAC DMA underrun interrupt flag)
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void dac_interrupt_flag_clear(void)
+{
+ DAC_STAT |= DAC_STAT_DDUDR;
+}
+
+#endif /* GD32F350 */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_dbg.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_dbg.c
new file mode 100644
index 00000000..adbe38f8
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_dbg.c
@@ -0,0 +1,135 @@
+/*!
+ \file gd32f3x0_dbg.c
+ \brief DBG driver
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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.
+*/
+
+#include "gd32f3x0_dbg.h"
+
+#define DBG_RESET_VAL ((uint32_t)0x00000000U) /*!< DBG reset value */
+
+/*!
+ \brief deinitialize the DBG
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void dbg_deinit(void)
+{
+ DBG_CTL0 = DBG_RESET_VAL;
+ DBG_CTL1 = DBG_RESET_VAL;
+}
+
+/*!
+ \brief read DBG_ID code register
+ \param[in] none
+ \param[out] none
+ \retval DBG_ID code
+*/
+uint32_t dbg_id_get(void)
+{
+ return DBG_ID;
+}
+
+/*!
+ \brief enable low power behavior when the mcu is in debug mode
+ \param[in] dbg_low_power:
+ one or more parameters can be selected which are shown as below:
+ \arg DBG_LOW_POWER_SLEEP: keep debugger connection during sleep mode
+ \arg DBG_LOW_POWER_DEEPSLEEP: keep debugger connection during deepsleep mode
+ \arg DBG_LOW_POWER_STANDBY: keep debugger connection during standby mode
+ \param[out] none
+ \retval none
+*/
+void dbg_low_power_enable(uint32_t dbg_low_power)
+{
+ DBG_CTL0 |= dbg_low_power;
+}
+
+/*!
+ \brief disable low power behavior when the mcu is in debug mode
+ \param[in] dbg_low_power:
+ one or more parameters can be selected which are shown as below:
+ \arg DBG_LOW_POWER_SLEEP: donot keep debugger connection during sleep mode
+ \arg DBG_LOW_POWER_DEEPSLEEP: donot keep debugger connection during deepsleep mode
+ \arg DBG_LOW_POWER_STANDBY: donot keep debugger connection during standby mode
+ \param[out] none
+ \retval none
+*/
+void dbg_low_power_disable(uint32_t dbg_low_power)
+{
+ DBG_CTL0 &= ~dbg_low_power;
+}
+
+/*!
+ \brief enable peripheral behavior when the mcu is in debug mode
+ \param[in] dbg_periph: refer to dbg_periph_enum
+ only one parameter can be selected which are shown as below:
+ \arg DBG_SLEEP_HOLD: keep debugger connection during sleep mode
+ \arg DBG_DEEPSLEEP_HOLD: keep debugger connection during deepsleep mode
+ \arg DBG_STANDBY_HOLD: keep debugger connection during standby mode
+ \arg DBG_FWDGT_HOLD: debug FWDGT kept when core is halted
+ \arg DBG_WWDGT_HOLD: debug WWDGT kept when core is halted
+ \arg DBG_TIMERx_HOLD (x=0,1,2,5,13,14,15,16,TIMER5 is only available in GD32F350,
+ TIMER1 is only available in GD32F350 and GD32F330): hold TIMERx counter when core is halted
+ \arg DBG_I2Cx_HOLD (x=0,1): hold I2Cx smbus when core is halted
+ \arg DBG_RTC_HOLD: hold RTC calendar and wakeup counter when core is halted
+ \param[out] none
+ \retval none
+*/
+void dbg_periph_enable(dbg_periph_enum dbg_periph)
+{
+ DBG_REG_VAL(dbg_periph) |= BIT(DBG_BIT_POS(dbg_periph));
+}
+
+/*!
+ \brief disable peripheral behavior when the mcu is in debug mode
+ \param[in] dbg_periph: refer to dbg_periph_enum
+ only one parameter can be selected which are shown as below:
+ \arg DBG_SLEEP_HOLD: keep debugger connection during sleep mode
+ \arg DBG_DEEPSLEEP_HOLD: keep debugger connection during deepsleep mode
+ \arg DBG_STANDBY_HOLD: keep debugger connection during standby mode
+ \arg DBG_FWDGT_HOLD: debug FWDGT kept when core is halted
+ \arg DBG_WWDGT_HOLD: debug WWDGT kept when core is halted
+ \arg DBG_TIMERx_HOLD (x=0,1,2,5,13,14,15,16,TIMER5 is only available in GD32F350,
+ TIMER1 is only available in GD32F350 and GD32F330): hold TIMERx counter when core is halted
+ \arg DBG_I2Cx_HOLD (x=0,1): hold I2Cx smbus when core is halted
+ \arg DBG_RTC_HOLD: hold RTC calendar and wakeup counter when core is halted
+ \param[out] none
+ \retval none
+*/
+void dbg_periph_disable(dbg_periph_enum dbg_periph)
+{
+ DBG_REG_VAL(dbg_periph) &= ~BIT(DBG_BIT_POS(dbg_periph));
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_dma.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_dma.c
new file mode 100644
index 00000000..22a806de
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_dma.c
@@ -0,0 +1,563 @@
+/*!
+ \file gd32f3x0_dma.c
+ \brief DMA driver
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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.
+*/
+
+#include "gd32f3x0_dma.h"
+
+/*!
+ \brief deinitialize DMA a channel registers
+ \param[in] channelx: specify which DMA channel is deinitialized
+ only one parameter can be selected which is shown as below:
+ \arg DMA_CHx(x=0..6)
+ \param[out] none
+ \retval none
+*/
+void dma_deinit(dma_channel_enum channelx)
+{
+ /* disable DMA a channel */
+ DMA_CHCTL(channelx) &= ~DMA_CHXCTL_CHEN;
+ /* reset DMA channel registers */
+ DMA_CHCTL(channelx) = DMA_CHCTL_RESET_VALUE;
+ DMA_CHCNT(channelx) = DMA_CHCNT_RESET_VALUE;
+ DMA_CHPADDR(channelx) = DMA_CHPADDR_RESET_VALUE;
+ DMA_CHMADDR(channelx) = DMA_CHMADDR_RESET_VALUE;
+ DMA_INTC |= DMA_FLAG_ADD(DMA_CHINTF_RESET_VALUE, channelx);
+}
+
+/*!
+ \brief initialize the parameters of DMA struct with the default values
+ \param[in] init_struct: the initialization data needed to initialize DMA channel
+ \param[out] none
+ \retval none
+*/
+void dma_struct_para_init(dma_parameter_struct *init_struct)
+{
+ /* set the DMA struct with the default values */
+ init_struct->periph_addr = 0U;
+ init_struct->periph_width = 0U;
+ init_struct->periph_inc = (uint8_t)DMA_PERIPH_INCREASE_DISABLE;
+ init_struct->memory_addr = 0U;
+ init_struct->memory_width = 0U;
+ init_struct->memory_inc = (uint8_t)DMA_MEMORY_INCREASE_DISABLE;
+ init_struct->number = 0U;
+ init_struct->direction = (uint8_t)DMA_PERIPHERAL_TO_MEMORY;
+ init_struct->priority = (uint32_t)DMA_PRIORITY_LOW;
+}
+
+/*!
+ \brief initialize DMA channel
+ \param[in] channelx: specify which DMA channel is initialized
+ only one parameter can be selected which is shown as below:
+ \arg DMA_CHx(x=0..6)
+ \param[in] init_struct: the data needed to initialize DMA channel
+ periph_addr: peripheral base address
+ periph_width: DMA_PERIPHERAL_WIDTH_8BIT,DMA_PERIPHERAL_WIDTH_16BIT,DMA_PERIPHERAL_WIDTH_32BIT
+ periph_inc: DMA_PERIPH_INCREASE_ENABLE,DMA_PERIPH_INCREASE_DISABLE
+ memory_addr: memory base address
+ memory_width: DMA_MEMORY_WIDTH_8BIT,DMA_MEMORY_WIDTH_16BIT,DMA_MEMORY_WIDTH_32BIT
+ memory_inc: DMA_MEMORY_INCREASE_ENABLE,DMA_MEMORY_INCREASE_DISABLE
+ direction: DMA_PERIPHERAL_TO_MEMORY,DMA_MEMORY_TO_PERIPHERAL
+ number: the number of remaining data to be transferred by the DMA
+ priority: DMA_PRIORITY_LOW,DMA_PRIORITY_MEDIUM,DMA_PRIORITY_HIGH,DMA_PRIORITY_ULTRA_HIGH
+ \param[out] none
+ \retval none
+*/
+void dma_init(dma_channel_enum channelx, dma_parameter_struct *init_struct)
+{
+ uint32_t ctl;
+
+ dma_channel_disable(channelx);
+
+ /* configure peripheral base address */
+ DMA_CHPADDR(channelx) = init_struct->periph_addr;
+
+ /* configure memory base address */
+ DMA_CHMADDR(channelx) = init_struct->memory_addr;
+
+ /* configure the number of remaining data to be transferred */
+ DMA_CHCNT(channelx) = (init_struct->number & DMA_CHANNEL_CNT_MASK);
+
+ /* configure peripheral transfer width,memory transfer width,channel priotity */
+ ctl = DMA_CHCTL(channelx);
+ ctl &= ~(DMA_CHXCTL_PWIDTH | DMA_CHXCTL_MWIDTH | DMA_CHXCTL_PRIO);
+ ctl |= (init_struct->periph_width | init_struct->memory_width | init_struct->priority);
+ DMA_CHCTL(channelx) = ctl;
+
+ /* configure peripheral increasing mode */
+ if(DMA_PERIPH_INCREASE_ENABLE == init_struct->periph_inc) {
+ DMA_CHCTL(channelx) |= DMA_CHXCTL_PNAGA;
+ } else {
+ DMA_CHCTL(channelx) &= ~DMA_CHXCTL_PNAGA;
+ }
+
+ /* configure memory increasing mode */
+ if(DMA_MEMORY_INCREASE_ENABLE == init_struct->memory_inc) {
+ DMA_CHCTL(channelx) |= DMA_CHXCTL_MNAGA;
+ } else {
+ DMA_CHCTL(channelx) &= ~DMA_CHXCTL_MNAGA;
+ }
+
+ /* configure the direction of data transfer */
+ if(DMA_PERIPHERAL_TO_MEMORY == init_struct->direction) {
+ DMA_CHCTL(channelx) &= ~DMA_CHXCTL_DIR;
+ } else {
+ DMA_CHCTL(channelx) |= DMA_CHXCTL_DIR;
+ }
+}
+
+/*!
+ \brief enable DMA circulation mode
+ \param[in] channelx: specify which DMA channel to set
+ only one parameter can be selected which is shown as below:
+ \arg DMA_CHx(x=0..6)
+ \param[out] none
+ \retval none
+*/
+void dma_circulation_enable(dma_channel_enum channelx)
+{
+ DMA_CHCTL(channelx) |= DMA_CHXCTL_CMEN;
+}
+
+/*!
+ \brief disable DMA circulation mode
+ \param[in] channelx: specify which DMA channel to set
+ only one parameter can be selected which is shown as below:
+ \arg DMA_CHx(x=0..6)
+ \param[out] none
+ \retval none
+*/
+void dma_circulation_disable(dma_channel_enum channelx)
+{
+ DMA_CHCTL(channelx) &= ~DMA_CHXCTL_CMEN;
+}
+
+/*!
+ \brief enable memory to memory mode
+ \param[in] channelx: specify which DMA channel to set
+ only one parameter can be selected which is shown as below:
+ \arg DMA_CHx(x=0..6)
+ \param[out] none
+ \retval none
+*/
+void dma_memory_to_memory_enable(dma_channel_enum channelx)
+{
+ DMA_CHCTL(channelx) |= DMA_CHXCTL_M2M;
+}
+
+/*!
+ \brief disable memory to memory mode
+ \param[in] channelx: specify which DMA channel to set
+ only one parameter can be selected which is shown as below:
+ \arg DMA_CHx(x=0..6)
+ \param[out] none
+ \retval none
+*/
+void dma_memory_to_memory_disable(dma_channel_enum channelx)
+{
+ DMA_CHCTL(channelx) &= ~DMA_CHXCTL_M2M;
+}
+
+/*!
+ \brief enable DMA channel
+ \param[in] channelx: specify which DMA channel to set
+ only one parameter can be selected which is shown as below:
+ \arg DMA_CHx(x=0..6)
+ \param[out] none
+ \retval none
+*/
+void dma_channel_enable(dma_channel_enum channelx)
+{
+ DMA_CHCTL(channelx) |= DMA_CHXCTL_CHEN;
+}
+
+/*!
+ \brief disable DMA channel
+ \param[in] channelx: specify which DMA channel to set
+ only one parameter can be selected which is shown as below:
+ \arg DMA_CHx(x=0..6)
+ \param[out] none
+ \retval none
+*/
+void dma_channel_disable(dma_channel_enum channelx)
+{
+ DMA_CHCTL(channelx) &= ~DMA_CHXCTL_CHEN;
+}
+
+/*!
+ \brief set DMA peripheral base address
+ \param[in] channelx: specify which DMA channel to set peripheral base address
+ only one parameter can be selected which is shown as below:
+ \arg DMA_CHx(x=0..6)
+ \param[in] address: peripheral base address
+ \param[out] none
+ \retval none
+*/
+void dma_periph_address_config(dma_channel_enum channelx, uint32_t address)
+{
+ DMA_CHPADDR(channelx) = address;
+}
+
+/*!
+ \brief set DMA memory base address
+ \param[in] channelx: specify which DMA channel to set memory base address
+ only one parameter can be selected which is shown as below:
+ \arg DMA_CHx(x=0..6)
+ \param[in] address: memory base address
+ \param[out] none
+ \retval none
+*/
+void dma_memory_address_config(dma_channel_enum channelx, uint32_t address)
+{
+ DMA_CHMADDR(channelx) = address;
+}
+
+/*!
+ \brief set the number of remaining data to be transferred by the DMA
+ \param[in] channelx: specify which DMA channel to set number
+ only one parameter can be selected which is shown as below:
+ \arg DMA_CHx(x=0..6)
+ \param[in] number: the number of remaining data to be transferred by the DMA
+ \param[out] none
+ \retval none
+*/
+void dma_transfer_number_config(dma_channel_enum channelx, uint32_t number)
+{
+ DMA_CHCNT(channelx) = (number & DMA_CHANNEL_CNT_MASK);
+}
+
+/*!
+ \brief get the number of remaining data to be transferred by the DMA
+ \param[in] channelx: specify which DMA channel to set number
+ only one parameter can be selected which is shown as below:
+ \arg DMA_CHx(x=0..6)
+ \param[out] none
+ \retval the number of remaining data to be transferred by the DMA
+*/
+uint32_t dma_transfer_number_get(dma_channel_enum channelx)
+{
+ return (uint32_t)DMA_CHCNT(channelx);
+}
+
+/*!
+ \brief configure priority level of DMA channel
+ \param[in] channelx: specify which DMA channel to set
+ only one parameter can be selected which is shown as below:
+ \arg DMA_CHx(x=0..6)
+ \param[in] priority: priority level of this channel
+ only one parameter can be selected which is shown as below:
+ \arg DMA_PRIORITY_LOW: low priority
+ \arg DMA_PRIORITY_MEDIUM: medium priority
+ \arg DMA_PRIORITY_HIGH: high priority
+ \arg DMA_PRIORITY_ULTRA_HIGH: ultra high priority
+ \param[out] none
+ \retval none
+*/
+void dma_priority_config(dma_channel_enum channelx, uint32_t priority)
+{
+ uint32_t ctl;
+
+ /* acquire DMA_CHxCTL register */
+ ctl = DMA_CHCTL(channelx);
+ /* assign regiser */
+ ctl &= ~DMA_CHXCTL_PRIO;
+ ctl |= priority;
+ DMA_CHCTL(channelx) = ctl;
+}
+
+/*!
+ \brief configure transfer data width of memory
+ \param[in] channelx: specify which DMA channel to set
+ only one parameter can be selected which is shown as below:
+ \arg DMA_CHx(x=0..6)
+ \param[in] mwidth: transfer data width of memory
+ only one parameter can be selected which is shown as below:
+ \arg DMA_MEMORY_WIDTH_8BIT: transfer data width of memory is 8-bit
+ \arg DMA_MEMORY_WIDTH_16BIT: transfer data width of memory is 16-bit
+ \arg DMA_MEMORY_WIDTH_32BIT: transfer data width of memory is 32-bit
+ \param[out] none
+ \retval none
+*/
+void dma_memory_width_config(dma_channel_enum channelx, uint32_t mwidth)
+{
+ uint32_t ctl;
+
+ /* acquire DMA_CHxCTL register */
+ ctl = DMA_CHCTL(channelx);
+ /* assign regiser */
+ ctl &= ~DMA_CHXCTL_MWIDTH;
+ ctl |= mwidth;
+ DMA_CHCTL(channelx) = ctl;
+}
+
+/*!
+ \brief configure transfer data width of peripheral
+ \param[in] channelx: specify which DMA channel
+ only one parameter can be selected which is shown as below:
+ \arg DMA_CHx(x=0..6)
+ \param[in] pwidth: transfer data width of peripheral
+ only one parameter can be selected which is shown as below:
+ \arg DMA_PERIPHERAL_WIDTH_8BIT: transfer data width of peripheral is 8-bit
+ \arg DMA_PERIPHERAL_WIDTH_16BIT: transfer data width of peripheral is 16-bit
+ \arg DMA_PERIPHERAL_WIDTH_32BIT: transfer data width of peripheral is 32-bit
+ \param[out] none
+ \retval none
+*/
+void dma_periph_width_config(dma_channel_enum channelx, uint32_t pwidth)
+{
+ uint32_t ctl;
+
+ /* acquire DMA_CHxCTL register */
+ ctl = DMA_CHCTL(channelx);
+ /* assign regiser */
+ ctl &= ~DMA_CHXCTL_PWIDTH;
+ ctl |= pwidth;
+ DMA_CHCTL(channelx) = ctl;
+}
+
+/*!
+ \brief enable next address increasement algorithm of memory
+ \param[in] channelx: specify which DMA channel to set
+ only one parameter can be selected which is shown as below:
+ \arg DMA_CHx(x=0..6)
+ \param[out] none
+ \retval none
+*/
+void dma_memory_increase_enable(dma_channel_enum channelx)
+{
+ DMA_CHCTL(channelx) |= DMA_CHXCTL_MNAGA;
+}
+
+/*!
+ \brief disable next address increasement algorithm of memory
+ \param[in] channelx: specify which DMA channel to set
+ only one parameter can be selected which is shown as below:
+ \arg DMA_CHx(x=0..6)
+ \param[out] none
+ \retval none
+*/
+void dma_memory_increase_disable(dma_channel_enum channelx)
+{
+ DMA_CHCTL(channelx) &= ~DMA_CHXCTL_MNAGA;
+}
+
+/*!
+ \brief enable next address increasement algorithm of peripheral
+ \param[in] channelx: specify which DMA channel to set
+ only one parameter can be selected which is shown as below:
+ \arg DMA_CHx(x=0..6)
+ \param[out] none
+ \retval none
+*/
+void dma_periph_increase_enable(dma_channel_enum channelx)
+{
+ DMA_CHCTL(channelx) |= DMA_CHXCTL_PNAGA;
+}
+
+/*!
+ \brief disable next address increasement algorithm of peripheral
+ \param[in] channelx: specify which DMA channel to set
+ only one parameter can be selected which is shown as below:
+ \arg DMA_CHx(x=0..6)
+ \param[out] none
+ \retval none
+*/
+void dma_periph_increase_disable(dma_channel_enum channelx)
+{
+ DMA_CHCTL(channelx) &= ~DMA_CHXCTL_PNAGA;
+}
+
+/*!
+ \brief configure the direction of data transfer on the channel
+ \param[in] channelx: specify which DMA channel to set
+ only one parameter can be selected which is shown as below:
+ \arg DMA_CHx(x=0..6)
+ \param[in] direction: specify the direction of data transfer
+ only one parameter can be selected which is shown as below:
+ \arg DMA_PERIPHERAL_TO_MEMORY: read from peripheral and write to memory
+ \arg DMA_MEMORY_TO_PERIPHERAL: read from memory and write to peripheral
+ \param[out] none
+ \retval none
+*/
+void dma_transfer_direction_config(dma_channel_enum channelx, uint32_t direction)
+{
+ if(DMA_PERIPHERAL_TO_MEMORY == direction) {
+ DMA_CHCTL(channelx) &= ~DMA_CHXCTL_DIR;
+ } else {
+ DMA_CHCTL(channelx) |= DMA_CHXCTL_DIR;
+ }
+}
+
+/*!
+ \brief check DMA flag is set or not
+ \param[in] channelx: specify which DMA channel to get flag
+ only one parameter can be selected which is shown as below:
+ \arg DMA_CHx(x=0..6)
+ \param[in] flag: specify get which flag
+ only one parameter can be selected which is shown as below:
+ \arg DMA_FLAG_G: global interrupt flag of channel
+ \arg DMA_FLAG_FTF: full transfer finish flag of channel
+ \arg DMA_FLAG_HTF: half transfer finish flag of channel
+ \arg DMA_FLAG_ERR: error flag of channel
+ \param[out] none
+ \retval FlagStatus: SET or RESET
+*/
+FlagStatus dma_flag_get(dma_channel_enum channelx, uint32_t flag)
+{
+ FlagStatus reval;
+
+ if(RESET != (DMA_INTF & DMA_FLAG_ADD(flag, channelx))) {
+ reval = SET;
+ } else {
+ reval = RESET;
+ }
+
+ return reval;
+}
+
+/*!
+ \brief clear DMA a channel flag
+ \param[in] channelx: specify which DMA channel to clear flag
+ only one parameter can be selected which is shown as below:
+ \arg DMA_CHx(x=0..6)
+ \param[in] flag: specify get which flag
+ only one parameter can be selected which is shown as below:
+ \arg DMA_FLAG_G: global interrupt flag of channel
+ \arg DMA_FLAG_FTF: full transfer finish flag of channel
+ \arg DMA_FLAG_HTF: half transfer finish flag of channel
+ \arg DMA_FLAG_ERR: error flag of channel
+ \param[out] none
+ \retval none
+*/
+void dma_flag_clear(dma_channel_enum channelx, uint32_t flag)
+{
+ DMA_INTC |= DMA_FLAG_ADD(flag, channelx);
+}
+
+/*!
+ \brief enable DMA interrupt
+ \param[in] channelx: specify which DMA channel to set
+ only one parameter can be selected which is shown as below:
+ \arg DMA_CHx(x=0..6)
+ \param[in] source: specify which interrupt to enable
+ only one parameter can be selected which is shown as below:
+ \arg DMA_INT_ERR: channel error interrupt
+ \arg DMA_INT_HTF: channel half transfer finish interrupt
+ \arg DMA_INT_FTF: channel full transfer finish interrupt
+ \param[out] none
+ \retval none
+*/
+void dma_interrupt_enable(dma_channel_enum channelx, uint32_t source)
+{
+ DMA_CHCTL(channelx) |= source;
+}
+
+/*!
+ \brief disable DMA interrupt
+ \param[in] channelx: specify which DMA channel to set
+ only one parameter can be selected which is shown as below:
+ \arg DMA_CHx(x=0..6)
+ \param[in] source: specify which interrupt to disable
+ only one parameter can be selected which is shown as below:
+ \arg DMA_INT_ERR: channel error interrupt
+ \arg DMA_INT_HTF: channel half transfer finish interrupt
+ \arg DMA_INT_FTF: channel full transfer finish interrupt
+ \param[out] none
+ \retval none
+*/
+void dma_interrupt_disable(dma_channel_enum channelx, uint32_t source)
+{
+ DMA_CHCTL(channelx) &= ~source;
+}
+
+/*!
+ \brief check DMA flag and interrupt enable bit is set or not
+ \param[in] channelx: specify which DMA channel to get flag
+ only one parameter can be selected which is shown as below:
+ \arg DMA_CHx(x=0..6)
+ \param[in] flag: specify get which flag
+ only one parameter can be selected which is shown as below:
+ \arg DMA_INT_FLAG_FTF: transfer finish flag of channel
+ \arg DMA_INT_FLAG_HTF: half transfer finish flag of channel
+ \arg DMA_INT_FLAG_ERR: error flag of channel
+ \param[out] none
+ \retval FlagStatus: SET or RESET
+*/
+FlagStatus dma_interrupt_flag_get(dma_channel_enum channelx, uint32_t flag)
+{
+ uint32_t interrupt_enable = 0U, interrupt_flag = 0U;
+
+ switch(flag) {
+ case DMA_INT_FLAG_FTF:
+ interrupt_flag = DMA_INTF & DMA_FLAG_ADD(flag, channelx);
+ interrupt_enable = DMA_CHCTL(channelx) & DMA_CHXCTL_FTFIE;
+ break;
+ case DMA_INT_FLAG_HTF:
+ interrupt_flag = DMA_INTF & DMA_FLAG_ADD(flag, channelx);
+ interrupt_enable = DMA_CHCTL(channelx) & DMA_CHXCTL_HTFIE;
+ break;
+ case DMA_INT_FLAG_ERR:
+ interrupt_flag = DMA_INTF & DMA_FLAG_ADD(flag, channelx);
+ interrupt_enable = DMA_CHCTL(channelx) & DMA_CHXCTL_ERRIE;
+ break;
+ default:
+ break;
+ }
+
+ if(interrupt_flag && interrupt_enable) {
+ return SET;
+ } else {
+ return RESET;
+ }
+}
+
+/*!
+ \brief clear DMA a channel interrupt flag
+ \param[in] channelx: specify which DMA channel to clear flag
+ only one parameter can be selected which is shown as below:
+ \arg DMA_CHx(x=0..6)
+ \param[in] flag: specify get which flag
+ only one parameter can be selected which is shown as below:
+ \arg DMA_INT_FLAG_G: global interrupt flag of channel
+ \arg DMA_INT_FLAG_FTF: transfer finish flag of channel
+ \arg DMA_INT_FLAG_HTF: half transfer finish flag of channel
+ \arg DMA_INT_FLAG_ERR: error flag of channel
+ \param[out] none
+ \retval none
+*/
+void dma_interrupt_flag_clear(dma_channel_enum channelx, uint32_t flag)
+{
+ DMA_INTC |= DMA_FLAG_ADD(flag, channelx);
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_exti.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_exti.c
new file mode 100644
index 00000000..15106f27
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_exti.c
@@ -0,0 +1,257 @@
+/*!
+ \file gd32f3x0_exti.c
+ \brief EXTI driver
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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.
+*/
+
+#include "gd32f3x0_exti.h"
+
+/*!
+ \brief reset EXTI, reset the value of all EXTI registers into initial values
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void exti_deinit(void)
+{
+ /* reset the value of all the EXTI registers */
+ EXTI_INTEN = (uint32_t)0x0F940000U;
+ EXTI_EVEN = (uint32_t)0x00000000U;
+ EXTI_RTEN = (uint32_t)0x00000000U;
+ EXTI_FTEN = (uint32_t)0x00000000U;
+ EXTI_SWIEV = (uint32_t)0x00000000U;
+}
+
+/*!
+ \brief initialize the EXTI, enable the configuration of EXTI initialize
+ \param[in] linex: EXTI line number, refer to exti_line_enum
+ only one parameter can be selected which is shown as below:
+ \arg EXTI_x (x=0..19,21,22): EXTI line x
+ \param[in] mode: interrupt or event mode, refer to exti_mode_enum
+ only one parameter can be selected which is shown as below:
+ \arg EXTI_INTERRUPT: interrupt mode
+ \arg EXTI_EVENT: event mode
+ \param[in] trig_type: interrupt trigger type, refer to exti_trig_type_enum
+ only one parameter can be selected which is shown as below:
+ \arg EXTI_TRIG_RISING: rising edge trigger
+ \arg EXTI_TRIG_FALLING: falling trigger
+ \arg EXTI_TRIG_BOTH: rising and falling trigger
+ \arg EXTI_TRIG_NONE: without rising edge or falling edge trigger
+ \param[out] none
+ \retval none
+*/
+void exti_init(exti_line_enum linex, \
+ exti_mode_enum mode, \
+ exti_trig_type_enum trig_type)
+{
+ /* reset the EXTI line x */
+ EXTI_INTEN &= ~(uint32_t)linex;
+ EXTI_EVEN &= ~(uint32_t)linex;
+ EXTI_RTEN &= ~(uint32_t)linex;
+ EXTI_FTEN &= ~(uint32_t)linex;
+
+ /* set the EXTI mode and enable the interrupts or events from EXTI line x */
+ switch(mode) {
+ case EXTI_INTERRUPT:
+ EXTI_INTEN |= (uint32_t)linex;
+ break;
+ case EXTI_EVENT:
+ EXTI_EVEN |= (uint32_t)linex;
+ break;
+ default:
+ break;
+ }
+
+ /* set the EXTI trigger type */
+ switch(trig_type) {
+ case EXTI_TRIG_RISING:
+ EXTI_RTEN |= (uint32_t)linex;
+ EXTI_FTEN &= ~(uint32_t)linex;
+ break;
+ case EXTI_TRIG_FALLING:
+ EXTI_RTEN &= ~(uint32_t)linex;
+ EXTI_FTEN |= (uint32_t)linex;
+ break;
+ case EXTI_TRIG_BOTH:
+ EXTI_RTEN |= (uint32_t)linex;
+ EXTI_FTEN |= (uint32_t)linex;
+ break;
+ case EXTI_TRIG_NONE:
+ default:
+ break;
+ }
+}
+
+/*!
+ \brief enable the interrupts from EXTI line x
+ \param[in] linex: EXTI line number, refer to exti_line_enum
+ only one parameter can be selected which is shown as below:
+ \arg EXTI_x (x=0..27): EXTI line x
+ \param[out] none
+ \retval none
+*/
+void exti_interrupt_enable(exti_line_enum linex)
+{
+ EXTI_INTEN |= (uint32_t)linex;
+}
+
+/*!
+ \brief disable the interrupt from EXTI line x
+ \param[in] linex: EXTI line number, refer to exti_line_enum
+ only one parameter can be selected which is shown as below:
+ \arg EXTI_x (x=0..27): EXTI line x
+ \param[out] none
+ \retval none
+*/
+void exti_interrupt_disable(exti_line_enum linex)
+{
+ EXTI_INTEN &= ~(uint32_t)linex;
+}
+
+/*!
+ \brief enable the events from EXTI line x
+ \param[in] linex: EXTI line number, refer to exti_line_enum
+ only one parameter can be selected which is shown as below:
+ \arg EXTI_x (x=0..27): EXTI line x
+ \param[out] none
+ \retval none
+*/
+void exti_event_enable(exti_line_enum linex)
+{
+ EXTI_EVEN |= (uint32_t)linex;
+}
+
+/*!
+ \brief disable the events from EXTI line x
+ \param[in] linex: EXTI line number, refer to exti_line_enum
+ only one parameter can be selected which is shown as below:
+ \arg EXTI_x (x=0..27): EXTI line x
+ \param[out] none
+ \retval none
+*/
+void exti_event_disable(exti_line_enum linex)
+{
+ EXTI_EVEN &= ~(uint32_t)linex;
+}
+
+/*!
+ \brief enable EXTI software interrupt event
+ \param[in] linex: EXTI line number, refer to exti_line_enum
+ only one parameter can be selected which is shown as below:
+ \arg EXTI_x (x=0..19,21,22): EXTI line x
+ \param[out] none
+ \retval none
+*/
+void exti_software_interrupt_enable(exti_line_enum linex)
+{
+ EXTI_SWIEV |= (uint32_t)linex;
+}
+
+/*!
+ \brief disable EXTI software interrupt event
+ \param[in] linex: EXTI line number, refer to exti_line_enum
+ only one parameter can be selected which is shown as below:
+ \arg EXTI_x (x=0..19,21,22): EXTI line x
+ \param[out] none
+ \retval none
+*/
+void exti_software_interrupt_disable(exti_line_enum linex)
+{
+ EXTI_SWIEV &= ~(uint32_t)linex;
+}
+
+/*!
+ \brief get EXTI line x pending flag
+ \param[in] linex: EXTI line number, refer to exti_line_enum
+ only one parameter can be selected which is shown as below:
+ \arg EXTI_x (x=0..19,21,22): EXTI line x
+ \param[out] none
+ \retval FlagStatus: status of flag (RESET or SET)
+*/
+FlagStatus exti_flag_get(exti_line_enum linex)
+{
+ if(RESET != (EXTI_PD & (uint32_t)linex)) {
+ return SET;
+ } else {
+ return RESET;
+ }
+}
+
+/*!
+ \brief clear EXTI line x pending flag
+ \param[in] linex: EXTI line number, refer to exti_line_enum
+ only one parameter can be selected which is shown as below:
+ \arg EXTI_x (x=0..19,21,22): EXTI line x
+ \param[out] none
+ \retval none
+*/
+void exti_flag_clear(exti_line_enum linex)
+{
+ EXTI_PD = (uint32_t)linex;
+}
+
+/*!
+ \brief get EXTI line x flag when the interrupt flag is set
+ \param[in] linex: EXTI line number, refer to exti_line_enum
+ only one parameter can be selected which is shown as below:
+ \arg EXTI_x (x=0..19,21,22): EXTI line x
+ \param[out] none
+ \retval FlagStatus: status of flag (RESET or SET)
+*/
+FlagStatus exti_interrupt_flag_get(exti_line_enum linex)
+{
+ uint32_t flag_left, flag_right;
+
+ flag_left = EXTI_PD & (uint32_t)linex;
+ flag_right = EXTI_INTEN & (uint32_t)linex;
+
+ if((RESET != flag_left) && (RESET != flag_right)) {
+ return SET;
+ } else {
+ return RESET;
+ }
+}
+
+/*!
+ \brief clear EXTI line x pending flag
+ \param[in] linex: EXTI line number, refer to exti_line_enum
+ only one parameter can be selected which is shown as below:
+ \arg EXTI_x (x=0..19,21,22): EXTI line x
+ \param[out] none
+ \retval none
+*/
+void exti_interrupt_flag_clear(exti_line_enum linex)
+{
+ EXTI_PD = (uint32_t)linex;
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_fmc.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_fmc.c
new file mode 100644
index 00000000..2981aa1a
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_fmc.c
@@ -0,0 +1,889 @@
+/*!
+ \file gd32f3x0_fmc.c
+ \brief FMC driver
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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.
+*/
+
+#include "gd32f3x0_fmc.h"
+
+/* FMC main memory programming functions */
+
+/*!
+ \brief unlock the main FMC operation
+ it is better to used in pairs with fmc_lock
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void fmc_unlock(void)
+{
+ if((RESET != (FMC_CTL & FMC_CTL_LK))) {
+ /* write the FMC key */
+ FMC_KEY = UNLOCK_KEY0;
+ FMC_KEY = UNLOCK_KEY1;
+ }
+}
+
+/*!
+ \brief lock the main FMC operation
+ it is better to used in pairs with fmc_unlock after an operation
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void fmc_lock(void)
+{
+ /* set the LK bit*/
+ FMC_CTL |= FMC_CTL_LK;
+}
+
+/*!
+ \brief set the wait state counter value
+ \param[in] wscnt: wait state counter value
+ only one parameter can be selected which is shown as below:
+ \arg WS_WSCNT_0: 0 wait state added
+ \arg WS_WSCNT_1: 1 wait state added
+ \arg WS_WSCNT_2: 2 wait state added
+ \param[out] none
+ \retval none
+*/
+void fmc_wscnt_set(uint8_t wscnt)
+{
+ uint32_t reg;
+
+ reg = FMC_WS;
+ /* set the wait state counter value */
+ reg &= ~FMC_WS_WSCNT;
+ FMC_WS = (reg | wscnt);
+}
+
+/*!
+ \brief fmc wait state enable
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void fmc_wait_state_enable(void)
+{
+ /* unlock the main flash */
+ fmc_unlock();
+
+ /* set the WSEN bit in register FMC_WSEN */
+ FMC_WSEN |= FMC_WSEN_WSEN;
+
+ /* lock the main flash after operation */
+ fmc_lock();
+}
+
+/*!
+ \brief fmc wait state disable
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void fmc_wait_state_disable(void)
+{
+ /* unlock the main flash */
+ fmc_unlock();
+
+ /* reset the WSEN bit in register FMC_WSEN */
+ FMC_WSEN &= ~FMC_WSEN_WSEN;
+
+ /* lock the main flash after operation */
+ fmc_lock();
+}
+
+/*!
+ \brief erase page
+ \param[in] page_address: target page start address
+ \param[out] none
+ \retval fmc_state
+*/
+fmc_state_enum fmc_page_erase(uint32_t page_address)
+{
+ fmc_state_enum fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT);
+
+ if(FMC_READY == fmc_state) {
+ /* start page erase */
+ FMC_CTL |= FMC_CTL_PER;
+ FMC_ADDR = page_address;
+ FMC_CTL |= FMC_CTL_START;
+
+ /* wait for the FMC ready */
+ fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT);
+
+ /* reset the PER bit */
+ FMC_CTL &= ~FMC_CTL_PER;
+ }
+
+ /* return the FMC state */
+ return fmc_state;
+}
+
+/*!
+ \brief erase whole chip
+ \param[in] none
+ \param[out] none
+ \retval fmc_state
+*/
+fmc_state_enum fmc_mass_erase(void)
+{
+ fmc_state_enum fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT);
+
+ if(FMC_READY == fmc_state) {
+ /* start chip erase */
+ FMC_CTL |= FMC_CTL_MER;
+ FMC_CTL |= FMC_CTL_START;
+
+ /* wait for the FMC ready */
+ fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT);
+
+ /* reset the MER bit */
+ FMC_CTL &= ~FMC_CTL_MER;
+ }
+
+ /* return the fmc state */
+ return fmc_state;
+}
+
+/*!
+ \brief program a word at the corresponding address
+ \param[in] address: address to program
+ \param[in] data: word to program
+ \param[out] none
+ \retval fmc_state
+*/
+fmc_state_enum fmc_word_program(uint32_t address, uint32_t data)
+{
+ fmc_state_enum fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT);
+
+ if(FMC_READY == fmc_state) {
+ /* set the PG bit to start program */
+ FMC_CTL |= FMC_CTL_PG;
+
+ REG32(address) = data;
+
+ /* wait for the FMC ready */
+ fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT);
+
+ /* reset the PG bit */
+ FMC_CTL &= ~FMC_CTL_PG;
+ }
+
+ /* return the FMC state */
+ return fmc_state;
+}
+
+/*!
+ \brief program a half word at the corresponding address
+ \param[in] address: address to program
+ \param[in] data: word to program
+ \param[out] none
+ \retval fmc_state
+*/
+fmc_state_enum fmc_halfword_program(uint32_t address, uint16_t data)
+{
+ fmc_state_enum fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT);
+
+ if(FMC_READY == fmc_state) {
+ /* set the PG bit to start program */
+ FMC_CTL |= FMC_CTL_PG;
+
+ REG16(address) = data;
+
+ /* wait for the FMC ready */
+ fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT);
+
+ /* reset the PG bit */
+ FMC_CTL &= ~FMC_CTL_PG;
+ }
+
+ /* return the FMC state */
+ return fmc_state;
+}
+
+/*!
+ \brief program a word at the corresponding address without erasing
+ \param[in] address: address to program
+ \param[in] data: word to program
+ \param[out] none
+ \retval fmc_state
+*/
+fmc_state_enum fmc_word_reprogram(uint32_t address, uint32_t data)
+{
+ fmc_state_enum fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT);
+ FMC_WSEN |= FMC_WSEN_BPEN;
+
+ if(FMC_READY == fmc_state) {
+ /* set the PG bit to start program */
+ FMC_CTL |= FMC_CTL_PG;
+
+ REG32(address) = data;
+
+ /* wait for the FMC ready */
+ fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT);
+
+ /* reset the PG bit */
+ FMC_CTL &= ~FMC_CTL_PG;
+ }
+
+ /* return the FMC state */
+ return fmc_state;
+}
+
+/* FMC option bytes programming functions */
+
+/*!
+ \brief unlock the option byte operation
+ it is better to used in pairs with ob_lock
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void ob_unlock(void)
+{
+ if(RESET == (FMC_CTL & FMC_CTL_OBWEN)) {
+ /* write the FMC key */
+ FMC_OBKEY = UNLOCK_KEY0;
+ FMC_OBKEY = UNLOCK_KEY1;
+ }
+}
+
+/*!
+ \brief lock the option byte operation
+ it is better to used in pairs with ob_unlock after an operation
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void ob_lock(void)
+{
+ /* reset the OBWE bit */
+ FMC_CTL &= ~FMC_CTL_OBWEN;
+}
+
+/*!
+ \brief reload the option byte and generate a system reset
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void ob_reset(void)
+{
+ /* set the OBRLD bit */
+ FMC_CTL |= FMC_CTL_OBRLD;
+}
+
+/*!
+ \brief erase the option byte
+ programmer must ensure FMC & option byte are both unlocked before calling this function
+ \param[in] none
+ \param[out] none
+ \retval fmc_state
+*/
+fmc_state_enum ob_erase(void)
+{
+ uint16_t fmc_spc;
+
+ uint32_t fmc_plevel = ob_obstat_plevel_get();
+ fmc_state_enum fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT);
+
+ /* get the original option byte security protection code */
+ if(OB_OBSTAT_PLEVEL_NO == fmc_plevel) {
+ fmc_spc = FMC_NSPC;
+ } else if(OB_OBSTAT_PLEVEL_LOW == fmc_plevel) {
+ fmc_spc = FMC_LSPC;
+ } else {
+ fmc_spc = FMC_HSPC;
+ fmc_state = FMC_OB_HSPC;
+ }
+
+ if(FMC_READY == fmc_state) {
+ /* start erase the option byte */
+ FMC_CTL |= FMC_CTL_OBER;
+ FMC_CTL |= FMC_CTL_START;
+
+ /* wait for the FMC ready */
+ fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT);
+
+ if(FMC_READY == fmc_state) {
+ /* reset the OBER bit */
+ FMC_CTL &= ~FMC_CTL_OBER;
+
+ /* set the OBPG bit */
+ FMC_CTL |= FMC_CTL_OBPG;
+
+ /* restore the last get option byte security protection code */
+ OB_SPC = fmc_spc;
+ OB_USER = OB_USER_DEFAULT;
+
+ /* wait for the FMC ready */
+ fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT);
+
+ if(FMC_TOERR != fmc_state) {
+ /* reset the OBPG bit */
+ FMC_CTL &= ~FMC_CTL_OBPG;
+ }
+ } else {
+ if(FMC_TOERR != fmc_state) {
+ /* reset the OBPG bit */
+ FMC_CTL &= ~FMC_CTL_OBPG;
+ }
+ }
+ }
+ /* return the FMC state */
+ return fmc_state;
+}
+
+/*!
+ \brief enable option byte write protection(OB_WP) depending on current option byte
+ \param[in] ob_wp: write protection configuration data
+ setting the bit of ob_wp means enabling the corresponding sector write protection
+ \param[out] none
+ \retval fmc_state
+*/
+fmc_state_enum ob_write_protection_enable(uint16_t ob_wp)
+{
+ uint8_t ob_wrp0, ob_wrp1;
+ ob_parm_struct ob_parm;
+ fmc_state_enum fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT);
+ ob_parm_get(&ob_parm);
+ ob_wp = (uint16_t)(~ob_wp);
+ ob_wrp0 = (uint8_t)(ob_wp & OB_LWP);
+ ob_wrp1 = (uint8_t)((ob_wp & OB_HWP) >> 8U);
+
+ if(0xFFFFU == OB_WP0) {
+ if(0xFFFFU == OB_WP1) {
+ if(FMC_READY == fmc_state) {
+ /* set the OBPG bit*/
+ FMC_CTL |= FMC_CTL_OBPG;
+
+ if(0xFFU != ob_wrp0) {
+ OB_WP0 = ob_wrp0 ;
+ /* wait for the FMC ready */
+ fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT);
+ }
+
+ if((FMC_READY == fmc_state) && (0xFFU != ob_wrp1)) {
+ OB_WP1 = ob_wrp1 ;
+ /* wait for the FMC ready */
+ fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT);
+ }
+
+ if(FMC_TOERR != fmc_state) {
+ /* reset the OBPG bit */
+ FMC_CTL &= ~FMC_CTL_OBPG;
+ }
+ }
+ }
+ } else {
+ if(FMC_READY == fmc_state) {
+ /* start erase the option byte */
+ FMC_CTL |= FMC_CTL_OBER;
+ FMC_CTL |= FMC_CTL_START;
+
+ /* wait for the FMC ready */
+ fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT);
+
+ if(FMC_READY == fmc_state) {
+
+ /* reset the OBER bit */
+ FMC_CTL &= ~FMC_CTL_OBER;
+
+ /* enable the option bytes programming */
+ FMC_CTL |= FMC_CTL_OBPG;
+
+ ob_value_modify(OB_WP_ADDR0, ob_wp, &ob_parm);
+ /* wait for the FMC ready */
+ fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT);
+
+ if(FMC_TOERR != fmc_state) {
+ /* reset the OBPG bit */
+ FMC_CTL &= ~FMC_CTL_OBPG;
+ }
+ } else {
+ if(FMC_TOERR != fmc_state) {
+ /* reset the OBER bit */
+ FMC_CTL &= ~FMC_CTL_OBER;
+ }
+ }
+ }
+ }
+ /* return the FMC state */
+ return fmc_state;
+}
+
+/*!
+ \brief configure security protection
+ \param[in] ob_spc: specify security protection code
+ only one parameter can be selected which is shown as below:
+ \arg FMC_NSPC: no security protection
+ \arg FMC_LSPC: low security protection
+ \arg FMC_HSPC: high security protection
+ \param[out] none
+ \retval fmc_state
+*/
+fmc_state_enum ob_security_protection_config(uint8_t ob_spc)
+{
+ fmc_state_enum fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT);
+
+ ob_parm_struct ob_parm;
+ ob_parm_get(&ob_parm);
+
+ /* the OB_SPC byte cannot be reprogrammed if protection level is high */
+ if(OB_OBSTAT_PLEVEL_HIGH == ob_obstat_plevel_get()) {
+ fmc_state = FMC_OB_HSPC;
+ }
+
+ if(FMC_READY == fmc_state) {
+ /* start erase the option byte */
+ FMC_CTL |= FMC_CTL_OBER;
+ FMC_CTL |= FMC_CTL_START;
+
+ /* wait for the FMC ready */
+ fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT);
+
+ if(FMC_READY == fmc_state) {
+
+ /* reset the OBER bit */
+ FMC_CTL &= ~FMC_CTL_OBER;
+
+ /* enable the option bytes programming */
+ FMC_CTL |= FMC_CTL_OBPG;
+
+ ob_value_modify(OB_SPC_ADDR, (uint16_t)ob_spc, &ob_parm);
+ /* wait for the FMC ready */
+ fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT);
+
+ if(FMC_TOERR != fmc_state) {
+ /* reset the OBPG bit */
+ FMC_CTL &= ~FMC_CTL_OBPG;
+ }
+ } else {
+ if(FMC_TOERR != fmc_state) {
+ /* reset the OBER bit */
+ FMC_CTL &= ~FMC_CTL_OBER;
+ }
+ }
+ }
+ /* return the FMC state */
+ return fmc_state;
+}
+
+/*!
+ \brief program the FMC user option byte depending on current option byte
+ \param[in] ob_user: user option byte
+ one or more parameters (bitwise AND) can be selected which are shown as below:
+ \arg OB_FWDGT_HW: hardware free watchdog timer
+ \arg OB_DEEPSLEEP_RST: generate a reset instead of entering deepsleep mode
+ \arg OB_STDBY_RST: generate a reset instead of entering standby mode
+ \arg OB_BOOT1_SET_1: BOOT1 bit is 1
+ \arg OB_VDDA_DISABLE: disable VDDA monitor
+ \arg OB_SRAM_PARITY_ENABLE: enable sram parity check
+ \param[out] none
+ \retval fmc_state
+*/
+fmc_state_enum ob_user_write(uint8_t ob_user)
+{
+ /* check whether FMC is ready or not */
+ fmc_state_enum fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT);
+ ob_parm_struct ob_parm;
+ ob_parm_get(&ob_parm);
+
+ if(FMC_READY == fmc_state) {
+ /* start erase the option byte */
+ FMC_CTL |= FMC_CTL_OBER;
+ FMC_CTL |= FMC_CTL_START;
+
+ /* wait for the FMC ready */
+ fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT);
+
+ if(FMC_READY == fmc_state) {
+ /* reset the OBER bit */
+ FMC_CTL &= ~FMC_CTL_OBER;
+
+ /* set the OBPG bit */
+ FMC_CTL |= FMC_CTL_OBPG;
+
+ /* restore the last get option byte security protection code */
+ ob_value_modify(OB_USER_ADDR, (uint16_t)ob_user, &ob_parm);
+
+ /* wait for the FMC ready */
+ fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT);
+
+ if(FMC_TOERR != fmc_state) {
+ /* reset the OBPG bit */
+ FMC_CTL &= ~FMC_CTL_OBPG;
+ }
+ } else {
+ if(FMC_TOERR != fmc_state) {
+ /* reset the OBPG bit */
+ FMC_CTL &= ~FMC_CTL_OBPG;
+ }
+ }
+ }
+ /* return the FMC state */
+ return fmc_state;
+}
+
+/*!
+ \brief program the FMC data option byte
+ \param[in] address: OB_DATA_ADDR0 or OB_DATA_ADDR1
+ only one parameter can be selected which is shown as below:
+ \arg OB_DATA_ADDR0: option byte data address 0
+ \arg OB_DATA_ADDR1: option byte data address 1
+ \param[in] data: the byte to be programmed
+ \param[out] none
+ \retval fmc_state
+*/
+fmc_state_enum ob_data_program(uint32_t address, uint8_t data)
+{
+ fmc_state_enum fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT);
+ ob_parm_struct ob_parm;
+ ob_parm_get(&ob_parm);
+ if(0xFFFFU == REG16(address)) {
+ if(FMC_READY == fmc_state) {
+ /* set the OBPG bit */
+ FMC_CTL |= FMC_CTL_OBPG;
+
+ REG16(address) = data ;
+
+ /* wait for the FMC ready */
+ fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT);
+
+ if(FMC_TOERR != fmc_state) {
+ /* reset the OBPG bit */
+ FMC_CTL &= ~FMC_CTL_OBPG;
+ }
+ }
+ } else {
+ if(FMC_READY == fmc_state) {
+ /* start erase the option byte */
+ FMC_CTL |= FMC_CTL_OBER;
+ FMC_CTL |= FMC_CTL_START;
+
+ /* wait for the FMC ready */
+ fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT);
+
+ if(FMC_READY == fmc_state) {
+
+ /* reset the OBER bit */
+ FMC_CTL &= ~FMC_CTL_OBER;
+
+ /* enable the option bytes programming */
+ FMC_CTL |= FMC_CTL_OBPG;
+
+ ob_value_modify(address, (uint16_t)data, &ob_parm);
+ /* wait for the FMC ready */
+ fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT);
+
+ if(FMC_TOERR != fmc_state) {
+ /* reset the OBPG bit */
+ FMC_CTL &= ~FMC_CTL_OBPG;
+ }
+ } else {
+ if(FMC_TOERR != fmc_state) {
+ /* reset the OBER bit */
+ FMC_CTL &= ~FMC_CTL_OBER;
+ }
+ }
+ }
+ }
+
+ /* return the FMC state */
+ return fmc_state;
+}
+
+/*!
+ \brief get OB_USER in register FMC_OBSTAT
+ \param[in] none
+ \param[out] none
+ \retval ob_user
+*/
+uint8_t ob_user_get(void)
+{
+ return (uint8_t)(FMC_OBSTAT >> 8U);
+}
+
+/*!
+ \brief get OB_DATA in register FMC_OBSTAT
+ \param[in] none
+ \param[out] none
+ \retval ob_data
+*/
+uint16_t ob_data_get(void)
+{
+ return (uint16_t)(FMC_OBSTAT >> 16U);
+}
+
+/*!
+ \brief get the FMC option byte write protection (OB_WP) in register FMC_WP
+ \param[in] none
+ \param[out] none
+ \retval OB_WP
+*/
+uint16_t ob_write_protection_get(void)
+{
+ return (uint16_t)(FMC_WP);
+}
+
+/*!
+ \brief get the value of FMC option byte security protection level (PLEVEL) in FMC_OBSTAT register
+ \param[in] none
+ \param[out] none
+ \retval the value of PLEVEL
+*/
+uint32_t ob_obstat_plevel_get(void)
+{
+ return (FMC_OBSTAT & (FMC_OBSTAT_PLEVEL_BIT0 | FMC_OBSTAT_PLEVEL_BIT1));
+}
+
+/* FMC interrupts and flags management functions */
+/*!
+ \brief enable FMC interrupt
+ \param[in] interrupt: the FMC interrupt source
+ one or more parameters can be selected which are shown as below:
+ \arg FMC_INTEN_END: FMC end of operation interrupt
+ \arg FMC_INTEN_ERR: FMC error interrupt
+ \param[out] none
+ \retval none
+*/
+void fmc_interrupt_enable(uint32_t interrupt)
+{
+ FMC_CTL |= interrupt;
+}
+
+/*!
+ \brief disable FMC interrupt
+ \param[in] interrupt: the FMC interrupt source
+ one or more parameters can be selected which are shown as below:
+ \arg FMC_INTEN_END: FMC end of operation interrupt
+ \arg FMC_INTEN_ERR: FMC error interrupt
+ \param[out] none
+ \retval none
+*/
+void fmc_interrupt_disable(uint32_t interrupt)
+{
+ FMC_CTL &= ~(uint32_t)interrupt;
+}
+
+/*!
+ \brief get flag set or reset
+ \param[in] flag: check FMC flag
+ only one parameter can be selected which is shown as below:
+ \arg FMC_FLAG_BUSY: FMC busy flag
+ \arg FMC_FLAG_PGERR: FMC programming error flag
+ \arg FMC_FLAG_WPERR: FMC write protection error flag
+ \arg FMC_FLAG_END: FMC end of programming flag
+ \param[out] none
+ \retval FlagStatus: SET or RESET
+*/
+FlagStatus fmc_flag_get(uint32_t flag)
+{
+ FlagStatus status = RESET;
+
+ if(FMC_STAT & flag) {
+ status = SET;
+ }
+ /* return the state of corresponding FMC flag */
+ return status;
+}
+
+/*!
+ \brief clear the FMC pending flag by writing 1
+ \param[in] flag: clear FMC flag
+ only one parameter can be selected which is shown as below:
+ \arg FMC_FLAG_PGERR: FMC programming error flag
+ \arg FMC_FLAG_WPERR: FMC write protection error flag
+ \arg FMC_FLAG_END: fmc end of programming flag
+ \param[out] none
+ \retval none
+*/
+void fmc_flag_clear(uint32_t flag)
+{
+ /* clear the flags */
+ FMC_STAT = flag;
+}
+
+/*!
+ \brief get flag set or reset
+ \param[in] flag: check FMC flag
+ only one parameter can be selected which is shown as below:
+ \arg FMC_FLAG_PGERR: FMC programming error flag
+ \arg FMC_FLAG_WPERR: FMC write protection error flag
+ \arg FMC_FLAG_END: FMC end of programming flag
+ \param[out] none
+ \retval FlagStatus: SET or RESET
+*/
+FlagStatus fmc_interrupt_flag_get(uint32_t flag)
+{
+ FlagStatus status = RESET;
+
+ if(FMC_STAT & flag) {
+ status = SET;
+ }
+ /* return the state of corresponding FMC flag */
+ return status;
+}
+
+/*!
+ \brief clear the FMC pending flag by writing 1
+ \param[in] flag: clear FMC flag
+ only one parameter can be selected which is shown as below:
+ \arg FMC_FLAG_PGERR: FMC programming error flag
+ \arg FMC_FLAG_WPERR: FMC write protection error flag
+ \arg FMC_FLAG_END: fmc end of programming flag
+ \param[out] none
+ \retval none
+*/
+void fmc_interrupt_flag_clear(uint32_t flag)
+{
+ /* clear the flags */
+ FMC_STAT = flag;
+}
+
+/*!
+ \brief get the FMC state
+ \param[in] none
+ \param[out] none
+ \retval fmc_state
+*/
+fmc_state_enum fmc_state_get(void)
+{
+ fmc_state_enum fmc_state = FMC_READY;
+
+ if((uint32_t)0x00U != (FMC_STAT & FMC_STAT_BUSY)) {
+ fmc_state = FMC_BUSY;
+ } else {
+ if((uint32_t)0x00U != (FMC_STAT & FMC_STAT_WPERR)) {
+ fmc_state = FMC_WPERR;
+ } else {
+ if((uint32_t)0x00U != (FMC_STAT & FMC_STAT_PGERR)) {
+ fmc_state = FMC_PGERR;
+ }
+ }
+ }
+ /* return the FMC state */
+ return fmc_state;
+}
+
+/*!
+ \brief check whether FMC is ready or not
+ \param[in] timeout: timeout count
+ \param[out] none
+ \retval fmc_state
+*/
+fmc_state_enum fmc_ready_wait(uint32_t timeout)
+{
+ fmc_state_enum fmc_state = FMC_BUSY;
+
+ /* wait for FMC ready */
+ do {
+ /* get FMC state */
+ fmc_state = fmc_state_get();
+ timeout--;
+ } while((FMC_BUSY == fmc_state) && (0U != timeout));
+
+ if(FMC_BUSY == fmc_state) {
+ fmc_state = FMC_TOERR;
+ }
+ /* return the FMC state */
+ return fmc_state;
+}
+
+/*!
+ \brief get current option byte value
+ \param[in] ob_parm: pointer to option byte parameter struct
+ \param[out] ob_parm: pointer to option byte parameter struct
+ \retval none
+*/
+void ob_parm_get(ob_parm_struct *ob_parm)
+{
+ /* get current option byte value */
+ ob_parm->spc = (uint8_t)OB_SPC;
+ ob_parm->user = (uint8_t)OB_USER;
+ ob_parm->data0 = (uint8_t)OB_DATA0;
+ ob_parm->data1 = (uint8_t)OB_DATA1;
+ ob_parm->wp0 = (uint8_t)OB_WP0;
+ ob_parm->wp1 = (uint8_t)OB_WP1;
+}
+
+/*!
+ \brief modify the target option byte depending on the original value
+ \param[in] address: target option byte address
+ \param[in] value: target option byte value
+ \param[in] ob_parm: pointer to option byte parameter struct
+ \param[out] none
+ \retval none
+*/
+void ob_value_modify(uint32_t address, uint16_t value, ob_parm_struct *ob_parm)
+{
+ uint8_t spc, user, data0, data1, wp0, wp1;
+ /* store the original option bytes */
+ spc = ob_parm->spc;
+ user = ob_parm->user;
+ data0 = ob_parm->data0;
+ data1 = ob_parm->data1;
+ wp0 = ob_parm->wp0;
+ wp1 = ob_parm->wp1;
+
+ /* bring in the target option byte */
+ if(OB_SPC_ADDR == address) {
+ spc = (uint8_t)value;
+ } else if(OB_DATA_ADDR0 == address) {
+ data0 = (uint8_t)value;
+ } else if(OB_DATA_ADDR1 == address) {
+ data1 = (uint8_t)value;
+ } else if(OB_USER_ADDR == address) {
+ user = user & (uint8_t)value;
+ } else {
+ wp0 = wp0 & ((uint8_t)(value));
+ wp1 = wp1 & ((uint8_t)(value >> 8U));
+ }
+ /* basing on original value, modify the target option byte */
+ OB_SPC = spc;
+ OB_USER = user;
+ if(0xFFU != data0) {
+ OB_DATA0 = data0;
+ }
+ if(0xFFU != data1) {
+ OB_DATA1 = data1;
+ }
+ if(0xFFU != wp0) {
+ OB_WP0 = wp0;
+ }
+ if(0xFFU != wp1) {
+ OB_WP1 = wp1;
+ }
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_fwdgt.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_fwdgt.c
new file mode 100644
index 00000000..b6eb6f7e
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_fwdgt.c
@@ -0,0 +1,181 @@
+/*!
+ \file gd32f3x0_fwdgt.c
+ \brief FWDGT driver
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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.
+*/
+
+#include "gd32f3x0_fwdgt.h"
+
+/*!
+ \brief enable write access to FWDGT_PSC,FWDGT_RLD and FWDGT_WND
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void fwdgt_write_enable(void)
+{
+ FWDGT_CTL = FWDGT_WRITEACCESS_ENABLE;
+}
+
+/*!
+ \brief disable write access to FWDGT_PSC,FWDGT_RLD and FWDGT_WND
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void fwdgt_write_disable(void)
+{
+ FWDGT_CTL = FWDGT_WRITEACCESS_DISABLE;
+}
+
+/*!
+ \brief start the free watchdog timer counter
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void fwdgt_enable(void)
+{
+ FWDGT_CTL = FWDGT_KEY_ENABLE;
+}
+
+/*!
+ \brief configure the free watchdog timer counter window value
+ \param[in] window_value: specify window value(0x0000 - 0x0FFF)
+ \param[out] none
+ \retval ErrStatus: ERROR or SUCCESS
+*/
+ErrStatus fwdgt_window_value_config(uint16_t window_value)
+{
+ uint32_t time_index = FWDGT_WND_TIMEOUT;
+ uint32_t flag_status = RESET;
+
+ /* enable write access to FWDGT_WND */
+ FWDGT_CTL = FWDGT_WRITEACCESS_ENABLE;
+
+ /* wait until the WUD flag to be reset */
+ do {
+ flag_status = FWDGT_STAT & FWDGT_STAT_WUD;
+ } while((--time_index > 0U) && (RESET != flag_status));
+
+ if(RESET != flag_status) {
+ return ERROR;
+ }
+
+ FWDGT_WND = WND_WND(window_value);
+
+ return SUCCESS;
+}
+
+/*!
+ \brief reload the counter of FWDGT
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void fwdgt_counter_reload(void)
+{
+ FWDGT_CTL = FWDGT_KEY_RELOAD;
+}
+
+/*!
+ \brief configure counter reload value, and prescaler divider value
+ \param[in] reload_value: specify reload value(0x0000 - 0x0FFF)
+ \param[in] prescaler_div: FWDGT prescaler value
+ only one parameter can be selected which is shown as below:
+ \arg FWDGT_PSC_DIV4: FWDGT prescaler set to 4
+ \arg FWDGT_PSC_DIV8: FWDGT prescaler set to 8
+ \arg FWDGT_PSC_DIV16: FWDGT prescaler set to 16
+ \arg FWDGT_PSC_DIV32: FWDGT prescaler set to 32
+ \arg FWDGT_PSC_DIV64: FWDGT prescaler set to 64
+ \arg FWDGT_PSC_DIV128: FWDGT prescaler set to 128
+ \arg FWDGT_PSC_DIV256: FWDGT prescaler set to 256
+ \param[out] none
+ \retval ErrStatus: ERROR or SUCCESS
+*/
+ErrStatus fwdgt_config(uint16_t reload_value, uint8_t prescaler_div)
+{
+ uint32_t timeout = FWDGT_PSC_TIMEOUT;
+ uint32_t flag_status = RESET;
+
+ /* enable write access to FWDGT_PSC,and FWDGT_RLD */
+ FWDGT_CTL = FWDGT_WRITEACCESS_ENABLE;
+
+ /* wait until the PUD flag to be reset */
+ do {
+ flag_status = FWDGT_STAT & FWDGT_STAT_PUD;
+ } while((--timeout > 0U) && (RESET != flag_status));
+
+ if(RESET != flag_status) {
+ return ERROR;
+ }
+
+ /* configure FWDGT */
+ FWDGT_PSC = (uint32_t)prescaler_div;
+
+ timeout = FWDGT_RLD_TIMEOUT;
+ /* wait until the RUD flag to be reset */
+ do {
+ flag_status = FWDGT_STAT & FWDGT_STAT_RUD;
+ } while((--timeout > 0U) && (RESET != flag_status));
+
+ if(RESET != flag_status) {
+ return ERROR;
+ }
+
+ FWDGT_RLD = RLD_RLD(reload_value);
+
+ /* reload the counter */
+ FWDGT_CTL = FWDGT_KEY_RELOAD;
+
+ return SUCCESS;
+}
+
+/*!
+ \brief get flag state of FWDGT
+ \param[in] flag: flag to get
+ only one parameter can be selected which is shown as below:
+ \arg FWDGT_FLAG_PUD: a write operation to FWDGT_PSC register is on going
+ \arg FWDGT_FLAG_RUD: a write operation to FWDGT_RLD register is on going
+ \arg FWDGT_FLAG_WUD: a write operation to FWDGT_WND register is on going
+ \param[out] none
+ \retval FlagStatus: SET or RESET
+*/
+FlagStatus fwdgt_flag_get(uint16_t flag)
+{
+ if(FWDGT_STAT & flag) {
+ return SET;
+ }
+ return RESET;
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_gpio.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_gpio.c
new file mode 100644
index 00000000..1d8c7dc1
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_gpio.c
@@ -0,0 +1,426 @@
+/*!
+ \file gd32f3x0_gpio.c
+ \brief GPIO driver
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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.
+*/
+
+#include "gd32f3x0_gpio.h"
+
+/*!
+ \brief reset GPIO port
+ \param[in] gpio_periph: GPIOx(x = A,B,C,D,F)
+ only one parameter can be selected which is shown as below:
+ \arg GPIOx(x = A,B,C,D,F)
+ \param[out] none
+ \retval none
+*/
+void gpio_deinit(uint32_t gpio_periph)
+{
+ switch(gpio_periph) {
+ case GPIOA:
+ /* reset GPIOA */
+ rcu_periph_reset_enable(RCU_GPIOARST);
+ rcu_periph_reset_disable(RCU_GPIOARST);
+ break;
+ case GPIOB:
+ /* reset GPIOB */
+ rcu_periph_reset_enable(RCU_GPIOBRST);
+ rcu_periph_reset_disable(RCU_GPIOBRST);
+ break;
+ case GPIOC:
+ /* reset GPIOC */
+ rcu_periph_reset_enable(RCU_GPIOCRST);
+ rcu_periph_reset_disable(RCU_GPIOCRST);
+ break;
+ case GPIOD:
+ /* reset GPIOD */
+ rcu_periph_reset_enable(RCU_GPIODRST);
+ rcu_periph_reset_disable(RCU_GPIODRST);
+ break;
+ case GPIOF:
+ /* reset GPIOF */
+ rcu_periph_reset_enable(RCU_GPIOFRST);
+ rcu_periph_reset_disable(RCU_GPIOFRST);
+ break;
+ default:
+ break;
+ }
+}
+
+/*!
+ \brief set GPIO mode
+ \param[in] gpio_periph: GPIOx(x = A,B,C,D,F)
+ only one parameter can be selected which is shown as below:
+ \arg GPIOx(x = A,B,C,D,F)
+ \param[in] mode: gpio pin mode
+ only one parameter can be selected which is shown as below:
+ \arg GPIO_MODE_INPUT: input mode
+ \arg GPIO_MODE_OUTPUT: output mode
+ \arg GPIO_MODE_AF: alternate function mode
+ \arg GPIO_MODE_ANALOG: analog mode
+ \param[in] pull_up_down: gpio pin with pull-up or pull-down resistor
+ only one parameter can be selected which is shown as below:
+ \arg GPIO_PUPD_NONE: floating mode, no pull-up and pull-down resistors
+ \arg GPIO_PUPD_PULLUP: with pull-up resistor
+ \arg GPIO_PUPD_PULLDOWN:with pull-down resistor
+ \param[in] pin: GPIO pin
+ one or more parameters can be selected which are shown as below:
+ \arg GPIO_PIN_x(x=0..15), GPIO_PIN_ALL
+ \param[out] none
+ \retval none
+*/
+void gpio_mode_set(uint32_t gpio_periph, uint32_t mode, uint32_t pull_up_down, uint32_t pin)
+{
+ uint16_t i;
+ uint32_t ctl, pupd;
+
+ ctl = GPIO_CTL(gpio_periph);
+ pupd = GPIO_PUD(gpio_periph);
+
+ for(i = 0U; i < 16U; i++) {
+ if((1U << i) & pin) {
+ /* clear the specified pin mode bits */
+ ctl &= ~GPIO_MODE_MASK(i);
+ /* set the specified pin mode bits */
+ ctl |= GPIO_MODE_SET(i, mode);
+
+ /* clear the specified pin pupd bits */
+ pupd &= ~GPIO_PUPD_MASK(i);
+ /* set the specified pin pupd bits */
+ pupd |= GPIO_PUPD_SET(i, pull_up_down);
+ }
+ }
+
+ GPIO_CTL(gpio_periph) = ctl;
+ GPIO_PUD(gpio_periph) = pupd;
+}
+
+/*!
+ \brief set GPIO output type and speed
+ \param[in] gpio_periph: GPIOx(x = A,B,C,D,F)
+ only one parameter can be selected which is shown as below:
+ \arg GPIOx(x = A,B,C,D,F)
+ \param[in] otype: gpio pin output mode
+ only one parameter can be selected which is shown as below:
+ \arg GPIO_OTYPE_PP: push pull mode
+ \arg GPIO_OTYPE_OD: open drain mode
+ \param[in] speed: gpio pin output max speed
+ only one parameter can be selected which is shown as below:
+ \arg GPIO_OSPEED_2MHZ: output max speed 2MHz
+ \arg GPIO_OSPEED_10MHZ: output max speed 10MHz
+ \arg GPIO_OSPEED_50MHZ: output max speed 50MHz
+ \arg GPIO_OSPEED_MAX: GPIO very high output speed, max speed more than 50MHz
+ \param[in] pin: GPIO pin
+ one or more parameters can be selected which are shown as below:
+ \arg GPIO_PIN_x(x=0..15), GPIO_PIN_ALL
+ \param[out] none
+ \retval none
+*/
+void gpio_output_options_set(uint32_t gpio_periph, uint8_t otype, uint32_t speed, uint32_t pin)
+{
+ uint16_t i;
+ uint32_t ospeed0, ospeed1;
+
+ if(GPIO_OTYPE_OD == otype) {
+ GPIO_OMODE(gpio_periph) |= (uint32_t)pin;
+ } else {
+ GPIO_OMODE(gpio_periph) &= (uint32_t)(~pin);
+ }
+
+ /* get the specified pin output speed bits value */
+ ospeed0 = GPIO_OSPD0(gpio_periph);
+
+ if(GPIO_OSPEED_MAX == speed) {
+ ospeed1 = GPIO_OSPD1(gpio_periph);
+
+ for(i = 0U; i < 16U; i++) {
+ if((1U << i) & pin) {
+ /* enable very high output speed function of the pin when the corresponding OSPDy(y=0..15)
+ is "11" (output max speed 50MHz) */
+ ospeed0 |= GPIO_OSPEED_SET(i, 0x03);
+ ospeed1 |= (1U << i);
+ }
+ }
+ GPIO_OSPD0(gpio_periph) = ospeed0;
+ GPIO_OSPD1(gpio_periph) = ospeed1;
+ } else {
+ for(i = 0U; i < 16U; i++) {
+ if((1U << i) & pin) {
+ /* clear the specified pin output speed bits */
+ ospeed0 &= ~GPIO_OSPEED_MASK(i);
+ /* set the specified pin output speed bits */
+ ospeed0 |= GPIO_OSPEED_SET(i, speed);
+ }
+ }
+ GPIO_OSPD0(gpio_periph) = ospeed0;
+ }
+}
+
+/*!
+ \brief set GPIO pin bit
+ \param[in] gpio_periph: GPIOx(x = A,B,C,D,F)
+ only one parameter can be selected which is shown as below:
+ \arg GPIOx(x = A,B,C,D,F)
+ \param[in] pin: GPIO pin
+ one or more parameters can be selected which are shown as below:
+ \arg GPIO_PIN_x(x=0..15), GPIO_PIN_ALL
+ \param[out] none
+ \retval none
+*/
+void gpio_bit_set(uint32_t gpio_periph, uint32_t pin)
+{
+ GPIO_BOP(gpio_periph) = (uint32_t)pin;
+}
+
+/*!
+ \brief reset GPIO pin bit
+ \param[in] gpio_periph: GPIOx(x = A,B,C,D,F)
+ only one parameter can be selected which is shown as below:
+ \arg GPIOx(x = A,B,C,D,F)
+ \param[in] pin: GPIO pin
+ one or more parameters can be selected which are shown as below:
+ \arg GPIO_PIN_x(x=0..15), GPIO_PIN_ALL
+ \param[out] none
+ \retval none
+*/
+void gpio_bit_reset(uint32_t gpio_periph, uint32_t pin)
+{
+ GPIO_BC(gpio_periph) = (uint32_t)pin;
+}
+
+/*!
+ \brief write data to the specified GPIO pin
+ \param[in] gpio_periph: GPIOx(x = A,B,C,D,F)
+ only one parameter can be selected which is shown as below:
+ \arg GPIOx(x = A,B,C,D,F)
+ \param[in] pin: GPIO pin
+ one or more parameters can be selected which are shown as below:
+ \arg GPIO_PIN_x(x=0..15), GPIO_PIN_ALL
+ \param[in] bit_value: SET or RESET
+ only one parameter can be selected which is shown as below:
+ \arg RESET: clear the port pin
+ \arg SET: set the port pin
+ \param[out] none
+ \retval none
+*/
+void gpio_bit_write(uint32_t gpio_periph, uint32_t pin, bit_status bit_value)
+{
+ if(RESET != bit_value) {
+ GPIO_BOP(gpio_periph) = (uint32_t)pin;
+ } else {
+ GPIO_BC(gpio_periph) = (uint32_t)pin;
+ }
+}
+
+/*!
+ \brief write data to the specified GPIO port
+ \param[in] gpio_periph: GPIOx(x = A,B,C,D,F)
+ only one parameter can be selected which is shown as below:
+ \arg GPIOx(x = A,B,C,D,F)
+ \param[in] data: specify the value to be written to the port output control register
+ \param[out] none
+ \retval none
+*/
+void gpio_port_write(uint32_t gpio_periph, uint16_t data)
+{
+ GPIO_OCTL(gpio_periph) = (uint32_t)data;
+}
+
+/*!
+ \brief get GPIO pin input status
+ \param[in] gpio_periph: GPIOx(x = A,B,C,D,F)
+ only one parameter can be selected which is shown as below:
+ \arg GPIOx(x = A,B,C,D,F)
+ \param[in] pin: GPIO pin
+ one or more parameters can be selected which are shown as below:
+ \arg GPIO_PIN_x(x=0..15), GPIO_PIN_ALL
+ \param[out] none
+ \retval SET or RESET
+*/
+FlagStatus gpio_input_bit_get(uint32_t gpio_periph, uint32_t pin)
+{
+ if((uint32_t)RESET != (GPIO_ISTAT(gpio_periph) & (pin))) {
+ return SET;
+ } else {
+ return RESET;
+ }
+}
+
+/*!
+ \brief get GPIO all pins input status
+ \param[in] gpio_periph: GPIOx(x = A,B,C,D,F)
+ only one parameter can be selected which is shown as below:
+ \arg GPIOx(x = A,B,C,D,F)
+ \param[out] none
+ \retval state of GPIO all pins
+*/
+uint16_t gpio_input_port_get(uint32_t gpio_periph)
+{
+ return (uint16_t)GPIO_ISTAT(gpio_periph);
+}
+
+/*!
+ \brief get GPIO pin output status
+ \param[in] gpio_periph: GPIOx(x = A,B,C,D,F)
+ only one parameter can be selected which is shown as below:
+ \arg GPIOx(x = A,B,C,D,F)
+ \param[in] pin: GPIO pin
+ one or more parameters can be selected which are shown as below:
+ \arg GPIO_PIN_x(x=0..15), GPIO_PIN_ALL
+ \param[out] none
+ \retval SET or RESET
+*/
+FlagStatus gpio_output_bit_get(uint32_t gpio_periph, uint32_t pin)
+{
+ if((uint32_t)RESET != (GPIO_OCTL(gpio_periph) & (pin))) {
+ return SET;
+ } else {
+ return RESET;
+ }
+}
+
+/*!
+ \brief get GPIO all pins output status
+ \param[in] gpio_periph: GPIOx(x = A,B,C,D,F)
+ only one parameter can be selected which is shown as below:
+ \arg GPIOx(x = A,B,C,D,F)
+ \param[out] none
+ \retval state of GPIO all pins
+*/
+uint16_t gpio_output_port_get(uint32_t gpio_periph)
+{
+ return (uint16_t)GPIO_OCTL(gpio_periph);
+}
+
+/*!
+ \brief set GPIO alternate function
+ \param[in] gpio_periph: GPIOx(x = A,B,C)
+ only one parameter can be selected which is shown as below:
+ \arg GPIOx(x = A,B,C)
+ \param[in] alt_func_num: GPIO pin af function, please refer to specific device datasheet
+ only one parameter can be selected which is shown as below:
+ \arg GPIO_AF_0: TIMER2, TIMER13, TIMER14, TIMER16, SPI0, SPI1, I2S0, CK_OUT, USART0, CEC,
+ IFRP, TSI, CTC, I2C0, I2C1, SWDIO, SWCLK
+ \arg GPIO_AF_1: USART0, USART1, TIMER2, TIMER14, I2C0, I2C1, IFRP, CEC
+ \arg GPIO_AF_2: TIMER0, TIMER1, TIMER15, TIMER16, I2S0
+ \arg GPIO_AF_3: TSI, I2C0, TIMER14
+ \arg GPIO_AF_4(port A,B only): USART1, I2C0, I2C1, TIMER13
+ \arg GPIO_AF_5(port A,B only): TIMER15, TIMER16, USBFS, I2S0
+ \arg GPIO_AF_6(port A,B only): CTC, SPI1
+ \arg GPIO_AF_7(port A,B only): CMP0, CMP1
+ \param[in] pin: GPIO pin
+ one or more parameters can be selected which are shown as below:
+ \arg GPIO_PIN_x(x=0..15), GPIO_PIN_ALL
+ \param[out] none
+ \retval none
+*/
+void gpio_af_set(uint32_t gpio_periph, uint32_t alt_func_num, uint32_t pin)
+{
+ uint16_t i;
+ uint32_t afrl, afrh;
+
+ afrl = GPIO_AFSEL0(gpio_periph);
+ afrh = GPIO_AFSEL1(gpio_periph);
+
+ for(i = 0U; i < 8U; i++) {
+ if((1U << i) & pin) {
+ /* clear the specified pin alternate function bits */
+ afrl &= ~GPIO_AFR_MASK(i);
+ afrl |= GPIO_AFR_SET(i, alt_func_num);
+ }
+ }
+
+ for(i = 8U; i < 16U; i++) {
+ if((1U << i) & pin) {
+ /* clear the specified pin alternate function bits */
+ afrh &= ~GPIO_AFR_MASK(i - 8U);
+ afrh |= GPIO_AFR_SET(i - 8U, alt_func_num);
+ }
+ }
+
+ GPIO_AFSEL0(gpio_periph) = afrl;
+ GPIO_AFSEL1(gpio_periph) = afrh;
+}
+
+/*!
+ \brief lock GPIO pin bit
+ \param[in] gpio_periph: GPIOx(x = A,B)
+ only one parameter can be selected which is shown as below:
+ \arg GPIOx(x = A,B)
+ \param[in] pin: GPIO pin
+ one or more parameters can be selected which are shown as below:
+ \arg GPIO_PIN_x(x=0..15), GPIO_PIN_ALL
+ \param[out] none
+ \retval none
+*/
+void gpio_pin_lock(uint32_t gpio_periph, uint32_t pin)
+{
+ uint32_t lock = 0x00010000U;
+ lock |= pin;
+
+ /* lock key writing sequence: write 1->write 0->write 1->read 0->read 1 */
+ GPIO_LOCK(gpio_periph) = (uint32_t)lock;
+ GPIO_LOCK(gpio_periph) = (uint32_t)pin;
+ GPIO_LOCK(gpio_periph) = (uint32_t)lock;
+ lock = GPIO_LOCK(gpio_periph);
+ lock = GPIO_LOCK(gpio_periph);
+}
+
+/*!
+ \brief toggle GPIO pin status
+ \param[in] gpio_periph: GPIOx(x = A,B,C,D,F)
+ only one parameter can be selected which is shown as below:
+ \arg GPIOx(x = A,B,C,D,F)
+ \param[in] pin: GPIO pin
+ one or more parameters can be selected which are shown as below:
+ \arg GPIO_PIN_x(x=0..15), GPIO_PIN_ALL
+ \param[out] none
+ \retval none
+*/
+void gpio_bit_toggle(uint32_t gpio_periph, uint32_t pin)
+{
+ GPIO_TG(gpio_periph) = (uint32_t)pin;
+}
+
+/*!
+ \brief toggle GPIO port status
+ only one parameter can be selected which is shown as below:
+ \arg GPIOx(x = A,B,C,D,F)
+ \param[out] none
+ \retval none
+*/
+void gpio_port_toggle(uint32_t gpio_periph)
+{
+ GPIO_TG(gpio_periph) = 0x0000FFFFU;
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_i2c.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_i2c.c
new file mode 100644
index 00000000..6d25d2e3
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_i2c.c
@@ -0,0 +1,731 @@
+/*!
+ \file gd32f3x0_i2c.c
+ \brief I2C driver
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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.
+*/
+
+#include "gd32f3x0_i2c.h"
+
+/* I2C register bit mask */
+#define I2CCLK_MAX ((uint32_t)0x0000003FU) /*!< i2cclk maximum value */
+#define I2CCLK_MIN ((uint32_t)0x00000002U) /*!< i2cclk minimum value */
+#define I2C_FLAG_MASK ((uint32_t)0x0000FFFFU) /*!< i2c flag mask */
+#define I2C_ADDRESS_MASK ((uint32_t)0x000003FFU) /*!< i2c address mask */
+#define I2C_ADDRESS2_MASK ((uint32_t)0x000000FEU) /*!< the second i2c address mask */
+
+/* I2C register bit offset */
+#define STAT1_PECV_OFFSET ((uint32_t)8U) /* bit offset of PECV in I2C_STAT1 */
+
+/*!
+ \brief reset I2C
+ \param[in] i2c_periph: I2Cx(x=0,1)
+ \param[out] none
+ \retval none
+*/
+void i2c_deinit(uint32_t i2c_periph)
+{
+ switch(i2c_periph) {
+ case I2C0:
+ /* reset I2C0 */
+ rcu_periph_reset_enable(RCU_I2C0RST);
+ rcu_periph_reset_disable(RCU_I2C0RST);
+ break;
+ case I2C1:
+ /* reset I2C1 */
+ rcu_periph_reset_enable(RCU_I2C1RST);
+ rcu_periph_reset_disable(RCU_I2C1RST);
+ break;
+ default:
+ break;
+ }
+}
+
+/*!
+ \brief configure I2C clock
+ \param[in] i2c_periph: I2Cx(x=0,1)
+ \param[in] clkspeed: I2C clock speed, supports standard mode (up to 100 kHz), fast mode (up to 400 kHz)
+ and fast mode plus (up to 1MHz)
+ \param[in] dutycyc: duty cycle in fast mode or fast mode plus
+ only one parameter can be selected which is shown as below:
+ \arg I2C_DTCY_2: T_low/T_high=2
+ \arg I2C_DTCY_16_9: T_low/T_high=16/9
+ \param[out] none
+ \retval none
+*/
+void i2c_clock_config(uint32_t i2c_periph, uint32_t clkspeed, uint32_t dutycyc)
+{
+ uint32_t pclk1, clkc, freq, risetime;
+ uint32_t temp;
+
+ pclk1 = rcu_clock_freq_get(CK_APB1);
+ /* I2C peripheral clock frequency */
+ freq = (uint32_t)(pclk1 / 1000000U);
+ if(freq >= I2CCLK_MAX) {
+ freq = I2CCLK_MAX;
+ }
+ temp = I2C_CTL1(i2c_periph);
+ temp &= ~I2C_CTL1_I2CCLK;
+ temp |= freq;
+
+ I2C_CTL1(i2c_periph) = temp;
+
+ if(100000U >= clkspeed) {
+ /* the maximum SCL rise time is 1000ns in standard mode */
+ risetime = (uint32_t)((pclk1 / 1000000U) + 1U);
+ if(risetime >= I2CCLK_MAX) {
+ I2C_RT(i2c_periph) = I2CCLK_MAX;
+ } else if(risetime <= I2CCLK_MIN) {
+ I2C_RT(i2c_periph) = I2CCLK_MIN;
+ } else {
+ I2C_RT(i2c_periph) = risetime;
+ }
+ clkc = (uint32_t)(pclk1 / (clkspeed * 2U));
+ if(clkc < 0x04U) {
+ /* the CLKC in standard mode minmum value is 4 */
+ clkc = 0x04U;
+ }
+ I2C_CKCFG(i2c_periph) |= (I2C_CKCFG_CLKC & clkc);
+
+ } else if(400000U >= clkspeed) {
+ /* the maximum SCL rise time is 300ns in fast mode */
+ I2C_RT(i2c_periph) = (uint32_t)(((freq * (uint32_t)300U) / (uint32_t)1000U) + (uint32_t)1U);
+ if(I2C_DTCY_2 == dutycyc) {
+ /* I2C duty cycle is 2 */
+ clkc = (uint32_t)(pclk1 / (clkspeed * 3U));
+ I2C_CKCFG(i2c_periph) &= ~I2C_CKCFG_DTCY;
+ } else {
+ /* I2C duty cycle is 16/9 */
+ clkc = (uint32_t)(pclk1 / (clkspeed * 25U));
+ I2C_CKCFG(i2c_periph) |= I2C_CKCFG_DTCY;
+ }
+ if(0U == (clkc & I2C_CKCFG_CLKC)) {
+ /* the CLKC in fast mode minmum value is 1 */
+ clkc |= 0x0001U;
+ }
+ I2C_CKCFG(i2c_periph) |= I2C_CKCFG_FAST;
+ I2C_CKCFG(i2c_periph) |= clkc;
+ } else {
+ /* fast mode plus, the maximum SCL rise time is 120ns */
+ I2C_RT(i2c_periph) = (uint32_t)(((freq * (uint32_t)120U) / (uint32_t)1000U) + (uint32_t)1U);
+ if(I2C_DTCY_2 == dutycyc) {
+ /* I2C duty cycle is 2 */
+ clkc = (uint32_t)(pclk1 / (clkspeed * 3U));
+ I2C_CKCFG(i2c_periph) &= ~I2C_CKCFG_DTCY;
+ } else {
+ /* I2C duty cycle is 16/9 */
+ clkc = (uint32_t)(pclk1 / (clkspeed * 25U));
+ I2C_CKCFG(i2c_periph) |= I2C_CKCFG_DTCY;
+ }
+ /* enable fast mode */
+ I2C_CKCFG(i2c_periph) |= I2C_CKCFG_FAST;
+ I2C_CKCFG(i2c_periph) |= clkc;
+ /* enable I2C fast mode plus */
+ I2C_FMPCFG(i2c_periph) = I2C_FMPCFG_FMPEN;
+ }
+}
+
+/*!
+ \brief configure I2C address
+ \param[in] i2c_periph: I2Cx(x=0,1)
+ \param[in] mode:
+ only one parameter can be selected which is shown as below:
+ \arg I2C_I2CMODE_ENABLE: I2C mode
+ \arg I2C_SMBUSMODE_ENABLE: SMBus mode
+ \param[in] addformat: 7bits or 10bits
+ only one parameter can be selected which is shown as below:
+ \arg I2C_ADDFORMAT_7BITS: 7bits
+ \arg I2C_ADDFORMAT_10BITS: 10bits
+ \param[in] addr: I2C address
+ \param[out] none
+ \retval none
+*/
+void i2c_mode_addr_config(uint32_t i2c_periph, uint32_t mode, uint32_t addformat, uint32_t addr)
+{
+ /* SMBus/I2C mode selected */
+ uint32_t ctl = 0U;
+
+ ctl = I2C_CTL0(i2c_periph);
+ ctl &= ~(I2C_CTL0_SMBEN);
+ ctl |= mode;
+ I2C_CTL0(i2c_periph) = ctl;
+
+ /* configure address */
+ addr = addr & I2C_ADDRESS_MASK;
+ I2C_SADDR0(i2c_periph) = (addformat | addr);
+}
+
+/*!
+ \brief SMBus type selection
+ \param[in] i2c_periph: I2Cx(x=0,1)
+ \param[in] type:
+ only one parameter can be selected which is shown as below:
+ \arg I2C_SMBUS_DEVICE: device
+ \arg I2C_SMBUS_HOST: host
+ \param[out] none
+ \retval none
+*/
+void i2c_smbus_type_config(uint32_t i2c_periph, uint32_t type)
+{
+ if(I2C_SMBUS_HOST == type) {
+ I2C_CTL0(i2c_periph) |= I2C_CTL0_SMBSEL;
+ } else {
+ I2C_CTL0(i2c_periph) &= ~(I2C_CTL0_SMBSEL);
+ }
+}
+
+/*!
+ \brief whether or not to send an ACK
+ \param[in] i2c_periph: I2Cx(x=0,1)
+ \param[in] ack:
+ only one parameter can be selected which is shown as below:
+ \arg I2C_ACK_ENABLE: ACK will be sent
+ \arg I2C_ACK_DISABLE: ACK will not be sent
+ \param[out] none
+ \retval none
+*/
+void i2c_ack_config(uint32_t i2c_periph, uint32_t ack)
+{
+ if(I2C_ACK_ENABLE == ack) {
+ I2C_CTL0(i2c_periph) |= I2C_CTL0_ACKEN;
+ } else {
+ I2C_CTL0(i2c_periph) &= ~(I2C_CTL0_ACKEN);
+ }
+}
+
+/*!
+ \brief configure I2C position of ACK and PEC when receiving
+ \param[in] i2c_periph: I2Cx(x=0,1)
+ \param[in] pos:
+ only one parameter can be selected which is shown as below:
+ \arg I2C_ACKPOS_CURRENT: whether to send ACK or not for the current
+ \arg I2C_ACKPOS_NEXT: whether to send ACK or not for the next byte
+ \param[out] none
+ \retval none
+*/
+void i2c_ackpos_config(uint32_t i2c_periph, uint32_t pos)
+{
+ /* configure I2C POAP position */
+ if(I2C_ACKPOS_NEXT == pos) {
+ I2C_CTL0(i2c_periph) |= I2C_CTL0_POAP;
+ } else {
+ I2C_CTL0(i2c_periph) &= ~(I2C_CTL0_POAP);
+ }
+}
+
+/*!
+ \brief master sends slave address
+ \param[in] i2c_periph: I2Cx(x=0,1)
+ \param[in] addr: slave address
+ \param[in] trandirection: transmitter or receiver
+ only one parameter can be selected which is shown as below:
+ \arg I2C_TRANSMITTER: transmitter
+ \arg I2C_RECEIVER: receiver
+ \param[out] none
+ \retval none
+*/
+void i2c_master_addressing(uint32_t i2c_periph, uint32_t addr, uint32_t trandirection)
+{
+ /* master is a transmitter or a receiver */
+ if(I2C_TRANSMITTER == trandirection) {
+ addr = addr & I2C_TRANSMITTER;
+ } else {
+ addr = addr | I2C_RECEIVER;
+ }
+ /* send slave address */
+ I2C_DATA(i2c_periph) = addr;
+}
+
+/*!
+ \brief enable dual-address mode
+ \param[in] i2c_periph: I2Cx(x=0,1)
+ \param[in] addr: the second address in dual-address mode
+ \param[out] none
+ \retval none
+*/
+void i2c_dualaddr_enable(uint32_t i2c_periph, uint32_t addr)
+{
+ /* configure address */
+ addr = addr & I2C_ADDRESS2_MASK;
+ I2C_SADDR1(i2c_periph) = (I2C_SADDR1_DUADEN | addr);
+}
+
+/*!
+ \brief disable dual-address mode
+ \param[in] i2c_periph: I2Cx(x=0,1)
+ \param[out] none
+ \retval none
+*/
+void i2c_dualaddr_disable(uint32_t i2c_periph)
+{
+ I2C_SADDR1(i2c_periph) &= ~(I2C_SADDR1_DUADEN);
+}
+
+/*!
+ \brief enable I2C
+ \param[in] i2c_periph: I2Cx(x=0,1)
+ \param[out] none
+ \retval none
+*/
+void i2c_enable(uint32_t i2c_periph)
+{
+ I2C_CTL0(i2c_periph) |= I2C_CTL0_I2CEN;
+}
+
+/*!
+ \brief disable I2C
+ \param[in] i2c_periph: I2Cx(x=0,1)
+ \param[out] none
+ \retval none
+*/
+void i2c_disable(uint32_t i2c_periph)
+{
+ I2C_CTL0(i2c_periph) &= ~(I2C_CTL0_I2CEN);
+}
+
+/*!
+ \brief generate a START condition on I2C bus
+ \param[in] i2c_periph: I2Cx(x=0,1)
+ \param[out] none
+ \retval none
+*/
+void i2c_start_on_bus(uint32_t i2c_periph)
+{
+ I2C_CTL0(i2c_periph) |= I2C_CTL0_START;
+}
+
+/*!
+ \brief generate a STOP condition on I2C bus
+ \param[in] i2c_periph: I2Cx(x=0,1)
+ \param[out] none
+ \retval none
+*/
+void i2c_stop_on_bus(uint32_t i2c_periph)
+{
+ I2C_CTL0(i2c_periph) |= I2C_CTL0_STOP;
+}
+
+/*!
+ \brief I2C transmit data function
+ \param[in] i2c_periph: I2Cx(x=0,1)
+ \param[in] data: data of transmission
+ \param[out] none
+ \retval none
+*/
+void i2c_data_transmit(uint32_t i2c_periph, uint8_t data)
+{
+ I2C_DATA(i2c_periph) = DATA_TRANS(data);
+}
+
+/*!
+ \brief I2C receive data function
+ \param[in] i2c_periph: I2Cx(x=0,1)
+ \param[out] none
+ \retval data of received
+*/
+uint8_t i2c_data_receive(uint32_t i2c_periph)
+{
+ return (uint8_t)DATA_RECV(I2C_DATA(i2c_periph));
+}
+
+/*!
+ \brief enable I2C DMA mode
+ \param[in] i2c_periph: I2Cx(x=0,1)
+ \param[in] dmastate:
+ only one parameter can be selected which is shown as below:
+ \arg I2C_DMA_ON: DMA mode enable
+ \arg I2C_DMA_OFF: DMA mode disable
+ \param[out] none
+ \retval none
+*/
+void i2c_dma_enable(uint32_t i2c_periph, uint32_t dmastate)
+{
+ /* configure I2C DMA function */
+ uint32_t ctl = 0U;
+
+ ctl = I2C_CTL1(i2c_periph);
+ ctl &= ~(I2C_CTL1_DMAON);
+ ctl |= dmastate;
+ I2C_CTL1(i2c_periph) = ctl;
+}
+
+/*!
+ \brief configure whether next DMA EOT is DMA last transfer or not
+ \param[in] i2c_periph: I2Cx(x=0,1)
+ \param[in] dmalast:
+ only one parameter can be selected which is shown as below:
+ \arg I2C_DMALST_ON: next DMA EOT is the last transfer
+ \arg I2C_DMALST_OFF: next DMA EOT is not the last transfer
+ \param[out] none
+ \retval none
+*/
+void i2c_dma_last_transfer_config(uint32_t i2c_periph, uint32_t dmalast)
+{
+ /* configure DMA last transfer */
+ uint32_t ctl = 0U;
+
+ ctl = I2C_CTL1(i2c_periph);
+ ctl &= ~(I2C_CTL1_DMALST);
+ ctl |= dmalast;
+ I2C_CTL1(i2c_periph) = ctl;
+}
+
+/*!
+ \brief whether to stretch SCL low when data is not ready in slave mode
+ \param[in] i2c_periph: I2Cx(x=0,1)
+ \param[in] stretchpara:
+ only one parameter can be selected which is shown as below:
+ \arg I2C_SCLSTRETCH_ENABLE: SCL stretching is enabled
+ \arg I2C_SCLSTRETCH_DISABLE: SCL stretching is disabled
+ \param[out] none
+ \retval none
+*/
+void i2c_stretch_scl_low_config(uint32_t i2c_periph, uint32_t stretchpara)
+{
+ /* configure I2C SCL strerching enable or disable */
+ uint32_t ctl = 0U;
+
+ ctl = I2C_CTL0(i2c_periph);
+ ctl &= ~(I2C_CTL0_SS);
+ ctl |= stretchpara;
+ I2C_CTL0(i2c_periph) = ctl;
+}
+
+/*!
+ \brief whether or not to response to a general call
+ \param[in] i2c_periph: I2Cx(x=0,1)
+ \param[in] gcallpara:
+ only one parameter can be selected which is shown as below:
+ \arg I2C_GCEN_ENABLE: slave will response to a general call
+ \arg I2C_GCEN_DISABLE: slave will not response to a general call
+ \param[out] none
+ \retval none
+*/
+void i2c_slave_response_to_gcall_config(uint32_t i2c_periph, uint32_t gcallpara)
+{
+ /* configure slave response to a general call enable or disable */
+ uint32_t ctl = 0U;
+
+ ctl = I2C_CTL0(i2c_periph);
+ ctl &= ~(I2C_CTL0_GCEN);
+ ctl |= gcallpara;
+ I2C_CTL0(i2c_periph) = ctl;
+}
+
+/*!
+ \brief software reset I2C
+ \param[in] i2c_periph: I2Cx(x=0,1)
+ \param[in] sreset:
+ only one parameter can be selected which is shown as below:
+ \arg I2C_SRESET_SET: I2C is under reset
+ \arg I2C_SRESET_RESET: I2C is not under reset
+ \param[out] none
+ \retval none
+*/
+void i2c_software_reset_config(uint32_t i2c_periph, uint32_t sreset)
+{
+ /* modify CTL0 and configure software reset I2C state */
+ uint32_t ctl = 0U;
+
+ ctl = I2C_CTL0(i2c_periph);
+ ctl &= ~(I2C_CTL0_SRESET);
+ ctl |= sreset;
+ I2C_CTL0(i2c_periph) = ctl;
+}
+
+/*!
+ \brief whether to enable I2C PEC calculation or not
+ \param[in] i2c_periph: I2Cx(x=0,1)
+ \param[in] pecpara:
+ only one parameter can be selected which is shown as below:
+ \arg I2C_PEC_ENABLE: PEC calculation on
+ \arg I2C_PEC_DISABLE: PEC calculation off
+ \param[out] none
+ \retval none
+*/
+void i2c_pec_enable(uint32_t i2c_periph, uint32_t pecstate)
+{
+ /* on/off PEC calculation */
+ uint32_t ctl = 0U;
+
+ ctl = I2C_CTL0(i2c_periph);
+ ctl &= ~(I2C_CTL0_PECEN);
+ ctl |= pecstate;
+ I2C_CTL0(i2c_periph) = ctl;
+}
+
+/*!
+ \brief I2C whether to transfer PEC value
+ \param[in] i2c_periph: I2Cx(x=0,1)
+ \param[in] pecpara:
+ only one parameter can be selected which is shown as below:
+ \arg I2C_PECTRANS_ENABLE: transfer PEC
+ \arg I2C_PECTRANS_DISABLE: not transfer PEC
+ \param[out] none
+ \retval none
+*/
+void i2c_pec_transfer_enable(uint32_t i2c_periph, uint32_t pecpara)
+{
+ /* whether to transfer PEC */
+ uint32_t ctl = 0U;
+
+ ctl = I2C_CTL0(i2c_periph);
+ ctl &= ~(I2C_CTL0_PECTRANS);
+ ctl |= pecpara;
+ I2C_CTL0(i2c_periph) = ctl;
+}
+
+/*!
+ \brief get packet error checking value
+ \param[in] i2c_periph: I2Cx(x=0,1)
+ \param[out] none
+ \retval PEC value
+*/
+uint8_t i2c_pec_value_get(uint32_t i2c_periph)
+{
+ return (uint8_t)((I2C_STAT1(i2c_periph) & I2C_STAT1_PECV) >> STAT1_PECV_OFFSET);
+}
+
+/*!
+ \brief I2C issue alert through SMBA pin
+ \param[in] i2c_periph: I2Cx(x=0,1)
+ \param[in] smbuspara:
+ only one parameter can be selected which is shown as below:
+ \arg I2C_SALTSEND_ENABLE: issue alert through SMBA pin
+ \arg I2C_SALTSEND_DISABLE: not issue alert through SMBA pin
+ \param[out] none
+ \retval none
+*/
+void i2c_smbus_issue_alert(uint32_t i2c_periph, uint32_t smbuspara)
+{
+ /* issue alert through SMBA pin configure*/
+ uint32_t ctl = 0U;
+
+ ctl = I2C_CTL0(i2c_periph);
+ ctl &= ~(I2C_CTL0_SALT);
+ ctl |= smbuspara;
+ I2C_CTL0(i2c_periph) = ctl;
+}
+
+/*!
+ \brief whether ARP is enabled under SMBus
+ \param[in] i2c_periph: I2Cx(x=0,1)
+ \param[in] arpstate:
+ only one parameter can be selected which is shown as below:
+ \arg I2C_ARP_ENABLE: enable ARP
+ \arg I2C_ARP_DISABLE: disable ARP
+ \param[out] none
+ \retval none
+*/
+void i2c_smbus_arp_enable(uint32_t i2c_periph, uint32_t arpstate)
+{
+ /* enable or disable I2C ARP protocol */
+ uint32_t ctl = 0U;
+
+ ctl = I2C_CTL0(i2c_periph);
+ ctl &= ~(I2C_CTL0_ARPEN);
+ ctl |= arpstate;
+ I2C_CTL0(i2c_periph) = ctl;
+}
+
+/*!
+ \brief check I2C flag is set or not
+ \param[in] i2c_periph: I2Cx(x=0,1)
+ \param[in] flag: I2C flags, refer to i2c_flag_enum
+ only one parameter can be selected which is shown as below:
+ \arg I2C_FLAG_SBSEND: start condition send out
+ \arg I2C_FLAG_ADDSEND: address is sent in master mode or received and matches in slave mode
+ \arg I2C_FLAG_BTC: byte transmission finishes
+ \arg I2C_FLAG_ADD10SEND: header of 10-bit address is sent in master mode
+ \arg I2C_FLAG_STPDET: stop condition detected in slave mode
+ \arg I2C_FLAG_RBNE: I2C_DATA is not empty during receiving
+ \arg I2C_FLAG_TBE: I2C_DATA is empty during transmitting
+ \arg I2C_FLAG_BERR: a bus error occurs indication a unexpected start or stop condition on I2C bus
+ \arg I2C_FLAG_LOSTARB: arbitration lost in master mode
+ \arg I2C_FLAG_AERR: acknowledge error
+ \arg I2C_FLAG_OUERR: overrun or underrun situation occurs in slave mode
+ \arg I2C_FLAG_PECERR: PEC error when receiving data
+ \arg I2C_FLAG_SMBTO: timeout signal in SMBus mode
+ \arg I2C_FLAG_SMBALT: SMBus alert status
+ \arg I2C_FLAG_MASTER: a flag indicating whether I2C block is in master or slave mode
+ \arg I2C_FLAG_I2CBSY: busy flag
+ \arg I2C_FLAG_TR: whether the I2C is a transmitter or a receiver
+ \arg I2C_FLAG_RXGC: general call address (00h) received
+ \arg I2C_FLAG_DEFSMB: default address of SMBus device
+ \arg I2C_FLAG_HSTSMB: SMBus host header detected in slave mode
+ \arg I2C_FLAG_DUMOD: dual flag in slave mode indicating which address is matched in dual-address mode
+ \param[out] none
+ \retval FlagStatus: SET or RESET
+*/
+FlagStatus i2c_flag_get(uint32_t i2c_periph, i2c_flag_enum flag)
+{
+ if(RESET != (I2C_REG_VAL(i2c_periph, flag) & BIT(I2C_BIT_POS(flag)))) {
+ return SET;
+ } else {
+ return RESET;
+ }
+}
+
+/*!
+ \brief clear I2C flag
+ \param[in] i2c_periph: I2Cx(x=0,1)
+ \param[in] flag: I2C flags, refer to i2c_flag_enum
+ only one parameter can be selected which is shown as below:
+ \arg I2C_FLAG_SMBALT: SMBus Alert status
+ \arg I2C_FLAG_SMBTO: timeout signal in SMBus mode
+ \arg I2C_FLAG_PECERR: PEC error when receiving data
+ \arg I2C_FLAG_OUERR: over-run or under-run situation occurs in slave mode
+ \arg I2C_FLAG_AERR: acknowledge error
+ \arg I2C_FLAG_LOSTARB: arbitration lost in master mode
+ \arg I2C_FLAG_BERR: a bus error
+ \arg I2C_FLAG_ADDSEND: cleared by reading I2C_STAT0 and reading I2C_STAT1
+ \param[out] none
+ \retval none
+*/
+void i2c_flag_clear(uint32_t i2c_periph, i2c_flag_enum flag)
+{
+ if(I2C_FLAG_ADDSEND == flag) {
+ /* read I2C_STAT0 and then read I2C_STAT1 to clear ADDSEND */
+ I2C_STAT0(i2c_periph);
+ I2C_STAT1(i2c_periph);
+ } else {
+ I2C_REG_VAL(i2c_periph, flag) &= ~BIT(I2C_BIT_POS(flag));
+ }
+}
+
+/*!
+ \brief enable I2C interrupt
+ \param[in] i2c_periph: I2Cx(x=0,1)
+ \param[in] interrupt: I2C interrupts, refer to i2c_interrupt_enum
+ only one parameter can be selected which is shown as below:
+ \arg I2C_INT_ERR: error interrupt enable
+ \arg I2C_INT_EV: event interrupt enable
+ \arg I2C_INT_BUF: buffer interrupt enable
+ \param[out] none
+ \retval none
+*/
+void i2c_interrupt_enable(uint32_t i2c_periph, i2c_interrupt_enum interrupt)
+{
+ I2C_REG_VAL(i2c_periph, interrupt) |= BIT(I2C_BIT_POS(interrupt));
+}
+
+/*!
+ \brief disable I2C interrupt
+ \param[in] i2c_periph: I2Cx(x=0,1)
+ \param[in] interrupt: interrupt type
+ only one parameter can be selected which is shown as below:
+ \arg I2C_INT_ERR: error interrupt enable
+ \arg I2C_INT_EV: event interrupt enable
+ \arg I2C_INT_BUF: buffer interrupt enable
+ \param[out] none
+ \retval none
+*/
+void i2c_interrupt_disable(uint32_t i2c_periph, i2c_interrupt_enum interrupt)
+{
+ I2C_REG_VAL(i2c_periph, interrupt) &= ~BIT(I2C_BIT_POS(interrupt));
+}
+
+/*!
+ \brief check I2C interrupt flag
+ \param[in] i2c_periph: I2Cx(x=0,1)
+ \param[in] int_flag: I2C interrupt flags, refer to i2c_interrupt_flag_enum
+ only one parameter can be selected which is shown as below:
+ \arg I2C_INT_FLAG_SBSEND: start condition sent out in master mode interrupt flag
+ \arg I2C_INT_FLAG_ADDSEND: address is sent in master mode or received and matches in slave mode interrupt flag
+ \arg I2C_INT_FLAG_BTC: byte transmission finishes
+ \arg I2C_INT_FLAG_ADD10SEND: header of 10-bit address is sent in master mode interrupt flag
+ \arg I2C_INT_FLAG_STPDET: etop condition detected in slave mode interrupt flag
+ \arg I2C_INT_FLAG_RBNE: I2C_DATA is not Empty during receiving interrupt flag
+ \arg I2C_INT_FLAG_TBE: I2C_DATA is empty during transmitting interrupt flag
+ \arg I2C_INT_FLAG_BERR: a bus error occurs indication a unexpected start or stop condition on I2C bus interrupt flag
+ \arg I2C_INT_FLAG_LOSTARB: arbitration lost in master mode interrupt flag
+ \arg I2C_INT_FLAG_AERR: acknowledge error interrupt flag
+ \arg I2C_INT_FLAG_OUERR: over-run or under-run situation occurs in slave mode interrupt flag
+ \arg I2C_INT_FLAG_PECERR: PEC error when receiving data interrupt flag
+ \arg I2C_INT_FLAG_SMBTO: timeout signal in SMBus mode interrupt flag
+ \arg I2C_INT_FLAG_SMBALT: SMBus Alert status interrupt flag
+ \param[out] none
+ \retval FlagStatus: SET or RESET
+*/
+FlagStatus i2c_interrupt_flag_get(uint32_t i2c_periph, i2c_interrupt_flag_enum int_flag)
+{
+ uint32_t intenable = 0U, flagstatus = 0U, bufie;
+
+ /* check BUFIE */
+ bufie = I2C_CTL1(i2c_periph)&I2C_CTL1_BUFIE;
+
+ /* get the interrupt enable bit status */
+ intenable = (I2C_REG_VAL(i2c_periph, int_flag) & BIT(I2C_BIT_POS(int_flag)));
+ /* get the corresponding flag bit status */
+ flagstatus = (I2C_REG_VAL2(i2c_periph, int_flag) & BIT(I2C_BIT_POS2(int_flag)));
+
+ if((I2C_INT_FLAG_RBNE == int_flag) || (I2C_INT_FLAG_TBE == int_flag)) {
+ if(intenable && bufie) {
+ intenable = 1U;
+ } else {
+ intenable = 0U;
+ }
+ }
+ if((0U != flagstatus) && (0U != intenable)) {
+ return SET;
+ } else {
+ return RESET;
+ }
+}
+
+/*!
+ \brief clear I2C interrupt flag
+ \param[in] i2c_periph: I2Cx(x=0,1)
+ \param[in] intflag: I2C interrupt flags, refer to i2c_interrupt_flag_enum
+ only one parameter can be selected which is shown as below:
+ \arg I2C_INT_FLAG_ADDSEND: address is sent in master mode or received and matches in slave mode interrupt flag
+ \arg I2C_INT_FLAG_BERR: a bus error occurs indication a unexpected start or stop condition on I2C bus interrupt flag
+ \arg I2C_INT_FLAG_LOSTARB: arbitration lost in master mode interrupt flag
+ \arg I2C_INT_FLAG_AERR: acknowledge error interrupt flag
+ \arg I2C_INT_FLAG_OUERR: over-run or under-run situation occurs in slave mode interrupt flag
+ \arg I2C_INT_FLAG_PECERR: PEC error when receiving data interrupt flag
+ \arg I2C_INT_FLAG_SMBTO: timeout signal in SMBus mode interrupt flag
+ \arg I2C_INT_FLAG_SMBALT: SMBus Alert status interrupt flag
+ \param[out] none
+ \retval none
+*/
+void i2c_interrupt_flag_clear(uint32_t i2c_periph, i2c_interrupt_flag_enum int_flag)
+{
+ if(I2C_INT_FLAG_ADDSEND == int_flag) {
+ /* read I2C_STAT0 and then read I2C_STAT1 to clear ADDSEND */
+ I2C_STAT0(i2c_periph);
+ I2C_STAT1(i2c_periph);
+ } else {
+ I2C_REG_VAL2(i2c_periph, int_flag) &= ~BIT(I2C_BIT_POS2(int_flag));
+ }
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_misc.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_misc.c
new file mode 100644
index 00000000..307ade50
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_misc.c
@@ -0,0 +1,192 @@
+/*!
+ \file gd32f3x0_misc.c
+ \brief MISC driver
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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.
+*/
+
+#include "gd32f3x0_misc.h"
+
+/*!
+ \brief set the priority group
+ \param[in] nvic_prigroup: the NVIC priority group
+ only one parameter can be selected which is shown as below:
+ \arg NVIC_PRIGROUP_PRE0_SUB4:0 bits for pre-emption priority 4 bits for subpriority
+ \arg NVIC_PRIGROUP_PRE1_SUB3:1 bits for pre-emption priority 3 bits for subpriority
+ \arg NVIC_PRIGROUP_PRE2_SUB2:2 bits for pre-emption priority 2 bits for subpriority
+ \arg NVIC_PRIGROUP_PRE3_SUB1:3 bits for pre-emption priority 1 bits for subpriority
+ \arg NVIC_PRIGROUP_PRE4_SUB0:4 bits for pre-emption priority 0 bits for subpriority
+ \param[out] none
+ \retval none
+*/
+void nvic_priority_group_set(uint32_t nvic_prigroup)
+{
+ /* set the priority group value */
+ SCB->AIRCR = NVIC_AIRCR_VECTKEY_MASK | nvic_prigroup;
+}
+
+/*!
+ \brief enable NVIC request
+ \param[in] nvic_irq: the NVIC interrupt request, detailed in IRQn_Type
+ \param[in] nvic_irq_pre_priority: the pre-emption priority needed to set
+ \param[in] nvic_irq_sub_priority: the subpriority needed to set
+ \param[out] none
+ \retval none
+*/
+void nvic_irq_enable(uint8_t nvic_irq,
+ uint8_t nvic_irq_pre_priority,
+ uint8_t nvic_irq_sub_priority)
+{
+ uint32_t temp_priority = 0x00U, temp_pre = 0x00U, temp_sub = 0x00U;
+
+ /* use the priority group value to get the temp_pre and the temp_sub */
+ switch((SCB->AIRCR) & (uint32_t)0x700U) {
+ case NVIC_PRIGROUP_PRE0_SUB4:
+ temp_pre = 0U;
+ temp_sub = 0x4U;
+ break;
+ case NVIC_PRIGROUP_PRE1_SUB3:
+ temp_pre = 1U;
+ temp_sub = 0x3U;
+ break;
+ case NVIC_PRIGROUP_PRE2_SUB2:
+ temp_pre = 2U;
+ temp_sub = 0x2U;
+ break;
+ case NVIC_PRIGROUP_PRE3_SUB1:
+ temp_pre = 3U;
+ temp_sub = 0x1U;
+ break;
+ case NVIC_PRIGROUP_PRE4_SUB0:
+ temp_pre = 4U;
+ temp_sub = 0x0U;
+ break;
+ default:
+ nvic_priority_group_set(NVIC_PRIGROUP_PRE2_SUB2);
+ temp_pre = 2U;
+ temp_sub = 0x2U;
+ break;
+ }
+
+ /* get the temp_priority to fill the NVIC->IP register */
+ temp_priority = (uint32_t)nvic_irq_pre_priority << (0x4U - temp_pre);
+ temp_priority |= nvic_irq_sub_priority & (0x0FU >> (0x4U - temp_sub));
+ temp_priority = temp_priority << 0x04U;
+ NVIC->IP[nvic_irq] = (uint8_t)temp_priority;
+
+ /* enable the selected IRQ */
+ NVIC->ISER[nvic_irq >> 0x05U] = (uint32_t)0x01U << (nvic_irq & (uint8_t)0x1FU);
+}
+
+/*!
+ \brief disable NVIC request
+ \param[in] nvic_irq: the NVIC interrupt request, detailed in IRQn_Type
+ \param[out] none
+ \retval none
+*/
+void nvic_irq_disable(uint8_t nvic_irq)
+{
+ /* disable the selected IRQ.*/
+ NVIC->ICER[nvic_irq >> 0x05U] = (uint32_t)0x01U << (nvic_irq & (uint8_t)0x1FU);
+}
+
+/*!
+ \brief set the NVIC vector table base address
+ \param[in] nvic_vict_tab: the RAM or FLASH base address
+ only one parameter can be selected which is shown as below:
+ \arg NVIC_VECTTAB_RAM: RAM base address
+ \are NVIC_VECTTAB_FLASH: Flash base address
+ \param[in] offset: Vector Table offset
+ \param[out] none
+ \retval none
+*/
+void nvic_vector_table_set(uint32_t nvic_vict_tab, uint32_t offset)
+{
+ SCB->VTOR = nvic_vict_tab | (offset & NVIC_VECTTAB_OFFSET_MASK);
+ __DSB();
+}
+
+/*!
+ \brief set the state of the low power mode
+ \param[in] lowpower_mode: the low power mode state
+ only one parameter can be selected which is shown as below:
+ \arg SCB_LPM_SLEEP_EXIT_ISR: if chose this para, the system always enter low power
+ mode by exiting from ISR
+ \arg SCB_LPM_DEEPSLEEP: if chose this para, the system will enter the DEEPSLEEP mode
+ \arg SCB_LPM_WAKE_BY_ALL_INT: if chose this para, the lowpower mode can be woke up
+ by all the enable and disable interrupts
+ \param[out] none
+ \retval none
+*/
+void system_lowpower_set(uint8_t lowpower_mode)
+{
+ SCB->SCR |= (uint32_t)lowpower_mode;
+}
+
+/*!
+ \brief reset the state of the low power mode
+ \param[in] lowpower_mode: the low power mode state
+ only one parameter can be selected which is shown as below:
+ \arg SCB_LPM_SLEEP_EXIT_ISR: if chose this para, the system will exit low power
+ mode by exiting from ISR
+ \arg SCB_LPM_DEEPSLEEP: if chose this para, the system will enter the SLEEP mode
+ \arg SCB_LPM_WAKE_BY_ALL_INT: if chose this para, the lowpower mode only can be
+ woke up by the enable interrupts
+ \param[out] none
+ \retval none
+*/
+void system_lowpower_reset(uint8_t lowpower_mode)
+{
+ SCB->SCR &= (~(uint32_t)lowpower_mode);
+}
+
+/*!
+ \brief set the systick clock source
+ \param[in] systick_clksource: the systick clock source needed to choose
+ only one parameter can be selected which is shown as below:
+ \arg SYSTICK_CLKSOURCE_HCLK: systick clock source is from HCLK
+ \arg SYSTICK_CLKSOURCE_HCLK_DIV8: systick clock source is from HCLK/8
+ \param[out] none
+ \retval none
+*/
+
+void systick_clksource_set(uint32_t systick_clksource)
+{
+ if(SYSTICK_CLKSOURCE_HCLK == systick_clksource) {
+ /* set the systick clock source from HCLK */
+ SysTick->CTRL |= SYSTICK_CLKSOURCE_HCLK;
+ } else {
+ /* set the systick clock source from HCLK/8 */
+ SysTick->CTRL &= SYSTICK_CLKSOURCE_HCLK_DIV8;
+ }
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_pmu.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_pmu.c
new file mode 100644
index 00000000..df255135
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_pmu.c
@@ -0,0 +1,423 @@
+/*!
+ \file gd32f3x0_pmu.c
+ \brief PMU driver
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2021, 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.
+*/
+
+#include "gd32f3x0_pmu.h"
+
+
+/*!
+ \brief reset PMU register
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void pmu_deinit(void)
+{
+ /* reset PMU */
+ rcu_periph_reset_enable(RCU_PMURST);
+ rcu_periph_reset_disable(RCU_PMURST);
+}
+
+/*!
+ \brief select low voltage detector threshold
+ \param[in] lvdt_n:
+ only one parameter can be selected which is shown as below:
+ \arg PMU_LVDT_0: voltage threshold is 2.1V
+ \arg PMU_LVDT_1: voltage threshold is 2.3V
+ \arg PMU_LVDT_2: voltage threshold is 2.4V
+ \arg PMU_LVDT_3: voltage threshold is 2.6V
+ \arg PMU_LVDT_4: voltage threshold is 2.7V
+ \arg PMU_LVDT_5: voltage threshold is 2.9V
+ \arg PMU_LVDT_6: voltage threshold is 3.0V
+ \arg PMU_LVDT_7: voltage threshold is 3.1V
+ \param[out] none
+ \retval none
+*/
+void pmu_lvd_select(uint32_t lvdt_n)
+{
+ /* disable LVD */
+ PMU_CTL &= ~PMU_CTL_LVDEN;
+ /* clear LVDT bits */
+ PMU_CTL &= ~PMU_CTL_LVDT;
+ /* set LVDT bits according to lvdt_n */
+ PMU_CTL |= lvdt_n;
+ /* enable LVD */
+ PMU_CTL |= PMU_CTL_LVDEN;
+}
+
+/*!
+ \brief select LDO output voltage
+ these bits set by software when the main PLL closed
+ \param[in] ldo_output:
+ only one parameter can be selected which is shown as below:
+ \arg PMU_LDOVS_LOW: LDO output voltage low mode
+ \arg PMU_LDOVS_MID: LDO output voltage mid mode
+ \arg PMU_LDOVS_HIGH: LDO output voltage high mode
+ \param[out] none
+ \retval none
+*/
+void pmu_ldo_output_select(uint32_t ldo_output)
+{
+ PMU_CTL &= ~PMU_CTL_LDOVS;
+ PMU_CTL |= ldo_output;
+}
+
+/*!
+ \brief disable PMU lvd
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void pmu_lvd_disable(void)
+{
+ /* disable LVD */
+ PMU_CTL &= ~PMU_CTL_LVDEN;
+}
+
+/*!
+ \brief enable low-driver mode in deep-sleep mode
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void pmu_lowdriver_mode_enable(void)
+{
+ PMU_CTL &= ~PMU_CTL_LDEN;
+ PMU_CTL |= PMU_LOWDRIVER_ENABLE;
+}
+
+/*!
+ \brief disable low-driver mode in deep-sleep mode
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void pmu_lowdriver_mode_disable(void)
+{
+ PMU_CTL &= ~PMU_CTL_LDEN;
+ PMU_CTL |= PMU_LOWDRIVER_DISABLE;
+}
+
+/*!
+ \brief enable high-driver mode
+ this bit set by software only when IRC8M or HXTAL used as system clock
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void pmu_highdriver_mode_enable(void)
+{
+ PMU_CTL |= PMU_CTL_HDEN;
+}
+
+/*!
+ \brief disable high-driver mode
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void pmu_highdriver_mode_disable(void)
+{
+ PMU_CTL &= ~PMU_CTL_HDEN;
+}
+
+/*!
+ \brief switch high-driver mode
+ this bit set by software only when IRC8M or HXTAL used as system clock
+ \param[in] highdr_switch:
+ only one parameter can be selected which is shown as below:
+ \arg PMU_HIGHDR_SWITCH_NONE: disable high-driver mode switch
+ \arg PMU_HIGHDR_SWITCH_EN: enable high-driver mode switch
+ \param[out] none
+ \retval none
+*/
+void pmu_highdriver_switch_select(uint32_t highdr_switch)
+{
+ /* wait for HDRF flag to be set */
+ while(SET != pmu_flag_get(PMU_FLAG_HDR)) {
+ }
+ PMU_CTL &= ~PMU_CTL_HDS;
+ PMU_CTL |= highdr_switch;
+}
+
+/*!
+ \brief low-driver mode when use low power LDO
+ \param[in] mode:
+ only one parameter can be selected which is shown as below:
+ \arg PMU_NORMALDR_LOWPWR: normal-driver when use low power LDO
+ \arg PMU_LOWDR_LOWPWR: low-driver mode enabled when LDEN is 11 and use low power LDO
+ \param[out] none
+ \retval none
+*/
+void pmu_lowpower_driver_config(uint32_t mode)
+{
+ PMU_CTL &= ~PMU_CTL_LDLP;
+ PMU_CTL |= mode;
+}
+
+/*!
+ \brief low-driver mode when use normal power LDO
+ \param[in] mode:
+ only one parameter can be selected which is shown as below:
+ \arg PMU_NORMALDR_NORMALPWR: normal-driver when use low power LDO
+ \arg PMU_LOWDR_NORMALPWR: low-driver mode enabled when LDEN is 11 and use low power LDO
+ \param[out] none
+ \retval none
+*/
+void pmu_normalpower_driver_config(uint32_t mode)
+{
+ PMU_CTL &= ~PMU_CTL_LDNP;
+ PMU_CTL |= mode;
+}
+
+/*!
+ \brief PMU work at sleep mode
+ \param[in] sleepmodecmd:
+ only one parameter can be selected which is shown as below:
+ \arg WFI_CMD: use WFI command
+ \arg WFE_CMD: use WFE command
+ \param[out] none
+ \retval none
+*/
+void pmu_to_sleepmode(uint8_t sleepmodecmd)
+{
+ /* clear sleepdeep bit of Cortex-M4 system control register */
+ SCB->SCR &= ~((uint32_t)SCB_SCR_SLEEPDEEP_Msk);
+
+ /* select WFI or WFE command to enter sleep mode */
+ if(WFI_CMD == sleepmodecmd) {
+ __WFI();
+ } else {
+ __WFE();
+ }
+}
+
+/*!
+ \brief PMU work at deepsleep mode
+ \param[in] ldo:
+ only one parameter can be selected which is shown as below:
+ \arg PMU_LDO_NORMAL: LDO operates normally when pmu enter deepsleep mode
+ \arg PMU_LDO_LOWPOWER: LDO work at low power mode when pmu enter deepsleep mode
+ \param[in] lowdrive:
+ only one parameter can be selected which is shown as below:
+ \arg PMU_LOWDRIVER_ENABLE: low-driver mode enable in deep-sleep mode
+ \arg PMU_LOWDRIVER_DISABLE: low-driver mode disable in deep-sleep mode
+ \param[in] deepsleepmodecmd:
+ only one parameter can be selected which is shown as below:
+ \arg WFI_CMD: use WFI command
+ \arg WFE_CMD: use WFE command
+ \param[out] none
+ \retval none
+*/
+void pmu_to_deepsleepmode(uint32_t ldo, uint32_t lowdrive, uint8_t deepsleepmodecmd)
+{
+ static uint32_t reg_snap[ 4 ];
+ /* clear stbmod and ldolp bits */
+ PMU_CTL &= ~((uint32_t)(PMU_CTL_STBMOD | PMU_CTL_LDOLP | PMU_CTL_LDEN | PMU_CTL_LDNP | PMU_CTL_LDLP));
+
+ /* set ldolp bit according to pmu_ldo */
+ PMU_CTL |= ldo;
+
+ /* low drive mode config in deep-sleep mode */
+ if(PMU_LOWDRIVER_ENABLE == lowdrive) {
+ if(PMU_LDO_NORMAL == ldo) {
+ PMU_CTL |= (uint32_t)(PMU_CTL_LDEN | PMU_CTL_LDNP);
+ } else {
+ PMU_CTL |= (uint32_t)(PMU_CTL_LDEN | PMU_CTL_LDLP);
+ }
+ }
+
+ /* set sleepdeep bit of Cortex-M4 system control register */
+ SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk;
+
+ reg_snap[0] = REG32(0xE000E010U);
+ reg_snap[1] = REG32(0xE000E100U);
+ reg_snap[2] = REG32(0xE000E104U);
+ reg_snap[3] = REG32(0xE000E108U);
+
+ REG32(0xE000E010U) &= 0x00010004U;
+ REG32(0xE000E180U) = 0XB7FFEF19U;
+ REG32(0xE000E184U) = 0XFFFFFBFFU;
+ REG32(0xE000E188U) = 0xFFFFFFFFU;
+
+ /* select WFI or WFE command to enter deepsleep mode */
+ if(WFI_CMD == deepsleepmodecmd) {
+ __WFI();
+ } else {
+ __SEV();
+ __WFE();
+ __WFE();
+ }
+
+ REG32(0xE000E010U) = reg_snap[0];
+ REG32(0xE000E100U) = reg_snap[1];
+ REG32(0xE000E104U) = reg_snap[2];
+ REG32(0xE000E108U) = reg_snap[3];
+
+ /* reset sleepdeep bit of Cortex-M4 system control register */
+ SCB->SCR &= ~((uint32_t)SCB_SCR_SLEEPDEEP_Msk);
+}
+
+/*!
+ \brief pmu work at standby mode
+ \param[in] standbymodecmd:
+ only one parameter can be selected which is shown as below:
+ \arg WFI_CMD: use WFI command
+ \arg WFE_CMD: use WFE command
+ \param[out] none
+ \retval none
+*/
+void pmu_to_standbymode(uint8_t standbymodecmd)
+{
+ /* set sleepdeep bit of Cortex-M4 system control register */
+ SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk;
+
+ /* set stbmod bit */
+ PMU_CTL |= PMU_CTL_STBMOD;
+
+ /* reset wakeup flag */
+ PMU_CTL |= PMU_CTL_WURST;
+
+ /* select WFI or WFE command to enter standby mode */
+ if(WFI_CMD == standbymodecmd) {
+ __WFI();
+ } else {
+ __WFE();
+ __WFE();
+ }
+}
+
+/*!
+ \brief enable wakeup pin
+ \param[in] wakeup_pin:
+ one or more parameters can be selected which are shown as below:
+ \arg PMU_WAKEUP_PIN0: WKUP Pin 0 (PA0)
+ \arg PMU_WAKEUP_PIN1: WKUP Pin 1 (PC13)
+ \arg PMU_WAKEUP_PIN4: WKUP Pin 4 (PC5)
+ \arg PMU_WAKEUP_PIN5: WKUP Pin 5 (PB5)
+ \arg PMU_WAKEUP_PIN6: WKUP Pin 6 (PB15)
+ \param[out] none
+ \retval none
+*/
+void pmu_wakeup_pin_enable(uint32_t wakeup_pin)
+{
+ PMU_CS |= wakeup_pin;
+}
+
+/*!
+ \brief disable wakeup pin
+ \param[in] wakeup_pin:
+ one or more parameters can be selected which are shown as below:
+ \arg PMU_WAKEUP_PIN0: WKUP Pin 0 (PA0)
+ \arg PMU_WAKEUP_PIN1: WKUP Pin 1 (PC13)
+ \arg PMU_WAKEUP_PIN4: WKUP Pin 4 (PC5)
+ \arg PMU_WAKEUP_PIN5: WKUP Pin 5 (PB5)
+ \arg PMU_WAKEUP_PIN6: WKUP Pin 6 (PB15)
+ \param[out] none
+ \retval none
+*/
+void pmu_wakeup_pin_disable(uint32_t wakeup_pin)
+{
+ PMU_CS &= ~(wakeup_pin);
+}
+
+/*!
+ \brief enable backup domain write
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void pmu_backup_write_enable(void)
+{
+ PMU_CTL |= PMU_CTL_BKPWEN;
+}
+
+/*!
+ \brief disable backup domain write
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void pmu_backup_write_disable(void)
+{
+ PMU_CTL &= ~PMU_CTL_BKPWEN;
+}
+
+/*!
+ \brief get flag state
+ \param[in] flag:
+ only one parameter can be selected which is shown as below:
+ \arg PMU_FLAG_WAKEUP: wakeup flag
+ \arg PMU_FLAG_STANDBY: standby flag
+ \arg PMU_FLAG_LVD: lvd flag
+ \arg PMU_FLAG_LDOVSR: LDO voltage select ready flag
+ \arg PMU_FLAG_HDR: high-driver ready flag
+ \arg PMU_FLAG_HDSR: high-driver switch ready flag
+ \arg PMU_FLAG_LDR: low-driver mode ready flag
+ \param[out] none
+ \retval FlagStatus SET or RESET
+*/
+FlagStatus pmu_flag_get(uint32_t flag)
+{
+ FlagStatus ret_status = RESET;
+
+ if(PMU_CS & flag) {
+ ret_status = SET;
+ }
+
+ return ret_status;
+}
+
+/*!
+ \brief clear flag bit
+ \param[in] flag:
+ one or more parameters can be selected which are shown as below:
+ \arg PMU_FLAG_RESET_WAKEUP: reset wakeup flag
+ \arg PMU_FLAG_RESET_STANDBY: reset standby flag
+ \param[out] none
+ \retval none
+*/
+void pmu_flag_clear(uint32_t flag)
+{
+ if(RESET != (flag & PMU_FLAG_RESET_WAKEUP)) {
+ /* reset wakeup flag */
+ PMU_CTL |= PMU_CTL_WURST;
+ }
+ if(RESET != (flag & PMU_FLAG_RESET_STANDBY)) {
+ /* reset standby flag */
+ PMU_CTL |= PMU_CTL_STBRST;
+ }
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_rcu.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_rcu.c
new file mode 100644
index 00000000..e3bfd52e
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_rcu.c
@@ -0,0 +1,1213 @@
+/*!
+ \file gd32f3x0_rcu.c
+ \brief RCU driver
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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.
+*/
+
+#include "gd32f3x0_rcu.h"
+
+/* define clock source */
+#define SEL_IRC8M ((uint32_t)0x00000000U)
+#define SEL_HXTAL ((uint32_t)0x00000001U)
+#define SEL_PLL ((uint32_t)0x00000002U)
+
+/* define startup timeout count */
+#define OSC_STARTUP_TIMEOUT ((uint32_t)0x000FFFFFU)
+#define LXTAL_STARTUP_TIMEOUT ((uint32_t)0x03FFFFFFU)
+
+/*!
+ \brief deinitialize the RCU
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void rcu_deinit(void)
+{
+ /* enable IRC8M */
+ RCU_CTL0 |= RCU_CTL0_IRC8MEN;
+ while(0U == (RCU_CTL0 & RCU_CTL0_IRC8MSTB)) {
+ }
+
+ RCU_CFG0 &= ~RCU_CFG0_SCS;
+
+ /* reset CTL register */
+ RCU_CTL0 &= ~(RCU_CTL0_HXTALEN | RCU_CTL0_CKMEN | RCU_CTL0_PLLEN | RCU_CTL0_HXTALBPS);
+ RCU_CTL1 &= ~RCU_CTL1_IRC28MEN;
+
+ /* reset RCU */
+ RCU_CFG0 &= ~(RCU_CFG0_SCS | RCU_CFG0_AHBPSC | RCU_CFG0_APB1PSC | RCU_CFG0_APB2PSC | \
+ RCU_CFG0_ADCPSC | RCU_CFG0_CKOUTSEL | RCU_CFG0_CKOUTDIV | RCU_CFG0_PLLDV);
+ RCU_CFG0 &= ~(RCU_CFG0_PLLSEL | RCU_CFG0_PLLMF | RCU_CFG0_PLLMF4 | RCU_CFG0_PLLDV);
+#if (defined(GD32F350))
+ RCU_CFG0 &= ~(RCU_CFG0_USBFSPSC);
+ RCU_CFG2 &= ~(RCU_CFG2_CECSEL | RCU_CFG2_USBFSPSC2);
+#endif /* GD32F350 */
+
+ RCU_CFG1 &= ~(RCU_CFG1_PREDV | RCU_CFG1_PLLMF5 | RCU_CFG1_PLLPRESEL);
+ RCU_CFG2 &= ~(RCU_CFG2_USART0SEL | RCU_CFG2_ADCSEL);
+ RCU_CFG2 &= ~RCU_CFG2_IRC28MDIV;
+ RCU_CFG2 &= ~RCU_CFG2_ADCPSC2;
+ RCU_ADDCTL &= ~RCU_ADDCTL_IRC48MEN;
+ RCU_INT = 0x00000000U;
+ RCU_ADDINT = 0x00000000U;
+}
+
+/*!
+ \brief enable the peripherals clock
+ \param[in] periph: RCU peripherals, refer to rcu_periph_enum
+ only one parameter can be selected which is shown as below:
+ \arg RCU_GPIOx (x=A,B,C,D,F): GPIO ports clock
+ \arg RCU_DMA: DMA clock
+ \arg RCU_CRC: CRC clock
+ \arg RCU_TSI: TSI clock
+ \arg RCU_CFGCMP: CFGCMP clock
+ \arg RCU_ADC: ADC clock
+ \arg RCU_TIMERx (x=0,1,2,5,13,14,15,16): TIMER clock (RCU_TIMER5 only for GD32F350)
+ \arg RCU_SPIx (x=0,1): SPI clock
+ \arg RCU_USARTx (x=0,1): USART clock
+ \arg RCU_WWDGT: WWDGT clock
+ \arg RCU_I2Cx (x=0,1): I2C clock
+ \arg RCU_USBFS: USBFS clock (only for GD32F350)
+ \arg RCU_PMU: PMU clock
+ \arg RCU_DAC: DAC clock (only for GD32F350)
+ \arg RCU_CEC: CEC clock (only for GD32F350)
+ \arg RCU_CTC: CTC clock
+ \arg RCU_RTC: RTC clock
+ \param[out] none
+ \retval none
+*/
+void rcu_periph_clock_enable(rcu_periph_enum periph)
+{
+ RCU_REG_VAL(periph) |= BIT(RCU_BIT_POS(periph));
+}
+
+/*!
+ \brief disable the peripherals clock
+ \param[in] periph: RCU peripherals, refer to rcu_periph_enum
+ only one parameter can be selected which is shown as below:
+ \arg RCU_GPIOx (x=A,B,C,D,F): GPIO ports clock
+ \arg RCU_DMA: DMA clock
+ \arg RCU_CRC: CRC clock
+ \arg RCU_TSI: TSI clock
+ \arg RCU_CFGCMP: CFGCMP clock
+ \arg RCU_ADC: ADC clock
+ \arg RCU_TIMERx (x=0,1,2,5,13,14,15,16): TIMER clock (RCU_TIMER5 only for GD32F350)
+ \arg RCU_SPIx (x=0,1): SPI clock
+ \arg RCU_USARTx (x=0,1): USART clock
+ \arg RCU_WWDGT: WWDGT clock
+ \arg RCU_I2Cx (x=0,1): I2C clock
+ \arg RCU_USBFS: USBFS clock (only for GD32F350)
+ \arg RCU_PMU: PMU clock
+ \arg RCU_DAC: DAC clock (only for GD32F350)
+ \arg RCU_CEC: CEC clock (only for GD32F350)
+ \arg RCU_CTC: CTC clock
+ \arg RCU_RTC: RTC clock
+ \param[out] none
+ \retval none
+*/
+void rcu_periph_clock_disable(rcu_periph_enum periph)
+{
+ RCU_REG_VAL(periph) &= ~BIT(RCU_BIT_POS(periph));
+}
+
+/*!
+ \brief enable the peripherals clock when sleep mode
+ \param[in] periph: RCU peripherals, refer to rcu_periph_sleep_enum
+ only one parameter can be selected which is shown as below:
+ \arg RCU_FMC_SLP: FMC clock
+ \arg RCU_SRAM_SLP: SRAM clock
+ \param[out] none
+ \retval none
+*/
+void rcu_periph_clock_sleep_enable(rcu_periph_sleep_enum periph)
+{
+ RCU_REG_VAL(periph) |= BIT(RCU_BIT_POS(periph));
+}
+
+/*!
+ \brief disable the peripherals clock when sleep mode
+ \param[in] periph: RCU peripherals, refer to rcu_periph_sleep_enum
+ only one parameter can be selected which is shown as below:
+ \arg RCU_FMC_SLP: FMC clock
+ \arg RCU_SRAM_SLP: SRAM clock
+ \param[out] none
+ \retval none
+*/
+void rcu_periph_clock_sleep_disable(rcu_periph_sleep_enum periph)
+{
+ RCU_REG_VAL(periph) &= ~BIT(RCU_BIT_POS(periph));
+}
+/*!
+ \brief reset the peripherals
+ \param[in] periph_reset: RCU peripherals reset, refer to rcu_periph_reset_enum
+ only one parameter can be selected which is shown as below:
+ \arg RCU_GPIOxRST (x=A,B,C,D,F): reset GPIO ports
+ \arg RCU_TSIRST: reset TSI
+ \arg RCU_CFGCMPRST: reset CFGCMP
+ \arg RCU_ADCRST: reset ADC
+ \arg RCU_TIMERxRST (x=0,1,2,5,13,14,15,16): reset TIMER (RCU_TIMER5 only for GD32F350)
+ \arg RCU_SPIxRST (x=0,1): reset SPI
+ \arg RCU_USARTxRST (x=0,1): reset USART
+ \arg RCU_WWDGTRST: reset WWDGT
+ \arg RCU_I2CxRST (x=0,1): reset I2C
+ \arg RCU_USBFSRST: reset USBFS (only for GD32F350)
+ \arg RCU_PMURST: reset PMU
+ \arg RCU_DACRST: reset DAC (only for GD32F350)
+ \arg RCU_CECRST: reset CEC (only for GD32F350)
+ \arg RCU_CTCRST: reset CTC
+ \param[out] none
+ \retval none
+*/
+void rcu_periph_reset_enable(rcu_periph_reset_enum periph_reset)
+{
+ RCU_REG_VAL(periph_reset) |= BIT(RCU_BIT_POS(periph_reset));
+}
+
+/*!
+ \brief disable reset the peripheral
+ \param[in] periph_reset: RCU peripherals reset, refer to rcu_periph_reset_enum
+ only one parameter can be selected which is shown as below:
+ \arg RCU_GPIOxRST (x=A,B,C,D,F): reset GPIO ports
+ \arg RCU_TSIRST: reset TSI
+ \arg RCU_CFGCMPRST: reset CFGCMP
+ \arg RCU_ADCRST: reset ADC
+ \arg RCU_TIMERxRST (x=0,1,2,5,13,14,15,16): reset TIMER (RCU_TIMER5 only for GD32F350)
+ \arg RCU_SPIxRST (x=0,1,2): reset SPI
+ \arg RCU_USARTxRST (x=0,1): reset USART
+ \arg RCU_WWDGTRST: reset WWDGT
+ \arg RCU_I2CxRST (x=0,1,2): reset I2C
+ \arg RCU_USBFSRST: reset USBFS (only for GD32F350)
+ \arg RCU_PMURST: reset PMU
+ \arg RCU_DACRST: reset DAC (only for GD32F350)
+ \arg RCU_CECRST: reset CEC (only for GD32F350)
+ \arg RCU_CTCRST: reset CTC
+ \param[out] none
+ \retval none
+*/
+void rcu_periph_reset_disable(rcu_periph_reset_enum periph_reset)
+{
+ RCU_REG_VAL(periph_reset) &= ~BIT(RCU_BIT_POS(periph_reset));
+}
+
+/*!
+ \brief reset the BKP
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void rcu_bkp_reset_enable(void)
+{
+ RCU_BDCTL |= RCU_BDCTL_BKPRST;
+}
+
+/*!
+ \brief disable the BKP reset
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void rcu_bkp_reset_disable(void)
+{
+ RCU_BDCTL &= ~RCU_BDCTL_BKPRST;
+}
+
+/*!
+ \brief configure the system clock source
+ \param[in] ck_sys: system clock source select
+ only one parameter can be selected which is shown as below:
+ \arg RCU_CKSYSSRC_IRC8M: select CK_IRC8M as the CK_SYS source
+ \arg RCU_CKSYSSRC_HXTAL: select CK_HXTAL as the CK_SYS source
+ \arg RCU_CKSYSSRC_PLL: select CK_PLL as the CK_SYS source
+ \param[out] none
+ \retval none
+*/
+void rcu_system_clock_source_config(uint32_t ck_sys)
+{
+ uint32_t cksys_source = 0U;
+ cksys_source = RCU_CFG0;
+ /* reset the SCS bits and set according to ck_sys */
+ cksys_source &= ~RCU_CFG0_SCS;
+ RCU_CFG0 = (ck_sys | cksys_source);
+}
+
+/*!
+ \brief get the system clock source
+ \param[in] none
+ \param[out] none
+ \retval which clock is selected as CK_SYS source
+ only one parameter can be selected which is shown as below:
+ \arg RCU_SCSS_IRC8M: select CK_IRC8M as the CK_SYS source
+ \arg RCU_SCSS_HXTAL: select CK_HXTAL as the CK_SYS source
+ \arg RCU_SCSS_PLL: select CK_PLL as the CK_SYS source
+*/
+uint32_t rcu_system_clock_source_get(void)
+{
+ return (RCU_CFG0 & RCU_CFG0_SCSS);
+}
+
+/*!
+ \brief configure the AHB clock prescaler selection
+ \param[in] ck_ahb: AHB clock prescaler selection
+ only one parameter can be selected which is shown as below:
+ \arg RCU_AHB_CKSYS_DIVx, x=1, 2, 4, 8, 16, 64, 128, 256, 512
+ \param[out] none
+ \retval none
+*/
+void rcu_ahb_clock_config(uint32_t ck_ahb)
+{
+ uint32_t ahbpsc = 0U;
+ ahbpsc = RCU_CFG0;
+ /* reset the AHBPSC bits and set according to ck_ahb */
+ ahbpsc &= ~RCU_CFG0_AHBPSC;
+ RCU_CFG0 = (ck_ahb | ahbpsc);
+}
+
+/*!
+ \brief configure the APB1 clock prescaler selection
+ \param[in] ck_apb1: APB1 clock prescaler selection
+ only one parameter can be selected which is shown as below:
+ \arg RCU_APB1_CKAHB_DIV1: select CK_AHB as CK_APB1
+ \arg RCU_APB1_CKAHB_DIV2: select CK_AHB/2 as CK_APB1
+ \arg RCU_APB1_CKAHB_DIV4: select CK_AHB/4 as CK_APB1
+ \arg RCU_APB1_CKAHB_DIV8: select CK_AHB/8 as CK_APB1
+ \arg RCU_APB1_CKAHB_DIV16: select CK_AHB/16 as CK_APB1
+ \param[out] none
+ \retval none
+*/
+void rcu_apb1_clock_config(uint32_t ck_apb1)
+{
+ uint32_t apb1psc = 0U;
+ apb1psc = RCU_CFG0;
+ /* reset the APB1PSC and set according to ck_apb1 */
+ apb1psc &= ~RCU_CFG0_APB1PSC;
+ RCU_CFG0 = (ck_apb1 | apb1psc);
+}
+
+/*!
+ \brief configure the APB2 clock prescaler selection
+ \param[in] ck_apb2: APB2 clock prescaler selection
+ only one parameter can be selected which is shown as below:
+ \arg RCU_APB2_CKAHB_DIV1: select CK_AHB as CK_APB2
+ \arg RCU_APB2_CKAHB_DIV2: select CK_AHB/2 as CK_APB2
+ \arg RCU_APB2_CKAHB_DIV4: select CK_AHB/4 as CK_APB2
+ \arg RCU_APB2_CKAHB_DIV8: select CK_AHB/8 as CK_APB2
+ \arg RCU_APB2_CKAHB_DIV16: select CK_AHB/16 as CK_APB2
+ \param[out] none
+ \retval none
+*/
+void rcu_apb2_clock_config(uint32_t ck_apb2)
+{
+ uint32_t apb2psc = 0U;
+ apb2psc = RCU_CFG0;
+ /* reset the APB2PSC and set according to ck_apb2 */
+ apb2psc &= ~RCU_CFG0_APB2PSC;
+ RCU_CFG0 = (ck_apb2 | apb2psc);
+}
+
+/*!
+ \brief configure the ADC clock prescaler selection
+ \param[in] ck_adc: ADC clock prescaler selection, refer to rcu_adc_clock_enum
+ only one parameter can be selected which is shown as below:
+ \arg RCU_ADCCK_IRC28M_DIV2: select CK_IRC28M/2 as CK_ADC
+ \arg RCU_ADCCK_IRC28M: select CK_IRC28M as CK_ADC
+ \arg RCU_ADCCK_APB2_DIV2: select CK_APB2/2 as CK_ADC
+ \arg RCU_ADCCK_AHB_DIV3: select CK_AHB/3 as CK_ADC
+ \arg RCU_ADCCK_APB2_DIV4: select CK_APB2/4 as CK_ADC
+ \arg RCU_ADCCK_AHB_DIV5: select CK_AHB/5 as CK_ADC
+ \arg RCU_ADCCK_APB2_DIV6: select CK_APB2/6 as CK_ADC
+ \arg RCU_ADCCK_AHB_DIV7: select CK_AHB/7 as CK_ADC
+ \arg RCU_ADCCK_APB2_DIV8: select CK_APB2/8 as CK_ADC
+ \arg RCU_ADCCK_AHB_DIV9: select CK_AHB/9 as CK_ADC
+ \param[out] none
+ \retval none
+*/
+void rcu_adc_clock_config(rcu_adc_clock_enum ck_adc)
+{
+ /* reset the ADCPSC, ADCSEL, IRC28MDIV bits */
+ RCU_CFG0 &= ~RCU_CFG0_ADCPSC;
+ RCU_CFG2 &= ~(RCU_CFG2_ADCSEL | RCU_CFG2_IRC28MDIV | RCU_CFG2_ADCPSC2);
+
+ /* set the ADC clock according to ck_adc */
+ switch(ck_adc) {
+ case RCU_ADCCK_IRC28M_DIV2:
+ RCU_CFG2 &= ~RCU_CFG2_IRC28MDIV;
+ RCU_CFG2 &= ~RCU_CFG2_ADCSEL;
+ break;
+ case RCU_ADCCK_IRC28M:
+ RCU_CFG2 |= RCU_CFG2_IRC28MDIV;
+ RCU_CFG2 &= ~RCU_CFG2_ADCSEL;
+ break;
+ case RCU_ADCCK_APB2_DIV2:
+ RCU_CFG0 |= RCU_ADC_CKAPB2_DIV2;
+ RCU_CFG2 |= RCU_CFG2_ADCSEL;
+ break;
+ case RCU_ADCCK_AHB_DIV3:
+ RCU_CFG0 |= RCU_ADC_CKAPB2_DIV2;
+ RCU_CFG2 |= RCU_CFG2_ADCPSC2;
+ RCU_CFG2 |= RCU_CFG2_ADCSEL;
+ break;
+ case RCU_ADCCK_APB2_DIV4:
+ RCU_CFG0 |= RCU_ADC_CKAPB2_DIV4;
+ RCU_CFG2 |= RCU_CFG2_ADCSEL;
+ break;
+ case RCU_ADCCK_AHB_DIV5:
+ RCU_CFG0 |= RCU_ADC_CKAPB2_DIV4;
+ RCU_CFG2 |= RCU_CFG2_ADCPSC2;
+ RCU_CFG2 |= RCU_CFG2_ADCSEL;
+ break;
+ case RCU_ADCCK_APB2_DIV6:
+ RCU_CFG0 |= RCU_ADC_CKAPB2_DIV6;
+ RCU_CFG2 |= RCU_CFG2_ADCSEL;
+ break;
+ case RCU_ADCCK_AHB_DIV7:
+ RCU_CFG0 |= RCU_ADC_CKAPB2_DIV6;
+ RCU_CFG2 |= RCU_CFG2_ADCPSC2;
+ RCU_CFG2 |= RCU_CFG2_ADCSEL;
+ break;
+ case RCU_ADCCK_APB2_DIV8:
+ RCU_CFG0 |= RCU_ADC_CKAPB2_DIV8;
+ RCU_CFG2 |= RCU_CFG2_ADCSEL;
+ break;
+ case RCU_ADCCK_AHB_DIV9:
+ RCU_CFG0 |= RCU_ADC_CKAPB2_DIV8;
+ RCU_CFG2 |= RCU_CFG2_ADCPSC2;
+ RCU_CFG2 |= RCU_CFG2_ADCSEL;
+ break;
+ default:
+ break;
+ }
+}
+
+/*!
+ \brief configure the USBFS clock prescaler selection
+ \param[in] ck_usbfs: USBFS clock prescaler selection
+ only one parameter can be selected which is shown as below:
+ \arg RCU_USBFS_CKPLL_DIV1_5: select CK_PLL/1.5 as CK_USBFS
+ \arg RCU_USBFS_CKPLL_DIV1: select CK_PLL as CK_USBFS
+ \arg RCU_USBFS_CKPLL_DIV2_5: select CK_PLL/2.5 as CK_USBFS
+ \arg RCU_USBFS_CKPLL_DIV2: select CK_PLL/2 as CK_USBFS
+ \arg RCU_USBFS_CKPLL_DIV3: select CK_PLL/3 as CK_USBFS
+ \arg RCU_USBFS_CKPLL_DIV3_5: select CK_PLL/3.5 as CK_USBFS
+ \param[out] none
+ \retval none
+*/
+void rcu_usbfs_clock_config(uint32_t ck_usbfs)
+{
+ /* reset the USBFSPSC bits and set according to ck_usbfs */
+ RCU_CFG0 &= ~RCU_CFG0_USBFSPSC;
+ RCU_CFG2 &= ~RCU_CFG2_USBFSPSC2;
+
+ RCU_CFG0 |= (ck_usbfs & (~RCU_CFG2_USBFSPSC2));
+ RCU_CFG2 |= (ck_usbfs & RCU_CFG2_USBFSPSC2);
+}
+
+/*!
+ \brief configure the CK_OUT clock source and divider
+ \param[in] ckout_src: CK_OUT clock source selection
+ only one parameter can be selected which is shown as below:
+ \arg RCU_CKOUTSRC_NONE: no clock selected
+ \arg RCU_CKOUTSRC_IRC28M: IRC28M selected
+ \arg RCU_CKOUTSRC_IRC40K: IRC40K selected
+ \arg RCU_CKOUTSRC_LXTAL: LXTAL selected
+ \arg RCU_CKOUTSRC_CKSYS: CKSYS selected
+ \arg RCU_CKOUTSRC_IRC8M: IRC8M selected
+ \arg RCU_CKOUTSRC_HXTAL: HXTAL selected
+ \arg RCU_CKOUTSRC_CKPLL_DIV1: CK_PLL selected
+ \arg RCU_CKOUTSRC_CKPLL_DIV2: CK_PLL/2 selected
+ \param[in] ckout_div: CK_OUT divider
+ \arg RCU_CKOUT_DIVx(x=1,2,4,8,16,32,64,128): CK_OUT is divided by x
+ \param[out] none
+ \retval none
+*/
+void rcu_ckout_config(uint32_t ckout_src, uint32_t ckout_div)
+{
+ uint32_t ckout = 0U;
+ ckout = RCU_CFG0;
+ /* reset the CKOUTSEL, CKOUTDIV and PLLDV bits and set according to ckout_src and ckout_div */
+ ckout &= ~(RCU_CFG0_CKOUTSEL | RCU_CFG0_CKOUTDIV | RCU_CFG0_PLLDV);
+ RCU_CFG0 = (ckout | ckout_src | ckout_div);
+}
+
+/*!
+ \brief configure the PLL clock source preselection
+ \param[in] pll_presel: PLL clock source preselection
+ only one parameter can be selected which is shown as below:
+ \arg RCU_PLLPRESEL_IRC48M: select IRC48M as PLL preselection clock
+ \arg RCU_PLLPRESEL_HXTAL: select HXTAL as PLL preselection clock
+ \param[out] none
+ \retval none
+*/
+void rcu_pll_preselection_config(uint32_t pll_presel)
+{
+ RCU_CFG1 &= ~(RCU_CFG1_PLLPRESEL);
+ RCU_CFG1 |= pll_presel;
+}
+
+/*!
+ \brief configure the PLL clock source selection and PLL multiply factor
+ \param[in] pll_src: PLL clock source selection
+ only one parameter can be selected which is shown as below:
+ \arg RCU_PLLSRC_IRC8M_DIV2: select CK_IRC8M/2 as PLL source clock
+ \arg RCU_PLLSRC_HXTAL_IRC48M: select HXTAL or IRC48M as PLL source clock
+ \param[in] pll_mul: PLL multiply factor
+ only one parameter can be selected which is shown as below:
+ \arg RCU_PLL_MULx(x=2..64): PLL source clock * x
+ \param[out] none
+ \retval none
+*/
+void rcu_pll_config(uint32_t pll_src, uint32_t pll_mul)
+{
+ RCU_CFG0 &= ~(RCU_CFG0_PLLSEL | RCU_CFG0_PLLMF | RCU_CFG0_PLLMF4);
+ RCU_CFG1 &= ~(RCU_CFG1_PLLMF5);
+ RCU_CFG0 |= (pll_src | (pll_mul & (~RCU_CFG1_PLLMF5)));
+ RCU_CFG1 |= (pll_mul & RCU_CFG1_PLLMF5);
+}
+
+/*!
+ \brief configure the USART clock source selection
+ \param[in] ck_usart: USART clock source selection
+ only one parameter can be selected which is shown as below:
+ \arg RCU_USART0SRC_CKAPB2: CK_USART0 select CK_APB2
+ \arg RCU_USART0SRC_CKSYS: CK_USART0 select CK_SYS
+ \arg RCU_USART0SRC_LXTAL: CK_USART0 select CK_LXTAL
+ \arg RCU_USART0SRC_IRC8M: CK_USART0 select CK_IRC8M
+ \param[out] none
+ \retval none
+*/
+void rcu_usart_clock_config(uint32_t ck_usart)
+{
+ /* reset the USART0SEL bits and set according to ck_usart */
+ RCU_CFG2 &= ~RCU_CFG2_USART0SEL;
+ RCU_CFG2 |= ck_usart;
+}
+
+/*!
+ \brief configure the CEC clock source selection
+ \param[in] ck_cec: CEC clock source selection
+ only one parameter can be selected which is shown as below:
+ \arg RCU_CECSRC_IRC8M_DIV244: CK_CEC select CK_IRC8M/244
+ \arg RCU_CECSRC_LXTAL: CK_CEC select CK_LXTAL
+ \param[out] none
+ \retval none
+*/
+void rcu_cec_clock_config(uint32_t ck_cec)
+{
+ /* reset the CECSEL bit and set according to ck_cec */
+ RCU_CFG2 &= ~RCU_CFG2_CECSEL;
+ RCU_CFG2 |= ck_cec;
+}
+
+/*!
+ \brief configure the RTC clock source selection
+ \param[in] rtc_clock_source: RTC clock source selection
+ only one parameter can be selected which is shown as below:
+ \arg RCU_RTCSRC_NONE: no clock selected
+ \arg RCU_RTCSRC_LXTAL: CK_LXTAL selected as RTC source clock
+ \arg RCU_RTCSRC_IRC40K: CK_IRC40K selected as RTC source clock
+ \arg RCU_RTCSRC_HXTAL_DIV32: CK_HXTAL/32 selected as RTC source clock
+ \param[out] none
+ \retval none
+*/
+void rcu_rtc_clock_config(uint32_t rtc_clock_source)
+{
+ /* reset the RTCSRC bits and set according to rtc_clock_source */
+ RCU_BDCTL &= ~RCU_BDCTL_RTCSRC;
+ RCU_BDCTL |= rtc_clock_source;
+}
+
+/*!
+ \brief configure the CK48M clock source selection
+ \param[in] ck48m_clock_source: CK48M clock source selection
+ only one parameter can be selected which is shown as below:
+ \arg RCU_CK48MSRC_PLL48M: CK_PLL48M selected as CK48M source clock
+ \arg RCU_CK48MSRC_IRC48M: CK_IRC48M selected as CK48M source clock
+ \param[out] none
+ \retval none
+*/
+void rcu_ck48m_clock_config(uint32_t ck48m_clock_source)
+{
+ uint32_t reg;
+
+ reg = RCU_ADDCTL;
+ /* reset the CK48MSEL bit and set according to ck48m_clock_source */
+ reg &= ~RCU_ADDCTL_CK48MSEL;
+ RCU_ADDCTL = (reg | ck48m_clock_source);
+}
+
+/*!
+ \brief configure the HXTAL divider used as input of PLL
+ \param[in] hxtal_prediv: HXTAL divider used as input of PLL
+ only one parameter can be selected which is shown as below:
+ \arg RCU_PLL_PREDVx(x=1..16): HXTAL or IRC48M divided x used as input of PLL
+ \param[out] none
+ \retval none
+*/
+void rcu_hxtal_prediv_config(uint32_t hxtal_prediv)
+{
+ uint32_t prediv = 0U;
+ prediv = RCU_CFG1;
+ /* reset the HXTALPREDV bits and set according to hxtal_prediv */
+ prediv &= ~RCU_CFG1_PREDV;
+ RCU_CFG1 = (prediv | hxtal_prediv);
+}
+
+/*!
+ \brief configure the LXTAL drive capability
+ \param[in] lxtal_dricap: drive capability of LXTAL
+ only one parameter can be selected which is shown as below:
+ \arg RCU_LXTAL_LOWDRI: lower driving capability
+ \arg RCU_LXTAL_MED_LOWDRI: medium low driving capability
+ \arg RCU_LXTAL_MED_HIGHDRI: medium high driving capability
+ \arg RCU_LXTAL_HIGHDRI: higher driving capability
+ \param[out] none
+ \retval none
+*/
+void rcu_lxtal_drive_capability_config(uint32_t lxtal_dricap)
+{
+ /* reset the LXTALDRI bits and set according to lxtal_dricap */
+ RCU_BDCTL &= ~RCU_BDCTL_LXTALDRI;
+ RCU_BDCTL |= lxtal_dricap;
+}
+
+/*!
+ \brief get the clock stabilization and periphral reset flags
+ \param[in] flag: the clock stabilization and periphral reset flags, refer to rcu_flag_enum
+ only one parameter can be selected which is shown as below:
+ \arg RCU_FLAG_IRC40KSTB: IRC40K stabilization flag
+ \arg RCU_FLAG_LXTALSTB: LXTAL stabilization flag
+ \arg RCU_FLAG_IRC8MSTB: IRC8M stabilization flag
+ \arg RCU_FLAG_HXTALSTB: HXTAL stabilization flag
+ \arg RCU_FLAG_PLLSTB: PLL stabilization flag
+ \arg RCU_FLAG_IRC28MSTB: IRC28M stabilization flag
+ \arg RCU_FLAG_IRC48MSTB: IRC48M stabilization flag
+ \arg RCU_FLAG_V12RST: V12 domain power reset flag
+ \arg RCU_FLAG_OBLRST: option byte loader reset flag
+ \arg RCU_FLAG_EPRST: external pin reset flag
+ \arg RCU_FLAG_PORRST: power reset flag
+ \arg RCU_FLAG_SWRST: software reset flag
+ \arg RCU_FLAG_FWDGTRST: free watchdog timer reset flag
+ \arg RCU_FLAG_WWDGTRST: window watchdog timer reset flag
+ \arg RCU_FLAG_LPRST: low-power reset flag
+ \param[out] none
+ \retval FlagStatus: SET or RESET
+*/
+FlagStatus rcu_flag_get(rcu_flag_enum flag)
+{
+ if(RESET != (RCU_REG_VAL(flag) & BIT(RCU_BIT_POS(flag)))) {
+ return SET;
+ } else {
+ return RESET;
+ }
+}
+
+/*!
+ \brief clear the reset flag
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void rcu_all_reset_flag_clear(void)
+{
+ RCU_RSTSCK |= RCU_RSTSCK_RSTFC;
+}
+
+/*!
+ \brief get the clock stabilization interrupt and ckm flags
+ \param[in] int_flag: interrupt and ckm flags, refer to rcu_int_flag_enum
+ only one parameter can be selected which is shown as below:
+ \arg RCU_INT_FLAG_IRC40KSTB: IRC40K stabilization interrupt flag
+ \arg RCU_INT_FLAG_LXTALSTB: LXTAL stabilization interrupt flag
+ \arg RCU_INT_FLAG_IRC8MSTB: IRC8M stabilization interrupt flag
+ \arg RCU_INT_FLAG_HXTALSTB: HXTAL stabilization interrupt flag
+ \arg RCU_INT_FLAG_PLLSTB: PLL stabilization interrupt flag
+ \arg RCU_INT_FLAG_IRC28MSTB: IRC28M stabilization interrupt flag
+ \arg RCU_INT_FLAG_IRC48MSTB: IRC48M stabilization interrupt flag
+ \arg RCU_INT_FLAG_CKM: HXTAL clock stuck interrupt flag
+ \param[out] none
+ \retval FlagStatus: SET or RESET
+*/
+FlagStatus rcu_interrupt_flag_get(rcu_int_flag_enum int_flag)
+{
+ if(RESET != (RCU_REG_VAL(int_flag) & BIT(RCU_BIT_POS(int_flag)))) {
+ return SET;
+ } else {
+ return RESET;
+ }
+}
+
+/*!
+ \brief clear the interrupt flags
+ \param[in] int_flag_clear: clock stabilization and stuck interrupt flags clear, refer to rcu_int_flag_clear_enum
+ only one parameter can be selected which is shown as below:
+ \arg RCU_INT_FLAG_IRC40KSTB_CLR: IRC40K stabilization interrupt flag clear
+ \arg RCU_INT_FLAG_LXTALSTB_CLR: LXTAL stabilization interrupt flag clear
+ \arg RCU_INT_FLAG_IRC8MSTB_CLR: IRC8M stabilization interrupt flag clear
+ \arg RCU_INT_FLAG_HXTALSTB_CLR: HXTAL stabilization interrupt flag clear
+ \arg RCU_INT_FLAG_PLLSTB_CLR: PLL stabilization interrupt flag clear
+ \arg RCU_INT_FLAG_IRC28MSTB_CLR: IRC28M stabilization interrupt flag clear
+ \arg RCU_INT_FLAG_IRC48MSTB_CLR: IRC48M stabilization interrupt flag clear
+ \arg RCU_INT_FLAG_CKM_CLR: clock stuck interrupt flag clear
+ \param[out] none
+ \retval none
+*/
+void rcu_interrupt_flag_clear(rcu_int_flag_clear_enum int_flag_clear)
+{
+ RCU_REG_VAL(int_flag_clear) |= BIT(RCU_BIT_POS(int_flag_clear));
+}
+
+/*!
+ \brief enable the stabilization interrupt
+ \param[in] stab_int: clock stabilization interrupt, refer to rcu_int_enum
+ only one parameter can be selected which is shown as below:
+ \arg RCU_INT_IRC40KSTB: IRC40K stabilization interrupt enable
+ \arg RCU_INT_LXTALSTB: LXTAL stabilization interrupt enable
+ \arg RCU_INT_IRC8MSTB: IRC8M stabilization interrupt enable
+ \arg RCU_INT_HXTALSTB: HXTAL stabilization interrupt enable
+ \arg RCU_INT_PLLSTB: PLL stabilization interrupt enable
+ \arg RCU_INT_IRC28MSTB: IRC28M stabilization interrupt enable
+ \arg RCU_INT_IRC48MSTB: IRC48M stabilization interrupt enable
+ \param[out] none
+ \retval none
+*/
+void rcu_interrupt_enable(rcu_int_enum stab_int)
+{
+ RCU_REG_VAL(stab_int) |= BIT(RCU_BIT_POS(stab_int));
+}
+
+
+/*!
+ \brief disable the stabilization interrupt
+ \param[in] stab_int: clock stabilization interrupt, refer to rcu_int_enum
+ only one parameter can be selected which is shown as below:
+ \arg RCU_INT_IRC40KSTB: IRC40K stabilization interrupt disable
+ \arg RCU_INT_LXTALSTB: LXTAL stabilization interrupt disable
+ \arg RCU_INT_IRC8MSTB: IRC8M stabilization interrupt disable
+ \arg RCU_INT_HXTALSTB: HXTAL stabilization interrupt disable
+ \arg RCU_INT_PLLSTB: PLL stabilization interrupt disable
+ \arg RCU_INT_IRC28MSTB: IRC28M stabilization interrupt disable
+ \arg RCU_INT_IRC48MSTB: IRC48M stabilization interrupt disable
+ \param[out] none
+ \retval none
+*/
+void rcu_interrupt_disable(rcu_int_enum stab_int)
+{
+ RCU_REG_VAL(stab_int) &= ~BIT(RCU_BIT_POS(stab_int));
+}
+
+/*!
+ \brief wait until oscillator stabilization flags is SET
+ \param[in] osci: oscillator types, refer to rcu_osci_type_enum
+ only one parameter can be selected which is shown as below:
+ \arg RCU_HXTAL: HXTAL
+ \arg RCU_LXTAL: LXTAL
+ \arg RCU_IRC8M: IRC8M
+ \arg RCU_IRC28M: IRC28M
+ \arg RCU_IRC48M: IRC48M
+ \arg RCU_IRC40K: IRC40K
+ \arg RCU_PLL_CK: PLL
+ \param[out] none
+ \retval ErrStatus: SUCCESS or ERROR
+*/
+ErrStatus rcu_osci_stab_wait(rcu_osci_type_enum osci)
+{
+ uint32_t stb_cnt = 0U;
+ ErrStatus reval = ERROR;
+ FlagStatus osci_stat = RESET;
+ switch(osci) {
+ case RCU_HXTAL:
+ /* wait until HXTAL is stabilization and osci_stat is not more than timeout */
+ while((RESET == osci_stat) && (HXTAL_STARTUP_TIMEOUT != stb_cnt)) {
+ osci_stat = rcu_flag_get(RCU_FLAG_HXTALSTB);
+ stb_cnt++;
+ }
+ if(RESET != rcu_flag_get(RCU_FLAG_HXTALSTB)) {
+ reval = SUCCESS;
+ }
+ break;
+ /* wait LXTAL stable */
+ case RCU_LXTAL:
+ while((RESET == osci_stat) && (LXTAL_STARTUP_TIMEOUT != stb_cnt)) {
+ osci_stat = rcu_flag_get(RCU_FLAG_LXTALSTB);
+ stb_cnt++;
+ }
+
+ /* check whether flag is set or not */
+ if(RESET != rcu_flag_get(RCU_FLAG_LXTALSTB)) {
+ reval = SUCCESS;
+ }
+ break;
+
+ /* wait IRC8M stable */
+ case RCU_IRC8M:
+ while((RESET == osci_stat) && (IRC8M_STARTUP_TIMEOUT != stb_cnt)) {
+ osci_stat = rcu_flag_get(RCU_FLAG_IRC8MSTB);
+ stb_cnt++;
+ }
+
+ /* check whether flag is set or not */
+ if(RESET != rcu_flag_get(RCU_FLAG_IRC8MSTB)) {
+ reval = SUCCESS;
+ }
+ break;
+
+ /* wait IRC28M stable */
+ case RCU_IRC28M:
+ while((RESET == osci_stat) && (OSC_STARTUP_TIMEOUT != stb_cnt)) {
+ osci_stat = rcu_flag_get(RCU_FLAG_IRC28MSTB);
+ stb_cnt++;
+ }
+
+ /* check whether flag is set or not */
+ if(RESET != rcu_flag_get(RCU_FLAG_IRC28MSTB)) {
+ reval = SUCCESS;
+ }
+ break;
+ /* wait IRC48M stable */
+ case RCU_IRC48M:
+ while((RESET == osci_stat) && (OSC_STARTUP_TIMEOUT != stb_cnt)) {
+ osci_stat = rcu_flag_get(RCU_FLAG_IRC48MSTB);
+ stb_cnt++;
+ }
+
+ /* check whether flag is set or not */
+ if(RESET != rcu_flag_get(RCU_FLAG_IRC48MSTB)) {
+ reval = SUCCESS;
+ }
+ break;
+
+ /* wait IRC40K stable */
+ case RCU_IRC40K:
+ while((RESET == osci_stat) && (OSC_STARTUP_TIMEOUT != stb_cnt)) {
+ osci_stat = rcu_flag_get(RCU_FLAG_IRC40KSTB);
+ stb_cnt++;
+ }
+
+ /* check whether flag is set or not */
+ if(RESET != rcu_flag_get(RCU_FLAG_IRC40KSTB)) {
+ reval = SUCCESS;
+ }
+ break;
+
+ /* wait PLL stable */
+ case RCU_PLL_CK:
+ while((RESET == osci_stat) && (OSC_STARTUP_TIMEOUT != stb_cnt)) {
+ osci_stat = rcu_flag_get(RCU_FLAG_PLLSTB);
+ stb_cnt++;
+ }
+
+ /* check whether flag is set or not */
+ if(RESET != rcu_flag_get(RCU_FLAG_PLLSTB)) {
+ reval = SUCCESS;
+ }
+ break;
+
+ default:
+ break;
+ }
+ /* return value */
+ return reval;
+}
+
+/*!
+ \brief turn on the oscillator
+ \param[in] osci: oscillator types, refer to rcu_osci_type_enum
+ only one parameter can be selected which is shown as below:
+ \arg RCU_HXTAL: HXTAL
+ \arg RCU_LXTAL: LXTAL
+ \arg RCU_IRC8M: IRC8M
+ \arg RCU_IRC28M: IRC28M
+ \arg RCU_IRC48M: IRC48M
+ \arg RCU_IRC40K: IRC40K
+ \arg RCU_PLL_CK: PLL
+ \param[out] none
+ \retval none
+*/
+void rcu_osci_on(rcu_osci_type_enum osci)
+{
+ RCU_REG_VAL(osci) |= BIT(RCU_BIT_POS(osci));
+}
+
+/*!
+ \brief turn off the oscillator
+ \param[in] osci: oscillator types, refer to rcu_osci_type_enum
+ only one parameter can be selected which is shown as below:
+ \arg RCU_HXTAL: HXTAL
+ \arg RCU_LXTAL: LXTAL
+ \arg RCU_IRC8M: IRC8M
+ \arg RCU_IRC28M: IRC28M
+ \arg RCU_IRC48M: IRC48M
+ \arg RCU_IRC40K: IRC40K
+ \arg RCU_PLL_CK: PLL
+ \param[out] none
+ \retval none
+*/
+void rcu_osci_off(rcu_osci_type_enum osci)
+{
+ RCU_REG_VAL(osci) &= ~BIT(RCU_BIT_POS(osci));
+}
+
+/*!
+ \brief enable the oscillator bypass mode, HXTALEN or LXTALEN must be reset before it
+ \param[in] osci: oscillator types, refer to rcu_osci_type_enum
+ only one parameter can be selected which is shown as below:
+ \arg RCU_HXTAL: HXTAL
+ \arg RCU_LXTAL: LXTAL
+ \param[out] none
+ \retval none
+*/
+void rcu_osci_bypass_mode_enable(rcu_osci_type_enum osci)
+{
+ uint32_t reg;
+ switch(osci) {
+ case RCU_HXTAL:
+ /* HXTALEN must be reset before enable the oscillator bypass mode */
+ reg = RCU_CTL0;
+ RCU_CTL0 &= ~RCU_CTL0_HXTALEN;
+ RCU_CTL0 = (reg | RCU_CTL0_HXTALBPS);
+ break;
+ case RCU_LXTAL:
+ /* LXTALEN must be reset before enable the oscillator bypass mode */
+ reg = RCU_BDCTL;
+ RCU_BDCTL &= ~RCU_BDCTL_LXTALEN;
+ RCU_BDCTL = (reg | RCU_BDCTL_LXTALBPS);
+ break;
+ case RCU_IRC8M:
+ case RCU_IRC28M:
+ case RCU_IRC48M:
+ case RCU_IRC40K:
+ case RCU_PLL_CK:
+ break;
+ default:
+ break;
+ }
+}
+
+/*!
+ \brief disable the oscillator bypass mode, HXTALEN or LXTALEN must be reset before it
+ \param[in] osci: oscillator types, refer to rcu_osci_type_enum
+ only one parameter can be selected which is shown as below:
+ \arg RCU_HXTAL: HXTAL
+ \arg RCU_LXTAL: LXTAL
+ \param[out] none
+ \retval none
+*/
+void rcu_osci_bypass_mode_disable(rcu_osci_type_enum osci)
+{
+ uint32_t reg;
+ switch(osci) {
+ case RCU_HXTAL:
+ /* HXTALEN must be reset before disable the oscillator bypass mode */
+ reg = RCU_CTL0;
+ RCU_CTL0 &= ~RCU_CTL0_HXTALEN;
+ RCU_CTL0 = (reg & (~RCU_CTL0_HXTALBPS));
+ break;
+ case RCU_LXTAL:
+ /* LXTALEN must be reset before disable the oscillator bypass mode */
+ reg = RCU_BDCTL;
+ RCU_BDCTL &= ~RCU_BDCTL_LXTALEN;
+ RCU_BDCTL = (reg & (~RCU_BDCTL_LXTALBPS));
+ break;
+ case RCU_IRC8M:
+ case RCU_IRC28M:
+ case RCU_IRC48M:
+ case RCU_IRC40K:
+ case RCU_PLL_CK:
+ break;
+ default:
+ break;
+ }
+}
+
+/*!
+ \brief enable the HXTAL clock monitor
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void rcu_hxtal_clock_monitor_enable(void)
+{
+ RCU_CTL0 |= RCU_CTL0_CKMEN;
+}
+
+/*!
+ \brief disable the HXTAL clock monitor
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void rcu_hxtal_clock_monitor_disable(void)
+{
+ RCU_CTL0 &= ~RCU_CTL0_CKMEN;
+}
+
+/*!
+ \brief set the IRC8M adjust value
+ \param[in] irc8m_adjval: IRC8M adjust value, must be between 0 and 0x1F
+ \param[out] none
+ \retval none
+*/
+void rcu_irc8m_adjust_value_set(uint8_t irc8m_adjval)
+{
+ uint32_t adjust = 0U;
+ adjust = RCU_CTL0;
+ /* reset the IRC8MADJ bits and set according to irc8m_adjval */
+ adjust &= ~RCU_CTL0_IRC8MADJ;
+ RCU_CTL0 = (adjust | (((uint32_t)irc8m_adjval) << 3));
+}
+
+/*!
+ \brief set the IRC28M adjust value
+ \param[in] irc28m_adjval: IRC28M adjust value, must be between 0 and 0x1F
+ \param[out] none
+ \retval none
+*/
+void rcu_irc28m_adjust_value_set(uint8_t irc28m_adjval)
+{
+ uint32_t adjust = 0U;
+ adjust = RCU_CTL1;
+ /* reset the IRC28MADJ bits and set according to irc28m_adjval */
+ adjust &= ~RCU_CTL1_IRC28MADJ;
+ RCU_CTL1 = (adjust | (((uint32_t)irc28m_adjval) << 3));
+}
+
+/*!
+ \brief unlock the voltage key
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void rcu_voltage_key_unlock(void)
+{
+ /* reset the KEY bits and set 0x1A2B3C4D */
+ RCU_VKEY &= ~RCU_VKEY_KEY;
+ RCU_VKEY |= RCU_VKEY_UNLOCK;
+}
+
+/*!
+ \brief set voltage in deep sleep mode
+ \param[in] dsvol: deep sleep mode voltage
+ only one parameter can be selected which is shown as below:
+ \arg RCU_DEEPSLEEP_V_0: the core voltage is default value
+ \arg RCU_DEEPSLEEP_V_1: the core voltage is (default value-0.1)V (customers are not recommended to use it)
+ \arg RCU_DEEPSLEEP_V_2: the core voltage is (default value-0.2)V (customers are not recommended to use it)
+ \arg RCU_DEEPSLEEP_V_3: the core voltage is (default value-0.3)V (customers are not recommended to use it)
+ \param[out] none
+ \retval none
+*/
+void rcu_deepsleep_voltage_set(uint32_t dsvol)
+{
+ /* reset the DSLPVS bits and set according to dsvol */
+ RCU_DSV &= ~RCU_DSV_DSLPVS;
+ RCU_DSV |= dsvol;
+}
+
+/*!
+ \brief get the system clock, bus and peripheral clock frequency
+ \param[in] clock: the clock frequency which to get
+ only one parameter can be selected which is shown as below:
+ \arg CK_SYS: system clock frequency
+ \arg CK_AHB: AHB clock frequency
+ \arg CK_APB1: APB1 clock frequency
+ \arg CK_APB2: APB2 clock frequency
+ \arg CK_ADC: ADC clock frequency
+ \arg CK_CEC: CEC clock frequency
+ \arg CK_USART: USART clock frequency
+ \param[out] none
+ \retval clock frequency of system, AHB, APB1, APB2, ADC, CEC or USRAT
+*/
+uint32_t rcu_clock_freq_get(rcu_clock_freq_enum clock)
+{
+ uint32_t sws = 0U, adcps = 0U, adcps2 = 0U, ck_freq = 0U;
+ uint32_t cksys_freq = 0U, ahb_freq = 0U, apb1_freq = 0U, apb2_freq = 0U;
+ uint32_t adc_freq = 0U, cec_freq = 0U, usart_freq = 0U;
+ uint32_t pllmf = 0U, pllmf4 = 0U, pllmf5 = 0U, pllsel = 0U, pllpresel = 0U, prediv = 0U, idx = 0U, clk_exp = 0U;
+ /* exponent of AHB, APB1 and APB2 clock divider */
+ const uint8_t ahb_exp[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
+ const uint8_t apb1_exp[8] = {0, 0, 0, 0, 1, 2, 3, 4};
+ const uint8_t apb2_exp[8] = {0, 0, 0, 0, 1, 2, 3, 4};
+
+ sws = GET_BITS(RCU_CFG0, 2, 3);
+ switch(sws) {
+ /* IRC8M is selected as CK_SYS */
+ case SEL_IRC8M:
+ cksys_freq = IRC8M_VALUE;
+ break;
+ /* HXTAL is selected as CK_SYS */
+ case SEL_HXTAL:
+ cksys_freq = HXTAL_VALUE;
+ break;
+ /* PLL is selected as CK_SYS */
+ case SEL_PLL:
+ /* get the value of PLLMF[3:0] */
+ pllmf = GET_BITS(RCU_CFG0, 18, 21);
+ pllmf4 = GET_BITS(RCU_CFG0, 27, 27);
+ pllmf5 = GET_BITS(RCU_CFG1, 31, 31);
+ /* high 16 bits */
+ /* high 16 bits */
+ if((0U == pllmf4) && (0U == pllmf5)) {
+ pllmf += 2U;
+ }
+ if((1U == pllmf4) && (0U == pllmf5)) {
+ pllmf += 17U;
+ }
+ if((0U == pllmf4) && (1U == pllmf5)) {
+ pllmf += 33U;
+ }
+ if((1U == pllmf4) && (1U == pllmf5)) {
+ pllmf += 49U;
+ }
+
+ /* PLL clock source selection, HXTAL or IRC48M or IRC8M/2 */
+ pllsel = GET_BITS(RCU_CFG0, 16, 16);
+ pllpresel = GET_BITS(RCU_CFG1, 30, 30);
+ if(0U != pllsel) {
+ prediv = (GET_BITS(RCU_CFG1, 0, 3) + 1U);
+ if(0U == pllpresel) {
+ cksys_freq = (HXTAL_VALUE / prediv) * pllmf;
+ } else {
+ cksys_freq = (IRC48M_VALUE / prediv) * pllmf;
+ }
+ } else {
+ cksys_freq = (IRC8M_VALUE >> 1) * pllmf;
+ }
+ break;
+ /* IRC8M is selected as CK_SYS */
+ default:
+ cksys_freq = IRC8M_VALUE;
+ break;
+ }
+ /* calculate AHB clock frequency */
+ idx = GET_BITS(RCU_CFG0, 4, 7);
+ clk_exp = ahb_exp[idx];
+ ahb_freq = cksys_freq >> clk_exp;
+
+ /* calculate APB1 clock frequency */
+ idx = GET_BITS(RCU_CFG0, 8, 10);
+ clk_exp = apb1_exp[idx];
+ apb1_freq = ahb_freq >> clk_exp;
+
+ /* calculate APB2 clock frequency */
+ idx = GET_BITS(RCU_CFG0, 11, 13);
+ clk_exp = apb2_exp[idx];
+ apb2_freq = ahb_freq >> clk_exp;
+
+ /* return the clocks frequency */
+ switch(clock) {
+ case CK_SYS:
+ ck_freq = cksys_freq;
+ break;
+ case CK_AHB:
+ ck_freq = ahb_freq;
+ break;
+ case CK_APB1:
+ ck_freq = apb1_freq;
+ break;
+ case CK_APB2:
+ ck_freq = apb2_freq;
+ break;
+ case CK_ADC:
+ /* calculate ADC clock frequency */
+ if(RCU_ADCSRC_AHB_APB2DIV != (RCU_CFG2 & RCU_CFG2_ADCSEL)) {
+ if(RCU_ADC_IRC28M_DIV1 != (RCU_CFG2 & RCU_CFG2_IRC28MDIV)) {
+ adc_freq = IRC28M_VALUE >> 1;
+ } else {
+ adc_freq = IRC28M_VALUE;
+ }
+ } else {
+ /* ADC clock select CK_APB2 divided by 2/4/6/8 or CK_AHB divided by 3/5/7/9 */
+ adcps = GET_BITS(RCU_CFG0, 14, 15);
+ adcps2 = GET_BITS(RCU_CFG2, 31, 31);
+ switch(adcps) {
+ case 0:
+ if(0U == adcps2) {
+ adc_freq = apb2_freq / 2U;
+ } else {
+ adc_freq = ahb_freq / 3U;
+ }
+ break;
+ case 1:
+ if(0U == adcps2) {
+ adc_freq = apb2_freq / 4U;
+ } else {
+ adc_freq = ahb_freq / 5U;
+ }
+ break;
+ case 2:
+ if(0U == adcps2) {
+ adc_freq = apb2_freq / 6U;
+ } else {
+ adc_freq = ahb_freq / 7U;
+ }
+ break;
+ case 3:
+ if(0U == adcps2) {
+ adc_freq = apb2_freq / 8U;
+ } else {
+ adc_freq = ahb_freq / 9U;
+ }
+ break;
+ default:
+ break;
+ }
+ }
+ ck_freq = adc_freq;
+ break;
+ case CK_CEC:
+ /* calculate CEC clock frequency */
+ if(RCU_CECSRC_LXTAL != (RCU_CFG2 & RCU_CFG2_CECSEL)) {
+ cec_freq = IRC8M_VALUE / 244U;
+ } else {
+ cec_freq = LXTAL_VALUE;
+ }
+ ck_freq = cec_freq;
+ break;
+ case CK_USART:
+ /* calculate USART clock frequency */
+ if(RCU_USART0SRC_CKAPB2 == (RCU_CFG2 & RCU_CFG2_USART0SEL)) {
+ usart_freq = apb2_freq;
+ } else if(RCU_USART0SRC_CKSYS == (RCU_CFG2 & RCU_CFG2_USART0SEL)) {
+ usart_freq = cksys_freq;
+ } else if(RCU_USART0SRC_LXTAL == (RCU_CFG2 & RCU_CFG2_USART0SEL)) {
+ usart_freq = LXTAL_VALUE;
+ } else if(RCU_USART0SRC_IRC8M == (RCU_CFG2 & RCU_CFG2_USART0SEL)) {
+ usart_freq = IRC8M_VALUE;
+ } else {
+ }
+ ck_freq = usart_freq;
+ break;
+ default:
+ break;
+ }
+ return ck_freq;
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_rtc.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_rtc.c
new file mode 100644
index 00000000..58d6cc9a
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_rtc.c
@@ -0,0 +1,965 @@
+/*!
+ \file gd32f3x0_rtc.c
+ \brief RTC driver
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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.
+*/
+
+#include "gd32f3x0_rtc.h"
+
+/*!
+ \brief reset most of the RTC registers
+ \param[in] none
+ \param[out] none
+ \retval ErrStatus: ERROR or SUCCESS
+*/
+ErrStatus rtc_deinit(void)
+{
+ ErrStatus error_status = ERROR;
+
+ /* RTC_TAMP register is not under write protection */
+ RTC_TAMP = RTC_REGISTER_RESET;
+
+ /* disable the write protection */
+ RTC_WPK = RTC_UNLOCK_KEY1;
+ RTC_WPK = RTC_UNLOCK_KEY2;
+
+ /* reset RTC_CTL register, this can be done without the init mode */
+ RTC_CTL &= RTC_REGISTER_RESET;
+
+ /* enter init mode */
+ error_status = rtc_init_mode_enter();
+
+ if(ERROR != error_status) {
+ /* before reset RTC_TIME and RTC_DATE, BPSHAD bit in RTC_CTL should be reset as the condition.
+ in order to read calendar from shadow register, not the real registers being reset */
+ RTC_TIME = RTC_REGISTER_RESET;
+ RTC_DATE = RTC_DATE_RESET;
+
+ RTC_PSC = RTC_PSC_RESET;
+
+ /* reset RTC_STAT register, also exit init mode.
+ at the same time, RTC_STAT_SOPF bit is reset, as the condition to reset RTC_SHIFTCTL register later */
+ RTC_STAT = RTC_STAT_RESET;
+
+ /* to write RTC_ALRM0SS register, ALRM0EN bit in RTC_CTL register should be reset as the condition */
+ RTC_ALRM0TD = RTC_REGISTER_RESET;
+ RTC_ALRM0SS = RTC_REGISTER_RESET;
+
+ /* reset RTC_SHIFTCTL and RTC_HRFC register, this can be done without the init mode */
+ RTC_SHIFTCTL = RTC_REGISTER_RESET;
+ RTC_HRFC = RTC_REGISTER_RESET;
+
+ error_status = rtc_register_sync_wait();
+ }
+
+ /* enable the write protection */
+ RTC_WPK = RTC_LOCK_KEY;
+
+ return error_status;
+}
+
+/*!
+ \brief initialize RTC registers
+ \param[in] rtc_initpara_struct: pointer to a rtc_parameter_struct structure which contains
+ parameters for initialization of the rtc peripheral
+ members of the structure and the member values are shown as below:
+ rtc_year: 0x0 - 0x99(BCD format)
+ rtc_month: RTC_JAN, RTC_FEB, RTC_MAR, RTC_APR, RTC_MAY, RTC_JUN,
+ RTC_JUL, RTC_AUG, RTC_SEP, RTC_OCT, RTC_NOV, RTC_DEC
+ rtc_date: 0x1 - 0x31(BCD format)
+ rtc_day_of_week: RTC_MONDAY, RTC_TUESDAY, RTC_WEDSDAY, RTC_THURSDAY
+ RTC_FRIDAY, RTC_SATURDAY, RTC_SUNDAY
+ rtc_hour: 0x0 - 0x12(BCD format) or 0x0 - 0x23(BCD format) depending on the rtc_display_format chose
+ rtc_minute: 0x0 - 0x59(BCD format)
+ rtc_second: 0x0 - 0x59(BCD format)
+ rtc_factor_asyn: 0x0 - 0x7F
+ rtc_factor_syn: 0x0 - 0x7FFF
+ rtc_am_pm: RTC_AM, RTC_PM
+ rtc_display_format: RTC_24HOUR, RTC_12HOUR
+ \param[out] none
+ \retval ErrStatus: ERROR or SUCCESS
+*/
+ErrStatus rtc_init(rtc_parameter_struct *rtc_initpara_struct)
+{
+ ErrStatus error_status = ERROR;
+ uint32_t reg_time = 0x00U, reg_date = 0x00U;
+
+ reg_date = (DATE_YR(rtc_initpara_struct->rtc_year) | \
+ DATE_DOW(rtc_initpara_struct->rtc_day_of_week) | \
+ DATE_MON(rtc_initpara_struct->rtc_month) | \
+ DATE_DAY(rtc_initpara_struct->rtc_date));
+
+ reg_time = (rtc_initpara_struct->rtc_am_pm | \
+ TIME_HR(rtc_initpara_struct->rtc_hour) | \
+ TIME_MN(rtc_initpara_struct->rtc_minute) | \
+ TIME_SC(rtc_initpara_struct->rtc_second));
+
+ /* 1st: disable the write protection */
+ RTC_WPK = RTC_UNLOCK_KEY1;
+ RTC_WPK = RTC_UNLOCK_KEY2;
+
+ /* 2nd: enter init mode */
+ error_status = rtc_init_mode_enter();
+
+ if(ERROR != error_status) {
+ RTC_PSC = (uint32_t)(PSC_FACTOR_A(rtc_initpara_struct->rtc_factor_asyn) | \
+ PSC_FACTOR_S(rtc_initpara_struct->rtc_factor_syn));
+
+ RTC_TIME = (uint32_t)reg_time;
+ RTC_DATE = (uint32_t)reg_date;
+
+ RTC_CTL &= (uint32_t)(~RTC_CTL_CS);
+ RTC_CTL |= rtc_initpara_struct->rtc_display_format;
+
+ /* 3rd: exit init mode */
+ rtc_init_mode_exit();
+
+ /* 4th: wait the RSYNF flag to set */
+ error_status = rtc_register_sync_wait();
+ }
+
+ /* 5th: enable the write protection */
+ RTC_WPK = RTC_LOCK_KEY;
+
+ return error_status;
+}
+
+/*!
+ \brief enter RTC init mode
+ \param[in] none
+ \param[out] none
+ \retval ErrStatus: ERROR or SUCCESS
+*/
+ErrStatus rtc_init_mode_enter(void)
+{
+ uint32_t time_index = RTC_INITM_TIMEOUT;
+ uint32_t flag_status = RESET;
+ ErrStatus error_status = ERROR;
+
+ /* check whether it has been in init mode */
+ if(RESET == (RTC_STAT & RTC_STAT_INITF)) {
+ RTC_STAT |= RTC_STAT_INITM;
+
+ /* wait until the INITF flag to be set */
+ do {
+ flag_status = RTC_STAT & RTC_STAT_INITF;
+ } while((--time_index > 0x00U) && (RESET == flag_status));
+
+ if(RESET != flag_status) {
+ error_status = SUCCESS;
+ }
+ } else {
+ error_status = SUCCESS;
+ }
+ return error_status;
+}
+
+/*!
+ \brief exit RTC init mode
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void rtc_init_mode_exit(void)
+{
+ RTC_STAT &= (uint32_t)(~RTC_STAT_INITM);
+}
+
+/*!
+ \brief wait until RTC_TIME and RTC_DATE registers are synchronized with APB clock, and the shadow
+ registers are updated
+ \param[in] none
+ \param[out] none
+ \retval ErrStatus: ERROR or SUCCESS
+*/
+ErrStatus rtc_register_sync_wait(void)
+{
+ volatile uint32_t time_index = RTC_RSYNF_TIMEOUT;
+ uint32_t flag_status = RESET;
+ ErrStatus error_status = ERROR;
+
+ if(RESET == (RTC_CTL & RTC_CTL_BPSHAD)) {
+ /* disable the write protection */
+ RTC_WPK = RTC_UNLOCK_KEY1;
+ RTC_WPK = RTC_UNLOCK_KEY2;
+
+ /* firstly clear RSYNF flag */
+ RTC_STAT &= (uint32_t)(~RTC_STAT_RSYNF);
+
+ /* wait until RSYNF flag to be set */
+ do {
+ flag_status = RTC_STAT & RTC_STAT_RSYNF;
+ } while((--time_index > 0x00U) && (RESET == flag_status));
+
+ if(RESET != flag_status) {
+ error_status = SUCCESS;
+ }
+
+ /* enable the write protection */
+ RTC_WPK = RTC_LOCK_KEY;
+ } else {
+ error_status = SUCCESS;
+ }
+
+ return error_status;
+}
+
+/*!
+ \brief get current time and date
+ \param[in] none
+ \param[out] rtc_initpara_struct: pointer to a rtc_parameter_struct structure which contains
+ parameters for initialization of the rtc peripheral
+ members of the structure and the member values are shown as below:
+ rtc_year: 0x0 - 0x99(BCD format)
+ rtc_month: RTC_JAN, RTC_FEB, RTC_MAR, RTC_APR, RTC_MAY, RTC_JUN,
+ RTC_JUL, RTC_AUG, RTC_SEP, RTC_OCT, RTC_NOV, RTC_DEC
+ rtc_date: 0x1 - 0x31(BCD format)
+ rtc_day_of_week: RTC_MONDAY, RTC_TUESDAY, RTC_WEDSDAY, RTC_THURSDAY
+ RTC_FRIDAY, RTC_SATURDAY, RTC_SUNDAY
+ rtc_hour: 0x0 - 0x12(BCD format) or 0x0 - 0x23(BCD format) depending on the rtc_display_format chose
+ rtc_minute: 0x0 - 0x59(BCD format)
+ rtc_second: 0x0 - 0x59(BCD format)
+ rtc_factor_asyn: 0x0 - 0x7F
+ rtc_factor_syn: 0x0 - 0x7FFF
+ rtc_am_pm: RTC_AM, RTC_PM
+ rtc_display_format: RTC_24HOUR, RTC_12HOUR
+ \retval none
+*/
+void rtc_current_time_get(rtc_parameter_struct *rtc_initpara_struct)
+{
+ uint32_t temp_tr = 0x00U, temp_dr = 0x00U, temp_pscr = 0x00U, temp_ctlr = 0x00U;
+
+ temp_tr = (uint32_t)RTC_TIME;
+ temp_dr = (uint32_t)RTC_DATE;
+ temp_pscr = (uint32_t)RTC_PSC;
+ temp_ctlr = (uint32_t)RTC_CTL;
+
+ /* get current time and construct rtc_parameter_struct structure */
+ rtc_initpara_struct->rtc_year = (uint8_t)GET_DATE_YR(temp_dr);
+ rtc_initpara_struct->rtc_month = (uint8_t)GET_DATE_MON(temp_dr);
+ rtc_initpara_struct->rtc_date = (uint8_t)GET_DATE_DAY(temp_dr);
+ rtc_initpara_struct->rtc_day_of_week = (uint8_t)GET_DATE_DOW(temp_dr);
+ rtc_initpara_struct->rtc_hour = (uint8_t)GET_TIME_HR(temp_tr);
+ rtc_initpara_struct->rtc_minute = (uint8_t)GET_TIME_MN(temp_tr);
+ rtc_initpara_struct->rtc_second = (uint8_t)GET_TIME_SC(temp_tr);
+ rtc_initpara_struct->rtc_factor_asyn = (uint16_t)GET_PSC_FACTOR_A(temp_pscr);
+ rtc_initpara_struct->rtc_factor_syn = (uint16_t)GET_PSC_FACTOR_S(temp_pscr);
+ rtc_initpara_struct->rtc_am_pm = (uint32_t)(temp_pscr & RTC_TIME_PM);
+ rtc_initpara_struct->rtc_display_format = (uint32_t)(temp_ctlr & RTC_CTL_CS);
+}
+
+/*!
+ \brief get current subsecond value
+ \param[in] none
+ \param[out] none
+ \retval current subsecond value
+*/
+uint32_t rtc_subsecond_get(void)
+{
+ uint32_t reg = 0x00U;
+ /* if BPSHAD bit is reset, reading RTC_SS will lock RTC_TIME and RTC_DATE automatically */
+ reg = (uint32_t)RTC_SS;
+ /* read RTC_DATE to unlock the 3 shadow registers */
+ (void)(RTC_DATE);
+
+ return reg;
+}
+
+/*!
+ \brief configure RTC alarm
+ \param[in] rtc_alarm_time: pointer to a rtc_alarm_struct structure which contains
+ parameters for RTC alarm configuration
+ members of the structure and the member values are shown as below:
+ rtc_alarm_mask: RTC_ALARM_NONE_MASK, RTC_ALARM_DATE_MASK, RTC_ALARM_HOUR_MASK
+ RTC_ALARM_MINUTE_MASK, RTC_ALARM_SECOND_MASK, RTC_ALARM_ALL_MASK
+ rtc_weekday_or_date: RTC_ALARM_DATE_SELECTED, RTC_ALARM_WEEKDAY_SELECTED
+ rtc_alarm_day: 1) 0x1 - 0x31(BCD format) if RTC_ALARM_DATE_SELECTED is set
+ 2) RTC_MONDAY, RTC_TUESDAY, RTC_WEDSDAY, RTC_THURSDAY, RTC_FRIDAY,
+ RTC_SATURDAY, RTC_SUNDAY if RTC_ALARM_WEEKDAY_SELECTED is set
+ rtc_alarm_hour: 0x0 - 0x12(BCD format) or 0x0 - 0x23(BCD format) depending on the rtc_display_format
+ rtc_alarm_minute: 0x0 - 0x59(BCD format)
+ rtc_alarm_second: 0x0 - 0x59(BCD format)
+ rtc_am_pm: RTC_AM, RTC_PM
+ \param[out] none
+ \retval none
+*/
+void rtc_alarm_config(rtc_alarm_struct *rtc_alarm_time)
+{
+ uint32_t reg_alrm0td = 0x00U;
+
+ reg_alrm0td = (rtc_alarm_time->rtc_alarm_mask | \
+ rtc_alarm_time->rtc_weekday_or_date | \
+ rtc_alarm_time->rtc_am_pm | \
+ ALRM0TD_DAY(rtc_alarm_time->rtc_alarm_day) | \
+ ALRM0TD_HR(rtc_alarm_time->rtc_alarm_hour) | \
+ ALRM0TD_MN(rtc_alarm_time->rtc_alarm_minute) | \
+ ALRM0TD_SC(rtc_alarm_time->rtc_alarm_second));
+
+ /* disable the write protection */
+ RTC_WPK = RTC_UNLOCK_KEY1;
+ RTC_WPK = RTC_UNLOCK_KEY2;
+
+ RTC_ALRM0TD = (uint32_t)reg_alrm0td;
+
+ /* enable the write protection */
+ RTC_WPK = RTC_LOCK_KEY;
+}
+
+/*!
+ \brief configure subsecond of RTC alarm
+ \param[in] mask_subsecond: alarm subsecond mask
+ only one parameter can be selected which is shown as below:
+ \arg RTC_MASKSSC_0_14: mask alarm subsecond configuration
+ \arg RTC_MASKSSC_1_14: mask RTC_ALRM0SS_SSC[14:1], and RTC_ALRM0SS_SSC[0] is to be compared
+ \arg RTC_MASKSSC_2_14: mask RTC_ALRM0SS_SSC[14:2], and RTC_ALRM0SS_SSC[1:0] is to be compared
+ \arg RTC_MASKSSC_3_14: mask RTC_ALRM0SS_SSC[14:3], and RTC_ALRM0SS_SSC[2:0] is to be compared
+ \arg RTC_MASKSSC_4_14: mask RTC_ALRM0SS_SSC[14:4], and RTC_ALRM0SS_SSC[3:0] is to be compared
+ \arg RTC_MASKSSC_5_14: mask RTC_ALRM0SS_SSC[14:5], and RTC_ALRM0SS_SSC[4:0] is to be compared
+ \arg RTC_MASKSSC_6_14: mask RTC_ALRM0SS_SSC[14:6], and RTC_ALRM0SS_SSC[5:0] is to be compared
+ \arg RTC_MASKSSC_7_14: mask RTC_ALRM0SS_SSC[14:7], and RTC_ALRM0SS_SSC[6:0] is to be compared
+ \arg RTC_MASKSSC_8_14: mask RTC_ALRM0SS_SSC[14:8], and RTC_ALRM0SS_SSC[7:0] is to be compared
+ \arg RTC_MASKSSC_9_14: mask RTC_ALRM0SS_SSC[14:9], and RTC_ALRM0SS_SSC[8:0] is to be compared
+ \arg RTC_MASKSSC_10_14: mask RTC_ALRM0SS_SSC[14:10], and RTC_ALRM0SS_SSC[9:0] is to be compared
+ \arg RTC_MASKSSC_11_14: mask RTC_ALRM0SS_SSC[14:11], and RTC_ALRM0SS_SSC[10:0] is to be compared
+ \arg RTC_MASKSSC_12_14: mask RTC_ALRM0SS_SSC[14:12], and RTC_ALRM0SS_SSC[11:0] is to be compared
+ \arg RTC_MASKSSC_13_14: mask RTC_ALRM0SS_SSC[14:13], and RTC_ALRM0SS_SSC[12:0] is to be compared
+ \arg RTC_MASKSSC_14: mask RTC_ALRM0SS_SSC[14], and RTC_ALRM0SS_SSC[13:0] is to be compared
+ \arg RTC_MASKSSC_NONE: mask none, and RTC_ALRM0SS_SSC[14:0] is to be compared
+ \param[in] subsecond: alarm subsecond value(0x000 - 0x7FFF)
+ \param[out] none
+ \retval none
+*/
+void rtc_alarm_subsecond_config(uint32_t mask_subsecond, uint32_t subsecond)
+{
+ /* disable the write protection */
+ RTC_WPK = RTC_UNLOCK_KEY1;
+ RTC_WPK = RTC_UNLOCK_KEY2;
+
+ RTC_ALRM0SS = mask_subsecond | subsecond;
+
+ /* enable the write protection */
+ RTC_WPK = RTC_LOCK_KEY;
+}
+
+/*!
+ \brief get RTC alarm
+ \param[in] none
+ \param[out] rtc_alarm_time: pointer to a rtc_alarm_struct structure which contains
+ parameters for RTC alarm configuration
+ members of the structure and the member values are shown as below:
+ rtc_alarm_mask: RTC_ALARM_NONE_MASK, RTC_ALARM_DATE_MASK, RTC_ALARM_HOUR_MASK
+ RTC_ALARM_MINUTE_MASK, RTC_ALARM_SECOND_MASK, RTC_ALARM_ALL_MASK
+ rtc_weekday_or_date: RTC_ALARM_DATE_SELECTED, RTC_ALARM_WEEKDAY_SELECTED
+ rtc_alarm_day: 1) 0x1 - 0x31(BCD format) if RTC_ALARM_DATE_SELECTED is set
+ 2) RTC_MONDAY, RTC_TUESDAY, RTC_WEDSDAY, RTC_THURSDAY, RTC_FRIDAY,
+ RTC_SATURDAY, RTC_SUNDAY if RTC_ALARM_WEEKDAY_SELECTED is set
+ rtc_alarm_hour: 0x0 - 0x12(BCD format) or 0x0 - 0x23(BCD format) depending on the rtc_display_format
+ rtc_alarm_minute: 0x0 - 0x59(BCD format)
+ rtc_alarm_second: 0x0 - 0x59(BCD format)
+ rtc_am_pm: RTC_AM, RTC_PM
+ \retval none
+*/
+void rtc_alarm_get(rtc_alarm_struct *rtc_alarm_time)
+{
+ uint32_t reg_alrm0td = 0x00U;
+
+ /* get the value of RTC_ALRM0TD register */
+ reg_alrm0td = RTC_ALRM0TD;
+
+ /* get alarm parameters and construct the rtc_alarm_struct structure */
+ rtc_alarm_time->rtc_alarm_mask = reg_alrm0td & RTC_ALARM_ALL_MASK;
+ rtc_alarm_time->rtc_am_pm = (uint32_t)(reg_alrm0td & RTC_ALRM0TD_PM);
+ rtc_alarm_time->rtc_weekday_or_date = (uint32_t)(reg_alrm0td & RTC_ALRM0TD_DOWS);
+ rtc_alarm_time->rtc_alarm_day = (uint8_t)GET_ALRM0TD_DAY(reg_alrm0td);
+ rtc_alarm_time->rtc_alarm_hour = (uint8_t)GET_ALRM0TD_HR(reg_alrm0td);
+ rtc_alarm_time->rtc_alarm_minute = (uint8_t)GET_ALRM0TD_MN(reg_alrm0td);
+ rtc_alarm_time->rtc_alarm_second = (uint8_t)GET_ALRM0TD_SC(reg_alrm0td);
+}
+
+/*!
+ \brief get RTC alarm subsecond
+ \param[in] none
+ \param[out] none
+ \retval RTC alarm subsecond value
+*/
+uint32_t rtc_alarm_subsecond_get(void)
+{
+ return ((uint32_t)(RTC_ALRM0SS & RTC_ALRM0SS_SSC));
+}
+
+/*!
+ \brief enable RTC alarm
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void rtc_alarm_enable(void)
+{
+ /* disable the write protection */
+ RTC_WPK = RTC_UNLOCK_KEY1;
+ RTC_WPK = RTC_UNLOCK_KEY2;
+
+ RTC_CTL |= RTC_CTL_ALRM0EN;
+
+ /* enable the write protection */
+ RTC_WPK = RTC_LOCK_KEY;
+}
+
+/*!
+ \brief disable RTC alarm
+ \param[in] none
+ \param[out] none
+ \retval ErrStatus: ERROR or SUCCESS
+*/
+ErrStatus rtc_alarm_disable(void)
+{
+ volatile uint32_t time_index = RTC_ALRM0WF_TIMEOUT;
+ ErrStatus error_status = ERROR;
+ uint32_t flag_status = RESET;
+
+ /* disable the write protection */
+ RTC_WPK = RTC_UNLOCK_KEY1;
+ RTC_WPK = RTC_UNLOCK_KEY2;
+
+ /* clear the state of alarm */
+ RTC_CTL &= (uint32_t)(~RTC_CTL_ALRM0EN);
+
+ /* wait until ALRM0WF flag to be set after the alarm is disabled */
+ do {
+ flag_status = RTC_STAT & RTC_STAT_ALRM0WF;
+ } while((--time_index > 0x00U) && (RESET == flag_status));
+
+ if(RESET != flag_status) {
+ error_status = SUCCESS;
+ }
+
+ /* enable the write protection */
+ RTC_WPK = RTC_LOCK_KEY;
+
+ return error_status;
+}
+
+/*!
+ \brief enable RTC time-stamp
+ \param[in] edge: specify which edge to detect of time-stamp
+ only one parameter can be selected which is shown as below:
+ \arg RTC_TIMESTAMP_RISING_EDGE: rising edge is valid event edge for timestamp event
+ \arg RTC_TIMESTAMP_FALLING_EDGE: falling edge is valid event edge for timestamp event
+ \param[out] none
+ \retval none
+*/
+void rtc_timestamp_enable(uint32_t edge)
+{
+ uint32_t reg_ctl = 0x00U;
+
+ /* clear the bits to be configured in RTC_CTL */
+ reg_ctl = (uint32_t)(RTC_CTL & (uint32_t)(~(RTC_CTL_TSEG | RTC_CTL_TSEN)));
+
+ /* new configuration */
+ reg_ctl |= (uint32_t)(edge | RTC_CTL_TSEN);
+
+ /* disable the write protection */
+ RTC_WPK = RTC_UNLOCK_KEY1;
+ RTC_WPK = RTC_UNLOCK_KEY2;
+
+ RTC_CTL = (uint32_t)reg_ctl;
+
+ /* enable the write protection */
+ RTC_WPK = RTC_LOCK_KEY;
+}
+
+/*!
+ \brief disable RTC time-stamp
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void rtc_timestamp_disable(void)
+{
+ /* disable the write protection */
+ RTC_WPK = RTC_UNLOCK_KEY1;
+ RTC_WPK = RTC_UNLOCK_KEY2;
+
+ /* clear the TSEN bit */
+ RTC_CTL &= (uint32_t)(~ RTC_CTL_TSEN);
+
+ /* enable the write protection */
+ RTC_WPK = RTC_LOCK_KEY;
+}
+
+/*!
+ \brief get RTC timestamp time and date
+ \param[in] none
+ \param[out] rtc_timestamp: pointer to a rtc_timestamp_struct structure which contains
+ parameters for RTC time-stamp configuration
+ members of the structure and the member values are shown as below:
+ rtc_timestamp_month: RTC_JAN, RTC_FEB, RTC_MAR, RTC_APR, RTC_MAY, RTC_JUN,
+ RTC_JUL, RTC_AUG, RTC_SEP, RTC_OCT, RTC_NOV, RTC_DEC
+ rtc_timestamp_date: 0x1 - 0x31(BCD format)
+ rtc_timestamp_day: RTC_MONDAY, RTC_TUESDAY, RTC_WEDSDAY, RTC_THURSDAY, RTC_FRIDAY,
+ RTC_SATURDAY, RTC_SUNDAY if RTC_ALARM_WEEKDAY_SELECTED is set
+ rtc_timestamp_hour: 0x0 - 0x12(BCD format) or 0x0 - 0x23(BCD format) depending on the rtc_display_format
+ rtc_timestamp_minute: 0x0 - 0x59(BCD format)
+ rtc_timestamp_second: 0x0 - 0x59(BCD format)
+ rtc_am_pm: RTC_AM, RTC_PM
+ \retval none
+*/
+void rtc_timestamp_get(rtc_timestamp_struct *rtc_timestamp)
+{
+ uint32_t temp_tts = 0x00U, temp_dts = 0x00U;
+
+ /* get the value of time_stamp registers */
+ temp_tts = (uint32_t)RTC_TTS;
+ temp_dts = (uint32_t)RTC_DTS;
+
+ /* get timestamp time and construct the rtc_timestamp_struct structure */
+ rtc_timestamp->rtc_am_pm = (uint32_t)(temp_tts & RTC_TTS_PM);
+ rtc_timestamp->rtc_timestamp_month = (uint8_t)GET_DTS_MON(temp_dts);
+ rtc_timestamp->rtc_timestamp_date = (uint8_t)GET_DTS_DAY(temp_dts);
+ rtc_timestamp->rtc_timestamp_day = (uint8_t)GET_DTS_DOW(temp_dts);
+ rtc_timestamp->rtc_timestamp_hour = (uint8_t)GET_TTS_HR(temp_tts);
+ rtc_timestamp->rtc_timestamp_minute = (uint8_t)GET_TTS_MN(temp_tts);
+ rtc_timestamp->rtc_timestamp_second = (uint8_t)GET_TTS_SC(temp_tts);
+}
+
+/*!
+ \brief get RTC time-stamp subsecond
+ \param[in] none
+ \param[out] none
+ \retval RTC time-stamp subsecond value
+*/
+uint32_t rtc_timestamp_subsecond_get(void)
+{
+ return ((uint32_t)RTC_SSTS);
+}
+
+/*!
+ \brief enable RTC tamper
+ \param[in] rtc_tamper: pointer to a rtc_tamper_struct structure which contains
+ parameters for RTC tamper configuration
+ members of the structure and the member values are shown as below:
+ rtc_tamper_source: RTC_TAMPER0, RTC_TAMPER1
+ rtc_tamper_trigger: RTC_TAMPER_TRIGGER_EDGE_RISING, RTC_TAMPER_TRIGGER_EDGE_FALLING
+ RTC_TAMPER_TRIGGER_LEVEL_LOW, RTC_TAMPER_TRIGGER_LEVEL_HIGH
+ rtc_tamper_filter: RTC_FLT_EDGE, RTC_FLT_2S, RTC_FLT_4S, RTC_FLT_8S
+ rtc_tamper_sample_frequency: RTC_FREQ_DIV32768, RTC_FREQ_DIV16384, RTC_FREQ_DIV8192,
+ RTC_FREQ_DIV4096, RTC_FREQ_DIV2048, RTC_FREQ_DIV1024,
+ RTC_FREQ_DIV512, RTC_FREQ_DIV256
+ rtc_tamper_precharge_enable: DISABLE, ENABLE
+ rtc_tamper_precharge_time: RTC_PRCH_1C, RTC_PRCH_2C, RTC_PRCH_4C, RTC_PRCH_8C
+ rtc_tamper_with_timestamp: DISABLE, ENABLE
+ \param[out] none
+ \retval none
+*/
+void rtc_tamper_enable(rtc_tamper_struct *rtc_tamper)
+{
+ /* disable tamper */
+ RTC_TAMP &= (uint32_t)~(rtc_tamper->rtc_tamper_source);
+
+ /* tamper filter must be used when the tamper source is voltage level detection */
+ RTC_TAMP &= (uint32_t)~RTC_TAMP_FLT;
+
+ /* the tamper source is voltage level detection */
+ if(rtc_tamper->rtc_tamper_filter != RTC_FLT_EDGE) {
+ RTC_TAMP &= (uint32_t)~(RTC_TAMP_DISPU | RTC_TAMP_PRCH | RTC_TAMP_FREQ | RTC_TAMP_FLT);
+
+ /* check if the tamper pin need precharge, if need, then configure the precharge time */
+ if(DISABLE == rtc_tamper->rtc_tamper_precharge_enable) {
+ RTC_TAMP |= (uint32_t)RTC_TAMP_DISPU;
+ } else {
+ RTC_TAMP |= (uint32_t)(rtc_tamper->rtc_tamper_precharge_time);
+ }
+
+ RTC_TAMP |= (uint32_t)(rtc_tamper->rtc_tamper_sample_frequency);
+ RTC_TAMP |= (uint32_t)(rtc_tamper->rtc_tamper_filter);
+ }
+
+ RTC_TAMP &= (uint32_t)~RTC_TAMP_TPTS;
+
+ if(DISABLE != rtc_tamper->rtc_tamper_with_timestamp) {
+ /* the tamper event also cause a time-stamp event */
+ RTC_TAMP |= (uint32_t)RTC_TAMP_TPTS;
+ }
+
+ /* configure the tamper trigger */
+ RTC_TAMP &= ((uint32_t)~((rtc_tamper->rtc_tamper_source) << RTC_TAMPER_TRIGGER_POS));
+ if(RTC_TAMPER_TRIGGER_EDGE_RISING != rtc_tamper->rtc_tamper_trigger) {
+ RTC_TAMP |= (uint32_t)((rtc_tamper->rtc_tamper_source) << RTC_TAMPER_TRIGGER_POS);
+ }
+ /* enable tamper */
+ RTC_TAMP |= (uint32_t)(rtc_tamper->rtc_tamper_source);
+}
+
+/*!
+ \brief disable RTC tamper
+ \param[in] source: specify which tamper source to be disabled
+ only one parameter can be selected which is shown as below:
+ \arg RTC_TAMPER0
+ \arg RTC_TAMPER1
+ \param[out] none
+ \retval none
+*/
+void rtc_tamper_disable(uint32_t source)
+{
+ /* disable tamper */
+ RTC_TAMP &= (uint32_t)~source;
+}
+
+/*!
+ \brief enable specified RTC interrupt
+ \param[in] interrupt: specify which interrupt source to be enabled
+ only one parameter can be selected which is shown as below:
+ \arg RTC_INT_TIMESTAMP: timestamp interrupt
+ \arg RTC_INT_ALARM: alarm interrupt
+ \arg RTC_INT_TAMP: tamp interrupt
+ \param[out] none
+ \retval none
+*/
+void rtc_interrupt_enable(uint32_t interrupt)
+{
+ /* disable the write protection */
+ RTC_WPK = RTC_UNLOCK_KEY1;
+ RTC_WPK = RTC_UNLOCK_KEY2;
+
+ /* enable the interrupts in RTC_CTL register */
+ RTC_CTL |= (uint32_t)(interrupt & (uint32_t)~RTC_TAMP_TPIE);
+ /* enable the interrupts in RTC_TAMP register */
+ RTC_TAMP |= (uint32_t)(interrupt & RTC_TAMP_TPIE);
+
+ /* enable the write protection */
+ RTC_WPK = RTC_LOCK_KEY;
+}
+
+/*!
+ \brief disble specified RTC interrupt
+ \param[in] interrupt: specify which interrupt source to be disabled
+ only one parameter can be selected which is shown as below:
+ \arg RTC_INT_TIMESTAMP: timestamp interrupt
+ \arg RTC_INT_ALARM: alarm interrupt
+ \arg RTC_INT_TAMP: tamp interrupt
+ \param[out] none
+ \retval none
+*/
+void rtc_interrupt_disable(uint32_t interrupt)
+{
+ /* disable the write protection */
+ RTC_WPK = RTC_UNLOCK_KEY1;
+ RTC_WPK = RTC_UNLOCK_KEY2;
+
+ /* disable the interrupts in RTC_CTL register */
+ RTC_CTL &= (uint32_t)~(interrupt & (uint32_t)~RTC_TAMP_TPIE);
+ /* disable the interrupts in RTC_TAMP register */
+ RTC_TAMP &= (uint32_t)~(interrupt & RTC_TAMP_TPIE);
+
+ /* enable the write protection */
+ RTC_WPK = RTC_LOCK_KEY;
+}
+
+/*!
+ \brief check specified flag
+ \param[in] flag: specify which flag to check
+ only one parameter can be selected which is shown as below:
+ \arg RTC_FLAG_RECALIBRATION: recalibration pending flag
+ \arg RTC_FLAG_TAMP1: tamper 1 event flag
+ \arg RTC_FLAG_TAMP0: tamper 0 event flag
+ \arg RTC_FLAG_TIMESTAMP_OVERFLOW: time-stamp overflow event flag
+ \arg RTC_FLAG_TIMESTAMP: time-stamp event flag
+ \arg RTC_FLAG_ALARM0: alarm event flag
+ \arg RTC_FLAG_INIT: init mode event flag
+ \arg RTC_FLAG_RSYN: time and date registers synchronized event flag
+ \arg RTC_FLAG_YCM: year parameter configured event flag
+ \arg RTC_FLAG_SHIFT: shift operation pending flag
+ \arg RTC_FLAG_ALARM0_WRITTEN: alarm writen available flag
+ \param[out] none
+ \retval FlagStatus: SET or RESET
+*/
+FlagStatus rtc_flag_get(uint32_t flag)
+{
+ FlagStatus flag_state = RESET;
+
+ if(RESET != (RTC_STAT & flag)) {
+ flag_state = SET;
+ }
+ return flag_state;
+}
+
+/*!
+ \brief clear specified flag
+ \param[in] flag: specify which flag to clear
+ \arg RTC_FLAG_TAMP1: tamper 1 event flag
+ \arg RTC_FLAG_TAMP0: tamper 0 event flag
+ \arg RTC_FLAG_TIMESTAMP_OVERFLOW: time-stamp overflow event flag
+ \arg RTC_FLAG_TIMESTAMP: time-stamp event flag
+ \arg RTC_FLAG_ALARM0: alarm event flag
+ \arg RTC_FLAG_RSYN: time and date registers synchronized event flag
+ \param[out] none
+ \retval none
+*/
+void rtc_flag_clear(uint32_t flag)
+{
+ RTC_STAT &= (uint32_t)(~flag);
+}
+
+/*!
+ \brief configure rtc alternate output source
+ \param[in] source: specify signal to output
+ only one parameter can be selected which is shown as below:
+ \arg RTC_CALIBRATION_512HZ: when the LSE freqency is 32768Hz and the RTC_PSC
+ is the default value, output 512Hz signal
+ \arg RTC_CALIBRATION_1HZ: when the LSE freqency is 32768Hz and the RTC_PSC
+ is the default value, output 1Hz signal
+ \arg RTC_ALARM_HIGH: when the alarm flag is set, the output pin is high
+ \arg RTC_ALARM_LOW: when the Alarm flag is set, the output pin is low
+ \param[in] mode: specify the output pin (PC13) mode when output alarm signal
+ only one parameter can be selected which is shown as below:
+ \arg RTC_ALARM_OUTPUT_OD: open drain mode
+ \arg RTC_ALARM_OUTPUT_PP: push pull mode
+ \param[out] none
+ \retval none
+*/
+void rtc_alter_output_config(uint32_t source, uint32_t mode)
+{
+ /* disable the write protection */
+ RTC_WPK = RTC_UNLOCK_KEY1;
+ RTC_WPK = RTC_UNLOCK_KEY2;
+
+ RTC_CTL &= (uint32_t)~(RTC_CTL_COEN | RTC_CTL_OS | RTC_CTL_OPOL | RTC_CTL_COS);
+
+ RTC_CTL |= (uint32_t)(source);
+
+ /* alarm output */
+ if(RESET != (source & RTC_OS_ENABLE)) {
+ RTC_TAMP &= (uint32_t)~(RTC_TAMP_PC13VAL);
+ RTC_TAMP |= (uint32_t)(mode);
+ }
+
+ /* enable the write protection */
+ RTC_WPK = RTC_LOCK_KEY;
+}
+
+
+/*!
+ \brief configure RTC calibration register
+ \param[in] window: select calibration window
+ only one parameter can be selected which is shown as below:
+ \arg RTC_CALIBRATION_WINDOW_32S: 2exp20 RTCCLK cycles, 32s if RTCCLK = 32768 Hz
+ \arg RTC_CALIBRATION_WINDOW_16S: 2exp19 RTCCLK cycles, 16s if RTCCLK = 32768 Hz
+ \arg RTC_CALIBRATION_WINDOW_8S: 2exp18 RTCCLK cycles, 8s if RTCCLK = 32768 Hz
+ \param[in] plus: add RTC clock or not
+ only one parameter can be selected which is shown as below:
+ \arg RTC_CALIBRATION_PLUS_SET: add one RTC clock every 2048 rtc clock
+ \arg RTC_CALIBRATION_PLUS_RESET: no effect
+ \param[in] minus: the RTC clock to minus during the calibration window(0x0 - 0x1FF)
+ \param[out] none
+ \retval ErrStatus: ERROR or SUCCESS
+*/
+ErrStatus rtc_calibration_config(uint32_t window, uint32_t plus, uint32_t minus)
+{
+ uint32_t time_index = RTC_HRFC_TIMEOUT;
+ ErrStatus error_status = ERROR;
+ uint32_t flag_status = RESET;
+
+ /* disable the write protection */
+ RTC_WPK = RTC_UNLOCK_KEY1;
+ RTC_WPK = RTC_UNLOCK_KEY2;
+
+ /* check if a calibration operation is ongoing */
+ do {
+ flag_status = RTC_STAT & RTC_STAT_SCPF;
+ } while((--time_index > 0x00U) && (RESET != flag_status));
+
+ if(RESET == flag_status) {
+ RTC_HRFC = (uint32_t)(window | plus | HRFC_CMSK(minus));
+ error_status = SUCCESS;
+ }
+
+ /* enable the write protection */
+ RTC_WPK = RTC_LOCK_KEY;
+
+ return error_status;
+}
+
+/*!
+ \brief ajust the daylight saving time by adding or substracting one hour from the current time
+ \param[in] operation: hour ajustment operation
+ only one parameter can be selected which is shown as below:
+ \arg RTC_CTL_A1H: add one hour
+ \arg RTC_CTL_S1H: substract one hour
+ \param[out] none
+ \retval none
+*/
+void rtc_hour_adjust(uint32_t operation)
+{
+ /* disable the write protection */
+ RTC_WPK = RTC_UNLOCK_KEY1;
+ RTC_WPK = RTC_UNLOCK_KEY2;
+
+ RTC_CTL |= (uint32_t)(operation);
+
+ /* enable the write protection */
+ RTC_WPK = RTC_LOCK_KEY;
+}
+
+/*!
+ \brief ajust RTC second or subsecond value of current time
+ \param[in] add: add 1s to current time or not
+ only one parameter can be selected which is shown as below:
+ \arg RTC_SHIFT_ADD1S_RESET: no effect
+ \arg RTC_SHIFT_ADD1S_SET: add 1s to current time
+ \param[in] minus: number of subsecond to minus from current time(0x0 - 0x7FFF)
+ \param[out] none
+ \retval ErrStatus: ERROR or SUCCESS
+*/
+ErrStatus rtc_second_adjust(uint32_t add, uint32_t minus)
+{
+ uint32_t time_index = RTC_SHIFTCTL_TIMEOUT;
+ ErrStatus error_status = ERROR;
+ uint32_t flag_status = RESET;
+ uint32_t temp = 0U;
+
+ /* disable the write protection */
+ RTC_WPK = RTC_UNLOCK_KEY1;
+ RTC_WPK = RTC_UNLOCK_KEY2;
+
+ /* check if a shift operation is ongoing */
+ do {
+ flag_status = RTC_STAT & RTC_STAT_SOPF;
+ } while((--time_index > 0x00U) && (RESET != flag_status));
+
+ temp = RTC_CTL & RTC_CTL_REFEN;
+ /* check if the function of reference clock detection is disabled */
+ if((RESET == flag_status) && (RESET == temp)) {
+ RTC_SHIFTCTL = (uint32_t)(add | SHIFTCTL_SFS(minus));
+ error_status = rtc_register_sync_wait();
+ }
+
+ /* enable the write protection */
+ RTC_WPK = RTC_LOCK_KEY;
+
+ return error_status;
+}
+
+/*!
+ \brief enable RTC bypass shadow registers function
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void rtc_bypass_shadow_enable(void)
+{
+ /* disable the write protection */
+ RTC_WPK = RTC_UNLOCK_KEY1;
+ RTC_WPK = RTC_UNLOCK_KEY2;
+
+ RTC_CTL |= (uint8_t)RTC_CTL_BPSHAD;
+
+ /* enable the write protection */
+ RTC_WPK = RTC_LOCK_KEY;
+}
+
+/*!
+ \brief disable RTC bypass shadow registers function
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void rtc_bypass_shadow_disable(void)
+{
+ /* disable the write protection */
+ RTC_WPK = RTC_UNLOCK_KEY1;
+ RTC_WPK = RTC_UNLOCK_KEY2;
+
+ RTC_CTL &= (uint8_t)~RTC_CTL_BPSHAD;
+
+ /* enable the write protection */
+ RTC_WPK = RTC_LOCK_KEY;
+}
+
+/*!
+ \brief enable RTC reference clock detection function
+ \param[in] none
+ \param[out] none
+ \retval ErrStatus: ERROR or SUCCESS
+*/
+ErrStatus rtc_refclock_detection_enable(void)
+{
+ ErrStatus error_status = ERROR;
+
+ /* disable the write protection */
+ RTC_WPK = RTC_UNLOCK_KEY1;
+ RTC_WPK = RTC_UNLOCK_KEY2;
+
+ /* enter init mode */
+ error_status = rtc_init_mode_enter();
+
+ if(ERROR != error_status) {
+ RTC_CTL |= (uint32_t)RTC_CTL_REFEN;
+ /* exit init mode */
+ rtc_init_mode_exit();
+ }
+
+ /* enable the write protection */
+ RTC_WPK = RTC_LOCK_KEY;
+
+ return error_status;
+}
+
+/*!
+ \brief disable RTC reference clock detection function
+ \param[in] none
+ \param[out] none
+ \retval ErrStatus: ERROR or SUCCESS
+*/
+ErrStatus rtc_refclock_detection_disable(void)
+{
+ ErrStatus error_status = ERROR;
+
+ /* disable the write protection */
+ RTC_WPK = RTC_UNLOCK_KEY1;
+ RTC_WPK = RTC_UNLOCK_KEY2;
+
+ /* enter init mode */
+ error_status = rtc_init_mode_enter();
+
+ if(ERROR != error_status) {
+ RTC_CTL &= (uint32_t)~RTC_CTL_REFEN;
+ /* exit init mode */
+ rtc_init_mode_exit();
+ }
+
+ /* enable the write protection */
+ RTC_WPK = RTC_LOCK_KEY;
+
+ return error_status;
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_spi.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_spi.c
new file mode 100644
index 00000000..cd1318c6
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_spi.c
@@ -0,0 +1,794 @@
+/*!
+ \file gd32f3x0_spi.c
+ \brief SPI driver
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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.
+*/
+
+#include "gd32f3x0_spi.h"
+
+#define SPI_INIT_MASK ((uint32_t)0x00003040U) /*!< SPI parameter initialization mask */
+#define I2S_INIT_MASK ((uint32_t)0x0000F047U) /*!< I2S parameter initialization mask */
+
+#define SPI_I2SPSC_DEFAULT_VALUE ((uint32_t)0x00000002U) /*!< default value of SPI_I2SPSC register */
+
+/*!
+ \brief reset SPI and I2S
+ \param[in] spi_periph: SPIx(x=0,1)
+ \param[out] none
+ \retval none
+*/
+void spi_i2s_deinit(uint32_t spi_periph)
+{
+ switch(spi_periph) {
+ case SPI0:
+ /* reset SPI0 and I2S0 */
+ rcu_periph_reset_enable(RCU_SPI0RST);
+ rcu_periph_reset_disable(RCU_SPI0RST);
+ break;
+ case SPI1:
+ /* reset SPI1 */
+ rcu_periph_reset_enable(RCU_SPI1RST);
+ rcu_periph_reset_disable(RCU_SPI1RST);
+ break;
+ default :
+ break;
+ }
+}
+
+/*!
+ \brief initialize the parameters of SPI struct with the default values
+ \param[in] spi_struct: SPI parameter stuct
+ \param[out] none
+ \retval none
+*/
+void spi_struct_para_init(spi_parameter_struct *spi_struct)
+{
+ /* set the SPI struct with the default values */
+ spi_struct->device_mode = SPI_SLAVE;
+ spi_struct->trans_mode = SPI_TRANSMODE_FULLDUPLEX;
+ spi_struct->frame_size = SPI_FRAMESIZE_8BIT;
+ spi_struct->nss = SPI_NSS_HARD;
+ spi_struct->clock_polarity_phase = SPI_CK_PL_LOW_PH_1EDGE;
+ spi_struct->prescale = SPI_PSC_2;
+}
+
+/*!
+ \brief initialize SPI parameter
+ \param[in] spi_periph: SPIx(x=0,1)
+ \param[in] spi_struct: SPI parameter initialization stuct members of the structure
+ and the member values are shown as below:
+ device_mode: SPI_MASTER, SPI_SLAVE
+ trans_mode: SPI_TRANSMODE_FULLDUPLEX, SPI_TRANSMODE_RECEIVEONLY,
+ SPI_TRANSMODE_BDRECEIVE, SPI_TRANSMODE_BDTRANSMIT
+ frame_size: SPI_FRAMESIZE_16BIT, SPI_FRAMESIZE_8BIT
+ nss: SPI_NSS_SOFT, SPI_NSS_HARD
+ endian: SPI_ENDIAN_MSB, SPI_ENDIAN_LSB
+ clock_polarity_phase: SPI_CK_PL_LOW_PH_1EDGE, SPI_CK_PL_HIGH_PH_1EDGE
+ SPI_CK_PL_LOW_PH_2EDGE, SPI_CK_PL_HIGH_PH_2EDGE
+ prescale: SPI_PSC_n (n=2,4,8,16,32,64,128,256)
+ \param[out] none
+ \retval none
+*/
+void spi_init(uint32_t spi_periph, spi_parameter_struct *spi_struct)
+{
+ uint32_t reg = 0U;
+ reg = SPI_CTL0(spi_periph);
+ reg &= SPI_INIT_MASK;
+
+ /* select SPI as master or slave */
+ reg |= spi_struct->device_mode;
+ /* select SPI transfer mode */
+ reg |= spi_struct->trans_mode;
+ /* select SPI frame size */
+ reg |= spi_struct->frame_size;
+ /* select SPI NSS use hardware or software */
+ reg |= spi_struct->nss;
+ /* select SPI LSB or MSB */
+ reg |= spi_struct->endian;
+ /* select SPI polarity and phase */
+ reg |= spi_struct->clock_polarity_phase;
+ /* select SPI prescale to adjust transmit speed */
+ reg |= spi_struct->prescale;
+
+ /* write to SPI_CTL0 register */
+ SPI_CTL0(spi_periph) = (uint32_t)reg;
+
+ /* select SPI mode */
+ SPI_I2SCTL(spi_periph) &= (uint32_t)(~SPI_I2SCTL_I2SSEL);
+}
+
+/*!
+ \brief enable SPI
+ \param[in] spi_periph: SPIx(x=0,1)
+ \param[out] none
+ \retval none
+*/
+void spi_enable(uint32_t spi_periph)
+{
+ SPI_CTL0(spi_periph) |= (uint32_t)SPI_CTL0_SPIEN;
+}
+
+/*!
+ \brief disable SPI
+ \param[in] spi_periph: SPIx(x=0,1)
+ \param[out] none
+ \retval none
+*/
+void spi_disable(uint32_t spi_periph)
+{
+ SPI_CTL0(spi_periph) &= (uint32_t)(~SPI_CTL0_SPIEN);
+}
+
+
+#if (defined(GD32F350) || defined(GD32F310))
+/*!
+ \brief initialize I2S parameter
+ \param[in] spi_periph: SPI0
+ \param[in] mode: I2S operation mode
+ only one parameter can be selected which is shown as below:
+ \arg I2S_MODE_SLAVETX: I2S slave transmit mode
+ \arg I2S_MODE_SLAVERX: I2S slave receive mode
+ \arg I2S_MODE_MASTERTX: I2S master transmit mode
+ \arg I2S_MODE_MASTERRX: I2S master receive mode
+ \param[in] standard: I2S standard
+ only one parameter can be selected which is shown as below:
+ \arg I2S_STD_PHILLIPS: I2S phillips standard
+ \arg I2S_STD_MSB: I2S MSB standard
+ \arg I2S_STD_LSB: I2S LSB standard
+ \arg I2S_STD_PCMSHORT: I2S PCM short standard
+ \arg I2S_STD_PCMLONG: I2S PCM long standard
+ \param[in] ckpl: I2S idle state clock polarity
+ only one parameter can be selected which is shown as below:
+ \arg I2S_CKPL_LOW: I2S clock polarity low level
+ \arg I2S_CKPL_HIGH: I2S clock polarity high level
+ \param[out] none
+ \retval none
+*/
+void i2s_init(uint32_t spi_periph, uint32_t mode, uint32_t standard, uint32_t ckpl)
+{
+ uint32_t reg = 0U;
+ reg = SPI_I2SCTL(spi_periph);
+ reg &= I2S_INIT_MASK;
+
+ /* enable I2S mode */
+ reg |= (uint32_t)SPI_I2SCTL_I2SSEL;
+ /* select I2S mode */
+ reg |= (uint32_t)mode;
+ /* select I2S standard */
+ reg |= (uint32_t)standard;
+ /* select I2S polarity */
+ reg |= (uint32_t)ckpl;
+
+ /* write to SPI_I2SCTL register */
+ SPI_I2SCTL(spi_periph) = (uint32_t)reg;
+}
+
+/*!
+ \brief configure I2S prescaler
+ \param[in] spi_periph: SPI0
+ \param[in] audiosample: I2S audio sample rate
+ only one parameter can be selected which is shown as below:
+ \arg I2S_AUDIOSAMPLE_8K: audio sample rate is 8KHz
+ \arg I2S_AUDIOSAMPLE_11K: audio sample rate is 11KHz
+ \arg I2S_AUDIOSAMPLE_16K: audio sample rate is 16KHz
+ \arg I2S_AUDIOSAMPLE_22K: audio sample rate is 22KHz
+ \arg I2S_AUDIOSAMPLE_32K: audio sample rate is 32KHz
+ \arg I2S_AUDIOSAMPLE_44K: audio sample rate is 44KHz
+ \arg I2S_AUDIOSAMPLE_48K: audio sample rate is 48KHz
+ \arg I2S_AUDIOSAMPLE_96K: audio sample rate is 96KHz
+ \arg I2S_AUDIOSAMPLE_192K: audio sample rate is 192KHz
+ \param[in] frameformat: I2S data length and channel length
+ only one parameter can be selected which is shown as below:
+ \arg I2S_FRAMEFORMAT_DT16B_CH16B: I2S data length is 16 bit and channel length is 16 bit
+ \arg I2S_FRAMEFORMAT_DT16B_CH32B: I2S data length is 16 bit and channel length is 32 bit
+ \arg I2S_FRAMEFORMAT_DT24B_CH32B: I2S data length is 24 bit and channel length is 32 bit
+ \arg I2S_FRAMEFORMAT_DT32B_CH32B: I2S data length is 32 bit and channel length is 32 bit
+ \param[in] mckout: I2S master clock output
+ only one parameter can be selected which is shown as below:
+ \arg I2S_MCKOUT_ENABLE: I2S master clock output enable
+ \arg I2S_MCKOUT_DISABLE: I2S master clock output disable
+ \param[out] none
+ \retval none
+*/
+void i2s_psc_config(uint32_t spi_periph, uint32_t audiosample, uint32_t frameformat, uint32_t mckout)
+{
+ uint32_t i2sdiv = 2U, i2sof = 0U;
+ uint32_t clks = 0U;
+ uint32_t i2sclock = 0U;
+
+ /* deinit SPI_I2SPSC register */
+ SPI_I2SPSC(spi_periph) = SPI_I2SPSC_DEFAULT_VALUE;
+
+ /* get system clock */
+ i2sclock = rcu_clock_freq_get(CK_SYS);
+
+ /* config the prescaler depending on the mclk output state, the frame format and audio sample rate */
+ if(I2S_MCKOUT_ENABLE == mckout) {
+ clks = (uint32_t)(((i2sclock / 256U) * 10U) / audiosample);
+ } else {
+ if(I2S_FRAMEFORMAT_DT16B_CH16B == frameformat) {
+ clks = (uint32_t)(((i2sclock / 32U) * 10U) / audiosample);
+ } else {
+ clks = (uint32_t)(((i2sclock / 64U) * 10U) / audiosample);
+ }
+ }
+
+ /* remove the floating point */
+ clks = (clks + 5U) / 10U;
+ i2sof = (clks & 0x00000001U);
+ i2sdiv = ((clks - i2sof) / 2U);
+ i2sof = (i2sof << 8U);
+
+ /* set the default values */
+ if((i2sdiv < 2U) || (i2sdiv > 255U)) {
+ i2sdiv = 2U;
+ i2sof = 0U;
+ }
+
+ /* configure SPI_I2SPSC */
+ SPI_I2SPSC(spi_periph) = (uint32_t)(i2sdiv | i2sof | mckout);
+
+ /* clear SPI_I2SCTL_DTLEN and SPI_I2SCTL_CHLEN bits */
+ SPI_I2SCTL(spi_periph) &= (uint32_t)(~(SPI_I2SCTL_DTLEN | SPI_I2SCTL_CHLEN));
+ /* configure data frame format */
+ SPI_I2SCTL(spi_periph) |= (uint32_t)frameformat;
+}
+
+/*!
+ \brief enable I2S
+ \param[in] spi_periph: SPI0
+ \param[out] none
+ \retval none
+*/
+void i2s_enable(uint32_t spi_periph)
+{
+ SPI_I2SCTL(spi_periph) |= (uint32_t)SPI_I2SCTL_I2SEN;
+}
+
+/*!
+ \brief disable I2S
+ \param[in] spi_periph: SPI0
+ \param[out] none
+ \retval none
+*/
+void i2s_disable(uint32_t spi_periph)
+{
+ SPI_I2SCTL(spi_periph) &= (uint32_t)(~SPI_I2SCTL_I2SEN);
+}
+
+#endif /* GD32F350 and GD32F310 */
+
+/*!
+ \brief enable SPI NSS output
+ \param[in] spi_periph: SPIx(x=0,1)
+ \param[out] none
+ \retval none
+*/
+void spi_nss_output_enable(uint32_t spi_periph)
+{
+ SPI_CTL1(spi_periph) |= (uint32_t)SPI_CTL1_NSSDRV;
+}
+
+/*!
+ \brief disable SPI NSS output
+ \param[in] spi_periph: SPIx(x=0,1)
+ \param[out] none
+ \retval none
+*/
+void spi_nss_output_disable(uint32_t spi_periph)
+{
+ SPI_CTL1(spi_periph) &= (uint32_t)(~SPI_CTL1_NSSDRV);
+}
+
+/*!
+ \brief pull NSS pin high in software mode
+ \param[in] spi_periph: SPIx(x=0,1)
+ \param[out] none
+ \retval none
+*/
+void spi_nss_internal_high(uint32_t spi_periph)
+{
+ SPI_CTL0(spi_periph) |= (uint32_t)SPI_CTL0_SWNSS;
+}
+
+/*!
+ \brief pull NSS pin low in software mode
+ \param[in] spi_periph: SPIx(x=0,1)
+ \param[out] none
+ \retval none
+*/
+void spi_nss_internal_low(uint32_t spi_periph)
+{
+ SPI_CTL0(spi_periph) &= (uint32_t)(~SPI_CTL0_SWNSS);
+}
+
+/*!
+ \brief enable SPI DMA send or receive
+ \param[in] spi_periph: SPIx(x=0,1)
+ \param[in] dma: SPI DMA mode
+ only one parameter can be selected which is shown as below:
+ \arg SPI_DMA_TRANSMIT: SPI transmit data using DMA
+ \arg SPI_DMA_RECEIVE: SPI receive data using DMA
+ \param[out] none
+ \retval none
+*/
+void spi_dma_enable(uint32_t spi_periph, uint8_t dma)
+{
+ if(SPI_DMA_TRANSMIT == dma) {
+ SPI_CTL1(spi_periph) |= (uint32_t)SPI_CTL1_DMATEN;
+ } else {
+ SPI_CTL1(spi_periph) |= (uint32_t)SPI_CTL1_DMAREN;
+ }
+}
+
+/*!
+ \brief disable SPI DMA send or receive
+ \param[in] spi_periph: SPIx(x=0,1)
+ \param[in] dma: SPI DMA mode
+ only one parameter can be selected which is shown as below:
+ \arg SPI_DMA_TRANSMIT: SPI transmit data using DMA
+ \arg SPI_DMA_RECEIVE: SPI receive data using DMA
+ \param[out] none
+ \retval none
+*/
+void spi_dma_disable(uint32_t spi_periph, uint8_t dma)
+{
+ if(SPI_DMA_TRANSMIT == dma) {
+ SPI_CTL1(spi_periph) &= (uint32_t)(~SPI_CTL1_DMATEN);
+ } else {
+ SPI_CTL1(spi_periph) &= (uint32_t)(~SPI_CTL1_DMAREN);
+ }
+}
+
+/*!
+ \brief configure SPI/I2S data frame format
+ \param[in] spi_periph: SPIx(x=0,1)
+ \param[in] frame_format: SPI frame size
+ only one parameter can be selected which is shown as below:
+ \arg SPI_FRAMESIZE_16BIT: SPI frame size is 16 bits
+ \arg SPI_FRAMESIZE_8BIT: SPI frame size is 8 bits
+ \param[out] none
+ \retval none
+*/
+void spi_i2s_data_frame_format_config(uint32_t spi_periph, uint16_t frame_format)
+{
+ /* clear SPI_CTL0_FF16 bit */
+ SPI_CTL0(spi_periph) &= (uint32_t)(~SPI_CTL0_FF16);
+ /* confige SPI_CTL0_FF16 bit */
+ SPI_CTL0(spi_periph) |= (uint32_t)frame_format;
+}
+
+/*!
+ \brief SPI transmit data
+ \param[in] spi_periph: SPIx(x=0,1)
+ \param[in] data: 16-bit data
+ \param[out] none
+ \retval none
+*/
+void spi_i2s_data_transmit(uint32_t spi_periph, uint16_t data)
+{
+ SPI_DATA(spi_periph) = (uint32_t)data;
+}
+
+/*!
+ \brief SPI receive data
+ \param[in] spi_periph: SPIx(x=0,1)
+ \param[out] none
+ \retval 16-bit data
+*/
+uint16_t spi_i2s_data_receive(uint32_t spi_periph)
+{
+ return ((uint16_t)SPI_DATA(spi_periph));
+}
+
+/*!
+ \brief configure SPI bidirectional transfer direction
+ \param[in] spi_periph: SPIx(x=0,1)
+ \param[in] transfer_direction: SPI transfer direction
+ only one parameter can be selected which is shown as below:
+ \arg SPI_BIDIRECTIONAL_TRANSMIT: SPI work in transmit-only mode
+ \arg SPI_BIDIRECTIONAL_RECEIVE: SPI work in receive-only mode
+ \param[out] none
+ \retval none
+*/
+void spi_bidirectional_transfer_config(uint32_t spi_periph, uint32_t transfer_direction)
+{
+ if(SPI_BIDIRECTIONAL_TRANSMIT == transfer_direction) {
+ /* set the transmit only mode */
+ SPI_CTL0(spi_periph) |= (uint32_t)SPI_BIDIRECTIONAL_TRANSMIT;
+ } else {
+ /* set the receive only mode */
+ SPI_CTL0(spi_periph) &= SPI_BIDIRECTIONAL_RECEIVE;
+ }
+}
+
+/*!
+ \brief set CRC polynomial
+ \param[in] spi_periph: SPIx(x=0,1)
+ \param[in] crc_poly: CRC polynomial value
+ \param[out] none
+ \retval none
+*/
+void spi_crc_polynomial_set(uint32_t spi_periph, uint16_t crc_poly)
+{
+ /* enable SPI CRC */
+ SPI_CTL0(spi_periph) |= (uint32_t)SPI_CTL0_CRCEN;
+ /* set SPI CRC polynomial */
+ SPI_CRCPOLY(spi_periph) = (uint32_t)crc_poly;
+}
+
+/*!
+ \brief get SPI CRC polynomial
+ \param[in] spi_periph: SPIx(x=0,1)
+ \param[out] none
+ \retval 16-bit CRC polynomial
+*/
+uint16_t spi_crc_polynomial_get(uint32_t spi_periph)
+{
+ return ((uint16_t)SPI_CRCPOLY(spi_periph));
+}
+
+/*!
+ \brief turn on CRC function
+ \param[in] spi_periph: SPIx(x=0,1)
+ \param[out] none
+ \retval none
+*/
+void spi_crc_on(uint32_t spi_periph)
+{
+ SPI_CTL0(spi_periph) |= (uint32_t)SPI_CTL0_CRCEN;
+}
+
+/*!
+ \brief turn off CRC function
+ \param[in] spi_periph: SPIx(x=0,1)
+ \param[out] none
+ \retval none
+*/
+void spi_crc_off(uint32_t spi_periph)
+{
+ SPI_CTL0(spi_periph) &= (uint32_t)(~SPI_CTL0_CRCEN);
+}
+
+/*!
+ \brief SPI next data is CRC value
+ \param[in] spi_periph: SPIx(x=0,1)
+ \param[out] none
+ \retval none
+*/
+void spi_crc_next(uint32_t spi_periph)
+{
+ SPI_CTL0(spi_periph) |= (uint32_t)SPI_CTL0_CRCNT;
+}
+
+/*!
+ \brief get SPI CRC send value or receive value
+ \param[in] spi_periph: SPIx(x=0,1)
+ \param[in] crc: SPI crc value
+ \arg SPI_CRC_TX: get transmit crc value
+ \arg SPI_CRC_RX: get receive crc value
+ \param[out] none
+ \retval 16-bit CRC value
+*/
+uint16_t spi_crc_get(uint32_t spi_periph, uint8_t crc)
+{
+ if(SPI_CRC_TX == crc) {
+ return ((uint16_t)(SPI_TCRC(spi_periph)));
+ } else {
+ return ((uint16_t)(SPI_RCRC(spi_periph)));
+ }
+}
+
+/*!
+ \brief enable SPI TI mode
+ \param[in] spi_periph: SPIx(x=0,1)
+ \param[out] none
+ \retval none
+*/
+void spi_ti_mode_enable(uint32_t spi_periph)
+{
+ SPI_CTL1(spi_periph) |= (uint32_t)SPI_CTL1_TMOD;
+}
+
+/*!
+ \brief disable SPI TI mode
+ \param[in] spi_periph: SPIx(x=0,1)
+ \param[out] none
+ \retval none
+*/
+void spi_ti_mode_disable(uint32_t spi_periph)
+{
+ SPI_CTL1(spi_periph) &= (uint32_t)(~SPI_CTL1_TMOD);
+}
+
+/*!
+ \brief enable SPI NSS pulse mode
+ \param[in] spi_periph: SPIx(x=0,1)
+ \param[out] none
+ \retval none
+*/
+void spi_nssp_mode_enable(uint32_t spi_periph)
+{
+ SPI_CTL1(spi_periph) |= (uint32_t)SPI_CTL1_NSSP;
+}
+
+/*!
+ \brief disable SPI NSS pulse mode
+ \param[in] spi_periph: SPIx(x=0,1)
+ \param[out] none
+ \retval none
+*/
+void spi_nssp_mode_disable(uint32_t spi_periph)
+{
+ SPI_CTL1(spi_periph) &= (uint32_t)(~SPI_CTL1_NSSP);
+}
+
+/*!
+ \brief enable quad wire SPI
+ \param[in] spi_periph: SPI1
+ \param[out] none
+ \retval none
+*/
+void qspi_enable(uint32_t spi_periph)
+{
+ SPI_QCTL(spi_periph) |= (uint32_t)SPI_QCTL_QMOD;
+}
+
+/*!
+ \brief disable quad wire SPI
+ \param[in] spi_periph: SPI1
+ \param[out] none
+ \retval none
+*/
+void qspi_disable(uint32_t spi_periph)
+{
+ SPI_QCTL(spi_periph) &= (uint32_t)(~SPI_QCTL_QMOD);
+}
+
+/*!
+ \brief enable quad wire SPI write
+ \param[in] spi_periph: SPI1
+ \param[out] none
+ \retval none
+*/
+void qspi_write_enable(uint32_t spi_periph)
+{
+ SPI_QCTL(spi_periph) &= (uint32_t)(~SPI_QCTL_QRD);
+}
+
+/*!
+ \brief enable quad wire SPI read
+ \param[in] spi_periph: SPI1
+ \param[out] none
+ \retval none
+*/
+void qspi_read_enable(uint32_t spi_periph)
+{
+ SPI_QCTL(spi_periph) |= (uint32_t)SPI_QCTL_QRD;
+}
+
+/*!
+ \brief enable SPI_IO2 and SPI_IO3 pin output
+ \param[in] spi_periph: SPI1
+ \param[out] none
+ \retval none
+*/
+void qspi_io23_output_enable(uint32_t spi_periph)
+{
+ SPI_QCTL(spi_periph) |= (uint32_t)SPI_QCTL_IO23_DRV;
+}
+
+/*!
+ \brief disable SPI_IO2 and SPI_IO3 pin output
+ \param[in] spi_periph: SPI1
+ \param[out] none
+ \retval none
+*/
+void qspi_io23_output_disable(uint32_t spi_periph)
+{
+ SPI_QCTL(spi_periph) &= (uint32_t)(~SPI_QCTL_IO23_DRV);
+}
+
+/*!
+ \brief enable SPI and I2S interrupt
+ \param[in] spi_periph: SPIx(x=0,1)
+ \param[in] interrupt: SPI/I2S interrupt
+ only one parameter can be selected which is shown as below:
+ \arg SPI_I2S_INT_TBE: transmit buffer empty interrupt
+ \arg SPI_I2S_INT_RBNE: receive buffer not empty interrupt
+ \arg SPI_I2S_INT_ERR: CRC error,configuration error,reception overrun error,
+ transmission underrun error and format error interrupt
+ \param[out] none
+ \retval none
+*/
+void spi_i2s_interrupt_enable(uint32_t spi_periph, uint8_t interrupt)
+{
+ switch(interrupt) {
+ /* SPI/I2S transmit buffer empty interrupt */
+ case SPI_I2S_INT_TBE:
+ SPI_CTL1(spi_periph) |= (uint32_t)SPI_CTL1_TBEIE;
+ break;
+ /* SPI/I2S receive buffer not empty interrupt */
+ case SPI_I2S_INT_RBNE:
+ SPI_CTL1(spi_periph) |= (uint32_t)SPI_CTL1_RBNEIE;
+ break;
+ /* SPI/I2S error */
+ case SPI_I2S_INT_ERR:
+ SPI_CTL1(spi_periph) |= (uint32_t)SPI_CTL1_ERRIE;
+ break;
+ default:
+ break;
+ }
+}
+
+/*!
+ \brief disable SPI and I2S interrupt
+ \param[in] spi_periph: SPIx(x=0,1)
+ \param[in] interrupt: SPI/I2S interrupt
+ only one parameter can be selected which is shown as below:
+ \arg SPI_I2S_INT_TBE: transmit buffer empty interrupt
+ \arg SPI_I2S_INT_RBNE: receive buffer not empty interrupt
+ \arg SPI_I2S_INT_ERR: CRC error,configuration error,reception overrun error,
+ transmission underrun error and format error interrupt
+ \param[out] none
+ \retval none
+*/
+void spi_i2s_interrupt_disable(uint32_t spi_periph, uint8_t interrupt)
+{
+ switch(interrupt) {
+ /* SPI/I2S transmit buffer empty interrupt */
+ case SPI_I2S_INT_TBE:
+ SPI_CTL1(spi_periph) &= (uint32_t)(~SPI_CTL1_TBEIE);
+ break;
+ /* SPI/I2S receive buffer not empty interrupt */
+ case SPI_I2S_INT_RBNE:
+ SPI_CTL1(spi_periph) &= (uint32_t)(~SPI_CTL1_RBNEIE);
+ break;
+ /* SPI/I2S error */
+ case SPI_I2S_INT_ERR:
+ SPI_CTL1(spi_periph) &= (uint32_t)(~SPI_CTL1_ERRIE);
+ break;
+ default :
+ break;
+ }
+}
+
+/*!
+ \brief get SPI and I2S interrupt flag status
+ \param[in] spi_periph: SPIx(x=0,1)
+ \param[in] interrupt: SPI/I2S interrupt flag status
+ only one parameter can be selected which is shown as below:
+ \arg SPI_I2S_INT_FLAG_TBE: transmit buffer empty interrupt flag
+ \arg SPI_I2S_INT_FLAG_RBNE: receive buffer not empty interrupt flag
+ \arg SPI_I2S_INT_FLAG_RXORERR: overrun interrupt flag
+ \arg SPI_INT_FLAG_CONFERR: config error interrupt flag
+ \arg SPI_INT_FLAG_CRCERR: CRC error interrupt flag
+ \arg I2S_INT_FLAG_TXURERR: underrun error interrupt flag
+ \arg SPI_I2S_INT_FLAG_FERR: format error interrupt flag
+ \param[out] none
+ \retval FlagStatus: SET or RESET
+*/
+FlagStatus spi_i2s_interrupt_flag_get(uint32_t spi_periph, uint8_t interrupt)
+{
+ uint32_t reg1 = SPI_STAT(spi_periph);
+ uint32_t reg2 = SPI_CTL1(spi_periph);
+
+ switch(interrupt) {
+ /* SPI/I2S transmit buffer empty interrupt */
+ case SPI_I2S_INT_FLAG_TBE:
+ reg1 = reg1 & SPI_STAT_TBE;
+ reg2 = reg2 & SPI_CTL1_TBEIE;
+ break;
+ /* SPI/I2S receive buffer not empty interrupt */
+ case SPI_I2S_INT_FLAG_RBNE:
+ reg1 = reg1 & SPI_STAT_RBNE;
+ reg2 = reg2 & SPI_CTL1_RBNEIE;
+ break;
+ /* SPI/I2S overrun interrupt */
+ case SPI_I2S_INT_FLAG_RXORERR:
+ reg1 = reg1 & SPI_STAT_RXORERR;
+ reg2 = reg2 & SPI_CTL1_ERRIE;
+ break;
+ /* SPI config error interrupt */
+ case SPI_INT_FLAG_CONFERR:
+ reg1 = reg1 & SPI_STAT_CONFERR;
+ reg2 = reg2 & SPI_CTL1_ERRIE;
+ break;
+ /* SPI CRC error interrupt */
+ case SPI_INT_FLAG_CRCERR:
+ reg1 = reg1 & SPI_STAT_CRCERR;
+ reg2 = reg2 & SPI_CTL1_ERRIE;
+ break;
+ /* I2S underrun error interrupt */
+ case I2S_INT_FLAG_TXURERR:
+ reg1 = reg1 & SPI_STAT_TXURERR;
+ reg2 = reg2 & SPI_CTL1_ERRIE;
+ break;
+ /* SPI/I2S format error interrupt */
+ case SPI_I2S_INT_FLAG_FERR:
+ reg1 = reg1 & SPI_STAT_FERR;
+ reg2 = reg2 & SPI_CTL1_ERRIE;
+ break;
+ default :
+ break;
+ }
+ /*get SPI/I2S interrupt flag status */
+ if((0U != reg1) && (0U != reg2)) {
+ return SET;
+ } else {
+ return RESET;
+ }
+}
+
+/*!
+ \brief get SPI and I2S flag status
+ \param[in] spi_periph: SPIx(x=0,1)
+ \param[in] flag: SPI/I2S flag status
+ one or more parameters can be selected which are shown as below:
+ \arg SPI_FLAG_TBE: transmit buffer empty flag
+ \arg SPI_FLAG_RBNE: receive buffer not empty flag
+ \arg SPI_FLAG_TRANS: transmit on-going flag
+ \arg SPI_FLAG_RXORERR: receive overrun error flag
+ \arg SPI_FLAG_CONFERR: mode config error flag
+ \arg SPI_FLAG_CRCERR: CRC error flag
+ \arg SPI_FLAG_FERR: format error interrupt flag
+ \arg I2S_FLAG_TBE: transmit buffer empty flag
+ \arg I2S_FLAG_RBNE: receive buffer not empty flag
+ \arg I2S_FLAG_TRANS: transmit on-going flag
+ \arg I2S_FLAG_RXORERR: overrun error flag
+ \arg I2S_FLAG_TXURERR: underrun error flag
+ \arg I2S_FLAG_CH: channel side flag
+ \arg I2S_FLAG_FERR: format error interrupt flag
+ \param[out] none
+ \retval FlagStatus: SET or RESET
+*/
+FlagStatus spi_i2s_flag_get(uint32_t spi_periph, uint32_t flag)
+{
+ if(RESET != (SPI_STAT(spi_periph) & flag)) {
+ return SET;
+ } else {
+ return RESET;
+ }
+}
+
+/*!
+ \brief clear SPI CRC error flag status
+ \param[in] spi_periph: SPIx(x=0,1)
+ \param[out] none
+ \retval none
+*/
+void spi_crc_error_clear(uint32_t spi_periph)
+{
+ SPI_STAT(spi_periph) &= (uint32_t)(~SPI_FLAG_CRCERR);
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_syscfg.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_syscfg.c
new file mode 100644
index 00000000..b9cc4457
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_syscfg.c
@@ -0,0 +1,229 @@
+/*!
+ \file gd32f3x0_syscfg.c
+ \brief SYSCFG driver
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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.
+*/
+
+#include "gd32f3x0_syscfg.h"
+
+/*!
+ \brief reset the SYSCFG registers
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void syscfg_deinit(void)
+{
+ rcu_periph_reset_enable(RCU_CFGCMPRST);
+ rcu_periph_reset_disable(RCU_CFGCMPRST);
+}
+
+/*!
+ \brief enable the DMA channels remapping
+ \param[in] syscfg_dma_remap: specify the DMA channels to remap
+ one or more parameters can be selected which is shown as below:
+ \arg SYSCFG_DMA_REMAP_TIMER16: remap TIMER16 channel0 and UP DMA requests to channel1(defaut channel0)
+ \arg SYSCFG_DMA_REMAP_TIMER15: remap TIMER15 channel2 and UP DMA requests to channel3(defaut channel2)
+ \arg SYSCFG_DMA_REMAP_USART0RX: remap USART0 Rx DMA request to channel4(default channel2)
+ \arg SYSCFG_DMA_REMAP_USART0TX: remap USART0 Tx DMA request to channel3(default channel1)
+ \arg SYSCFG_DMA_REMAP_ADC: remap ADC DMA requests from channel0 to channel1
+ \param[out] none
+ \retval none
+*/
+void syscfg_dma_remap_enable(uint32_t syscfg_dma_remap)
+{
+ SYSCFG_CFG0 |= syscfg_dma_remap;
+}
+
+/*!
+ \brief disable the DMA channels remapping
+ \param[in] syscfg_dma_remap: specify the DMA channels to remap
+ one or more parameters can be selected which is shown as below:
+ \arg SYSCFG_DMA_REMAP_TIMER16: remap TIMER16 channel0 and UP DMA requests to channel1(defaut channel0)
+ \arg SYSCFG_DMA_REMAP_TIMER15: remap TIMER15 channel2 and UP DMA requests to channel3(defaut channel2)
+ \arg SYSCFG_DMA_REMAP_USART0RX: remap USART0 Rx DMA request to channel4(default channel2)
+ \arg SYSCFG_DMA_REMAP_USART0TX: remap USART0 Tx DMA request to channel3(default channel1)
+ \arg SYSCFG_DMA_REMAP_ADC: remap ADC DMA requests from channel0 to channel1
+ \param[out] none
+ \retval none
+*/
+void syscfg_dma_remap_disable(uint32_t syscfg_dma_remap)
+{
+ SYSCFG_CFG0 &= ~syscfg_dma_remap;
+}
+
+/*!
+ \brief enable PB9 high current capability
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void syscfg_high_current_enable(void)
+{
+ SYSCFG_CFG0 |= SYSCFG_HIGH_CURRENT_ENABLE;
+}
+
+/*!
+ \brief disable PB9 high current capability
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void syscfg_high_current_disable(void)
+{
+ SYSCFG_CFG0 &= SYSCFG_HIGH_CURRENT_DISABLE;
+}
+
+/*!
+ \brief configure the GPIO pin as EXTI Line
+ \param[in] exti_port: specify the GPIO port used in EXTI
+ only one parameter can be selected which is shown as below:
+ \arg EXTI_SOURCE_GPIOx(x = A,B,C,D,F): EXTI GPIO port
+ \param[in] exti_pin: specify the EXTI line
+ only one parameter can be selected which is shown as below:
+ \arg EXTI_SOURCE_PINx(x = 0..15): EXTI GPIO pin
+ \param[out] none
+ \retval none
+*/
+void syscfg_exti_line_config(uint8_t exti_port, uint8_t exti_pin)
+{
+ uint32_t clear_exti_mask = ~((uint32_t)EXTI_SS_MASK << (EXTI_SS_MSTEP(exti_pin)));
+ uint32_t config_exti_mask = ((uint32_t)exti_port) << (EXTI_SS_MSTEP(exti_pin));
+
+ switch(exti_pin / EXTI_SS_JSTEP) {
+ case EXTISS0:
+ /* clear EXTI source line(0..3) */
+ SYSCFG_EXTISS0 &= clear_exti_mask;
+ /* configure EXTI soure line(0..3) */
+ SYSCFG_EXTISS0 |= config_exti_mask;
+ break;
+ case EXTISS1:
+ /* clear EXTI soure line(4..7) */
+ SYSCFG_EXTISS1 &= clear_exti_mask;
+ /* configure EXTI soure line(4..7) */
+ SYSCFG_EXTISS1 |= config_exti_mask;
+ break;
+ case EXTISS2:
+ /* clear EXTI soure line(8..11) */
+ SYSCFG_EXTISS2 &= clear_exti_mask;
+ /* configure EXTI soure line(8..11) */
+ SYSCFG_EXTISS2 |= config_exti_mask;
+ break;
+ case EXTISS3:
+ /* clear EXTI soure line(12..15) */
+ SYSCFG_EXTISS3 &= clear_exti_mask;
+ /* configure EXTI soure line(12..15) */
+ SYSCFG_EXTISS3 |= config_exti_mask;
+ break;
+ default:
+ break;
+ }
+}
+
+/*!
+ \brief connect TIMER0/14/15/16 break input to the selected parameter
+ \param[in] syscfg_lock: Specify the parameter to be connected
+ one or more parameters can be selected which is shown as below:
+ \arg SYSCFG_LOCK_LOCKUP: Cortex-M4 lockup output connected to the break input
+ \arg SYSCFG_LOCK_SRAM_PARITY_ERROR: SRAM_PARITY check error connected to the break input
+ \arg SYSCFG_LOCK_LVD: LVD interrupt connected to the break input
+ \param[out] none
+ \retval none
+*/
+void syscfg_lock_config(uint32_t syscfg_lock)
+{
+ SYSCFG_CFG2 |= syscfg_lock;
+}
+
+/*!
+ \brief check if the specified flag in SYSCFG_CFG2 is set or not.
+ \param[in] syscfg_flag: specify the flag in SYSCFG_CFG2 to check.
+ \arg SYSCFG_SRAM_PCEF: SRAM parity check error flag.
+ \param[out] none
+ \retval the syscfg_flag state returned (SET or RESET).
+ */
+FlagStatus syscfg_flag_get(uint32_t syscfg_flag)
+{
+ if((SYSCFG_CFG2 & syscfg_flag) != (uint32_t)RESET) {
+ return SET;
+ } else {
+ return RESET;
+ }
+}
+
+/*!
+ \brief clear the flag in SYSCFG_CFG2 by writing 1.
+ \param[in] syscfg_flag: Specify the flag in SYSCFG_CFG2 to clear.
+ \arg SYSCFG_SRAM_PCEF: SRAM parity check error flag.
+ \param[out] none
+ \retval none
+*/
+void syscfg_flag_clear(uint32_t syscfg_flag)
+{
+ SYSCFG_CFG2 |= (uint32_t) syscfg_flag;
+}
+
+/*!
+ \brief configure the I/O compensation cell
+ \param[in] syscfg_compensation: specifies the I/O compensation cell mode
+ only one parameter can be selected which is shown as below:
+ \arg SYSCFG_COMPENSATION_ENABLE: I/O compensation cell is enabled
+ \arg SYSCFG_COMPENSATION_DISABLE: I/O compensation cell is disabled
+ \param[out] none
+ \retval none
+*/
+void syscfg_compensation_config(uint32_t syscfg_compensation)
+{
+ uint32_t reg;
+
+ reg = SYSCFG_CPSCTL;
+ /* reset the SYSCFG_CPSCTL_CPS_EN bit and set according to syscfg_compensation */
+ reg &= ~SYSCFG_CPSCTL_CPS_EN;
+ SYSCFG_CPSCTL = (reg | syscfg_compensation);
+}
+
+/*!
+ \brief check if the I/O compensation cell ready flag is set or not
+ \param[in] none
+ \param[out] none
+ \retval FlagStatus: SET or RESET
+ */
+FlagStatus syscfg_cps_rdy_flag_get(void)
+{
+ if(((uint32_t)RESET) != (SYSCFG_CPSCTL & SYSCFG_CPSCTL_CPS_RDY)) {
+ return SET;
+ } else {
+ return RESET;
+ }
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_timer.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_timer.c
new file mode 100644
index 00000000..2a1a8f8f
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_timer.c
@@ -0,0 +1,2064 @@
+/*!
+ \file gd32f3x0_timer.c
+ \brief TIMER driver
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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.
+*/
+
+
+#include "gd32f3x0_timer.h"
+
+/*!
+ \brief deinit a TIMER
+ \param[in] timer_periph: TIMERx(x=0..2,13..16),TIMER5 just for GD32F350
+ \param[out] none
+ \retval none
+*/
+void timer_deinit(uint32_t timer_periph)
+{
+ switch(timer_periph) {
+ case TIMER0:
+ /* reset TIMER0 */
+ rcu_periph_reset_enable(RCU_TIMER0RST);
+ rcu_periph_reset_disable(RCU_TIMER0RST);
+ break;
+ case TIMER1:
+ /* reset TIMER1 */
+ rcu_periph_reset_enable(RCU_TIMER1RST);
+ rcu_periph_reset_disable(RCU_TIMER1RST);
+ break;
+ case TIMER2:
+ /* reset TIMER2 */
+ rcu_periph_reset_enable(RCU_TIMER2RST);
+ rcu_periph_reset_disable(RCU_TIMER2RST);
+ break;
+#ifdef GD32F350
+ case TIMER5:
+ /* reset TIMER5 */
+ rcu_periph_reset_enable(RCU_TIMER5RST);
+ rcu_periph_reset_disable(RCU_TIMER5RST);
+ break;
+#endif
+ case TIMER13:
+ /* reset TIMER13 */
+ rcu_periph_reset_enable(RCU_TIMER13RST);
+ rcu_periph_reset_disable(RCU_TIMER13RST);
+ break;
+ case TIMER14:
+ /* reset TIMER14 */
+ rcu_periph_reset_enable(RCU_TIMER14RST);
+ rcu_periph_reset_disable(RCU_TIMER14RST);
+ break;
+ case TIMER15:
+ /* reset TIMER15 */
+ rcu_periph_reset_enable(RCU_TIMER15RST);
+ rcu_periph_reset_disable(RCU_TIMER15RST);
+ break;
+ case TIMER16:
+ /* reset TIMER16 */
+ rcu_periph_reset_enable(RCU_TIMER16RST);
+ rcu_periph_reset_disable(RCU_TIMER16RST);
+ break;
+ default:
+ break;
+ }
+}
+
+/*!
+ \brief initialize TIMER init parameter struct with a default value
+ \param[in] initpara: init parameter struct
+ \param[out] none
+ \retval none
+*/
+void timer_struct_para_init(timer_parameter_struct *initpara)
+{
+ /* initialize the init parameter struct member with the default value */
+ initpara->prescaler = 0U;
+ initpara->alignedmode = TIMER_COUNTER_EDGE;
+ initpara->counterdirection = TIMER_COUNTER_UP;
+ initpara->period = 65535U;
+ initpara->clockdivision = TIMER_CKDIV_DIV1;
+ initpara->repetitioncounter = 0U;
+}
+
+/*!
+ \brief initialize TIMER counter
+ \param[in] timer_periph: TIMERx(x=0..2,13..16),TIMER5 just for GD32F350
+ \param[in] timer_initpara: init parameter struct
+ prescaler: prescaler value of the counter clock,0~65535
+ alignedmode: TIMER_COUNTER_EDGE,TIMER_COUNTER_CENTER_DOWN,TIMER_COUNTER_CENTER_UP,TIMER_COUNTER_CENTER_BOTH
+ counterdirection: TIMER_COUNTER_UP,TIMER_COUNTER_DOWN
+ period: counter auto reload value,(TIMER1 32 bit)
+ clockdivision: TIMER_CKDIV_DIV1,TIMER_CKDIV_DIV2,TIMER_CKDIV_DIV4
+ repetitioncounter: counter repetition value,0~255
+ \param[out] none
+ \retval none
+*/
+void timer_init(uint32_t timer_periph, timer_parameter_struct *initpara)
+{
+ /* configure the counter prescaler value */
+ TIMER_PSC(timer_periph) = (uint16_t)initpara->prescaler;
+
+ /* configure the counter direction and aligned mode */
+ if((TIMER0 == timer_periph) || (TIMER1 == timer_periph) || (TIMER2 == timer_periph)) {
+ TIMER_CTL0(timer_periph) &= ~(uint32_t)(TIMER_CTL0_DIR | TIMER_CTL0_CAM);
+ TIMER_CTL0(timer_periph) |= (uint32_t)initpara->alignedmode;
+ TIMER_CTL0(timer_periph) |= (uint32_t)initpara->counterdirection;
+ }
+
+ /* configure the autoreload value */
+ TIMER_CAR(timer_periph) = (uint32_t)initpara->period;
+
+ if((TIMER0 == timer_periph) || (TIMER1 == timer_periph) || (TIMER2 == timer_periph) || (TIMER13 == timer_periph)
+ || (TIMER14 == timer_periph) || (TIMER15 == timer_periph) || (TIMER16 == timer_periph)) {
+ /* reset the CKDIV bit */
+ TIMER_CTL0(timer_periph) &= ~(uint32_t)TIMER_CTL0_CKDIV;
+ TIMER_CTL0(timer_periph) |= (uint32_t)initpara->clockdivision;
+ }
+
+ if((TIMER0 == timer_periph) || (TIMER14 == timer_periph) || (TIMER15 == timer_periph) || (TIMER16 == timer_periph)) {
+ /* configure the repetition counter value */
+ TIMER_CREP(timer_periph) = (uint32_t)initpara->repetitioncounter;
+ }
+
+ /* generate an update event */
+ TIMER_SWEVG(timer_periph) |= (uint32_t)TIMER_SWEVG_UPG;
+}
+
+/*!
+ \brief enable a TIMER
+ \param[in] timer_periph: TIMERx(x=0..2,13..16),TIMER5 just for GD32F350
+ \param[out] none
+ \retval none
+*/
+void timer_enable(uint32_t timer_periph)
+{
+ TIMER_CTL0(timer_periph) |= (uint32_t)TIMER_CTL0_CEN;
+}
+
+/*!
+ \brief disable a TIMER
+ \param[in] timer_periph: TIMERx(x=0..2,13..16),TIMER5 just for GD32F350
+ \param[out] none
+ \retval none
+*/
+void timer_disable(uint32_t timer_periph)
+{
+ TIMER_CTL0(timer_periph) &= ~(uint32_t)TIMER_CTL0_CEN;
+}
+
+/*!
+ \brief enable the auto reload shadow function
+ \param[in] timer_periph: TIMERx(x=0..2,13..16),TIMER5 just for GD32F350
+ \param[out] none
+ \retval none
+*/
+void timer_auto_reload_shadow_enable(uint32_t timer_periph)
+{
+ TIMER_CTL0(timer_periph) |= (uint32_t)TIMER_CTL0_ARSE;
+}
+
+/*!
+ \brief disable the auto reload shadow function
+ \param[in] timer_periph: TIMERx(x=0..2,13..16),TIMER5 just for GD32F350
+ \param[out] none
+ \retval none
+*/
+void timer_auto_reload_shadow_disable(uint32_t timer_periph)
+{
+ TIMER_CTL0(timer_periph) &= ~(uint32_t)TIMER_CTL0_ARSE;
+}
+
+/*!
+ \brief enable the update event
+ \param[in] timer_periph: TIMERx(x=0..2,13..16),TIMER5 just for GD32F350
+ \param[out] none
+ \retval none
+*/
+void timer_update_event_enable(uint32_t timer_periph)
+{
+ TIMER_CTL0(timer_periph) &= ~(uint32_t)TIMER_CTL0_UPDIS;
+}
+
+/*!
+ \brief disable the update event
+ \param[in] timer_periph: TIMERx(x=0..2,13..16),TIMER5 just for GD32F350
+ \param[out] none
+ \retval none
+*/
+void timer_update_event_disable(uint32_t timer_periph)
+{
+ TIMER_CTL0(timer_periph) |= (uint32_t) TIMER_CTL0_UPDIS;
+}
+
+/*!
+ \brief set TIMER counter alignment mode
+ \param[in] timer_periph: TIMERx(x=0..2)
+ \param[in] aligned:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_COUNTER_EDGE: edge-aligned mode
+ \arg TIMER_COUNTER_CENTER_DOWN: center-aligned and counting down assert mode
+ \arg TIMER_COUNTER_CENTER_UP: center-aligned and counting up assert mode
+ \arg TIMER_COUNTER_CENTER_BOTH: center-aligned and counting up/down assert mode
+ \param[out] none
+ \retval none
+*/
+void timer_counter_alignment(uint32_t timer_periph, uint16_t aligned)
+{
+ TIMER_CTL0(timer_periph) &= ~(uint32_t)TIMER_CTL0_CAM;
+ TIMER_CTL0(timer_periph) |= (uint32_t)aligned;
+}
+
+/*!
+ \brief set TIMER counter up direction
+ \param[in] timer_periph: TIMERx(x=0..2)
+ \param[out] none
+ \retval none
+*/
+void timer_counter_up_direction(uint32_t timer_periph)
+{
+ TIMER_CTL0(timer_periph) &= ~(uint32_t)TIMER_CTL0_DIR;
+}
+
+/*!
+ \brief set TIMER counter down direction
+ \param[in] timer_periph: TIMERx(x=0..2)
+ \param[out] none
+ \retval none
+*/
+void timer_counter_down_direction(uint32_t timer_periph)
+{
+ TIMER_CTL0(timer_periph) |= (uint32_t)TIMER_CTL0_DIR;
+}
+
+/*!
+ \brief configure TIMER prescaler
+ \param[in] timer_periph: TIMERx(x=0..2,13..16),TIMER5 just for GD32F350
+ \param[in] prescaler: prescaler value
+ \param[in] pscreload: prescaler reload mode
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_PSC_RELOAD_NOW: the prescaler is loaded right now
+ \arg TIMER_PSC_RELOAD_UPDATE: the prescaler is loaded at the next update event
+ \param[out] none
+ \retval none
+*/
+void timer_prescaler_config(uint32_t timer_periph, uint16_t prescaler, uint8_t pscreload)
+{
+ TIMER_PSC(timer_periph) = (uint32_t)prescaler;
+
+ if(TIMER_PSC_RELOAD_NOW == pscreload) {
+ TIMER_SWEVG(timer_periph) |= (uint32_t)TIMER_SWEVG_UPG;
+ }
+}
+
+/*!
+ \brief configure TIMER repetition register value
+ \param[in] timer_periph: TIMERx(x=0,15,16)
+ \param[in] repetition: the counter repetition value,0~255
+ \param[out] none
+ \retval none
+*/
+void timer_repetition_value_config(uint32_t timer_periph, uint16_t repetition)
+{
+ TIMER_CREP(timer_periph) = (uint32_t)repetition;
+}
+
+/*!
+ \brief configure TIMER autoreload register value
+ \param[in] timer_periph: TIMERx(x=0..2,13..16),TIMER5 just for GD32F350
+ \param[in] autoreload: the counter auto-reload value
+ \param[out] none
+ \retval none
+*/
+void timer_autoreload_value_config(uint32_t timer_periph, uint32_t autoreload)
+{
+ TIMER_CAR(timer_periph) = (uint32_t)autoreload;
+}
+
+/*!
+ \brief configure TIMER counter register value
+ \param[in] timer_periph: TIMERx(x=0..2,13..16),TIMER5 just for GD32F350
+ \param[in] counter: the counter value
+ \param[out] none
+ \retval none
+*/
+void timer_counter_value_config(uint32_t timer_periph, uint32_t counter)
+{
+ TIMER_CNT(timer_periph) = (uint32_t)counter;
+}
+
+/*!
+ \brief read TIMER counter value
+ \param[in] timer_periph: TIMERx(x=0..2,13..16),TIMER5 just for GD32F350
+ \param[out] none
+ \retval counter value
+*/
+uint32_t timer_counter_read(uint32_t timer_periph)
+{
+ uint32_t count_value = 0U;
+ count_value = TIMER_CNT(timer_periph);
+ return (count_value);
+}
+
+/*!
+ \brief read TIMER prescaler value
+ \param[in] timer_periph: TIMERx(x=0..2,13..16),TIMER5 just for GD32F350
+ \param[out] none
+ \retval prescaler register value
+*/
+uint16_t timer_prescaler_read(uint32_t timer_periph)
+{
+ uint16_t prescaler_value = 0U;
+ prescaler_value = (uint16_t)(TIMER_PSC(timer_periph));
+ return (prescaler_value);
+}
+
+/*!
+ \brief configure TIMER single pulse mode
+ \param[in] timer_periph: TIMERx(x=0..2,14..16),TIMER5 just for GD32F350
+ \param[in] spmode:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_SP_MODE_SINGLE: single pulse mode
+ \arg TIMER_SP_MODE_REPETITIVE: repetitive pulse mode
+ \param[out] none
+ \retval none
+*/
+void timer_single_pulse_mode_config(uint32_t timer_periph, uint8_t spmode)
+{
+ if(TIMER_SP_MODE_SINGLE == spmode) {
+ TIMER_CTL0(timer_periph) |= (uint32_t)TIMER_CTL0_SPM;
+ } else if(TIMER_SP_MODE_REPETITIVE == spmode) {
+ TIMER_CTL0(timer_periph) &= ~((uint32_t)TIMER_CTL0_SPM);
+ } else {
+ /* illegal parameters */
+ }
+}
+
+/*!
+ \brief configure TIMER update source
+ \param[in] timer_periph: TIMERx(x=0..2,13..16),TIMER5 just for GD32F350
+ \param[in] update:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_UPDATE_SRC_GLOBAL: update generate by setting of UPG bit or the counter overflow/underflow,or the slave mode controller trigger
+ \arg TIMER_UPDATE_SRC_REGULAR: update generate only by counter overflow/underflow
+ \param[out] none
+ \retval none
+*/
+void timer_update_source_config(uint32_t timer_periph, uint8_t update)
+{
+ if(TIMER_UPDATE_SRC_REGULAR == update) {
+ TIMER_CTL0(timer_periph) |= (uint32_t)TIMER_CTL0_UPS;
+ } else if(TIMER_UPDATE_SRC_GLOBAL == update) {
+ TIMER_CTL0(timer_periph) &= ~(uint32_t)TIMER_CTL0_UPS;
+ } else {
+ /* illegal parameters */
+ }
+}
+
+/*!
+ \brief configure TIMER OCPRE clear source selection
+ \param[in] timer_periph: TIMERx(x=0..2)
+ \param[in] ocpreclear:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_OCPRE_CLEAR_SOURCE_CLR: OCPRE_CLR_INT is connected to the OCPRE_CLR input
+ \arg TIMER_OCPRE_CLEAR_SOURCE_ETIF: OCPRE_CLR_INT is connected to ETIF
+ \param[out] none
+ \retval none
+*/
+void timer_ocpre_clear_source_config(uint32_t timer_periph, uint8_t ocpreclear)
+{
+ if(TIMER_OCPRE_CLEAR_SOURCE_ETIF == ocpreclear) {
+ TIMER_SMCFG(timer_periph) |= (uint32_t)TIMER_SMCFG_OCRC;
+ } else if(TIMER_OCPRE_CLEAR_SOURCE_CLR == ocpreclear) {
+ TIMER_SMCFG(timer_periph) &= ~(uint32_t)TIMER_SMCFG_OCRC;
+ } else {
+ /* illegal parameters */
+ }
+}
+
+/*!
+ \brief get TIMER flags
+ \param[in] timer_periph: please refer to the following parameters
+ \param[in] flag: the timer interrupt flags
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_FLAG_UP: update flag, TIMERx(x=0..2,13..16),TIMER5 just for GD32F350
+ \arg TIMER_FLAG_CH0: channel 0 flag, TIMERx(x=0..2,13..16)
+ \arg TIMER_FLAG_CH1: channel 1 flag, TIMERx(x=0..2,14)
+ \arg TIMER_FLAG_CH2: channel 2 flag, TIMERx(x=0..2)
+ \arg TIMER_FLAG_CH3: channel 3 flag, TIMERx(x=0..2)
+ \arg TIMER_FLAG_CMT: channel control update flag, TIMERx(x=0,14..16)
+ \arg TIMER_FLAG_TRG: trigger flag, TIMERx(x=0..2,14)
+ \arg TIMER_FLAG_BRK: break flag,TIMERx(x=0,14..16)
+ \arg TIMER_FLAG_CH0O: channel 0 overcapture flag, TIMERx(x=0..2,13..16)
+ \arg TIMER_FLAG_CH1O: channel 1 overcapture flag, TIMERx(x=0..2,14)
+ \arg TIMER_FLAG_CH2O: channel 2 overcapture flag, TIMERx(x=0..2)
+ \arg TIMER_FLAG_CH3O: channel 3 overcapture flag, TIMERx(x=0..2)
+ \param[out] none
+ \retval FlagStatus: SET or RESET
+*/
+FlagStatus timer_flag_get(uint32_t timer_periph, uint32_t flag)
+{
+ if(RESET != (TIMER_INTF(timer_periph) & flag)) {
+ return SET;
+ } else {
+ return RESET;
+ }
+}
+
+/*!
+ \brief clear TIMER flags
+ \param[in] timer_periph: please refer to the following parameters
+ \param[in] flag: the timer interrupt flags
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_FLAG_UP: update flag, TIMERx(x=0..2,13..16),TIMER5 just for GD32F350
+ \arg TIMER_FLAG_CH0: channel 0 flag, TIMERx(x=0..2,13..16)
+ \arg TIMER_FLAG_CH1: channel 1 flag, TIMERx(x=0..2,14)
+ \arg TIMER_FLAG_CH2: channel 2 flag, TIMERx(x=0..2)
+ \arg TIMER_FLAG_CH3: channel 3 flag, TIMERx(x=0..2)
+ \arg TIMER_FLAG_CMT: channel control update flag, TIMERx(x=0,14..16)
+ \arg TIMER_FLAG_TRG: trigger flag, TIMERx(x=0..2,14)
+ \arg TIMER_FLAG_BRK: break flag,TIMERx(x=0,14..16)
+ \arg TIMER_FLAG_CH0O: channel 0 overcapture flag, TIMERx(x=0..2,13..16)
+ \arg TIMER_FLAG_CH1O: channel 1 overcapture flag, TIMERx(x=0..2,14)
+ \arg TIMER_FLAG_CH2O: channel 2 overcapture flag, TIMERx(x=0..2)
+ \arg TIMER_FLAG_CH3O: channel 3 overcapture flag, TIMERx(x=0..2)
+ \param[out] none
+ \retval none
+*/
+void timer_flag_clear(uint32_t timer_periph, uint32_t flag)
+{
+ TIMER_INTF(timer_periph) = (~(uint32_t)flag);
+}
+
+/*!
+ \brief enable the TIMER interrupt
+ \param[in] timer_periph: please refer to the following parameters
+ \param[in] interrupt: timer interrupt enable source
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_INT_UP: update interrupt enable, TIMERx(x=0..2,13..16),TIMER5 just for GD32F350
+ \arg TIMER_INT_CH0: channel 0 interrupt enable, TIMERx(x=0..2,13..16)
+ \arg TIMER_INT_CH1: channel 1 interrupt enable, TIMERx(x=0..2,14)
+ \arg TIMER_INT_CH2: channel 2 interrupt enable, TIMERx(x=0..2)
+ \arg TIMER_INT_CH3: channel 3 interrupt enable , TIMERx(x=0..2)
+ \arg TIMER_INT_CMT: commutation interrupt enable, TIMERx(x=0,14..16)
+ \arg TIMER_INT_TRG: trigger interrupt enable, TIMERx(x=0..2,14)
+ \arg TIMER_INT_BRK: break interrupt enable, TIMERx(x=0,14..16)
+ \param[out] none
+ \retval none
+*/
+void timer_interrupt_enable(uint32_t timer_periph, uint32_t interrupt)
+{
+ TIMER_DMAINTEN(timer_periph) |= (uint32_t) interrupt;
+}
+
+/*!
+ \brief disable the TIMER interrupt
+ \param[in] timer_periph: please refer to the following parameters
+ \param[in] interrupt: timer interrupt source disable
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_INT_UP: update interrupt disable, TIMERx(x=0..2,13..16),TIMER5 just for GD32F350
+ \arg TIMER_INT_CH0: channel 0 interrupt disable, TIMERx(x=0..2,13..16)
+ \arg TIMER_INT_CH1: channel 1 interrupt disable, TIMERx(x=0..2,14)
+ \arg TIMER_INT_CH2: channel 2 interrupt disable, TIMERx(x=0..2)
+ \arg TIMER_INT_CH3: channel 3 interrupt disable , TIMERx(x=0..2)
+ \arg TIMER_INT_CMT: commutation interrupt disable, TIMERx(x=0,14..16)
+ \arg TIMER_INT_TRG: trigger interrupt disable, TIMERx(x=0..2,14)
+ \arg TIMER_INT_BRK: break interrupt disable, TIMERx(x=0,14..16)
+ \param[out] none
+ \retval none
+*/
+void timer_interrupt_disable(uint32_t timer_periph, uint32_t interrupt)
+{
+ TIMER_DMAINTEN(timer_periph) &= (~(uint32_t)interrupt);
+}
+
+/*!
+ \brief get timer interrupt flag
+ \param[in] timer_periph: please refer to the following parameters
+ \param[in] interrupt: the timer interrupt bits
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_INT_FLAG_UP: update interrupt flag,TIMERx(x=0..2,13..16),TIMER5 just for GD32F350
+ \arg TIMER_INT_FLAG_CH0: channel 0 interrupt flag,TIMERx(x=0..2,13..16)
+ \arg TIMER_INT_FLAG_CH1: channel 1 interrupt flag,TIMERx(x=0..2,14)
+ \arg TIMER_INT_FLAG_CH2: channel 2 interrupt flag,TIMERx(x=0..2)
+ \arg TIMER_INT_FLAG_CH3: channel 3 interrupt flag,TIMERx(x=0..2)
+ \arg TIMER_INT_FLAG_CMT: channel commutation interrupt flag,TIMERx(x=0,14..16)
+ \arg TIMER_INT_FLAG_TRG: trigger interrupt flag,TIMERx(x=0..2,14)
+ \arg TIMER_INT_FLAG_BRK: break interrupt flag,TIMERx(x=0,14..16)
+ \param[out] none
+ \retval FlagStatus: SET or RESET
+*/
+FlagStatus timer_interrupt_flag_get(uint32_t timer_periph, uint32_t interrupt)
+{
+ uint32_t val;
+ val = (TIMER_DMAINTEN(timer_periph) & interrupt);
+ if((RESET != (TIMER_INTF(timer_periph) & interrupt)) && (RESET != val)) {
+ return SET;
+ } else {
+ return RESET;
+ }
+}
+
+/*!
+ \brief clear TIMER interrupt flag
+ \param[in] timer_periph: please refer to the following parameters
+ \param[in] interrupt: the timer interrupt bits
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_INT_FLAG_UP: update interrupt flag, TIMERx(x=0..2,13..16),TIMER5 just for GD32F350
+ \arg TIMER_INT_FLAG_CH0: channel 0 interrupt flag, TIMERx(x=0..2,13..16)
+ \arg TIMER_INT_FLAG_CH1: channel 1 interrupt flag, TIMERx(x=0..2,14)
+ \arg TIMER_INT_FLAG_CH2: channel 2 interrupt flag, TIMERx(x=0..2)
+ \arg TIMER_INT_FLAG_CH3: channel 3 interrupt flag, TIMERx(x=0..2)
+ \arg TIMER_INT_FLAG_CMT: channel commutation interrupt flag, TIMERx(x=0,14..16)
+ \arg TIMER_INT_FLAG_TRG: trigger interrupt flag, TIMERx(x=0..2,14)
+ \arg TIMER_INT_FLAG_BRK: break interrupt flag, TIMERx(x=0,14..16)
+ \param[out] none
+ \retval none
+*/
+void timer_interrupt_flag_clear(uint32_t timer_periph, uint32_t interrupt)
+{
+ TIMER_INTF(timer_periph) = (~(uint32_t)interrupt);
+}
+
+/*!
+ \brief enable the TIMER DMA
+ \param[in] timer_periph: please refer to the following parameters
+ \param[in] dma: specify which DMA to enable
+ one or more parameters can be selected which is shown as below:
+ \arg TIMER_DMA_UPD: update DMA, TIMERx(x=0..2,14..16),TIMER5 just for GD32F350
+ \arg TIMER_DMA_CH0D: channel 0 DMA request, TIMERx(x=0..2,14..16)
+ \arg TIMER_DMA_CH1D: channel 1 DMA request, TIMERx(x=0..2,14)
+ \arg TIMER_DMA_CH2D: channel 2 DMA request, TIMERx(x=0..2)
+ \arg TIMER_DMA_CH3D: channel 3 DMA request, TIMERx(x=0..2)
+ \arg TIMER_DMA_CMTD: commutation DMA request, TIMERx(x=0,14)
+ \arg TIMER_DMA_TRGD: trigger DMA request, TIMERx(x=0..2,14)
+ \param[out] none
+ \retval none
+*/
+void timer_dma_enable(uint32_t timer_periph, uint16_t dma)
+{
+ TIMER_DMAINTEN(timer_periph) |= (uint32_t) dma;
+}
+
+/*!
+ \brief disable the TIMER DMA
+ \param[in] timer_periph: please refer to the following parameters
+ \param[in] dma: specify which DMA to disable
+ one or more parameters can be selected which are shown as below:
+ \arg TIMER_DMA_UPD: update DMA, TIMERx(x=0..2,14..16),TIMER5 just for GD32F350
+ \arg TIMER_DMA_CH0D: channel 0 DMA request, TIMERx(x=0..2,14..16)
+ \arg TIMER_DMA_CH1D: channel 1 DMA request, TIMERx(x=0..2,14)
+ \arg TIMER_DMA_CH2D: channel 2 DMA request, TIMERx(x=0..2)
+ \arg TIMER_DMA_CH3D: channel 3 DMA request, TIMERx(x=0..2)
+ \arg TIMER_DMA_CMTD: commutation DMA request , TIMERx(x=0,14)
+ \arg TIMER_DMA_TRGD: trigger DMA request, TIMERx(x=0..2,14)
+ \param[out] none
+ \retval none
+*/
+void timer_dma_disable(uint32_t timer_periph, uint16_t dma)
+{
+ TIMER_DMAINTEN(timer_periph) &= (~(uint32_t)(dma));
+}
+
+/*!
+ \brief channel DMA request source selection
+ \param[in] timer_periph: TIMERx(x=0..2,14..16)
+ \param[in] dma_request: channel DMA request source selection
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_DMAREQUEST_CHANNELEVENT: DMA request of channel y is sent when channel y event occurs
+ \arg TIMER_DMAREQUEST_UPDATEEVENT: DMA request of channel y is sent when update event occurs
+ \param[out] none
+ \retval none
+*/
+void timer_channel_dma_request_source_select(uint32_t timer_periph, uint8_t dma_request)
+{
+ if(TIMER_DMAREQUEST_UPDATEEVENT == dma_request) {
+ TIMER_CTL1(timer_periph) |= (uint32_t)TIMER_CTL1_DMAS;
+ } else if(TIMER_DMAREQUEST_CHANNELEVENT == dma_request) {
+ TIMER_CTL1(timer_periph) &= ~(uint32_t)TIMER_CTL1_DMAS;
+ } else {
+ /* illegal parameters */
+ }
+}
+
+/*!
+ \brief configure the TIMER DMA transfer
+ \param[in] timer_periph: TIMERx(x=0..2,14..16)
+ \param[in] dma_baseaddr:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_DMACFG_DMATA_CTL0: DMA transfer address is TIMER_CTL0, TIMERx(x=0..2,14..16)
+ \arg TIMER_DMACFG_DMATA_CTL1: DMA transfer address is TIMER_CTL1, TIMERx(x=0..2,14..16)
+ \arg TIMER_DMACFG_DMATA_SMCFG: DMA transfer address is TIMER_SMCFG, TIMERx(x=0..2,14)
+ \arg TIMER_DMACFG_DMATA_DMAINTEN: DMA transfer address is TIMER_DMAINTEN, TIMERx(x=0..2,14..16)
+ \arg TIMER_DMACFG_DMATA_INTF: DMA transfer address is TIMER_INTF, TIMERx(x=0..2,14..16)
+ \arg TIMER_DMACFG_DMATA_SWEVG: DMA transfer address is TIMER_SWEVG, TIMERx(x=0..2,14..16)
+ \arg TIMER_DMACFG_DMATA_CHCTL0: DMA transfer address is TIMER_CHCTL0, TIMERx(x=0..2,14..16)
+ \arg TIMER_DMACFG_DMATA_CHCTL1: DMA transfer address is TIMER_CHCTL1, TIMERx(x=0..2)
+ \arg TIMER_DMACFG_DMATA_CHCTL2: DMA transfer address is TIMER_CHCTL2, TIMERx(x=0..2,14..16)
+ \arg TIMER_DMACFG_DMATA_CNT: DMA transfer address is TIMER_CNT, TIMERx(x=0..2,14..16)
+ \arg TIMER_DMACFG_DMATA_PSC: DMA transfer address is TIMER_PSC, TIMERx(x=0..2,14..16)
+ \arg TIMER_DMACFG_DMATA_CAR: DMA transfer address is TIMER_CAR, TIMERx(x=0..2,14..16)
+ \arg TIMER_DMACFG_DMATA_CREP: DMA transfer address is TIMER_CREP, TIMERx(x=0,14..16)
+ \arg TIMER_DMACFG_DMATA_CH0CV: DMA transfer address is TIMER_CH0CV, TIMERx(x=0..2,14..16)
+ \arg TIMER_DMACFG_DMATA_CH1CV: DMA transfer address is TIMER_CH1CV, TIMERx(x=0..2,14)
+ \arg TIMER_DMACFG_DMATA_CH2CV: DMA transfer address is TIMER_CH2CV, TIMERx(x=0..2)
+ \arg TIMER_DMACFG_DMATA_CH3CV: DMA transfer address is TIMER_CH3CV, TIMERx(x=0..2)
+ \arg TIMER_DMACFG_DMATA_CCHP: DMA transfer address is TIMER_CCHP, TIMERx(x=0,14..16)
+ \arg TIMER_DMACFG_DMATA_DMACFG: DMA transfer address is TIMER_DMACFG, TIMERx(x=0..2,14..16)
+ \arg TIMER_DMACFG_DMATA_DMATB: DMA transfer address is TIMER_DMATB, TIMERx(x=0..2,14..16)
+ \param[in] dma_lenth:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_DMACFG_DMATC_xTRANSFER(x=1..18): DMA transfer x time
+ \param[out] none
+ \retval none
+*/
+void timer_dma_transfer_config(uint32_t timer_periph, uint32_t dma_baseaddr, uint32_t dma_lenth)
+{
+ TIMER_DMACFG(timer_periph) &= (~(uint32_t)(TIMER_DMACFG_DMATA | TIMER_DMACFG_DMATC));
+ TIMER_DMACFG(timer_periph) |= (uint32_t)(dma_baseaddr | dma_lenth);
+}
+
+/*!
+ \brief software generate events
+ \param[in] timer_periph: please refer to the following parameters
+ \param[in] event: the timer software event generation sources
+ one or more parameters can be selected which are shown as below:
+ \arg TIMER_EVENT_SRC_UPG: update event,TIMERx(x=0..2,13..16), TIMER5 just for GD32F350
+ \arg TIMER_EVENT_SRC_CH0G: channel 0 capture or compare event generation, TIMERx(x=0..2,13..16)
+ \arg TIMER_EVENT_SRC_CH1G: channel 1 capture or compare event generation, TIMERx(x=0..2,14)
+ \arg TIMER_EVENT_SRC_CH2G: channel 2 capture or compare event generation, TIMERx(x=0..2)
+ \arg TIMER_EVENT_SRC_CH3G: channel 3 capture or compare event generation, TIMERx(x=0..2)
+ \arg TIMER_EVENT_SRC_CMTG: channel commutation event generation, TIMERx(x=0,14..16)
+ \arg TIMER_EVENT_SRC_TRGG: trigger event generation, TIMERx(x=0..2,14)
+ \arg TIMER_EVENT_SRC_BRKG: break event generation, TIMERx(x=0,14..16)
+ \param[out] none
+ \retval none
+*/
+void timer_event_software_generate(uint32_t timer_periph, uint16_t event)
+{
+ TIMER_SWEVG(timer_periph) |= (uint32_t)event;
+}
+
+/*!
+ \brief initialize TIMER break parameter struct with a default value
+ \param[in] breakpara: TIMER break parameter struct
+ \param[out] none
+ \retval none
+*/
+void timer_break_struct_para_init(timer_break_parameter_struct *breakpara)
+{
+ /* initialize the break parameter struct member with the default value */
+ breakpara->runoffstate = TIMER_ROS_STATE_DISABLE;
+ breakpara->ideloffstate = TIMER_IOS_STATE_DISABLE;
+ breakpara->deadtime = 0U;
+ breakpara->breakpolarity = TIMER_BREAK_POLARITY_LOW;
+ breakpara->outputautostate = TIMER_OUTAUTO_DISABLE;
+ breakpara->protectmode = TIMER_CCHP_PROT_OFF;
+ breakpara->breakstate = TIMER_BREAK_DISABLE;
+}
+
+/*!
+ \brief configure TIMER break function
+ \param[in] timer_periph: TIMERx(x=0,14..16)
+ \param[in] breakpara: TIMER break parameter struct
+ runoffstate: TIMER_ROS_STATE_ENABLE,TIMER_ROS_STATE_DISABLE
+ ideloffstate: TIMER_IOS_STATE_ENABLE,TIMER_IOS_STATE_DISABLE
+ deadtime: 0~255
+ breakpolarity: TIMER_BREAK_POLARITY_LOW,TIMER_BREAK_POLARITY_HIGH
+ outputautostate: TIMER_OUTAUTO_ENABLE,TIMER_OUTAUTO_DISABLE
+ protectmode: TIMER_CCHP_PROT_OFF,TIMER_CCHP_PROT_0,TIMER_CCHP_PROT_1,TIMER_CCHP_PROT_2
+ breakstate: TIMER_BREAK_ENABLE,TIMER_BREAK_DISABLE
+ \param[out] none
+ \retval none
+*/
+void timer_break_config(uint32_t timer_periph, timer_break_parameter_struct *breakpara)
+{
+ TIMER_CCHP(timer_periph) = (uint32_t)(((uint32_t)(breakpara->runoffstate)) |
+ ((uint32_t)(breakpara->ideloffstate)) |
+ ((uint32_t)(breakpara->deadtime)) |
+ ((uint32_t)(breakpara->breakpolarity)) |
+ ((uint32_t)(breakpara->outputautostate)) |
+ ((uint32_t)(breakpara->protectmode)) |
+ ((uint32_t)(breakpara->breakstate))) ;
+}
+
+/*!
+ \brief enable TIMER break function
+ \param[in] timer_periph: TIMERx(x=0,14..16)
+ \param[out] none
+ \retval none
+*/
+void timer_break_enable(uint32_t timer_periph)
+{
+ TIMER_CCHP(timer_periph) |= (uint32_t)TIMER_CCHP_BRKEN;
+}
+
+/*!
+ \brief disable TIMER break function
+ \param[in] timer_periph: TIMERx(x=0,14..16)
+ \param[out] none
+ \retval none
+*/
+void timer_break_disable(uint32_t timer_periph)
+{
+ TIMER_CCHP(timer_periph) &= ~(uint32_t)TIMER_CCHP_BRKEN;
+}
+
+/*!
+ \brief enable TIMER output automatic function
+ \param[in] timer_periph: TIMERx(x=0,14..16)
+ \param[out] none
+ \retval none
+*/
+void timer_automatic_output_enable(uint32_t timer_periph)
+{
+ TIMER_CCHP(timer_periph) |= (uint32_t)TIMER_CCHP_OAEN;
+}
+
+/*!
+ \brief disable TIMER output automatic function
+ \param[in] timer_periph: TIMERx(x=0,14..16)
+ \param[out] none
+ \retval none
+*/
+void timer_automatic_output_disable(uint32_t timer_periph)
+{
+ TIMER_CCHP(timer_periph) &= ~(uint32_t)TIMER_CCHP_OAEN;
+}
+
+/*!
+ \brief configure TIMER primary output function
+ \param[in] timer_periph: TIMERx(x=0,14..16)
+ \param[in] newvalue: ENABLE or DISABLE
+ \param[out] none
+ \retval none
+*/
+void timer_primary_output_config(uint32_t timer_periph, ControlStatus newvalue)
+{
+ if(ENABLE == newvalue) {
+ TIMER_CCHP(timer_periph) |= (uint32_t)TIMER_CCHP_POEN;
+ } else {
+ TIMER_CCHP(timer_periph) &= (~(uint32_t)TIMER_CCHP_POEN);
+ }
+}
+
+/*!
+ \brief enable or disable channel capture/compare control shadow register
+ \param[in] timer_periph: TIMERx(x=0,14..16)
+ \param[in] newvalue: ENABLE or DISABLE
+ \param[out] none
+ \retval none
+*/
+void timer_channel_control_shadow_config(uint32_t timer_periph, ControlStatus newvalue)
+{
+ if(ENABLE == newvalue) {
+ TIMER_CTL1(timer_periph) |= (uint32_t)TIMER_CTL1_CCSE;
+ } else {
+ TIMER_CTL1(timer_periph) &= (~(uint32_t)TIMER_CTL1_CCSE);
+ }
+}
+
+/*!
+ \brief configure TIMER channel control shadow register update control
+ \param[in] timer_periph: TIMERx(x=0,14..16)
+ \param[in] ccuctl: channel control shadow register update control
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_UPDATECTL_CCU: the shadow registers update by when CMTG bit is set
+ \arg TIMER_UPDATECTL_CCUTRI: the shadow registers update by when CMTG bit is set or an rising edge of TRGI occurs
+ \param[out] none
+ \retval none
+*/
+void timer_channel_control_shadow_update_config(uint32_t timer_periph, uint8_t ccuctl)
+{
+ if(TIMER_UPDATECTL_CCU == ccuctl) {
+ TIMER_CTL1(timer_periph) &= (~(uint32_t)TIMER_CTL1_CCUC);
+ } else if(TIMER_UPDATECTL_CCUTRI == ccuctl) {
+ TIMER_CTL1(timer_periph) |= (uint32_t)TIMER_CTL1_CCUC;
+ } else {
+ /* illegal parameters */
+ }
+}
+
+/*!
+ \brief initialize TIMER channel output parameter struct with a default value
+ \param[in] ocpara: TIMER channel n output parameter struct
+ \param[out] none
+ \retval none
+*/
+void timer_channel_output_struct_para_init(timer_oc_parameter_struct *ocpara)
+{
+ /* initialize the channel output parameter struct member with the default value */
+ ocpara->outputstate = (uint16_t)TIMER_CCX_DISABLE;
+ ocpara->outputnstate = TIMER_CCXN_DISABLE;
+ ocpara->ocpolarity = TIMER_OC_POLARITY_HIGH;
+ ocpara->ocnpolarity = TIMER_OCN_POLARITY_HIGH;
+ ocpara->ocidlestate = TIMER_OC_IDLE_STATE_LOW;
+ ocpara->ocnidlestate = TIMER_OCN_IDLE_STATE_LOW;
+}
+
+/*!
+ \brief configure TIMER channel output function
+ \param[in] timer_periph: please refer to the following parameters
+ \param[in] channel:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_CH_0: TIMER channel 0(TIMERx(x=0..2,13..16))
+ \arg TIMER_CH_1: TIMER channel 1(TIMERx(x=0..2,14))
+ \arg TIMER_CH_2: TIMER channel 2(TIMERx(x=0..2))
+ \arg TIMER_CH_3: TIMER channel 3(TIMERx(x=0..2))
+ \param[in] ocpara: TIMER channeln output parameter struct
+ outputstate: TIMER_CCX_ENABLE,TIMER_CCX_DISABLE
+ outputnstate: TIMER_CCXN_ENABLE,TIMER_CCXN_DISABLE
+ ocpolarity: TIMER_OC_POLARITY_HIGH,TIMER_OC_POLARITY_LOW
+ ocnpolarity: TIMER_OCN_POLARITY_HIGH,TIMER_OCN_POLARITY_LOW
+ ocidlestate: TIMER_OC_IDLE_STATE_LOW,TIMER_OC_IDLE_STATE_HIGH
+ ocnidlestate: TIMER_OCN_IDLE_STATE_LOW,TIMER_OCN_IDLE_STATE_HIGH
+ \param[out] none
+ \retval none
+*/
+void timer_channel_output_config(uint32_t timer_periph, uint16_t channel, timer_oc_parameter_struct *ocpara)
+{
+ switch(channel) {
+ /* configure TIMER_CH_0 */
+ case TIMER_CH_0:
+ /* reset the CH0EN bit */
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH0EN);
+ TIMER_CHCTL0(timer_periph) &= ~(uint32_t)TIMER_CHCTL0_CH0MS;
+ /* set the CH0EN bit */
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)ocpara->outputstate;
+ /* reset the CH0P bit */
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH0P);
+ /* set the CH0P bit */
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)ocpara->ocpolarity;
+
+ if((TIMER0 == timer_periph) || (TIMER14 == timer_periph) || (TIMER15 == timer_periph) || (TIMER16 == timer_periph)) {
+ /* reset the CH0NEN bit */
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH0NEN);
+ /* set the CH0NEN bit */
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)ocpara->outputnstate;
+ /* reset the CH0NP bit */
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH0NP);
+ /* set the CH0NP bit */
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)ocpara->ocnpolarity;
+ /* reset the ISO0 bit */
+ TIMER_CTL1(timer_periph) &= (~(uint32_t)TIMER_CTL1_ISO0);
+ /* set the ISO0 bit */
+ TIMER_CTL1(timer_periph) |= (uint32_t)ocpara->ocidlestate;
+ /* reset the ISO0N bit */
+ TIMER_CTL1(timer_periph) &= (~(uint32_t)TIMER_CTL1_ISO0N);
+ /* set the ISO0N bit */
+ TIMER_CTL1(timer_periph) |= (uint32_t)ocpara->ocnidlestate;
+ }
+ break;
+ /* configure TIMER_CH_1 */
+ case TIMER_CH_1:
+ /* reset the CH1EN bit */
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH1EN);
+ TIMER_CHCTL0(timer_periph) &= ~(uint32_t)TIMER_CHCTL0_CH1MS;
+ /* set the CH1EN bit */
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)(ocpara->outputstate << 4U);
+ /* reset the CH1P bit */
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH1P);
+ /* set the CH1P bit */
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)(ocpara->ocpolarity) << 4U);
+
+ if(TIMER0 == timer_periph) {
+ /* reset the CH1NEN bit */
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH1NEN);
+ /* set the CH1NEN bit */
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)(ocpara->outputnstate) << 4U);
+ /* reset the CH1NP bit */
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH1NP);
+ /* set the CH1NP bit */
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)(ocpara->ocnpolarity) << 4U);
+ /* reset the ISO1 bit */
+ TIMER_CTL1(timer_periph) &= (~(uint32_t)TIMER_CTL1_ISO1);
+ /* set the ISO1 bit */
+ TIMER_CTL1(timer_periph) |= (uint32_t)((uint32_t)(ocpara->ocidlestate) << 2U);
+ /* reset the ISO1N bit */
+ TIMER_CTL1(timer_periph) &= (~(uint32_t)TIMER_CTL1_ISO1N);
+ /* set the ISO1N bit */
+ TIMER_CTL1(timer_periph) |= (uint32_t)((uint32_t)(ocpara->ocnidlestate) << 2U);
+ }
+
+ if(TIMER14 == timer_periph) {
+ /* reset the ISO1 bit */
+ TIMER_CTL1(timer_periph) &= (~(uint32_t)TIMER_CTL1_ISO1);
+ /* set the ISO1 bit */
+ TIMER_CTL1(timer_periph) |= (uint32_t)((uint32_t)(ocpara->ocidlestate) << 2U);
+ }
+
+ break;
+ /* configure TIMER_CH_2 */
+ case TIMER_CH_2:
+ /* reset the CH2EN bit */
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH2EN);
+ TIMER_CHCTL1(timer_periph) &= ~(uint32_t)TIMER_CHCTL1_CH2MS;
+ /* set the CH2EN bit */
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)(ocpara->outputstate << 8U);
+ /* reset the CH2P bit */
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH2P);
+ /* set the CH2P bit */
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)(ocpara->ocpolarity) << 8U);
+
+ if(TIMER0 == timer_periph) {
+ /* reset the CH2NEN bit */
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH2NEN);
+ /* set the CH2NEN bit */
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)(ocpara->outputnstate) << 8U);
+ /* reset the CH2NP bit */
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH2NP);
+ /* set the CH2NP bit */
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)(ocpara->ocnpolarity) << 8U);
+ /* reset the ISO2 bit */
+ TIMER_CTL1(timer_periph) &= (~(uint32_t)TIMER_CTL1_ISO2);
+ /* set the ISO2 bit */
+ TIMER_CTL1(timer_periph) |= (uint32_t)((uint32_t)(ocpara->ocidlestate) << 4U);
+ /* reset the ISO2N bit */
+ TIMER_CTL1(timer_periph) &= (~(uint32_t)TIMER_CTL1_ISO2N);
+ /* set the ISO2N bit */
+ TIMER_CTL1(timer_periph) |= (uint32_t)((uint32_t)(ocpara->ocnidlestate) << 4U);
+ }
+ break;
+ /* configure TIMER_CH_3 */
+ case TIMER_CH_3:
+ /* reset the CH3EN bit */
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH3EN);
+ TIMER_CHCTL1(timer_periph) &= ~(uint32_t)TIMER_CHCTL1_CH3MS;
+ /* set the CH3EN bit */
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)(ocpara->outputstate << 12U);
+ /* reset the CH3P bit */
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH3P);
+ /* set the CH3P bit */
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)(ocpara->ocpolarity) << 12U);
+
+ if(TIMER0 == timer_periph) {
+ /* reset the ISO3 bit */
+ TIMER_CTL1(timer_periph) &= (~(uint32_t)TIMER_CTL1_ISO3);
+ /* set the ISO3 bit */
+ TIMER_CTL1(timer_periph) |= (uint32_t)((uint32_t)(ocpara->ocidlestate) << 6U);
+ }
+ break;
+ default:
+ break;
+ }
+}
+
+/*!
+ \brief configure TIMER channel output compare mode
+ \param[in] timer_periph: please refer to the following parameters
+ \param[in] channel:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_CH_0: TIMER channel0(TIMERx(x=0..2,13..16))
+ \arg TIMER_CH_1: TIMER channel1(TIMERx(x=0..2,14))
+ \arg TIMER_CH_2: TIMER channel2(TIMERx(x=0..2))
+ \arg TIMER_CH_3: TIMER channel3(TIMERx(x=0..2))
+ \param[in] ocmode: channel output compare mode
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_OC_MODE_TIMING: timing mode
+ \arg TIMER_OC_MODE_ACTIVE: active mode
+ \arg TIMER_OC_MODE_INACTIVE: inactive mode
+ \arg TIMER_OC_MODE_TOGGLE: toggle mode
+ \arg TIMER_OC_MODE_LOW: force low mode
+ \arg TIMER_OC_MODE_HIGH: force high mode
+ \arg TIMER_OC_MODE_PWM0: PWM0 mode
+ \arg TIMER_OC_MODE_PWM1: PWM1 mode
+ \param[out] none
+ \retval none
+*/
+void timer_channel_output_mode_config(uint32_t timer_periph, uint16_t channel, uint16_t ocmode)
+{
+ switch(channel) {
+ /* configure TIMER_CH_0 */
+ case TIMER_CH_0:
+ TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH0COMCTL);
+ TIMER_CHCTL0(timer_periph) |= (uint32_t)ocmode;
+ break;
+ /* configure TIMER_CH_1 */
+ case TIMER_CH_1:
+ TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH1COMCTL);
+ TIMER_CHCTL0(timer_periph) |= (uint32_t)((uint32_t)(ocmode) << 8U);
+ break;
+ /* configure TIMER_CH_2 */
+ case TIMER_CH_2:
+ TIMER_CHCTL1(timer_periph) &= (~(uint32_t)TIMER_CHCTL1_CH2COMCTL);
+ TIMER_CHCTL1(timer_periph) |= (uint32_t)ocmode;
+ break;
+ /* configure TIMER_CH_3 */
+ case TIMER_CH_3:
+ TIMER_CHCTL1(timer_periph) &= (~(uint32_t)TIMER_CHCTL1_CH3COMCTL);
+ TIMER_CHCTL1(timer_periph) |= (uint32_t)((uint32_t)(ocmode) << 8U);
+ break;
+ default:
+ break;
+ }
+}
+
+/*!
+ \brief configure TIMER channel output pulse value
+ \param[in] timer_periph: please refer to the following parameters
+ \param[in] channel:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_CH_0: TIMER channel0(TIMERx(x=0..2,13..16))
+ \arg TIMER_CH_1: TIMER channel1(TIMERx(x=0..2,14))
+ \arg TIMER_CH_2: TIMER channel2(TIMERx(x=0..2))
+ \arg TIMER_CH_3: TIMER channel3(TIMERx(x=0..2))
+ \param[in] pulse: channel output pulse value,0~65535
+ \param[out] none
+ \retval none
+*/
+void timer_channel_output_pulse_value_config(uint32_t timer_periph, uint16_t channel, uint32_t pulse)
+{
+ switch(channel) {
+ /* configure TIMER_CH_0 */
+ case TIMER_CH_0:
+ TIMER_CH0CV(timer_periph) = (uint32_t)pulse;
+ break;
+ /* configure TIMER_CH_1 */
+ case TIMER_CH_1:
+ TIMER_CH1CV(timer_periph) = (uint32_t)pulse;
+ break;
+ /* configure TIMER_CH_2 */
+ case TIMER_CH_2:
+ TIMER_CH2CV(timer_periph) = (uint32_t)pulse;
+ break;
+ /* configure TIMER_CH_3 */
+ case TIMER_CH_3:
+ TIMER_CH3CV(timer_periph) = (uint32_t)pulse;
+ break;
+ default:
+ break;
+ }
+}
+
+/*!
+ \brief configure TIMER channel output shadow function
+ \param[in] timer_periph: please refer to the following parameters
+ \param[in] channel:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_CH_0: TIMER channel0(TIMERx(x=0..2,13..16))
+ \arg TIMER_CH_1: TIMER channel1(TIMERx(x=0..2,14))
+ \arg TIMER_CH_2: TIMER channel2(TIMERx(x=0..2))
+ \arg TIMER_CH_3: TIMER channel3(TIMERx(x=0..2))
+ \param[in] ocshadow: channel output shadow state
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_OC_SHADOW_ENABLE: channel output shadow state enable
+ \arg TIMER_OC_SHADOW_DISABLE: channel output shadow state disable
+ \param[out] none
+ \retval none
+*/
+void timer_channel_output_shadow_config(uint32_t timer_periph, uint16_t channel, uint16_t ocshadow)
+{
+ switch(channel) {
+ /* configure TIMER_CH_0 */
+ case TIMER_CH_0:
+ TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH0COMSEN);
+ TIMER_CHCTL0(timer_periph) |= (uint32_t)ocshadow;
+ break;
+ /* configure TIMER_CH_1 */
+ case TIMER_CH_1:
+ TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH1COMSEN);
+ TIMER_CHCTL0(timer_periph) |= (uint32_t)((uint32_t)(ocshadow) << 8U);
+ break;
+ /* configure TIMER_CH_2 */
+ case TIMER_CH_2:
+ TIMER_CHCTL1(timer_periph) &= (~(uint32_t)TIMER_CHCTL1_CH2COMSEN);
+ TIMER_CHCTL1(timer_periph) |= (uint32_t)ocshadow;
+ break;
+ /* configure TIMER_CH_3 */
+ case TIMER_CH_3:
+ TIMER_CHCTL1(timer_periph) &= (~(uint32_t)TIMER_CHCTL1_CH3COMSEN);
+ TIMER_CHCTL1(timer_periph) |= (uint32_t)((uint32_t)(ocshadow) << 8U);
+ break;
+ default:
+ break;
+ }
+}
+
+/*!
+ \brief configure TIMER channel output fast function
+ \param[in] timer_periph: please refer to the following parameters
+ \param[in] channel:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_CH_0: TIMER channel0(TIMERx(x=0..2,13..16))
+ \arg TIMER_CH_1: TIMER channel1(TIMERx(x=0..2,14))
+ \arg TIMER_CH_2: TIMER channel2(TIMERx(x=0..2))
+ \arg TIMER_CH_3: TIMER channel3(TIMERx(x=0..2))
+ \param[in] ocfast: channel output fast function
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_OC_FAST_ENABLE: channel output fast function enable
+ \arg TIMER_OC_FAST_DISABLE: channel output fast function disable
+ \param[out] none
+ \retval none
+*/
+void timer_channel_output_fast_config(uint32_t timer_periph, uint16_t channel, uint16_t ocfast)
+{
+ switch(channel) {
+ /* configure TIMER_CH_0 */
+ case TIMER_CH_0:
+ TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH0COMFEN);
+ TIMER_CHCTL0(timer_periph) |= (uint32_t)ocfast;
+ break;
+ /* configure TIMER_CH_1 */
+ case TIMER_CH_1:
+ TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH1COMFEN);
+ TIMER_CHCTL0(timer_periph) |= (uint32_t)((uint32_t)ocfast << 8U);
+ break;
+ /* configure TIMER_CH_2 */
+ case TIMER_CH_2:
+ TIMER_CHCTL1(timer_periph) &= (~(uint32_t)TIMER_CHCTL1_CH2COMFEN);
+ TIMER_CHCTL1(timer_periph) |= (uint32_t)ocfast;
+ break;
+ /* configure TIMER_CH_3 */
+ case TIMER_CH_3:
+ TIMER_CHCTL1(timer_periph) &= (~(uint32_t)TIMER_CHCTL1_CH3COMFEN);
+ TIMER_CHCTL1(timer_periph) |= (uint32_t)((uint32_t)ocfast << 8U);
+ break;
+ default:
+ break;
+ }
+}
+
+/*!
+ \brief configure TIMER channel output clear function
+ \param[in] timer_periph: please refer to the following parameters
+ \param[in] channel:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_CH_0: TIMER channel0(TIMERx(x=0..2))
+ \arg TIMER_CH_1: TIMER channel1(TIMERx(x=0..2))
+ \arg TIMER_CH_2: TIMER channel2(TIMERx(x=0..2))
+ \arg TIMER_CH_3: TIMER channel3(TIMERx(x=0..2))
+ \param[in] occlear: channel output clear function
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_OC_CLEAR_ENABLE: channel output clear function enable
+ \arg TIMER_OC_CLEAR_DISABLE: channel output clear function disable
+ \param[out] none
+ \retval none
+*/
+void timer_channel_output_clear_config(uint32_t timer_periph, uint16_t channel, uint16_t occlear)
+{
+ switch(channel) {
+ /* configure TIMER_CH_0 */
+ case TIMER_CH_0:
+ TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH0COMCEN);
+ TIMER_CHCTL0(timer_periph) |= (uint32_t)occlear;
+ break;
+ /* configure TIMER_CH_1 */
+ case TIMER_CH_1:
+ TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH1COMCEN);
+ TIMER_CHCTL0(timer_periph) |= (uint32_t)((uint32_t)occlear << 8U);
+ break;
+ /* configure TIMER_CH_2 */
+ case TIMER_CH_2:
+ TIMER_CHCTL1(timer_periph) &= (~(uint32_t)TIMER_CHCTL1_CH2COMCEN);
+ TIMER_CHCTL1(timer_periph) |= (uint32_t)occlear;
+ break;
+ /* configure TIMER_CH_3 */
+ case TIMER_CH_3:
+ TIMER_CHCTL1(timer_periph) &= (~(uint32_t)TIMER_CHCTL1_CH3COMCEN);
+ TIMER_CHCTL1(timer_periph) |= (uint32_t)((uint32_t)occlear << 8U);
+ break;
+ default:
+ break;
+ }
+}
+
+/*!
+ \brief configure TIMER channel output polarity
+ \param[in] timer_periph: please refer to the following parameters
+ \param[in] channel:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_CH_0: TIMER channel0(TIMERx(x=0..2,13..16))
+ \arg TIMER_CH_1: TIMER channel1(TIMERx(x=0..2,14))
+ \arg TIMER_CH_2: TIMER channel2(TIMERx(x=0..2))
+ \arg TIMER_CH_3: TIMER channel3(TIMERx(x=0..2))
+ \param[in] ocpolarity: channel output polarity
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_OC_POLARITY_HIGH: channel output polarity is high
+ \arg TIMER_OC_POLARITY_LOW: channel output polarity is low
+ \param[out] none
+ \retval none
+*/
+void timer_channel_output_polarity_config(uint32_t timer_periph, uint16_t channel, uint16_t ocpolarity)
+{
+ switch(channel) {
+ /* configure TIMER_CH_0 */
+ case TIMER_CH_0:
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH0P);
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)ocpolarity;
+ break;
+ /* configure TIMER_CH_1 */
+ case TIMER_CH_1:
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH1P);
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)ocpolarity << 4U);
+ break;
+ /* configure TIMER_CH_2 */
+ case TIMER_CH_2:
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH2P);
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)ocpolarity << 8U);
+ break;
+ /* configure TIMER_CH_3 */
+ case TIMER_CH_3:
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH3P);
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)ocpolarity << 12U);
+ break;
+ default:
+ break;
+ }
+}
+
+/*!
+ \brief configure TIMER channel complementary output polarity
+ \param[in] timer_periph: TIMERx(x=0..2,14)
+ \param[in] channel:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_CH_0: TIMER channel0(TIMERx(x=0..2,13..16))
+ \arg TIMER_CH_1: TIMER channel1(TIMERx(x=0..2,14))
+ \arg TIMER_CH_2: TIMER channel2(TIMERx(x=0..2))
+ \arg TIMER_CH_3: TIMER channel2(TIMERx(x=1,2))
+ \param[in] ocnpolarity: channel complementary output polarity
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_OCN_POLARITY_HIGH: channel complementary output polarity is high
+ \arg TIMER_OCN_POLARITY_LOW: channel complementary output polarity is low
+ \param[out] none
+ \retval none
+*/
+void timer_channel_complementary_output_polarity_config(uint32_t timer_periph, uint16_t channel, uint16_t ocnpolarity)
+{
+ switch(channel) {
+ /* configure TIMER_CH_0 */
+ case TIMER_CH_0:
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH0NP);
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)ocnpolarity;
+ break;
+ /* configure TIMER_CH_1 */
+ case TIMER_CH_1:
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH1NP);
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)ocnpolarity << 4U);
+ break;
+ /* configure TIMER_CH_2 */
+ case TIMER_CH_2:
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH2NP);
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)ocnpolarity << 8U);
+ break;
+ /* configure TIMER_CH_3 */
+ case TIMER_CH_3:
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH3NP);
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)ocnpolarity << 12U);
+ break;
+ default:
+ break;
+ }
+}
+
+/*!
+ \brief configure TIMER channel enable state
+ \param[in] timer_periph: please refer to the following parameters
+ \param[in] channel:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_CH_0: TIMER channel0(TIMERx(x=0..2,13..16))
+ \arg TIMER_CH_1: TIMER channel1(TIMERx(x=0..2,14))
+ \arg TIMER_CH_2: TIMER channel2(TIMERx(x=0..2))
+ \arg TIMER_CH_3: TIMER channel3(TIMERx(x=0..2))
+ \param[in] state: TIMER channel enable state
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_CCX_ENABLE: channel enable
+ \arg TIMER_CCX_DISABLE: channel disable
+ \param[out] none
+ \retval none
+*/
+void timer_channel_output_state_config(uint32_t timer_periph, uint16_t channel, uint32_t state)
+{
+ switch(channel) {
+ /* configure TIMER_CH_0 */
+ case TIMER_CH_0:
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH0EN);
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)state;
+ break;
+ /* configure TIMER_CH_1 */
+ case TIMER_CH_1:
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH1EN);
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)state << 4U);
+ break;
+ /* configure TIMER_CH_2 */
+ case TIMER_CH_2:
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH2EN);
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)state << 8U);
+ break;
+ /* configure TIMER_CH_3 */
+ case TIMER_CH_3:
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH3EN);
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)state << 12U);
+ break;
+ default:
+ break;
+ }
+}
+
+/*!
+ \brief configure TIMER channel complementary output enable state
+ \param[in] timer_periph: TIMERx(x=0,14..16)
+ \param[in] channel:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_CH_0: TIMER channel0(TIMERx(x=0,14..16))
+ \arg TIMER_CH_1: TIMER channel1(TIMERx(x=0))
+ \arg TIMER_CH_2: TIMER channel2(TIMERx(x=0))
+ \param[in] ocnstate: TIMER channel complementary output enable state
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_CCXN_ENABLE: channel complementary enable
+ \arg TIMER_CCXN_DISABLE: channel complementary disable
+ \param[out] none
+ \retval none
+*/
+void timer_channel_complementary_output_state_config(uint32_t timer_periph, uint16_t channel, uint16_t ocnstate)
+{
+ switch(channel) {
+ /* configure TIMER_CH_0 */
+ case TIMER_CH_0:
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH0NEN);
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)ocnstate;
+ break;
+ /* configure TIMER_CH_1 */
+ case TIMER_CH_1:
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH1NEN);
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)ocnstate << 4U);
+ break;
+ /* configure TIMER_CH_2 */
+ case TIMER_CH_2:
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH2NEN);
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)ocnstate << 8U);
+ break;
+ default:
+ break;
+ }
+}
+
+/*!
+ \brief initialize TIMER channel input parameter struct with a default value
+ \param[in] icpara: TIMER channel intput parameter struct
+ \param[out] none
+ \retval none
+*/
+void timer_channel_input_struct_para_init(timer_ic_parameter_struct *icpara)
+{
+ /* initialize the channel input parameter struct member with the default value */
+ icpara->icpolarity = TIMER_IC_POLARITY_RISING;
+ icpara->icselection = TIMER_IC_SELECTION_DIRECTTI;
+ icpara->icprescaler = TIMER_IC_PSC_DIV1;
+ icpara->icfilter = 0U;
+}
+
+/*!
+ \brief configure TIMER input capture parameter
+ \param[in] timer_periph: please refer to the following parameters
+ \param[in] channel:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_CH_0: TIMER channel0(TIMERx(x=0..2,13..16))
+ \arg TIMER_CH_1: TIMER channel1(TIMERx(x=0..2,14))
+ \arg TIMER_CH_2: TIMER channel2(TIMERx(x=0..2))
+ \arg TIMER_CH_3: TIMER channel3(TIMERx(x=0..2))
+ \param[in] icpara: TIMER channel intput parameter struct
+ icpolarity: TIMER_IC_POLARITY_RISING,TIMER_IC_POLARITY_FALLING,TIMER_IC_POLARITY_BOTH_EDGE
+ icselection: TIMER_IC_SELECTION_DIRECTTI,TIMER_IC_SELECTION_INDIRECTTI,TIMER_IC_SELECTION_ITS
+ icprescaler: TIMER_IC_PSC_DIV1,TIMER_IC_PSC_DIV2,TIMER_IC_PSC_DIV4,TIMER_IC_PSC_DIV8
+ icfilter: 0~15
+ \param[out] none
+ \retval none
+*/
+void timer_input_capture_config(uint32_t timer_periph, uint16_t channel, timer_ic_parameter_struct *icpara)
+{
+ switch(channel) {
+ /* configure TIMER_CH_0 */
+ case TIMER_CH_0:
+ /* reset the CH0EN bit */
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH0EN);
+
+ /* reset the CH0P and CH0NP bits */
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)(TIMER_CHCTL2_CH0P | TIMER_CHCTL2_CH0NP));
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)(icpara->icpolarity);
+ /* reset the CH0MS bit */
+ TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH0MS);
+ TIMER_CHCTL0(timer_periph) |= (uint32_t)(icpara->icselection);
+ /* reset the CH0CAPFLT bit */
+ TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH0CAPFLT);
+ TIMER_CHCTL0(timer_periph) |= (uint32_t)((uint32_t)(icpara->icfilter) << 4U);
+
+ /* set the CH0EN bit */
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)TIMER_CHCTL2_CH0EN;
+ break;
+
+ /* configure TIMER_CH_1 */
+ case TIMER_CH_1:
+ /* reset the CH1EN bit */
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH1EN);
+
+ /* reset the CH1P and CH1NP bits */
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)(TIMER_CHCTL2_CH1P | TIMER_CHCTL2_CH1NP));
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)(icpara->icpolarity) << 4U);
+ /* reset the CH1MS bit */
+ TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH1MS);
+ TIMER_CHCTL0(timer_periph) |= (uint32_t)((uint32_t)(icpara->icselection) << 8U);
+ /* reset the CH1CAPFLT bit */
+ TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH1CAPFLT);
+ TIMER_CHCTL0(timer_periph) |= (uint32_t)((uint32_t)(icpara->icfilter) << 12U);
+
+ /* set the CH1EN bit */
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)TIMER_CHCTL2_CH1EN;
+ break;
+ /* configure TIMER_CH_2 */
+ case TIMER_CH_2:
+ /* reset the CH2EN bit */
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH2EN);
+
+ /* reset the CH2P and CH2NP bits */
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)(TIMER_CHCTL2_CH2P | TIMER_CHCTL2_CH2NP));
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)(icpara->icpolarity) << 8U);
+
+ /* reset the CH2MS bit */
+ TIMER_CHCTL1(timer_periph) &= (~(uint32_t)TIMER_CHCTL1_CH2MS);
+ TIMER_CHCTL1(timer_periph) |= (uint32_t)((uint32_t)(icpara->icselection));
+
+ /* reset the CH2CAPFLT bit */
+ TIMER_CHCTL1(timer_periph) &= (~(uint32_t)TIMER_CHCTL1_CH2CAPFLT);
+ TIMER_CHCTL1(timer_periph) |= (uint32_t)((uint32_t)(icpara->icfilter) << 4U);
+
+ /* set the CH2EN bit */
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)TIMER_CHCTL2_CH2EN;
+ break;
+ /* configure TIMER_CH_3 */
+ case TIMER_CH_3:
+ /* reset the CH3EN bit */
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH3EN);
+
+ /* reset the CH3P and CH3NP bits */
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)(TIMER_CHCTL2_CH3P | TIMER_CHCTL2_CH3NP));
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)(icpara->icpolarity) << 12U);
+
+ /* reset the CH3MS bit */
+ TIMER_CHCTL1(timer_periph) &= (~(uint32_t)TIMER_CHCTL1_CH3MS);
+ TIMER_CHCTL1(timer_periph) |= (uint32_t)((uint32_t)(icpara->icselection) << 8U);
+
+ /* reset the CH3CAPFLT bit */
+ TIMER_CHCTL1(timer_periph) &= (~(uint32_t)TIMER_CHCTL1_CH3CAPFLT);
+ TIMER_CHCTL1(timer_periph) |= (uint32_t)((uint32_t)(icpara->icfilter) << 12U);
+
+ /* set the CH3EN bit */
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)TIMER_CHCTL2_CH3EN;
+ break;
+ default:
+ break;
+ }
+ /* configure TIMER channel input capture prescaler value */
+ timer_channel_input_capture_prescaler_config(timer_periph, channel, (uint16_t)(icpara->icprescaler));
+}
+
+/*!
+ \brief configure TIMER channel input capture prescaler value
+ \param[in] timer_periph: please refer to the following parameters
+ \param[in] channel:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_CH_0: TIMER channel0(TIMERx(x=0..2,13..16))
+ \arg TIMER_CH_1: TIMER channel1(TIMERx(x=0..2,14))
+ \arg TIMER_CH_2: TIMER channel2(TIMERx(x=0..2))
+ \arg TIMER_CH_3: TIMER channel3(TIMERx(x=0..2))
+ \param[in] prescaler: channel input capture prescaler value
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_IC_PSC_DIV1: no prescaler
+ \arg TIMER_IC_PSC_DIV2: divided by 2
+ \arg TIMER_IC_PSC_DIV4: divided by 4
+ \arg TIMER_IC_PSC_DIV8: divided by 8
+ \param[out] none
+ \retval none
+*/
+void timer_channel_input_capture_prescaler_config(uint32_t timer_periph, uint16_t channel, uint16_t prescaler)
+{
+ switch(channel) {
+ /* configure TIMER_CH_0 */
+ case TIMER_CH_0:
+ TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH0CAPPSC);
+ TIMER_CHCTL0(timer_periph) |= (uint32_t)prescaler;
+ break;
+ /* configure TIMER_CH_1 */
+ case TIMER_CH_1:
+ TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH1CAPPSC);
+ TIMER_CHCTL0(timer_periph) |= ((uint32_t)prescaler << 8U);
+ break;
+ /* configure TIMER_CH_2 */
+ case TIMER_CH_2:
+ TIMER_CHCTL1(timer_periph) &= (~(uint32_t)TIMER_CHCTL1_CH2CAPPSC);
+ TIMER_CHCTL1(timer_periph) |= (uint32_t)prescaler;
+ break;
+ /* configure TIMER_CH_3 */
+ case TIMER_CH_3:
+ TIMER_CHCTL1(timer_periph) &= (~(uint32_t)TIMER_CHCTL1_CH3CAPPSC);
+ TIMER_CHCTL1(timer_periph) |= ((uint32_t)prescaler << 8U);
+ break;
+ default:
+ break;
+ }
+}
+
+/*!
+ \brief read TIMER channel capture compare register value
+ \param[in] timer_periph: please refer to the following parameters
+ \param[in] channel:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_CH_0: TIMER channel0(TIMERx(x=0..2,13..16))
+ \arg TIMER_CH_1: TIMER channel1(TIMERx(x=0..2,14))
+ \arg TIMER_CH_2: TIMER channel2(TIMERx(x=0..2))
+ \arg TIMER_CH_3: TIMER channel3(TIMERx(x=0..2))
+ \param[out] none
+ \retval channel capture compare register value
+*/
+uint32_t timer_channel_capture_value_register_read(uint32_t timer_periph, uint16_t channel)
+{
+ uint32_t count_value = 0U;
+
+ switch(channel) {
+ /* read TIMER channel 0 capture compare register value */
+ case TIMER_CH_0:
+ count_value = TIMER_CH0CV(timer_periph);
+ break;
+ /* read TIMER channel 1 capture compare register value */
+ case TIMER_CH_1:
+ count_value = TIMER_CH1CV(timer_periph);
+ break;
+ /* read TIMER channel 2 capture compare register value */
+ case TIMER_CH_2:
+ count_value = TIMER_CH2CV(timer_periph);
+ break;
+ /* read TIMER channel 3 capture compare register value */
+ case TIMER_CH_3:
+ count_value = TIMER_CH3CV(timer_periph);
+ break;
+ default:
+ break;
+ }
+ return (count_value);
+}
+
+/*!
+ \brief configure TIMER input pwm capture function
+ \param[in] timer_periph: TIMERx(x=0..2,14)
+ \param[in] channel:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_CH_0: TIMER channel0
+ \arg TIMER_CH_1: TIMER channel1
+ \param[in] icpwm:TIMER channel intput pwm parameter struct
+ icpolarity: TIMER_IC_POLARITY_RISING,TIMER_IC_POLARITY_FALLING
+ icselection: TIMER_IC_SELECTION_DIRECTTI,TIMER_IC_SELECTION_INDIRECTTI
+ icprescaler: TIMER_IC_PSC_DIV1,TIMER_IC_PSC_DIV2,TIMER_IC_PSC_DIV4,TIMER_IC_PSC_DIV8
+ icfilter: 0~15
+ \param[out] none
+ \retval none
+*/
+void timer_input_pwm_capture_config(uint32_t timer_periph, uint16_t channel, timer_ic_parameter_struct *icpwm)
+{
+ uint16_t icpolarity = 0x0U;
+ uint16_t icselection = 0x0U;
+
+ /* Set channel input polarity */
+ if(TIMER_IC_POLARITY_RISING == icpwm->icpolarity) {
+ icpolarity = TIMER_IC_POLARITY_FALLING;
+ } else {
+ icpolarity = TIMER_IC_POLARITY_RISING;
+ }
+
+ /* Set channel input mode selection */
+ if(TIMER_IC_SELECTION_DIRECTTI == icpwm->icselection) {
+ icselection = TIMER_IC_SELECTION_INDIRECTTI;
+ } else {
+ icselection = TIMER_IC_SELECTION_DIRECTTI;
+ }
+
+ if(TIMER_CH_0 == channel) {
+ /* reset the CH0EN bit */
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH0EN);
+ /* reset the CH0P and CH0NP bits */
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)(TIMER_CHCTL2_CH0P | TIMER_CHCTL2_CH0NP));
+ /* set the CH0P and CH0NP bits */
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)(icpwm->icpolarity);
+ /* reset the CH0MS bit */
+ TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH0MS);
+ /* set the CH0MS bit */
+ TIMER_CHCTL0(timer_periph) |= (uint32_t)(icpwm->icselection);
+ /* reset the CH0CAPFLT bit */
+ TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH0CAPFLT);
+ /* set the CH0CAPFLT bit */
+ TIMER_CHCTL0(timer_periph) |= ((uint32_t)(icpwm->icfilter) << 4U);
+ /* set the CH0EN bit */
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)TIMER_CHCTL2_CH0EN;
+ /* configure TIMER channel input capture prescaler value */
+ timer_channel_input_capture_prescaler_config(timer_periph, TIMER_CH_0, (uint16_t)(icpwm->icprescaler));
+
+ /* reset the CH1EN bit */
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH1EN);
+ /* reset the CH1P and CH1NP bits */
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)(TIMER_CHCTL2_CH1P | TIMER_CHCTL2_CH1NP));
+ /* set the CH1P and CH1NP bits */
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)icpolarity << 4U);
+ /* reset the CH1MS bit */
+ TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH1MS);
+ /* set the CH1MS bit */
+ TIMER_CHCTL0(timer_periph) |= (uint32_t)((uint32_t)icselection << 8U);
+ /* reset the CH1CAPFLT bit */
+ TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH1CAPFLT);
+ /* set the CH1CAPFLT bit */
+ TIMER_CHCTL0(timer_periph) |= (uint32_t)((uint32_t)(icpwm->icfilter) << 12U);
+ /* set the CH1EN bit */
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)TIMER_CHCTL2_CH1EN;
+ /* configure TIMER channel input capture prescaler value */
+ timer_channel_input_capture_prescaler_config(timer_periph, TIMER_CH_1, (uint16_t)(icpwm->icprescaler));
+ } else {
+ /* reset the CH1EN bit */
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH1EN);
+ /* reset the CH1P and CH1NP bits */
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)(TIMER_CHCTL2_CH1P | TIMER_CHCTL2_CH1NP));
+ /* set the CH1P and CH1NP bits */
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)(icpwm->icpolarity) << 4U);
+ /* reset the CH1MS bit */
+ TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH1MS);
+ /* set the CH1MS bit */
+ TIMER_CHCTL0(timer_periph) |= (uint32_t)((uint32_t)(icpwm->icselection) << 8U);
+ /* reset the CH1CAPFLT bit */
+ TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH1CAPFLT);
+ /* set the CH1CAPFLT bit */
+ TIMER_CHCTL0(timer_periph) |= (uint32_t)((uint32_t)(icpwm->icfilter) << 12U);
+ /* set the CH1EN bit */
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)TIMER_CHCTL2_CH1EN;
+ /* configure TIMER channel input capture prescaler value */
+ timer_channel_input_capture_prescaler_config(timer_periph, TIMER_CH_1, (uint16_t)(icpwm->icprescaler));
+
+ /* reset the CH0EN bit */
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH0EN);
+ /* reset the CH0P and CH0NP bits */
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)(TIMER_CHCTL2_CH0P | TIMER_CHCTL2_CH0NP));
+ /* set the CH0P and CH0NP bits */
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)icpolarity;
+ /* reset the CH0MS bit */
+ TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH0MS);
+ /* set the CH0MS bit */
+ TIMER_CHCTL0(timer_periph) |= (uint32_t)icselection;
+ /* reset the CH0CAPFLT bit */
+ TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH0CAPFLT);
+ /* set the CH0CAPFLT bit */
+ TIMER_CHCTL0(timer_periph) |= ((uint32_t)(icpwm->icfilter) << 4U);
+ /* set the CH0EN bit */
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)TIMER_CHCTL2_CH0EN;
+ /* configure TIMER channel input capture prescaler value */
+ timer_channel_input_capture_prescaler_config(timer_periph, TIMER_CH_0, (uint16_t)(icpwm->icprescaler));
+ }
+}
+
+/*!
+ \brief configure TIMER hall sensor mode
+ \param[in] timer_periph: TIMERx(x=0..2)
+ \param[in] hallmode:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_HALLINTERFACE_ENABLE: TIMER hall sensor mode enable
+ \arg TIMER_HALLINTERFACE_DISABLE: TIMER hall sensor mode disable
+ \param[out] none
+ \retval none
+*/
+void timer_hall_mode_config(uint32_t timer_periph, uint8_t hallmode)
+{
+ if(TIMER_HALLINTERFACE_ENABLE == hallmode) {
+ TIMER_CTL1(timer_periph) |= (uint32_t)TIMER_CTL1_TI0S;
+ } else if(TIMER_HALLINTERFACE_DISABLE == hallmode) {
+ TIMER_CTL1(timer_periph) &= ~(uint32_t)TIMER_CTL1_TI0S;
+ } else {
+ /* illegal parameters */
+ }
+}
+
+/*!
+ \brief select TIMER input trigger source
+ \param[in] timer_periph: TIMERx(x=0..2,14)
+ \param[in] intrigger:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_SMCFG_TRGSEL_ITI0: internal trigger 0(TIMERx(x=0..2,14))
+ \arg TIMER_SMCFG_TRGSEL_ITI1: internal trigger 1(TIMERx(x=0..2,14))
+ \arg TIMER_SMCFG_TRGSEL_ITI2: internal trigger 2(TIMERx(x=0..2))
+ \arg TIMER_SMCFG_TRGSEL_CI0F_ED: TI0 edge detector(TIMERx(x=0..2,14))
+ \arg TIMER_SMCFG_TRGSEL_CI0FE0: filtered TIMER input 0(TIMERx(x=0..2,14))
+ \arg TIMER_SMCFG_TRGSEL_CI1FE1: filtered TIMER input 1(TIMERx(x=0..2,14))
+ \arg TIMER_SMCFG_TRGSEL_ETIFP: external trigger(TIMERx(x=0..2))
+ \param[out] none
+ \retval none
+*/
+void timer_input_trigger_source_select(uint32_t timer_periph, uint32_t intrigger)
+{
+ TIMER_SMCFG(timer_periph) &= (~(uint32_t)TIMER_SMCFG_TRGS);
+ TIMER_SMCFG(timer_periph) |= (uint32_t)intrigger;
+}
+
+/*!
+ \brief select TIMER master mode output trigger source
+ \param[in] timer_periph: TIMERx(x=0..2,14),TIMER5 just for GD32F350
+ \param[in] outrigger:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_TRI_OUT_SRC_RESET: the UPG bit as trigger output(TIMERx(x=0..2,14),TIMER5 just for GD32F350)
+ \arg TIMER_TRI_OUT_SRC_ENABLE: the counter enable signal TIMER_CTL0_CEN as trigger output(TIMERx(x=0..2,14),TIMER5 just for GD32F350)
+ \arg TIMER_TRI_OUT_SRC_UPDATE: update event as trigger output(TIMERx(x=0..2,14),TIMER5 just for GD32F350)
+ \arg TIMER_TRI_OUT_SRC_CH0: a capture or a compare match occurred in channal0 as trigger output TRGO
+ \arg TIMER_TRI_OUT_SRC_O0CPRE: O0CPRE as trigger output(TIMERx(x=0..2,14))
+ \arg TIMER_TRI_OUT_SRC_O1CPRE: O1CPRE as trigger output(TIMERx(x=0..2,14))
+ \arg TIMER_TRI_OUT_SRC_O2CPRE: O2CPRE as trigger output(TIMERx(x=0..2,14))
+ \arg TIMER_TRI_OUT_SRC_O3CPRE: O3CPRE as trigger output(TIMERx(x=0..2,14))
+ \param[out] none
+ \retval none
+*/
+void timer_master_output_trigger_source_select(uint32_t timer_periph, uint32_t outrigger)
+{
+ TIMER_CTL1(timer_periph) &= (~(uint32_t)TIMER_CTL1_MMC);
+ TIMER_CTL1(timer_periph) |= (uint32_t)outrigger;
+}
+
+/*!
+ \brief select TIMER slave mode
+ \param[in] timer_periph: TIMERx(x=0..2,14)
+ \param[in] slavemode:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_SLAVE_MODE_DISABLE: slave mode disable(TIMERx(x=0..2,14))
+ \arg TIMER_ENCODER_MODE0: encoder mode 0(TIMERx(x=0..2))
+ \arg TIMER_ENCODER_MODE1: encoder mode 1(TIMERx(x=0..2))
+ \arg TIMER_ENCODER_MODE2: encoder mode 2(TIMERx(x=0..2))
+ \arg TIMER_SLAVE_MODE_RESTART: restart mode(TIMERx(x=0..2,14))
+ \arg TIMER_SLAVE_MODE_PAUSE: pause mode(TIMERx(x=0..2,14))
+ \arg TIMER_SLAVE_MODE_EVENT: event mode(TIMERx(x=0..2,14))
+ \arg TIMER_SLAVE_MODE_EXTERNAL0: external clock mode 0(TIMERx(x=0..2,14))
+ \param[out] none
+ \retval none
+*/
+
+void timer_slave_mode_select(uint32_t timer_periph, uint32_t slavemode)
+{
+ TIMER_SMCFG(timer_periph) &= (~(uint32_t)TIMER_SMCFG_SMC);
+
+ TIMER_SMCFG(timer_periph) |= (uint32_t)slavemode;
+}
+
+/*!
+ \brief configure TIMER master slave mode
+ \param[in] timer_periph: TIMERx(x=0..2,14)
+ \param[in] masterslave:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_MASTER_SLAVE_MODE_ENABLE: master slave mode enable
+ \arg TIMER_MASTER_SLAVE_MODE_DISABLE: master slave mode disable
+ \param[out] none
+ \retval none
+*/
+void timer_master_slave_mode_config(uint32_t timer_periph, uint8_t masterslave)
+{
+ if(TIMER_MASTER_SLAVE_MODE_ENABLE == masterslave) {
+ TIMER_SMCFG(timer_periph) |= (uint32_t)TIMER_SMCFG_MSM;
+ } else if(TIMER_MASTER_SLAVE_MODE_DISABLE == masterslave) {
+ TIMER_SMCFG(timer_periph) &= ~(uint32_t)TIMER_SMCFG_MSM;
+ } else {
+ /* illegal parameters */
+ }
+}
+
+/*!
+ \brief configure TIMER external trigger input
+ \param[in] timer_periph: TIMERx(x=0..2)
+ \param[in] extprescaler:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_EXT_TRI_PSC_OFF: no divided
+ \arg TIMER_EXT_TRI_PSC_DIV2: divided by 2
+ \arg TIMER_EXT_TRI_PSC_DIV4: divided by 4
+ \arg TIMER_EXT_TRI_PSC_DIV8: divided by 8
+ \param[in] extpolarity:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_ETP_FALLING: active low or falling edge active
+ \arg TIMER_ETP_RISING: active high or rising edge active
+ \param[in] extfilter: a value between 0 and 15
+ \param[out] none
+ \retval none
+*/
+void timer_external_trigger_config(uint32_t timer_periph, uint32_t extprescaler,
+ uint32_t extpolarity, uint32_t extfilter)
+{
+ TIMER_SMCFG(timer_periph) &= (~(uint32_t)(TIMER_SMCFG_ETP | TIMER_SMCFG_ETPSC | TIMER_SMCFG_ETFC));
+ TIMER_SMCFG(timer_periph) |= (uint32_t)(extprescaler | extpolarity);
+ TIMER_SMCFG(timer_periph) |= (uint32_t)(extfilter << 8U);
+}
+
+/*!
+ \brief configure TIMER quadrature decoder mode
+ \param[in] timer_periph: TIMERx(x=0..2)
+ \param[in] decomode:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_ENCODER_MODE0: counter counts on CI0FE0 edge depending on CI1FE1 level
+ \arg TIMER_ENCODER_MODE1: counter counts on CI1FE1 edge depending on CI0FE0 level
+ \arg TIMER_ENCODER_MODE2: counter counts on both CI0FE0 and CI1FE1 edges depending on the level of the other input
+ \param[in] ic0polarity:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_IC_POLARITY_RISING: capture rising edge
+ \arg TIMER_IC_POLARITY_FALLING: capture falling edge
+ \param[in] ic1polarity:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_IC_POLARITY_RISING: capture rising edge
+ \arg TIMER_IC_POLARITY_FALLING: capture falling edge
+ \param[out] none
+ \retval none
+*/
+void timer_quadrature_decoder_mode_config(uint32_t timer_periph, uint32_t decomode,
+ uint16_t ic0polarity, uint16_t ic1polarity)
+{
+ TIMER_SMCFG(timer_periph) &= (~(uint32_t)TIMER_SMCFG_SMC);
+ TIMER_SMCFG(timer_periph) |= (uint32_t)decomode;
+
+ TIMER_CHCTL0(timer_periph) &= (uint32_t)(((~(uint32_t)TIMER_CHCTL0_CH0MS)) & ((~(uint32_t)TIMER_CHCTL0_CH1MS)));
+ TIMER_CHCTL0(timer_periph) |= (uint32_t)(TIMER_IC_SELECTION_DIRECTTI | ((uint32_t)TIMER_IC_SELECTION_DIRECTTI << 8U));
+
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)(TIMER_CHCTL2_CH0P | TIMER_CHCTL2_CH0NP));
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)(TIMER_CHCTL2_CH1P | TIMER_CHCTL2_CH1NP));
+ TIMER_CHCTL2(timer_periph) |= ((uint32_t)ic0polarity | ((uint32_t)ic1polarity << 4U));
+}
+
+/*!
+ \brief configure TIMER internal clock mode
+ \param[in] timer_periph: TIMERx(x=0..2,14)
+ \param[out] none
+ \retval none
+*/
+void timer_internal_clock_config(uint32_t timer_periph)
+{
+ TIMER_SMCFG(timer_periph) &= ~(uint32_t)TIMER_SMCFG_SMC;
+}
+
+/*!
+ \brief configure TIMER the internal trigger as external clock input
+ \param[in] timer_periph: TIMERx(x=0..2,14)
+ \param[in] intrigger:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_SMCFG_TRGSEL_ITI0: internal trigger 0(TIMERx(x=0..2,14))
+ \arg TIMER_SMCFG_TRGSEL_ITI1: internal trigger 1(TIMERx(x=0..2,14))
+ \arg TIMER_SMCFG_TRGSEL_ITI2: internal trigger 2(TIMERx(x=0..2))
+ \param[out] none
+ \retval none
+*/
+void timer_internal_trigger_as_external_clock_config(uint32_t timer_periph, uint32_t intrigger)
+{
+ timer_input_trigger_source_select(timer_periph, intrigger);
+ TIMER_SMCFG(timer_periph) &= ~(uint32_t)TIMER_SMCFG_SMC;
+ TIMER_SMCFG(timer_periph) |= (uint32_t)TIMER_SLAVE_MODE_EXTERNAL0;
+}
+
+/*!
+ \brief configure TIMER the external trigger as external clock input
+ \param[in] timer_periph: TIMERx(x=0..2,14)
+ \param[in] extrigger:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_SMCFG_TRGSEL_CI0F_ED: TI0 edge detector
+ \arg TIMER_SMCFG_TRGSEL_CI0FE0: filtered TIMER input 0
+ \arg TIMER_SMCFG_TRGSEL_CI1FE1: filtered TIMER input 1
+ \param[in] extpolarity:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_IC_POLARITY_RISING: active high or rising edge active
+ \arg TIMER_IC_POLARITY_FALLING: active low or falling edge active
+ \arg TIMER_IC_POLARITY_BOTH_EDGE: active both edge
+ \param[in] extfilter: a value between 0 and 15
+ \param[out] none
+ \retval none
+*/
+void timer_external_trigger_as_external_clock_config(uint32_t timer_periph, uint32_t extrigger,
+ uint16_t extpolarity, uint32_t extfilter)
+{
+ if(TIMER_SMCFG_TRGSEL_CI1FE1 == extrigger) {
+ /* reset the CH1EN bit */
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH1EN);
+ /* reset the CH1NP bit */
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)(TIMER_CHCTL2_CH1P | TIMER_CHCTL2_CH1NP));
+ /* set the CH1NP bit */
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)extpolarity << 4U);
+ /* reset the CH1MS bit */
+ TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH1MS);
+ /* set the CH1MS bit */
+ TIMER_CHCTL0(timer_periph) |= (uint32_t)((uint32_t)TIMER_IC_SELECTION_DIRECTTI << 8U);
+ /* reset the CH1CAPFLT bit */
+ TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH1CAPFLT);
+ /* set the CH1CAPFLT bit */
+ TIMER_CHCTL0(timer_periph) |= (uint32_t)(extfilter << 12U);
+ /* set the CH1EN bit */
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)TIMER_CHCTL2_CH1EN;
+ } else {
+ /* reset the CH0EN bit */
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH0EN);
+ /* reset the CH0P and CH0NP bits */
+ TIMER_CHCTL2(timer_periph) &= (~(uint32_t)(TIMER_CHCTL2_CH0P | TIMER_CHCTL2_CH0NP));
+ /* set the CH0P and CH0NP bits */
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)extpolarity;
+ /* reset the CH0MS bit */
+ TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH0MS);
+ /* set the CH0MS bit */
+ TIMER_CHCTL0(timer_periph) |= (uint32_t)TIMER_IC_SELECTION_DIRECTTI;
+ /* reset the CH0CAPFLT bit */
+ TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH0CAPFLT);
+ /* reset the CH0CAPFLT bit */
+ TIMER_CHCTL0(timer_periph) |= (uint32_t)(extfilter << 4U);
+ /* set the CH0EN bit */
+ TIMER_CHCTL2(timer_periph) |= (uint32_t)TIMER_CHCTL2_CH0EN;
+ }
+ /* select TIMER input trigger source */
+ timer_input_trigger_source_select(timer_periph, extrigger);
+ /* reset the SMC bit */
+ TIMER_SMCFG(timer_periph) &= (~(uint32_t)TIMER_SMCFG_SMC);
+ /* set the SMC bit */
+ TIMER_SMCFG(timer_periph) |= (uint32_t)TIMER_SLAVE_MODE_EXTERNAL0;
+}
+
+/*!
+ \brief configure TIMER the external clock mode0
+ \param[in] timer_periph: TIMERx(x=0..2)
+ \param[in] extprescaler:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_EXT_TRI_PSC_OFF: no divided
+ \arg TIMER_EXT_TRI_PSC_DIV2: divided by 2
+ \arg TIMER_EXT_TRI_PSC_DIV4: divided by 4
+ \arg TIMER_EXT_TRI_PSC_DIV8: divided by 8
+ \param[in] extpolarity:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_ETP_FALLING: active low or falling edge active
+ \arg TIMER_ETP_RISING: active high or rising edge active
+ \param[in] extfilter: a value between 0 and 15
+ \param[out] none
+ \retval none
+*/
+void timer_external_clock_mode0_config(uint32_t timer_periph, uint32_t extprescaler,
+ uint32_t extpolarity, uint32_t extfilter)
+{
+ /* configure TIMER external trigger input */
+ timer_external_trigger_config(timer_periph, extprescaler, extpolarity, extfilter);
+
+ /* reset the SMC bit,TRGS bit */
+ TIMER_SMCFG(timer_periph) &= (~(uint32_t)(TIMER_SMCFG_SMC | TIMER_SMCFG_TRGS));
+ /* set the SMC bit,TRGS bit */
+ TIMER_SMCFG(timer_periph) |= (uint32_t)(TIMER_SLAVE_MODE_EXTERNAL0 | TIMER_SMCFG_TRGSEL_ETIFP);
+}
+
+/*!
+ \brief configure TIMER the external clock mode1
+ \param[in] timer_periph: TIMERx(x=0..2)
+ \param[in] extprescaler:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_EXT_TRI_PSC_OFF: no divided
+ \arg TIMER_EXT_TRI_PSC_DIV2: divided by 2
+ \arg TIMER_EXT_TRI_PSC_DIV4: divided by 4
+ \arg TIMER_EXT_TRI_PSC_DIV8: divided by 8
+ \param[in] extpolarity:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_ETP_FALLING: active low or falling edge active
+ \arg TIMER_ETP_RISING: active high or rising edge active
+ \param[in] extfilter: a value between 0 and 15
+ \param[out] none
+ \retval none
+*/
+void timer_external_clock_mode1_config(uint32_t timer_periph, uint32_t extprescaler,
+ uint32_t extpolarity, uint32_t extfilter)
+{
+ /* configure TIMER external trigger input */
+ timer_external_trigger_config(timer_periph, extprescaler, extpolarity, extfilter);
+
+ TIMER_SMCFG(timer_periph) |= (uint32_t)TIMER_SMCFG_SMC1;
+}
+
+/*!
+ \brief disable TIMER the external clock mode1
+ \param[in] timer_periph: TIMERx(x=0..2)
+ \param[out] none
+ \retval none
+*/
+void timer_external_clock_mode1_disable(uint32_t timer_periph)
+{
+ TIMER_SMCFG(timer_periph) &= ~(uint32_t)TIMER_SMCFG_SMC1;
+}
+
+/*!
+ \brief configure TIMER channel remap function
+ \param[in] timer_periph: TIMERx(x=13)
+ \param[in] remap:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER13_CI0_RMP_GPIO: timer13 channel 0 input is connected to GPIO(TIMER13_CH0)
+ \arg TIMER13_CI0_RMP_RTCCLK: timer13 channel 0 input is connected to the RTCCLK
+ \arg TIMER13_CI0_RMP_HXTAL_DIV32: timer13 channel 0 input is connected to HXTAL/32 clock
+ \arg TIMER13_CI0_RMP_CKOUTSEL: timer13 channel 0 input is connected to CKOUTSEL
+ \param[out] none
+ \retval none
+*/
+void timer_channel_remap_config(uint32_t timer_periph, uint32_t remap)
+{
+ TIMER_IRMP(timer_periph) = (uint32_t)remap;
+}
+
+/*!
+ \brief configure TIMER write CHxVAL register selection
+ \param[in] timer_periph: TIMERx(x=0..2,13..16)
+ \param[in] ccsel:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_CHVSEL_DISABLE: no effect
+ \arg TIMER_CHVSEL_ENABLE: when write the CHxVAL register, if the write value is same as the CHxVAL value, the write access is ignored
+ \param[out] none
+ \retval none
+*/
+void timer_write_chxval_register_config(uint32_t timer_periph, uint16_t ccsel)
+{
+ if(TIMER_CHVSEL_ENABLE == ccsel) {
+ TIMER_CFG(timer_periph) |= (uint32_t)TIMER_CFG_CHVSEL;
+ } else if(TIMER_CHVSEL_DISABLE == ccsel) {
+ TIMER_CFG(timer_periph) &= ~(uint32_t)TIMER_CFG_CHVSEL;
+ } else {
+ /* illegal parameters */
+ }
+}
+
+/*!
+ \brief configure TIMER output value selection
+ \param[in] timer_periph: TIMERx(x=0,14..16)
+ \param[in] outsel:
+ only one parameter can be selected which is shown as below:
+ \arg TIMER_OUTSEL_DISABLE: no effect
+ \arg TIMER_OUTSEL_ENABLE: if POEN and IOS is 0, the output disabled
+ \param[out] none
+ \retval none
+*/
+void timer_output_value_selection_config(uint32_t timer_periph, uint16_t outsel)
+{
+ if(TIMER_OUTSEL_ENABLE == outsel) {
+ TIMER_CFG(timer_periph) |= (uint32_t)TIMER_CFG_OUTSEL;
+ } else if(TIMER_OUTSEL_DISABLE == outsel) {
+ TIMER_CFG(timer_periph) &= ~(uint32_t)TIMER_CFG_OUTSEL;
+ } else {
+ /* illegal parameters */
+ }
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_tsi.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_tsi.c
new file mode 100644
index 00000000..6fe4a903
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_tsi.c
@@ -0,0 +1,690 @@
+/*!
+ \file gd32f3x0_tsi.c
+ \brief TSI driver
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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.
+*/
+
+#include "gd32f3x0_tsi.h"
+
+/*!
+ \brief reset TSI peripheral
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void tsi_deinit(void)
+{
+ rcu_periph_reset_enable(RCU_TSIRST);
+ rcu_periph_reset_disable(RCU_TSIRST);
+}
+
+/*!
+ \brief initialize TSI plus prescaler,charge plus,transfer plus,max cycle number
+ \param[in] prescaler: CTCLK clock division factor
+ only one parameter can be selected which is shown as below:
+ \arg TSI_CTCDIV_DIV1: fCTCLK = fHCLK
+ \arg TSI_CTCDIV_DIV2: fCTCLK = fHCLK/2
+ \arg TSI_CTCDIV_DIV4: fCTCLK = fHCLK/4
+ \arg TSI_CTCDIV_DIV8: fCTCLK = fHCLK/8
+ \arg TSI_CTCDIV_DIV16: fCTCLK = fHCLK/16
+ \arg TSI_CTCDIV_DIV32: fCTCLK = fHCLK/32
+ \arg TSI_CTCDIV_DIV64: fCTCLK = fHCLK/64
+ \arg TSI_CTCDIV_DIV128: fCTCLK = fHCLK/128
+ \arg TSI_CTCDIV_DIV256: fCTCLK = fHCLK/256
+ \arg TSI_CTCDIV_DIV512: fCTCLK = fHCLK/512
+ \arg TSI_CTCDIV_DIV1024: fCTCLK = fHCLK/1024
+ \arg TSI_CTCDIV_DIV2048: fCTCLK = fHCLK/2048
+ \arg TSI_CTCDIV_DIV4096: fCTCLK = fHCLK/4096
+ \arg TSI_CTCDIV_DIV8192: fCTCLK = fHCLK/8192
+ \arg TSI_CTCDIV_DIV16384: fCTCLK = fHCLK/16384
+ \arg TSI_CTCDIV_DIV32768: fCTCLK = fHCLK/32768
+ \param[in] charge_duration: charge state duration time
+ only one parameter can be selected which is shown as below:
+ \arg TSI_CHARGE_1CTCLK(x=1..16): the duration time of charge state is x CTCLK
+ \param[in] transfer_duration: charge transfer state duration time
+ only one parameter can be selected which is shown as below:
+ \arg TSI_TRANSFER_xCTCLK(x=1..16): the duration time of transfer state is x CTCLK
+ \param[in] max_number: max cycle number
+ only one parameter can be selected which is shown as below:
+ \arg TSI_MAXNUM255: the max cycle number of a sequence is 255
+ \arg TSI_MAXNUM511: the max cycle number of a sequence is 511
+ \arg TSI_MAXNUM1023: the max cycle number of a sequence is 1023
+ \arg TSI_MAXNUM2047: the max cycle number of a sequence is 2047
+ \arg TSI_MAXNUM4095: the max cycle number of a sequence is 4095
+ \arg TSI_MAXNUM8191: the max cycle number of a sequence is 8191
+ \arg TSI_MAXNUM16383: the max cycle number of a sequence is 16383
+ \param[out] none
+ \retval none
+*/
+void tsi_init(uint32_t prescaler, uint32_t charge_duration, uint32_t transfer_duration, uint32_t max_number)
+{
+ uint32_t ctl0,ctl1;
+ if(RESET == (TSI_CTL0 & TSI_CTL0_TSIS)){
+ if(TSI_CTCDIV_DIV256 > prescaler){
+ /* config TSI_CTL0 */
+ ctl0 = TSI_CTL0;
+ /*configure TSI clock division factor,charge state duration time,charge transfer state duration time */
+ ctl0 &= ~(TSI_CTL0_CTCDIV | TSI_CTL0_CTDT | TSI_CTL0_CDT | TSI_CTL0_MCN);
+ ctl0 |= ((prescaler << 12U) | charge_duration | transfer_duration | max_number);
+ TSI_CTL0 = ctl0;
+
+ /* config TSI_CTL1 */
+ ctl1 = TSI_CTL1;
+ ctl1 &= ~TSI_CTL1_CTCDIV;
+ TSI_CTL1 = ctl1;
+ }else{
+ /* config TSI_CTL0 */
+ ctl0 = TSI_CTL0;
+ prescaler &= ~0x08U;
+ /*configure TSI clock division factor,charge state duration time,charge transfer state duration time */
+ ctl0 &= ~(TSI_CTL0_CTCDIV | TSI_CTL0_CTDT | TSI_CTL0_CDT | TSI_CTL0_MCN);
+ ctl0 |= ((prescaler << 12U) | charge_duration | transfer_duration | max_number);
+ TSI_CTL0 = ctl0;
+
+ /* config TSI_CTL1 */
+ ctl1 = TSI_CTL1;
+ ctl1 |= TSI_CTL1_CTCDIV;
+ TSI_CTL1 = ctl1;
+ }
+ }
+}
+
+/*!
+ \brief enable TSI module
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void tsi_enable(void)
+{
+ TSI_CTL0 |= TSI_CTL0_TSIEN;
+}
+
+/*!
+ \brief disable TSI module
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void tsi_disable(void)
+{
+ TSI_CTL0 &= ~TSI_CTL0_TSIEN;
+}
+
+/*!
+ \brief enable sample pin
+ \param[in] sample: sample pin
+ one or more parameters can be selected which are shown as below:
+ \arg TSI_SAMPCFG_GxPy( x=0..5,y=0..3):pin y of group x is sample pin
+ \param[out] none
+ \retval none
+*/
+void tsi_sample_pin_enable(uint32_t sample)
+{
+ if(RESET == (TSI_CTL0 & TSI_CTL0_TSIS)){
+ TSI_SAMPCFG |= sample;
+ }
+}
+
+/*!
+ \brief disable sample pin
+ \param[in] sample: sample pin
+ one or more parameters can be selected which are shown as below:
+ \arg TSI_SAMPCFG_GxPy( x=0..5,y=0..3): pin y of group x is sample pin
+ \param[out] none
+ \retval none
+*/
+void tsi_sample_pin_disable(uint32_t sample)
+{
+ if(RESET == (TSI_CTL0 & TSI_CTL0_TSIS)){
+ TSI_SAMPCFG &= ~sample;
+ }
+}
+
+/*!
+ \brief enable channel pin
+ \param[in] channel: channel pin
+ one or more parameters can be selected which are shown as below:
+ \arg TSI_CHCFG_GxPy( x=0..5,y=0..3): pin y of group x
+ \param[out] none
+ \retval none
+*/
+void tsi_channel_pin_enable(uint32_t channel)
+{
+ TSI_CHCFG |= channel;
+}
+
+/*!
+ \brief disable channel pin
+ \param[in] channel: channel pin
+ one or more parameters can be selected which are shown as below:
+ \arg TSI_CHCFG_GxPy( x=0..5,y=0..3): pin y of group x
+ \param[out] none
+ \retval none
+*/
+void tsi_channel_pin_disable(uint32_t channel)
+{
+ TSI_CHCFG &= ~channel;
+}
+
+/*!
+ \brief configure TSI triggering by software
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void tsi_software_mode_config(void)
+{
+ if(RESET == (TSI_CTL0 & TSI_CTL0_TSIS)){
+ TSI_CTL0 &= ~TSI_CTL0_TRGMOD;
+ }
+}
+
+/*!
+ \brief start a charge-transfer sequence when TSI is in software trigger mode
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void tsi_software_start(void)
+{
+ TSI_CTL0 |= TSI_CTL0_TSIS;
+}
+
+/*!
+ \brief stop a charge-transfer sequence when TSI is in software trigger mode
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void tsi_software_stop(void)
+{
+ TSI_CTL0 &= ~TSI_CTL0_TSIS;
+}
+
+/*!
+ \brief configure TSI triggering by hardware
+ \param[in] trigger_edge: the edge type in hardware trigger mode
+ only one parameter can be selected which is shown as below:
+ \arg TSI_FALLING_TRIGGER: falling edge trigger TSI charge transfer sequence
+ \arg TSI_RISING_TRIGGER: rising edge trigger TSI charge transfer sequence
+ \param[out] none
+ \retval none
+*/
+void tsi_hardware_mode_config(uint8_t trigger_edge)
+{
+ if(RESET == (TSI_CTL0 & TSI_CTL0_TSIS)){
+ /*enable hardware mode*/
+ TSI_CTL0 |= TSI_CTL0_TRGMOD;
+ /*configure the edge type in hardware trigger mode*/
+ if(TSI_FALLING_TRIGGER == trigger_edge){
+ TSI_CTL0 &= ~TSI_CTL0_EGSEL;
+ }else{
+ TSI_CTL0 |= TSI_CTL0_EGSEL;
+ }
+ }
+}
+
+/*!
+ \brief configure TSI pin mode when charge-transfer sequence is IDLE
+ \param[in] pin_mode: pin mode when charge-transfer sequence is IDLE
+ only one parameter can be selected which is shown as below:
+ \arg TSI_OUTPUT_LOW: TSI pin will output low when IDLE
+ \arg TSI_INPUT_FLOATING: TSI pin will keep input_floating when IDLE
+ \param[out] none
+ \retval none
+*/
+void tsi_pin_mode_config(uint8_t pin_mode)
+{
+ if(RESET == (TSI_CTL0 & TSI_CTL0_TSIS)){
+ if(TSI_OUTPUT_LOW == pin_mode){
+ TSI_CTL0 &= ~TSI_CTL0_PINMOD;
+ }else{
+ TSI_CTL0 |= TSI_CTL0_PINMOD;
+ }
+ }
+}
+
+/*!
+ \brief configure extend charge state
+ \param[in] extend: enable or disable extend charge state
+ only one parameter can be selected which is shown as below:
+ \arg ENABLE: enable extend charge state
+ \arg DISABLE: disable extend charge state
+ \param[in] prescaler: ECCLK clock division factor
+ only one parameter can be selected which is shown as below:
+ \arg TSI_EXTEND_DIV1: fECCLK = fHCLK
+ \arg TSI_EXTEND_DIV2: fECCLK = fHCLK/2
+ \arg TSI_EXTEND_DIV3: fECCLK = fHCLK/3
+ \arg TSI_EXTEND_DIV4: fECCLK = fHCLK/4
+ \arg TSI_EXTEND_DIV5: fECCLK = fHCLK/5
+ \arg TSI_EXTEND_DIV6: fECCLK = fHCLK/6
+ \arg TSI_EXTEND_DIV7: fECCLK = fHCLK/7
+ \arg TSI_EXTEND_DIV8: fECCLK = fHCLK/8
+ \param[in] max_duration: value range 1...128,extend charge state maximum duration time is 1*tECCLK~128*tECCLK
+ \param[out] none
+ \retval none
+*/
+void tsi_extend_charge_config(ControlStatus extend, uint8_t prescaler, uint32_t max_duration)
+{
+ uint32_t ctl0,ctl1;
+
+ if(RESET == (TSI_CTL0 & TSI_CTL0_TSIS)){
+ if(DISABLE == extend){
+ /*disable extend charge state*/
+ TSI_CTL0 &= ~TSI_CTL0_ECEN;
+ }else{
+ if(TSI_EXTEND_DIV3 > prescaler){
+ /*configure extend charge state maximum duration time*/
+ ctl0 = TSI_CTL0;
+ ctl0 &= ~TSI_CTL0_ECDT;
+ ctl0 |= TSI_EXTENDMAX((max_duration - 1U));
+ TSI_CTL0 = ctl0;
+ /*configure ECCLK clock division factor*/
+ ctl0 = TSI_CTL0;
+ ctl0 &= ~TSI_CTL0_ECDIV;
+ ctl0 |= (uint32_t)prescaler << 15U;
+ TSI_CTL0 = ctl0;
+ /*enable extend charge state*/
+ TSI_CTL0 |= TSI_CTL0_ECEN;
+ }else{
+ /*configure extend charge state maximum duration time*/
+ ctl0 = TSI_CTL0;
+ ctl0 &= ~TSI_CTL0_ECDT;
+ ctl0 |= TSI_EXTENDMAX((max_duration - 1U));
+ TSI_CTL0 = ctl0;
+ /*configure ECCLK clock division factor*/
+ ctl0 = TSI_CTL0;
+ ctl0 &= ~TSI_CTL0_ECDIV;
+ ctl0 |= (prescaler & 0x01U) << 15U;
+ TSI_CTL0 = ctl0;
+ ctl1 = TSI_CTL1;
+ ctl1 &= ~TSI_CTL1_ECDIV;
+ ctl1 |= (prescaler & 0x06U) << 28U;
+ TSI_CTL1 = ctl1;
+ /*enable extend charge state*/
+ TSI_CTL0 |= TSI_CTL0_ECEN;
+ }
+ }
+ }
+}
+
+/*!
+ \brief configure charge plus and transfer plus
+ \param[in] prescaler: CTCLK clock division factor
+ only one parameter can be selected which is shown as below:
+ \arg TSI_CTCDIV_DIV1: fCTCLK = fHCLK
+ \arg TSI_CTCDIV_DIV2: fCTCLK = fHCLK/2
+ \arg TSI_CTCDIV_DIV4: fCTCLK = fHCLK/4
+ \arg TSI_CTCDIV_DIV8: fCTCLK = fHCLK/8
+ \arg TSI_CTCDIV_DIV16: fCTCLK = fHCLK/16
+ \arg TSI_CTCDIV_DIV32: fCTCLK = fHCLK/32
+ \arg TSI_CTCDIV_DIV64: fCTCLK = fHCLK/64
+ \arg TSI_CTCDIV_DIV128: fCTCLK = fHCLK/128
+ \arg TSI_CTCDIV_DIV256: fCTCLK = fHCLK/256
+ \arg TSI_CTCDIV_DIV512: fCTCLK = fHCLK/512
+ \arg TSI_CTCDIV_DIV1024: fCTCLK = fHCLK/1024
+ \arg TSI_CTCDIV_DIV2048: fCTCLK = fHCLK/2048
+ \arg TSI_CTCDIV_DIV4096: fCTCLK = fHCLK/4096
+ \arg TSI_CTCDIV_DIV8192: fCTCLK = fHCLK/8192
+ \arg TSI_CTCDIV_DIV16384: fCTCLK = fHCLK/16384
+ \arg TSI_CTCDIV_DIV32768: fCTCLK = fHCLK/32768
+ \param[in] charge_duration: charge state duration time
+ only one parameter can be selected which is shown as below:
+ \arg TSI_CHARGE_xCTCLK(x=1..16): the duration time of charge state is x CTCLK
+ \param[in] transfer_duration: charge transfer state duration time
+ only one parameter can be selected which is shown as below:
+ \arg TSI_TRANSFER_xCTCLK(x=1..16): the duration time of transfer state is x CTCLK
+ \param[out] none
+ \retval none
+*/
+void tsi_plus_config(uint32_t prescaler, uint32_t charge_duration, uint32_t transfer_duration)
+{
+ uint32_t ctl0,ctl1;
+
+ if(RESET == (TSI_CTL0 & TSI_CTL0_TSIS)){
+ if(TSI_CTCDIV_DIV256 > prescaler){
+ /* config TSI_CTL0 */
+ ctl0 = TSI_CTL0;
+ /*configure TSI clock division factor,charge state duration time,charge transfer state duration time */
+ ctl0 &= ~(TSI_CTL0_CTCDIV | TSI_CTL0_CTDT | TSI_CTL0_CDT);
+ ctl0 |= ((prescaler << 12U) | charge_duration | transfer_duration);
+ TSI_CTL0 = ctl0;
+
+ /* config TSI_CTL1 */
+ ctl1 = TSI_CTL1;
+ ctl1 &= ~TSI_CTL1_CTCDIV;
+ TSI_CTL1 = ctl1;
+ }else{
+ /* config TSI_CTL */
+ ctl0 = TSI_CTL0;
+ prescaler &= ~0x08U;
+ /*configure TSI clock division factor,charge state duration time,charge transfer state duration time */
+ ctl0 &= ~(TSI_CTL0_CTCDIV | TSI_CTL0_CTDT | TSI_CTL0_CDT);
+ ctl0 |= ((prescaler << 12U) | charge_duration | transfer_duration);
+ TSI_CTL0 = ctl0;
+
+ /* config TSI_CTL2 */
+ ctl1 = TSI_CTL1;
+ ctl1 |= TSI_CTL1_CTCDIV;
+ TSI_CTL1 = ctl1;
+ }
+ }
+}
+
+/*!
+ \brief configure the max cycle number of a charge-transfer sequence
+ \param[in] max_number: max cycle number
+ only one parameter can be selected which is shown as below:
+ \arg TSI_MAXNUM255: the max cycle number of a sequence is 255
+ \arg TSI_MAXNUM511: the max cycle number of a sequence is 511
+ \arg TSI_MAXNUM1023: the max cycle number of a sequence is 1023
+ \arg TSI_MAXNUM2047: the max cycle number of a sequence is 2047
+ \arg TSI_MAXNUM4095: the max cycle number of a sequence is 4095
+ \arg TSI_MAXNUM8191: the max cycle number of a sequence is 8191
+ \arg TSI_MAXNUM16383: the max cycle number of a sequence is 16383
+ \param[out] none
+ \retval none
+*/
+void tsi_max_number_config(uint32_t max_number)
+{
+ if(RESET == (TSI_CTL0 & TSI_CTL0_TSIS)){
+ uint32_t maxnum;
+ maxnum = TSI_CTL0;
+ /*configure the max cycle number of a charge-transfer sequence*/
+ maxnum &= ~TSI_CTL0_MCN;
+ maxnum |= max_number;
+ TSI_CTL0 = maxnum;
+ }
+}
+
+/*!
+ \brief switch on hysteresis pin
+ \param[in] group_pin: select pin which will be switched on hysteresis
+ one or more parameters can be selected which are shown as below:
+ \arg TSI_PHM_GxPy(x=0..5,y=0..3): pin y of group x switch on hysteresis
+ \param[out] none
+ \retval none
+*/
+void tsi_hysteresis_on(uint32_t group_pin)
+{
+ TSI_PHM |= group_pin;
+}
+
+/*!
+ \brief switch off hysteresis pin
+ \param[in] group_pin: select pin which will be switched off hysteresis
+ one or more parameters can be selected which are shown as below:
+ \arg TSI_PHM_GxPy(x=0..5,y=0..3): pin y of group x switch off hysteresis
+ \param[out] none
+ \retval none
+*/
+void tsi_hysteresis_off(uint32_t group_pin)
+{
+ TSI_PHM &= ~group_pin;
+}
+
+/*!
+ \brief switch on analog pin
+ \param[in] group_pin: select pin which will be switched on analog
+ one or more parameters can be selected which are shown as below:
+ \arg TSI_ASW_GxPy(x=0..5,y=0..3):pin y of group x switch on analog
+ \param[out] none
+ \retval none
+*/
+void tsi_analog_on(uint32_t group_pin)
+{
+ TSI_ASW |= group_pin;
+}
+
+/*!
+ \brief switch off analog pin
+ \param[in] group_pin: select pin which will be switched off analog
+ one or more parameters can be selected which are shown as below:
+ \arg TSI_ASW_GxPy(x=0..5,y=0..3):pin y of group x switch off analog
+ \param[out] none
+ \retval none
+*/
+void tsi_analog_off(uint32_t group_pin)
+{
+ TSI_ASW &= ~group_pin;
+}
+
+/*!
+ \brief enbale group
+ \param[in] group: select group to be enabled
+ one or more parameters can be selected which are shown as below:
+ \arg TSI_GCTL_GEx(x=0..5): the x group will be enabled
+ \param[out] none
+ \retval none
+*/
+void tsi_group_enable(uint32_t group)
+{
+ TSI_GCTL |= group;
+}
+
+/*!
+ \brief disbale group
+ \param[in] group: select group to be disabled
+ one or more parameters can be selected which are shown as below:
+ \arg TSI_GCTL_GEx(x=0..5):the x group will be disabled
+ \param[out] none
+ \retval none
+*/
+void tsi_group_disable(uint32_t group)
+{
+ TSI_GCTL &= ~group;
+}
+
+/*!
+ \brief get group complete status
+ \param[in] group: select group
+ only one parameter can be selected which is shown as below:
+ \arg TSI_GCTL_GCx(x=0..5): get the complete status of group x
+ \param[out] none
+ \retval FlagStatus: group complete status,SET or RESET
+*/
+FlagStatus tsi_group_status_get(uint32_t group)
+{
+ FlagStatus flag_status;
+ if(TSI_GCTL & group){
+ flag_status = SET;
+ }else{
+ flag_status = RESET;
+ }
+ return flag_status;
+}
+
+/*!
+ \brief get the cycle number for group0 as soon as a charge-transfer sequence completes
+ \param[in] none
+ \param[out] none
+ \retval group0 cycle number
+*/
+uint16_t tsi_group0_cycle_get(void)
+{
+ return (uint16_t)TSI_G0CYCN;
+}
+
+/*!
+ \brief get the cycle number for group1 as soon as a charge-transfer sequence completes
+ \param[in] none
+ \param[out] none
+ \retval group1 cycle number
+*/
+uint16_t tsi_group1_cycle_get(void)
+{
+ return (uint16_t)TSI_G1CYCN;
+}
+
+/*!
+ \brief get the cycle number for group2 as soon as a charge-transfer sequence completes
+ \param[in] none
+ \param[out] none
+ \retval group2 cycle number
+*/
+uint16_t tsi_group2_cycle_get(void)
+{
+ return (uint16_t)TSI_G2CYCN;
+}
+
+/*!
+ \brief get the cycle number for group3 as soon as a charge-transfer sequence completes
+ \param[in] none
+ \param[out] none
+ \retval group3 cycle number
+*/
+uint16_t tsi_group3_cycle_get(void)
+{
+ return (uint16_t)TSI_G3CYCN;
+}
+
+/*!
+ \brief get the cycle number for group4 as soon as a charge-transfer sequence completes
+ \param[in] none
+ \param[out] none
+ \retval group4 cycle number
+*/
+uint16_t tsi_group4_cycle_get(void)
+{
+ return (uint16_t)TSI_G4CYCN;
+}
+
+/*!
+ \brief get the cycle number for group5 as soon as a charge-transfer sequence completes
+ \param[in] none
+ \param[out] none
+ \retval group5 cycle number
+*/
+uint16_t tsi_group5_cycle_get(void)
+{
+ return (uint16_t)TSI_G5CYCN;
+}
+
+/*!
+ \brief clear flag
+ \param[in] flag: select flag which will be cleared
+ only one parameter can be selected which is shown as below:
+ \arg TSI_FLAG_CTCF: clear charge-transfer complete flag
+ \arg TSI_FLAG_MNERR: clear max cycle number error
+ \param[out] none
+ \retval none
+*/
+void tsi_flag_clear(uint32_t flag)
+{
+ TSI_INTC |= flag;
+}
+
+/*!
+ \brief get flag
+ \param[in] flag:
+ only one parameter can be selected which is shown as below:
+ \arg TSI_FLAG_CTCF: charge-transfer complete flag
+ \arg TSI_FLAG_MNERR: max cycle bumber error
+ \param[out] none
+ \retval FlagStatus:SET or RESET
+*/
+FlagStatus tsi_flag_get(uint32_t flag)
+{
+ FlagStatus flag_status;
+ if(TSI_INTF & flag){
+ flag_status = SET;
+ }else{
+ flag_status = RESET;
+ }
+ return flag_status;
+}
+
+/*!
+ \brief enable TSI interrupt
+ \param[in] source: select interrupt which will be enabled
+ only one parameter can be selected which is shown as below:
+ \arg TSI_INT_CCTCF: charge-transfer complete flag interrupt enable
+ \arg TSI_INT_MNERR: max cycle number error interrupt enable
+ \param[out] none
+ \retval none
+*/
+void tsi_interrupt_enable(uint32_t source)
+{
+ TSI_INTEN |= source;
+}
+
+/*!
+ \brief disable TSI interrupt
+ \param[in] source: select interrupt which will be disabled
+ only one parameter can be selected which is shown as below:
+ \arg TSI_INT_CCTCF: charge-transfer complete flag interrupt disable
+ \arg TSI_INT_MNERR: max cycle number error interrupt disable
+ \param[out] none
+ \retval none
+*/
+void tsi_interrupt_disable(uint32_t source)
+{
+ TSI_INTEN &= ~source;
+}
+
+/*!
+ \brief clear TSI interrupt flag
+ \param[in] flag: select flag which will be cleared
+ only one parameter can be selected which is shown as below:
+ \arg TSI_INT_FLAG_CTCF: clear charge-transfer complete flag
+ \arg TSI_INT_FLAG_MNERR: clear max cycle number error
+ \param[out] none
+ \retval none
+*/
+void tsi_interrupt_flag_clear(uint32_t flag)
+{
+ TSI_INTC |= flag;
+}
+
+/*!
+ \brief get TSI interrupt flag
+ \param[in] flag:
+ only one parameter can be selected which is shown as below:
+ \arg TSI_INT_FLAG_CTCF: charge-transfer complete flag
+ \arg TSI_INT_FLAG_MNERR: max Cycle Number Error
+ \param[out] none
+ \retval FlagStatus:SET or RESET
+*/
+FlagStatus tsi_interrupt_flag_get(uint32_t flag)
+{
+ uint32_t interrupt_enable = 0U,interrupt_flag = 0U;
+ interrupt_flag = (TSI_INTF & flag);
+ interrupt_enable = (TSI_INTEN & flag);
+ if(interrupt_flag && interrupt_enable){
+ return SET;
+ }else{
+ return RESET;
+ }
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_usart.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_usart.c
new file mode 100644
index 00000000..00e48599
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_usart.c
@@ -0,0 +1,1310 @@
+/*!
+ \file gd32f3x0_usart.c
+ \brief USART driver
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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.
+*/
+
+#include "gd32f3x0_usart.h"
+
+/* USART register bit offset */
+#define CTL1_ADDR_OFFSET ((uint32_t)24U) /* bit offset of ADDR in USART_CTL1 */
+#define GP_GUAT_OFFSET ((uint32_t)8U) /* bit offset of GUAT in USART_GP */
+#define CTL2_SCRTNUM_OFFSET ((uint32_t)17U) /* bit offset of SCRTNUM in USART_CTL2 */
+#define RT_BL_OFFSET ((uint32_t)24U) /* bit offset of BL in USART_RT */
+#define CTL0_DEA_OFFSET ((uint32_t)21U) /* bit offset of DEA in USART_CTL0 */
+#define CTL0_DED_OFFSET ((uint32_t)16U) /* bit offset of DED in USART_CTL0 */
+
+/*!
+ \brief reset USART
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[out] none
+ \retval none
+*/
+void usart_deinit(uint32_t usart_periph)
+{
+ switch(usart_periph) {
+ case USART0:
+ /* reset USART0 */
+ rcu_periph_reset_enable(RCU_USART0RST);
+ rcu_periph_reset_disable(RCU_USART0RST);
+ break;
+ case USART1:
+ /* reset USART1 */
+ rcu_periph_reset_enable(RCU_USART1RST);
+ rcu_periph_reset_disable(RCU_USART1RST);
+ break;
+ default:
+ break;
+ }
+}
+
+/*!
+ \brief configure USART baud rate value
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[in] baudval: baud rate value
+ \param[out] none
+ \retval none
+*/
+void usart_baudrate_set(uint32_t usart_periph, uint32_t baudval)
+{
+ uint32_t uclk = 0U, intdiv = 0U, fradiv = 0U, udiv = 0U;
+ switch(usart_periph) {
+ /* get clock frequency */
+ case USART0:
+ /* get USART0 clock */
+ uclk = rcu_clock_freq_get(CK_USART);
+ break;
+ case USART1:
+ /* get USART1 clock */
+ uclk = rcu_clock_freq_get(CK_APB1);
+ break;
+ default:
+ break;
+ }
+ if(USART_CTL0(usart_periph) & USART_CTL0_OVSMOD) {
+ /* oversampling by 8, configure the value of USART_BAUD */
+ udiv = ((2U * uclk) + baudval / 2U) / baudval;
+ intdiv = udiv & 0x0000fff0U;
+ fradiv = (udiv >> 1U) & 0x00000007U;
+ USART_BAUD(usart_periph) = ((USART_BAUD_FRADIV | USART_BAUD_INTDIV) & (intdiv | fradiv));
+ } else {
+ /* oversampling by 16, configure the value of USART_BAUD */
+ udiv = (uclk + baudval / 2U) / baudval;
+ intdiv = udiv & 0x0000fff0U;
+ fradiv = udiv & 0x0000000fU;
+ USART_BAUD(usart_periph) = ((USART_BAUD_FRADIV | USART_BAUD_INTDIV) & (intdiv | fradiv));
+ }
+}
+
+/*!
+ \brief configure USART parity
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[in] paritycfg: USART parity configure
+ only one parameter can be selected which is shown as below:
+ \arg USART_PM_NONE: no parity
+ \arg USART_PM_ODD: odd parity
+ \arg USART_PM_EVEN: even parity
+ \param[out] none
+ \retval none
+*/
+void usart_parity_config(uint32_t usart_periph, uint32_t paritycfg)
+{
+ /* disable USART */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+ /* clear USART_CTL0 PM,PCEN bits */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_PM | USART_CTL0_PCEN);
+ /* configure USART parity mode */
+ USART_CTL0(usart_periph) |= paritycfg;
+}
+
+/*!
+ \brief configure USART word length
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[in] wlen: USART word length configure
+ only one parameter can be selected which is shown as below:
+ \arg USART_WL_8BIT: 8 bits
+ \arg USART_WL_9BIT: 9 bits
+ \param[out] none
+ \retval none
+*/
+void usart_word_length_set(uint32_t usart_periph, uint32_t wlen)
+{
+ /* disable USART */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+ /* clear USART_CTL0 WL bit */
+ USART_CTL0(usart_periph) &= ~USART_CTL0_WL;
+ /* configure USART word length */
+ USART_CTL0(usart_periph) |= wlen;
+}
+
+/*!
+ \brief configure USART stop bit length
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[in] stblen: USART stop bit configure
+ only one parameter can be selected which is shown as below:
+ \arg USART_STB_1BIT: 1 bit
+ \arg USART_STB_0_5BIT: 0.5bit
+ \arg USART_STB_2BIT: 2 bits
+ \arg USART_STB_1_5BIT: 1.5bit
+ \param[out] none
+ \retval none
+*/
+void usart_stop_bit_set(uint32_t usart_periph, uint32_t stblen)
+{
+ /* disable USART */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+ /* clear USART_CTL1 STB bits */
+ USART_CTL1(usart_periph) &= ~USART_CTL1_STB;
+ USART_CTL1(usart_periph) |= stblen;
+}
+
+/*!
+ \brief enable USART
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[out] none
+ \retval none
+*/
+void usart_enable(uint32_t usart_periph)
+{
+ USART_CTL0(usart_periph) |= USART_CTL0_UEN;
+}
+
+/*!
+ \brief disable USART
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[out] none
+ \retval none
+*/
+void usart_disable(uint32_t usart_periph)
+{
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+}
+
+/*!
+ \brief configure USART transmitter
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[in] txconfig: enable or disable USART transmitter
+ only one parameter can be selected which is shown as below:
+ \arg USART_TRANSMIT_ENABLE: enable USART transmission
+ \arg USART_TRANSMIT_DISABLE: enable USART transmission
+ \param[out] none
+ \retval none
+*/
+void usart_transmit_config(uint32_t usart_periph, uint32_t txconfig)
+{
+ USART_CTL0(usart_periph) &= ~USART_CTL0_TEN;
+ /* configure transfer mode */
+ USART_CTL0(usart_periph) |= txconfig;
+}
+
+/*!
+ \brief configure USART receiver
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[in] rxconfig: enable or disable USART receiver
+ only one parameter can be selected which is shown as below:
+ \arg USART_RECEIVE_ENABLE: enable USART reception
+ \arg USART_RECEIVE_DISABLE: disable USART reception
+ \param[out] none
+ \retval none
+*/
+void usart_receive_config(uint32_t usart_periph, uint32_t rxconfig)
+{
+ USART_CTL0(usart_periph) &= ~USART_CTL0_REN;
+ /* configure receiver mode */
+ USART_CTL0(usart_periph) |= rxconfig;
+}
+
+/*!
+ \brief data is transmitted/received with the LSB/MSB first
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[in] msbf: LSB/MSB
+ only one parameter can be selected which is shown as below:
+ \arg USART_MSBF_LSB: LSB first
+ \arg USART_MSBF_MSB: MSB first
+ \param[out] none
+ \retval none
+*/
+void usart_data_first_config(uint32_t usart_periph, uint32_t msbf)
+{
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+ /* configure LSB or MSB first */
+ USART_CTL1(usart_periph) &= ~(USART_CTL1_MSBF);
+ USART_CTL1(usart_periph) |= (USART_CTL1_MSBF & msbf);
+}
+
+/*!
+ \brief USART inverted configure
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[in] invertpara: refer to usart_invert_enum
+ only one parameter can be selected which is shown as below:
+ \arg USART_DINV_ENABLE: data bit level inversion
+ \arg USART_DINV_DISABLE: data bit level not inversion
+ \arg USART_TXPIN_ENABLE: TX pin level inversion
+ \arg USART_TXPIN_DISABLE: TX pin level not inversion
+ \arg USART_RXPIN_ENABLE: RX pin level inversion
+ \arg USART_RXPIN_DISABLE: RX pin level not inversion
+ \arg USART_SWAP_ENABLE: swap TX/RX pins
+ \arg USART_SWAP_DISABLE: not swap TX/RX pins
+ \param[out] none
+ \retval none
+*/
+void usart_invert_config(uint32_t usart_periph, usart_invert_enum invertpara)
+{
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+ /* inverted or not the specified signal */
+ switch(invertpara) {
+ case USART_DINV_ENABLE:
+ USART_CTL1(usart_periph) |= USART_CTL1_DINV;
+ break;
+ case USART_DINV_DISABLE:
+ USART_CTL1(usart_periph) &= ~(USART_CTL1_DINV);
+ break;
+ case USART_TXPIN_ENABLE:
+ USART_CTL1(usart_periph) |= USART_CTL1_TINV;
+ break;
+ case USART_TXPIN_DISABLE:
+ USART_CTL1(usart_periph) &= ~(USART_CTL1_TINV);
+ break;
+ case USART_RXPIN_ENABLE:
+ USART_CTL1(usart_periph) |= USART_CTL1_RINV;
+ break;
+ case USART_RXPIN_DISABLE:
+ USART_CTL1(usart_periph) &= ~(USART_CTL1_RINV);
+ break;
+ case USART_SWAP_ENABLE:
+ USART_CTL1(usart_periph) |= USART_CTL1_STRP;
+ break;
+ case USART_SWAP_DISABLE:
+ USART_CTL1(usart_periph) &= ~(USART_CTL1_STRP);
+ break;
+ default:
+ break;
+ }
+}
+
+/*!
+ \brief enable the USART overrun function
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[out] none
+ \retval none
+*/
+void usart_overrun_enable(uint32_t usart_periph)
+{
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+ /* enable overrun function */
+ USART_CTL2(usart_periph) &= ~(USART_CTL2_OVRD);
+}
+
+/*!
+ \brief disable the USART overrun function
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[out] none
+ \retval none
+*/
+void usart_overrun_disable(uint32_t usart_periph)
+{
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+ /* disable overrun function */
+ USART_CTL2(usart_periph) |= USART_CTL2_OVRD;
+}
+
+/*!
+ \brief configure the USART oversample mode
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[in] oversamp: oversample value
+ only one parameter can be selected which is shown as below:
+ \arg USART_OVSMOD_8: oversampling by 8
+ \arg USART_OVSMOD_16: oversampling by 16
+ \param[out] none
+ \retval none
+*/
+void usart_oversample_config(uint32_t usart_periph, uint32_t oversamp)
+{
+ /* disable USART */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+ /* clear OVSMOD bit */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_OVSMOD);
+ USART_CTL0(usart_periph) |= oversamp;
+}
+
+/*!
+ \brief configure the sample bit method
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[in] osb: sample bit
+ only one parameter can be selected which is shown as below:
+ \arg USART_OSB_1BIT: 1 bit
+ \arg USART_OSB_3BIT: 3 bits
+ \param[out] none
+ \retval none
+*/
+void usart_sample_bit_config(uint32_t usart_periph, uint32_t osb)
+{
+ /* disable USART */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+
+ USART_CTL2(usart_periph) &= ~(USART_CTL2_OSB);
+ USART_CTL2(usart_periph) |= osb;
+}
+
+/*!
+ \brief enable receiver timeout
+ \param[in] usart_periph: USARTx(x=0)
+ \param[out] none
+ \retval none
+*/
+void usart_receiver_timeout_enable(uint32_t usart_periph)
+{
+ USART_CTL1(usart_periph) |= USART_CTL1_RTEN;
+}
+
+/*!
+ \brief disable receiver timeout
+ \param[in] usart_periph: USARTx(x=0)
+ \param[out] none
+ \retval none
+*/
+void usart_receiver_timeout_disable(uint32_t usart_periph)
+{
+ USART_CTL1(usart_periph) &= ~(USART_CTL1_RTEN);
+}
+
+/*!
+ \brief configure receiver timeout threshold
+ \param[in] usart_periph: USARTx(x=0)
+ \param[in] rtimeout: 0x00000000-0x00FFFFFF, receiver timeout value in terms of number of baud clocks
+ \param[out] none
+ \retval none
+*/
+void usart_receiver_timeout_threshold_config(uint32_t usart_periph, uint32_t rtimeout)
+{
+ USART_RT(usart_periph) &= ~(USART_RT_RT);
+ USART_RT(usart_periph) |= rtimeout;
+}
+
+/*!
+ \brief USART transmit data function
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[in] data: data of transmission
+ \param[out] none
+ \retval none
+*/
+void usart_data_transmit(uint32_t usart_periph, uint32_t data)
+{
+ USART_TDATA(usart_periph) = (USART_TDATA_TDATA & data);
+}
+
+/*!
+ \brief USART receive data function
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[out] none
+ \retval data of received
+*/
+uint16_t usart_data_receive(uint32_t usart_periph)
+{
+ return (uint16_t)(GET_BITS(USART_RDATA(usart_periph), 0U, 8U));
+}
+
+/*!
+ \brief enable auto baud rate detection
+ \param[in] usart_periph: USARTx(x=0)
+ \param[out] none
+ \retval none
+*/
+void usart_autobaud_detection_enable(uint32_t usart_periph)
+{
+ USART_CTL1(usart_periph) |= USART_CTL1_ABDEN;
+}
+
+/*!
+ \brief disable auto baud rate detection
+ \param[in] usart_periph: USARTx(x=0)
+ \param[out] none
+ \retval none
+*/
+void usart_autobaud_detection_disable(uint32_t usart_periph)
+{
+ USART_CTL1(usart_periph) &= ~(USART_CTL1_ABDEN);
+}
+
+/*!
+ \brief configure auto baud rate detection mode
+ \param[in] usart_periph: USARTx(x=0)
+ \param[in] abdmod: auto baud rate detection mode
+ only one parameter can be selected which is shown as below:
+ \arg USART_ABDM_FTOR: falling edge to rising edge measurement
+ \arg USART_ABDM_FTOF: falling edge to falling edge measurement
+ \param[out] none
+ \retval none
+*/
+void usart_autobaud_detection_mode_config(uint32_t usart_periph, uint32_t abdmod)
+{
+ /* reset ABDM bits */
+ USART_CTL1(usart_periph) &= ~(USART_CTL1_ABDM);
+ USART_CTL1(usart_periph) |= abdmod;
+}
+
+/*!
+ \brief address of the USART terminal
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[in] addr: 0x00-0xFF, address of USART terminal
+ \param[out] none
+ \retval none
+*/
+void usart_address_config(uint32_t usart_periph, uint8_t addr)
+{
+ /* disable USART */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+
+ USART_CTL1(usart_periph) &= ~(USART_CTL1_ADDR);
+ USART_CTL1(usart_periph) |= (USART_CTL1_ADDR & (((uint32_t)addr) << CTL1_ADDR_OFFSET));
+}
+
+/*!
+ \brief configure the address of the USART in wake up by address match mode
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[in] addmod: address detection mode
+ only one parameter can be selected which is shown as below:
+ \arg USART_ADDM_4BIT: 4 bits
+ \arg USART_ADDM_FULLBIT: full bits
+ \param[out] none
+ \retval none
+*/
+void usart_address_detection_mode_config(uint32_t usart_periph, uint32_t addmod)
+{
+ /* disable USART */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+
+ USART_CTL1(usart_periph) &= ~(USART_CTL1_ADDM);
+ USART_CTL1(usart_periph) |= USART_CTL1_ADDM & (addmod);
+}
+
+/*!
+ \brief enable mute mode
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[out] none
+ \retval none
+*/
+void usart_mute_mode_enable(uint32_t usart_periph)
+{
+ USART_CTL0(usart_periph) |= USART_CTL0_MEN;
+}
+
+/*!
+ \brief disable mute mode
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[out] none
+ \retval none
+*/
+void usart_mute_mode_disable(uint32_t usart_periph)
+{
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_MEN);
+}
+
+/*!
+ \brief configure wakeup method in mute mode
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[in] wmethod: two methods be used to enter or exit the mute mode
+ only one parameter can be selected which is shown as below:
+ \arg USART_WM_IDLE: idle line
+ \arg USART_WM_ADDR: address mark
+ \param[out] none
+ \retval none
+*/
+void usart_mute_mode_wakeup_config(uint32_t usart_periph, uint32_t wmethod)
+{
+ /* disable USART */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_WM);
+ USART_CTL0(usart_periph) |= wmethod;
+}
+
+/*!
+ \brief enable LIN mode
+ \param[in] usart_periph: USARTx(x=0)
+ \param[out] none
+ \retval none
+*/
+void usart_lin_mode_enable(uint32_t usart_periph)
+{
+ /* disable USART */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+
+ USART_CTL1(usart_periph) |= USART_CTL1_LMEN;
+}
+
+/*!
+ \brief disable LIN mode
+ \param[in] usart_periph: USARTx(x=0)
+ \param[out] none
+ \retval none
+*/
+void usart_lin_mode_disable(uint32_t usart_periph)
+{
+ /* disable USART */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+
+ USART_CTL1(usart_periph) &= ~(USART_CTL1_LMEN);
+}
+
+/*!
+ \brief configure LIN break frame length
+ \param[in] usart_periph: USARTx(x=0)
+ \param[in] lblen: LIN break detection length
+ only one parameter can be selected which is shown as below:
+ \arg USART_LBLEN_10B: 10 bits break detection
+ \arg USART_LBLEN_11B: 11 bits break detection
+ \param[out] none
+ \retval none
+*/
+void usart_lin_break_detection_length_config(uint32_t usart_periph, uint32_t lblen)
+{
+ /* disable USART */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+ USART_CTL1(usart_periph) &= ~(USART_CTL1_LBLEN);
+ USART_CTL1(usart_periph) |= USART_CTL1_LBLEN & (lblen);
+}
+
+/*!
+ \brief enable half-duplex mode
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[out] none
+ \retval none
+*/
+void usart_halfduplex_enable(uint32_t usart_periph)
+{
+ /* disable USART */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+
+ USART_CTL2(usart_periph) |= USART_CTL2_HDEN;
+}
+
+/*!
+ \brief disable half-duplex mode
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[out] none
+ \retval none
+*/
+void usart_halfduplex_disable(uint32_t usart_periph)
+{
+ /* disable USART */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+
+ USART_CTL2(usart_periph) &= ~(USART_CTL2_HDEN);
+}
+
+/*!
+ \brief enable USART clock
+ \param[in] usart_periph: USARTx(x=0)
+ \param[out] none
+ \retval none
+*/
+void usart_clock_enable(uint32_t usart_periph)
+{
+ /* disable USART */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+
+ USART_CTL1(usart_periph) |= USART_CTL1_CKEN;
+}
+
+/*!
+ \brief disable USART clock
+ \param[in] usart_periph: USARTx(x=0)
+ \param[out] none
+ \retval none
+*/
+void usart_clock_disable(uint32_t usart_periph)
+{
+ /* disable USART */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+
+ USART_CTL1(usart_periph) &= ~(USART_CTL1_CKEN);
+}
+
+/*!
+ \brief configure USART synchronous mode parameters
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[in] clen: last bit clock pulse
+ only one parameter can be selected which is shown as below:
+ \arg USART_CLEN_NONE: clock pulse of the last data bit (MSB) is not output to the CK pin
+ \arg USART_CLEN_EN: clock pulse of the last data bit (MSB) is output to the CK pin
+ \param[in] cph: clock phase
+ only one parameter can be selected which is shown as below:
+ \arg USART_CPH_1CK: first clock transition is the first data capture edge
+ \arg USART_CPH_2CK: second clock transition is the first data capture edge
+ \param[in] cpl: clock polarity
+ only one parameter can be selected which is shown as below:
+ \arg USART_CPL_LOW: steady low value on CK pin
+ \arg USART_CPL_HIGH: steady high value on CK pin
+ \param[out] none
+ \retval none
+*/
+void usart_synchronous_clock_config(uint32_t usart_periph, uint32_t clen, uint32_t cph, uint32_t cpl)
+{
+ /* disable USART */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+ /* reset USART_CTL1 CLEN,CPH,CPL bits */
+ USART_CTL1(usart_periph) &= ~(USART_CTL1_CLEN | USART_CTL1_CPH | USART_CTL1_CPL);
+
+ USART_CTL1(usart_periph) |= (USART_CTL1_CLEN & clen);
+ USART_CTL1(usart_periph) |= (USART_CTL1_CPH & cph);
+ USART_CTL1(usart_periph) |= (USART_CTL1_CPL & cpl);
+}
+
+/*!
+ \brief configure guard time value in smartcard mode
+ \param[in] usart_periph: USARTx(x=0)
+ \param[in] guat: 0x00-0xFF
+ \param[out] none
+ \retval none
+*/
+void usart_guard_time_config(uint32_t usart_periph, uint32_t guat)
+{
+ /* disable USART */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+
+ USART_GP(usart_periph) &= ~(USART_GP_GUAT);
+ USART_GP(usart_periph) |= (USART_GP_GUAT & ((guat) << GP_GUAT_OFFSET));
+}
+
+/*!
+ \brief enable smartcard mode
+ \param[in] usart_periph: USARTx(x=0)
+ \param[out] none
+ \retval none
+*/
+void usart_smartcard_mode_enable(uint32_t usart_periph)
+{
+ /* disable USART */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+
+ USART_CTL2(usart_periph) |= USART_CTL2_SCEN;
+}
+
+/*!
+ \brief disable smartcard mode
+ \param[in] usart_periph: USARTx(x=0)
+ \param[out] none
+ \retval none
+*/
+void usart_smartcard_mode_disable(uint32_t usart_periph)
+{
+ /* disable USART */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+
+ USART_CTL2(usart_periph) &= ~(USART_CTL2_SCEN);
+}
+
+/*!
+ \brief enable NACK in smartcard mode
+ \param[in] usart_periph: USARTx(x=0)
+ \param[out] none
+ \retval none
+*/
+void usart_smartcard_mode_nack_enable(uint32_t usart_periph)
+{
+ /* disable USART */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+
+ USART_CTL2(usart_periph) |= USART_CTL2_NKEN;
+}
+
+/*!
+ \brief disable NACK in smartcard mode
+ \param[in] usart_periph: USARTx(x=0)
+ \param[out] none
+ \retval none
+*/
+void usart_smartcard_mode_nack_disable(uint32_t usart_periph)
+{
+ /* disable USART */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+
+ USART_CTL2(usart_periph) &= ~(USART_CTL2_NKEN);
+}
+
+/*!
+ \brief enable early NACK in smartcard mode
+ \param[in] usart_periph: USARTx(x=0)
+ \param[out] none
+ \retval none
+*/
+void usart_smartcard_mode_early_nack_enable(uint32_t usart_periph)
+{
+ USART_RFCS(usart_periph) |= USART_RFCS_ELNACK;
+}
+
+/*!
+ \brief disable early NACK in smartcard mode
+ \param[in] usart_periph: USARTx(x=0)
+ \param[out] none
+ \retval none
+*/
+void usart_smartcard_mode_early_nack_disable(uint32_t usart_periph)
+{
+ USART_RFCS(usart_periph) &= ~USART_RFCS_ELNACK;
+}
+
+/*!
+ \brief configure smartcard auto-retry number
+ \param[in] usart_periph: USARTx(x=0)
+ \param[in] scrtnum: 0x00000000-0x00000007, smartcard auto-retry number
+ \param[out] none
+ \retval none
+*/
+void usart_smartcard_autoretry_config(uint32_t usart_periph, uint32_t scrtnum)
+{
+ /* disable USART */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+ USART_CTL2(usart_periph) &= ~(USART_CTL2_SCRTNUM);
+ USART_CTL2(usart_periph) |= (USART_CTL2_SCRTNUM & (scrtnum << CTL2_SCRTNUM_OFFSET));
+}
+
+/*!
+ \brief configure block length
+ \param[in] usart_periph: USARTx(x=0)
+ \param[in] bl: 0x00000000-0x000000FF
+ \param[out] none
+ \retval none
+*/
+void usart_block_length_config(uint32_t usart_periph, uint32_t bl)
+{
+ USART_RT(usart_periph) &= ~(USART_RT_BL);
+ USART_RT(usart_periph) |= (USART_RT_BL & ((bl) << RT_BL_OFFSET));
+}
+
+/*!
+ \brief enable IrDA mode
+ \param[in] usart_periph: USARTx(x=0)
+ \param[out] none
+ \retval none
+*/
+void usart_irda_mode_enable(uint32_t usart_periph)
+{
+ /* disable USART */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+
+ USART_CTL2(usart_periph) |= USART_CTL2_IREN;
+}
+
+/*!
+ \brief disable IrDA mode
+ \param[in] usart_periph: USARTx(x=0)
+ \param[out] none
+ \retval none
+*/
+void usart_irda_mode_disable(uint32_t usart_periph)
+{
+ /* disable USART */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+
+ USART_CTL2(usart_periph) &= ~(USART_CTL2_IREN);
+}
+
+/*!
+ \brief configure the peripheral clock prescaler in USART IrDA low-power or SmartCard mode
+ \param[in] usart_periph: USARTx(x=0)
+ \param[in] psc: 0x00000000-0x000000FF
+ \param[out] none
+ \retval none
+*/
+void usart_prescaler_config(uint32_t usart_periph, uint32_t psc)
+{
+ /* disable USART */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+ USART_GP(usart_periph) &= ~(USART_GP_PSC);
+ USART_GP(usart_periph) |= psc;
+}
+
+/*!
+ \brief configure IrDA low-power
+ \param[in] usart_periph: USARTx(x=0)
+ \param[in] irlp: IrDA low-power or normal
+ only one parameter can be selected which is shown as below:
+ \arg USART_IRLP_LOW: low-power
+ \arg USART_IRLP_NORMAL: normal
+ \param[out] none
+ \retval none
+*/
+void usart_irda_lowpower_config(uint32_t usart_periph, uint32_t irlp)
+{
+ /* disable USART */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+ USART_CTL2(usart_periph) &= ~(USART_CTL2_IRLP);
+ USART_CTL2(usart_periph) |= (USART_CTL2_IRLP & irlp);
+}
+
+/*!
+ \brief configure hardware flow control RTS
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[in] rtsconfig: enable or disable RTS
+ only one parameter can be selected which is shown as below:
+ \arg USART_RTS_ENABLE: enable RTS
+ \arg USART_RTS_DISABLE: disable RTS
+ \param[out] none
+ \retval none
+*/
+void usart_hardware_flow_rts_config(uint32_t usart_periph, uint32_t rtsconfig)
+{
+ /* disable USART */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+
+ USART_CTL2(usart_periph) &= ~(USART_CTL2_RTSEN);
+ USART_CTL2(usart_periph) |= rtsconfig;
+}
+
+/*!
+ \brief configure hardware flow control CTS
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[in] ctsconfig: enable or disable CTS
+ only one parameter can be selected which is shown as below:
+ \arg USART_CTS_ENABLE: enable CTS
+ \arg USART_CTS_DISABLE: disable CTS
+ \param[out] none
+ \retval none
+*/
+void usart_hardware_flow_cts_config(uint32_t usart_periph, uint32_t ctsconfig)
+{
+ /* disable USART */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+
+ USART_CTL2(usart_periph) &= ~USART_CTL2_CTSEN;
+ USART_CTL2(usart_periph) |= ctsconfig;
+}
+
+/*!
+ \brief enable RS485 driver
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[out] none
+ \retval none
+*/
+void usart_rs485_driver_enable(uint32_t usart_periph)
+{
+ /* disable USART */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+
+ USART_CTL2(usart_periph) |= USART_CTL2_DEM;
+}
+
+/*!
+ \brief disable RS485 driver
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[out] none
+ \retval none
+*/
+void usart_rs485_driver_disable(uint32_t usart_periph)
+{
+ /* disable USART */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+
+ USART_CTL2(usart_periph) &= ~(USART_CTL2_DEM);
+}
+
+/*!
+ \brief configure driver enable assertion time
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[in] deatime: 0x00000000-0x0000001F
+ \param[out] none
+ \retval none
+*/
+void usart_driver_assertime_config(uint32_t usart_periph, uint32_t deatime)
+{
+ /* disable USART */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_DEA);
+ USART_CTL0(usart_periph) |= (USART_CTL0_DEA & ((deatime) << CTL0_DEA_OFFSET));
+}
+
+/*!
+ \brief configure driver enable de-assertion time
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[in] dedtime: 0x00000000-0x0000001F
+ \param[out] none
+ \retval none
+*/
+void usart_driver_deassertime_config(uint32_t usart_periph, uint32_t dedtime)
+{
+ /* disable USART */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_DED);
+ USART_CTL0(usart_periph) |= (USART_CTL0_DED & ((dedtime) << CTL0_DED_OFFSET));
+}
+
+/*!
+ \brief configure driver enable polarity mode
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[in] dep: DE signal
+ only one parameter can be selected which is shown as below:
+ \arg USART_DEP_HIGH: DE signal is active high
+ \arg USART_DEP_LOW: DE signal is active low
+ \param[out] none
+ \retval none
+*/
+void usart_depolarity_config(uint32_t usart_periph, uint32_t dep)
+{
+ /* disable USART */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+ /* reset DEP bit */
+ USART_CTL2(usart_periph) &= ~(USART_CTL2_DEP);
+ USART_CTL2(usart_periph) |= (USART_CTL2_DEP & dep);
+}
+
+/*!
+ \brief configure USART DMA reception
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[in] dmacmd: enable or disable DMA for reception
+ only one parameter can be selected which is shown as below:
+ \arg USART_DENR_ENABLE: DMA enable for reception
+ \arg USART_DENR_DISABLE: DMA disable for reception
+ \param[out] none
+ \retval none
+*/
+void usart_dma_receive_config(uint32_t usart_periph, uint32_t dmacmd)
+{
+ USART_CTL2(usart_periph) &= ~USART_CTL2_DENR;
+ /* configure DMA reception */
+ USART_CTL2(usart_periph) |= dmacmd;
+}
+
+/*!
+ \brief configure USART DMA transmission
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[in] dmacmd: enable or disable DMA for transmission
+ only one parameter can be selected which is shown as below:
+ \arg USART_DENT_ENABLE: DMA enable for transmission
+ \arg USART_DENT_DISABLE: DMA disable for transmission
+ \param[out] none
+ \retval none
+*/
+void usart_dma_transmit_config(uint32_t usart_periph, uint32_t dmacmd)
+{
+ USART_CTL2(usart_periph) &= ~USART_CTL2_DENT;
+ /* configure DMA transmission */
+ USART_CTL2(usart_periph) |= dmacmd;
+}
+
+/*!
+ \brief disable DMA on reception error
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[out] none
+ \retval none
+*/
+void usart_reception_error_dma_disable(uint32_t usart_periph)
+{
+ /* disable USART */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+
+ USART_CTL2(usart_periph) |= USART_CTL2_DDRE;
+}
+
+/*!
+ \brief enable DMA on reception error
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[out] none
+ \retval none
+*/
+void usart_reception_error_dma_enable(uint32_t usart_periph)
+{
+ /* disable USART */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+
+ USART_CTL2(usart_periph) &= ~(USART_CTL2_DDRE);
+}
+
+/*!
+ \brief enable USART to wakeup the mcu from deep-sleep mode
+ \param[in] usart_periph: USARTx(x=0)
+ \param[out] none
+ \retval none
+*/
+void usart_wakeup_enable(uint32_t usart_periph)
+{
+ USART_CTL0(usart_periph) |= USART_CTL0_UESM;
+}
+
+/*!
+ \brief disable USART to wakeup the mcu from deep-sleep mode
+ \param[in] usart_periph: USARTx(x=0)
+ \param[out] none
+ \retval none
+*/
+void usart_wakeup_disable(uint32_t usart_periph)
+{
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UESM);
+}
+
+/*!
+ \brief configure the USART wakeup mode from deep-sleep mode
+ \param[in] usart_periph: USARTx(x=0)
+ \param[in] wum: wakeup mode
+ only one parameter can be selected which is shown as below:
+ \arg USART_WUM_ADDR: WUF active on address match
+ \arg USART_WUM_STARTB: WUF active on start bit
+ \arg USART_WUM_RBNE: WUF active on RBNE
+ \param[out] none
+ \retval none
+*/
+void usart_wakeup_mode_config(uint32_t usart_periph, uint32_t wum)
+{
+ /* disable USART */
+ USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
+ /* reset WUM bit */
+ USART_CTL2(usart_periph) &= ~(USART_CTL2_WUM);
+ USART_CTL2(usart_periph) |= USART_CTL2_WUM & (wum);
+}
+
+/*!
+ \brief enable USART command
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[in] cmdtype: command type
+ only one parameter can be selected which is shown as below:
+ \arg USART_CMD_ABDCMD: auto baudrate detection command
+ \arg USART_CMD_SBKCMD: send break command
+ \arg USART_CMD_MMCMD: mute mode command
+ \arg USART_CMD_RXFCMD: receive data flush command
+ \arg USART_CMD_TXFCMD: transmit data flush request
+ \param[out] none
+ \retval none
+*/
+void usart_command_enable(uint32_t usart_periph, uint32_t cmdtype)
+{
+ USART_CMD(usart_periph) |= (cmdtype);
+}
+
+/*!
+ \brief enable receive FIFO
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[out] none
+ \retval none
+*/
+void usart_receive_fifo_enable(uint32_t usart_periph)
+{
+ USART_RFCS(usart_periph) |= USART_RFCS_RFEN;
+}
+
+/*!
+ \brief disable receive FIFO
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[out] none
+ \retval none
+*/
+void usart_receive_fifo_disable(uint32_t usart_periph)
+{
+ USART_RFCS(usart_periph) &= ~(USART_RFCS_RFEN);
+}
+
+/*!
+ \brief read receive FIFO counter number
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[out] none
+ \retval receive FIFO counter number
+*/
+uint8_t usart_receive_fifo_counter_number(uint32_t usart_periph)
+{
+ return (uint8_t)(GET_BITS(USART_RFCS(usart_periph), 12U, 14U));
+}
+
+/*!
+ \brief get flag in STAT/CHC/RFCS register
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[in] flag: flag type
+ only one parameter can be selected which is shown as below:
+ \arg USART_FLAG_PERR: parity error flag
+ \arg USART_FLAG_FERR: frame error flag
+ \arg USART_FLAG_NERR: noise error flag
+ \arg USART_FLAG_ORERR: overrun error
+ \arg USART_FLAG_IDLE: idle line detected flag
+ \arg USART_FLAG_RBNE: read data buffer not empty
+ \arg USART_FLAG_TC: transmission completed
+ \arg USART_FLAG_TBE: transmit data register empty
+ \arg USART_FLAG_LBD: LIN break detected flag
+ \arg USART_FLAG_CTSF: CTS change flag
+ \arg USART_FLAG_CTS: CTS level
+ \arg USART_FLAG_RT: receiver timeout flag
+ \arg USART_FLAG_EB: end of block flag
+ \arg USART_FLAG_ABDE: auto baudrate detection error
+ \arg USART_FLAG_ABD: auto baudrate detection flag
+ \arg USART_FLAG_BSY: busy flag
+ \arg USART_FLAG_AM: address match flag
+ \arg USART_FLAG_SB: send break flag
+ \arg USART_FLAG_RWU: receiver wakeup from mute mode.
+ \arg USART_FLAG_WU: wakeup from deep-sleep mode flag
+ \arg USART_FLAG_TEA: transmit enable acknowledge flag
+ \arg USART_FLAG_REA: receive enable acknowledge flag
+ \arg USART_FLAG_EPERR: early parity error flag
+ \arg USART_FLAG_RFE: receive FIFO empty flag
+ \arg USART_FLAG_RFF: receive FIFO full flag
+ \param[out] none
+ \retval FlagStatus: SET or RESET
+*/
+FlagStatus usart_flag_get(uint32_t usart_periph, usart_flag_enum flag)
+{
+ if(RESET != (USART_REG_VAL(usart_periph, flag) & BIT(USART_BIT_POS(flag)))) {
+ return SET;
+ } else {
+ return RESET;
+ }
+}
+
+/*!
+ \brief clear USART status
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[in] flag: flag type
+ only one parameter can be selected which is shown as below:
+ \arg USART_FLAG_PERR: parity error flag
+ \arg USART_FLAG_FERR: frame error flag
+ \arg USART_FLAG_NERR: noise detected flag
+ \arg USART_FLAG_ORERR: overrun error flag
+ \arg USART_FLAG_IDLE: idle line detected flag
+ \arg USART_FLAG_TC: transmission complete flag
+ \arg USART_FLAG_LBD: LIN break detected flag
+ \arg USART_FLAG_CTSF: CTS change flag
+ \arg USART_FLAG_RT: receiver timeout flag
+ \arg USART_FLAG_EB: end of block flag
+ \arg USART_FLAG_AM: address match flag
+ \arg USART_FLAG_WU: wakeup from deep-sleep mode flag
+ \arg USART_FLAG_EPERR: early parity error flag
+ \param[out] none
+ \retval none
+*/
+void usart_flag_clear(uint32_t usart_periph, usart_flag_enum flag)
+{
+ USART_INTC(usart_periph) |= BIT(USART_BIT_POS(flag));
+}
+
+/*!
+ \brief enable USART interrupt
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[in] interrupt: interrupt
+ only one parameter can be selected which is shown as below:
+ \arg USART_INT_IDLE: idle interrupt
+ \arg USART_INT_RBNE: read data buffer not empty interrupt and
+ overrun error interrupt enable interrupt
+ \arg USART_INT_TC: transmission complete interrupt
+ \arg USART_INT_TBE: transmit data register empty interrupt
+ \arg USART_INT_PERR: parity error interrupt
+ \arg USART_INT_AM: address match interrupt
+ \arg USART_INT_RT: receiver timeout interrupt
+ \arg USART_INT_EB: end of block interrupt
+ \arg USART_INT_LBD: LIN break detection interrupt
+ \arg USART_INT_ERR: error interrupt enable in multibuffer communication
+ \arg USART_INT_CTS: CTS interrupt
+ \arg USART_INT_WU: wakeup from deep-sleep mode interrupt
+ \arg USART_INT_RFF: receive FIFO full interrupt enable
+ \param[out] none
+ \retval none
+*/
+void usart_interrupt_enable(uint32_t usart_periph, usart_interrupt_enum interrupt)
+{
+ USART_REG_VAL(usart_periph, interrupt) |= BIT(USART_BIT_POS(interrupt));
+}
+
+/*!
+ \brief disable USART interrupt
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[in] interrupt: interrupt
+ only one parameter can be selected which is shown as below:
+ \arg USART_INT_IDLE: idle interrupt
+ \arg USART_INT_RBNE: read data buffer not empty interrupt and
+ overrun error interrupt
+ \arg USART_INT_TC: transmission complete interrupt
+ \arg USART_INT_TBE: transmit data register empty interrupt
+ \arg USART_INT_PERR: parity error interrupt
+ \arg USART_INT_AM: address match interrupt
+ \arg USART_INT_RT: receiver timeout interrupt
+ \arg USART_INT_EB: end of block interrupt
+ \arg USART_INT_LBD: LIN break detection interrupt
+ \arg USART_INT_ERR: error interrupt enable in multibuffer communication
+ \arg USART_INT_CTS: CTS interrupt
+ \arg USART_INT_WU: wakeup from deep-sleep mode interrupt
+ \arg USART_INT_RFF: receive FIFO full interrupt enable
+ \param[out] none
+ \retval none
+*/
+void usart_interrupt_disable(uint32_t usart_periph, usart_interrupt_enum interrupt)
+{
+ USART_REG_VAL(usart_periph, interrupt) &= ~BIT(USART_BIT_POS(interrupt));
+}
+
+/*!
+ \brief get USART interrupt and flag status
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[in] int_flag: interrupt and flag type, refer to usart_interrupt_flag_enum
+ only one parameter can be selected which is shown as below:
+ \arg USART_INT_FLAG_EB: end of block interrupt and interrupt flag
+ \arg USART_INT_FLAG_RT: receiver timeout interrupt flag
+ \arg USART_INT_FLAG_AM: address match interrupt flag
+ \arg USART_INT_FLAG_PERR: parity error interrupt flag
+ \arg USART_INT_FLAG_TBE: transmitter buffer empty interrupt flag
+ \arg USART_INT_FLAG_TC: transmission complete interrupt flag
+ \arg USART_INT_FLAG_RBNE: read data buffer not empty interrupt flag
+ \arg USART_INT_FLAG_RBNE_ORERR: overrun error interrupt flag
+ \arg USART_INT_FLAG_IDLE: IDLE line detected interrupt flag
+ \arg USART_INT_FLAG_LBD: LIN break detected interrupt flag
+ \arg USART_INT_FLAG_WU: wakeup from deep-sleep mode interrupt flag
+ \arg USART_INT_FLAG_CTS: CTS interrupt flag
+ \arg USART_INT_FLAG_ERR_NERR: noise error interrupt flag
+ \arg USART_INT_FLAG_ERR_ORERR: overrun error interrupt flag
+ \arg USART_INT_FLAG_ERR_FERR: frame error interrupt flag
+ \arg USART_INT_FLAG_RFFINT: receive FIFO full interrupt flag
+ \param[out] none
+ \retval FlagStatus: SET or RESET
+*/
+FlagStatus usart_interrupt_flag_get(uint32_t usart_periph, usart_interrupt_flag_enum int_flag)
+{
+ uint32_t intenable = 0U, flagstatus = 0U;
+ /* get the interrupt enable bit status */
+ intenable = (USART_REG_VAL(usart_periph, int_flag) & BIT(USART_BIT_POS(int_flag)));
+ /* get the corresponding flag bit status */
+ flagstatus = (USART_REG_VAL2(usart_periph, int_flag) & BIT(USART_BIT_POS2(int_flag)));
+
+ if(flagstatus && intenable) {
+ return SET;
+ } else {
+ return RESET;
+ }
+}
+
+/*!
+ \brief clear USART interrupt flag
+ \param[in] usart_periph: USARTx(x=0,1)
+ \param[in] flag: USART interrupt flag
+ only one parameter can be selected which is shown as below:
+ \arg USART_INT_FLAG_PERR: parity error interrupt flag
+ \arg USART_INT_FLAG_ERR_FERR: frame error interrupt flag
+ \arg USART_INT_FLAG_ERR_NERR: noise detected interrupt flag
+ \arg USART_INT_FLAG_RBNE_ORERR: overrun error interrupt flag
+ \arg USART_INT_FLAG_ERR_ORERR: overrun error interrupt flag
+ \arg USART_INT_FLAG_IDLE: idle line detected interrupt flag
+ \arg USART_INT_FLAG_TC: transmission complete interrupt flag
+ \arg USART_INT_FLAG_LBD: LIN break detected interrupt flag
+ \arg USART_INT_FLAG_CTS: CTS change interrupt flag
+ \arg USART_INT_FLAG_RT: receiver timeout interrupt flag
+ \arg USART_INT_FLAG_EB: end of block interrupt flag
+ \arg USART_INT_FLAG_AM: address match interrupt flag
+ \arg USART_INT_FLAG_WU: wakeup from deep-sleep mode interrupt flag
+ \arg USART_INT_FLAG_RFFINT: receive FIFO full interrupt flag
+ \param[out] none
+ \retval none
+*/
+void usart_interrupt_flag_clear(uint32_t usart_periph, usart_interrupt_flag_enum int_flag)
+{
+ if(USART_INT_FLAG_RFFINT == int_flag) {
+ USART_RFCS(usart_periph) &= (uint32_t)(~USART_RFCS_RFFINT);
+ } else {
+ USART_INTC(usart_periph) |= BIT(USART_BIT_POS2(int_flag));
+ }
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_wwdgt.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_wwdgt.c
new file mode 100644
index 00000000..e5feebcb
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_standard_peripheral/Source/gd32f3x0_wwdgt.c
@@ -0,0 +1,128 @@
+/*!
+ \file gd32f3x0_wwdgt.c
+ \brief WWDGT driver
+
+ \version 2017-06-06, V1.0.0, firmware for GD32F3x0
+ \version 2019-06-01, V2.0.0, firmware for GD32F3x0
+ \version 2020-09-30, V2.1.0, firmware for GD32F3x0
+ \version 2022-01-06, V2.2.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2022, 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.
+*/
+
+#include "gd32f3x0_wwdgt.h"
+#include "gd32f3x0_rcu.h"
+
+/*!
+ \brief reset the window watchdog timer configuration
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void wwdgt_deinit(void)
+{
+ rcu_periph_reset_enable(RCU_WWDGTRST);
+ rcu_periph_reset_disable(RCU_WWDGTRST);
+}
+
+/*!
+ \brief start the window watchdog timer counter
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void wwdgt_enable(void)
+{
+ WWDGT_CTL |= WWDGT_CTL_WDGTEN;
+}
+
+/*!
+ \brief configure the window watchdog timer counter value
+ \param[in] counter_value: 0x00 - 0x7F
+ \param[out] none
+ \retval none
+*/
+void wwdgt_counter_update(uint16_t counter_value)
+{
+ WWDGT_CTL = (uint32_t)(CTL_CNT(counter_value));
+}
+
+/*!
+ \brief configure counter value, window value, and prescaler divider value
+ \param[in] counter: 0x00 - 0x7F
+ \param[in] window: 0x00 - 0x7F
+ \param[in] prescaler: wwdgt prescaler value
+ only one parameter can be selected which is shown as below:
+ \arg WWDGT_CFG_PSC_DIV1: the time base of window watchdog counter = (PCLK1/4096)/1
+ \arg WWDGT_CFG_PSC_DIV2: the time base of window watchdog counter = (PCLK1/4096)/2
+ \arg WWDGT_CFG_PSC_DIV4: the time base of window watchdog counter = (PCLK1/4096)/4
+ \arg WWDGT_CFG_PSC_DIV8: the time base of window watchdog counter = (PCLK1/4096)/8
+ \param[out] none
+ \retval none
+*/
+void wwdgt_config(uint16_t counter, uint16_t window, uint32_t prescaler)
+{
+ WWDGT_CTL = (uint32_t)(CTL_CNT(counter));
+ WWDGT_CFG = (uint32_t)(CFG_WIN(window) | prescaler);
+}
+
+/*!
+ \brief enable early wakeup interrupt of WWDGT
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void wwdgt_interrupt_enable(void)
+{
+ WWDGT_CFG |= WWDGT_CFG_EWIE;
+}
+
+/*!
+ \brief check early wakeup interrupt state of WWDGT
+ \param[in] none
+ \param[out] none
+ \retval FlagStatus: SET or RESET
+*/
+FlagStatus wwdgt_flag_get(void)
+{
+ if(WWDGT_STAT & WWDGT_STAT_EWIF) {
+ return SET;
+ }
+ return RESET;
+}
+
+/*!
+ \brief clear early wakeup interrupt state of WWDGT
+ \param[in] none
+ \param[out] none
+ \retval none
+*/
+void wwdgt_flag_clear(void)
+{
+ WWDGT_STAT = (uint32_t)(RESET);
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/audio/Include/audio_core.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/audio/Include/audio_core.h
new file mode 100644
index 00000000..986e1c6f
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/audio/Include/audio_core.h
@@ -0,0 +1,288 @@
+/*!
+ \file audio_core.h
+ \brief the header file of USB audio device class core functions
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __AUDIO_CORE_H
+#define __AUDIO_CORE_H
+
+#include "usbd_enum.h"
+
+#define FORMAT_24BIT(x) (uint8_t)(x);(uint8_t)(x >> 8U);(uint8_t)(x >> 16U)
+
+/* number of sub-packets in the audio transfer buffer. you can modify this value but always make sure
+ that it is an even number and higher than 3 */
+#define OUT_PACKET_NUM 4U
+
+/* total size of the audio transfer buffer */
+#define OUT_BUF_MARGIN 4U
+#define TOTAL_OUT_BUF_SIZE ((uint32_t)((SPEAKER_OUT_PACKET + OUT_BUF_MARGIN) * OUT_PACKET_NUM))
+
+#define AUDIO_CONFIG_DESC_SET_LEN (sizeof(usb_desc_config_set))
+#define AUDIO_INTERFACE_DESC_SIZE 9U
+
+#define USB_AUDIO_DESC_SIZ 0x09U
+#define AUDIO_STANDARD_EP_DESC_SIZE 0x09U
+#define AUDIO_STREAMING_EP_DESC_SIZE 0x07U
+
+/* audio interface class code */
+#define USB_CLASS_AUDIO 0x01U
+
+/* audio interface subclass codes */
+#define AUDIO_SUBCLASS_CONTROL 0x01U
+#define AUDIO_SUBCLASS_AUDIOSTREAMING 0x02U
+#define AUDIO_SUBCLASS_MIDISTREAMING 0x03U
+
+/* audio interface protocol codes */
+#define AUDIO_PROTOCOL_UNDEFINED 0x00U
+#define AUDIO_STREAMING_GENERAL 0x01U
+#define AUDIO_STREAMING_FORMAT_TYPE 0x02U
+
+/* audio class-specific descriptor types */
+#define AUDIO_DESCTYPE_UNDEFINED 0x20U
+#define AUDIO_DESCTYPE_DEVICE 0x21U
+#define AUDIO_DESCTYPE_CONFIGURATION 0x22U
+#define AUDIO_DESCTYPE_STRING 0x23U
+#define AUDIO_DESCTYPE_INTERFACE 0x24U
+#define AUDIO_DESCTYPE_ENDPOINT 0x25U
+
+/* audio control interface descriptor subtypes */
+#define AUDIO_CONTROL_HEADER 0x01U
+#define AUDIO_CONTROL_INPUT_TERMINAL 0x02U
+#define AUDIO_CONTROL_OUTPUT_TERMINAL 0x03U
+#define AUDIO_CONTROL_MIXER_UNIT 0x04U
+#define AUDIO_CONTROL_SELECTOR_UNIT 0x05U
+#define AUDIO_CONTROL_FEATURE_UNIT 0x06U
+#define AUDIO_CONTROL_PROCESSING_UNIT 0x07U
+#define AUDIO_CONTROL_EXTENSION_UNIT 0x08U
+
+#define AUDIO_INPUT_TERMINAL_DESC_SIZE 0x0CU
+#define AUDIO_OUTPUT_TERMINAL_DESC_SIZE 0x09U
+#define AUDIO_STREAMING_INTERFACE_DESC_SIZE 0x07U
+
+#define AUDIO_CONTROL_MUTE 0x01U
+#define AUDIO_CONTROL_VOLUME 0x02U
+
+#define AUDIO_FORMAT_TYPE_I 0x01U
+#define AUDIO_FORMAT_TYPE_III 0x03U
+
+#define USB_ENDPOINT_TYPE_ISOCHRONOUS 0x01U
+#define AUDIO_ENDPOINT_GENERAL 0x01U
+
+#define AUDIO_REQ_UNDEFINED 0x00U
+#define AUDIO_REQ_SET_CUR 0x01U
+#define AUDIO_REQ_GET_CUR 0x81U
+#define AUDIO_REQ_SET_MIN 0x02U
+#define AUDIO_REQ_GET_MIN 0x82U
+#define AUDIO_REQ_SET_MAX 0x03U
+#define AUDIO_REQ_GET_MAX 0x83U
+#define AUDIO_REQ_SET_RES 0x04U
+#define AUDIO_REQ_GET_RES 0x84U
+#define AUDIO_REQ_SET_MEM 0x05U
+#define AUDIO_REQ_GET_MEM 0x85U
+#define AUDIO_REQ_GET_STAT 0xFFU
+
+#define AUDIO_OUT_STREAMING_CTRL 0x05U
+#define AUDIO_IN_STREAMING_CTRL 0x02U
+
+/* audio stream interface number */
+enum {
+#ifdef USE_USB_AUDIO_MICPHONE
+ MIC_INTERFACE_COUNT,
+#endif
+#ifdef USE_USB_AUDIO_SPEAKER
+ SPEAK_INTERFACE_COUNT,
+#endif
+ CONFIG_DESC_AS_ITF_COUNT,
+};
+
+#define AC_ITF_TOTAL_LEN (sizeof(usb_desc_AC_itf) + CONFIG_DESC_AS_ITF_COUNT*(sizeof(usb_desc_input_terminal) + \
+ sizeof(usb_desc_mono_feature_unit) + sizeof(usb_desc_output_terminal)))
+
+#pragma pack(1)
+
+typedef struct {
+ usb_desc_header header; /*!< descriptor header, including type and size */
+ uint8_t bDescriptorSubtype; /*!< header descriptor subtype */
+ uint16_t bcdADC; /*!< audio device class specification release number in binary-coded decimal */
+ uint16_t wTotalLength; /*!< total number of bytes */
+ uint8_t bInCollection; /*!< the number of the streaming interfaces */
+#ifdef USE_USB_AUDIO_MICPHONE
+ uint8_t baInterfaceNr0; /*!< interface number of the streaming interfaces */
+#endif
+
+#ifdef USE_USB_AUDIO_SPEAKER
+ uint8_t baInterfaceNr1; /*!< interface number of the streaming interfaces */
+#endif
+} usb_desc_AC_itf;
+
+typedef struct {
+ usb_desc_header header; /*!< descriptor header, including type and size */
+ uint8_t bDescriptorSubtype; /*!< AS_GENERAL descriptor subtype */
+ uint8_t bTerminalLink; /*!< the terminal ID */
+ uint8_t bDelay; /*!< delay introduced by the data path */
+ uint16_t wFormatTag; /*!< the audio data format */
+} usb_desc_AS_itf;
+
+typedef struct {
+ usb_desc_header header; /*!< descriptor header, including type and size */
+ uint8_t bDescriptorSubtype; /*!< INPUT_TERMINAL descriptor subtype. */
+ uint8_t bTerminalID; /*!< constant uniquely identifying the terminal within the audio function */
+ uint16_t wTerminalType; /*!< constant characterizing the type of terminal */
+ uint8_t bAssocTerminal; /*!< ID of the output terminal */
+ uint8_t bNrChannels; /*!< number of logical output channels */
+ uint16_t wChannelConfig; /*!< describes the spatial location of the logical channels */
+ uint8_t iChannelNames; /*!< index of a string descriptor */
+ uint8_t iTerminal; /*!< index of a string descriptor */
+} usb_desc_input_terminal;
+
+typedef struct {
+ usb_desc_header header; /*!< descriptor header, including type and size */
+ uint8_t bDescriptorSubtype; /*!< OUTPUT_TERMINAL descriptor subtype */
+ uint8_t bTerminalID; /*!< constant uniquely identifying the terminal within the audio function */
+ uint16_t wTerminalType; /*!< constant characterizing the type of terminal */
+ uint8_t bAssocTerminal; /*!< constant, identifying the input terminal to which this output terminal is associated */
+ uint8_t bSourceID; /*!< ID of the unit or terminal */
+ uint8_t iTerminal; /*!< index of a string descriptor */
+} usb_desc_output_terminal;
+
+typedef struct {
+ usb_desc_header header; /*!< descriptor header, including type and size */
+ uint8_t bDescriptorSubtype; /*!< FEATURE_UNIT descriptor subtype */
+ uint8_t bUnitID; /*!< constant uniquely identifying the unit within the audio function */
+ uint8_t bSourceID; /*!< ID of the unit or terminal */
+ uint8_t bControlSize; /*!< size in bytes of an element of the bmaControls() array */
+ uint8_t bmaControls0; /*!< a bit set to 1 indicates that the mentioned control is supported for master channel 0 */
+ uint8_t bmaControls1; /*!< a bit set to 1 indicates that the mentioned control is supported for logical channel 1 */
+ uint8_t iFeature; /*!< index of a string descriptor */
+} usb_desc_mono_feature_unit;
+
+typedef struct {
+ usb_desc_header header; /*!< descriptor header, including type and size */
+ uint8_t bDescriptorSubtype; /*!< FEATURE_UNIT descriptor subtype */
+ uint8_t bUnitID; /*!< constant uniquely identifying the unit within the audio function */
+ uint8_t bSourceID; /*!< ID of the unit or terminal */
+ uint8_t bControlSize; /*!< size in bytes of an element of the bmaControls() array */
+ uint16_t bmaControls0; /*!< a bit set to 1 indicates that the mentioned control is supported for master channel 0 */
+ uint16_t bmaControls1; /*!< a bit set to 1 indicates that the mentioned control is supported for logical channel 1 */
+ uint16_t bmaControls2; /*!< a bit set to 1 indicates that the mentioned control is supported for logical channel 2 */
+ uint8_t iFeature; /*!< index of a string descriptor */
+} usb_desc_stereo_feature_unit;
+
+typedef struct {
+ usb_desc_header header; /*!< descriptor header, including type and size */
+ uint8_t bDescriptorSubtype; /*!< FORMAT_TYPE descriptor subtype */
+ uint8_t bFormatType; /*!< constant identifying the format type */
+ uint8_t bNrChannels; /*!< indicates the number of physical channels in the audio data stream */
+ uint8_t bSubFrameSize; /*!< the number of bytes occupied by one audio subframe */
+ uint8_t bBitResolution; /*!< the number of effectively used bits from the available bits in an audio subframe */
+ uint8_t bSamFreqType; /*!< indicates how the sampling frequency can be programmed */
+ uint8_t bSamFreq[3]; /*!< sampling frequency ns in Hz for this isochronous data endpoint */
+} usb_desc_format_type;
+
+typedef struct {
+ usb_desc_header header; /*!< descriptor header, including type and size */
+ uint8_t bEndpointAddress; /*!< the address of the endpoint */
+ uint8_t bmAttributes; /*!< transfer type and synchronization type */
+ uint16_t wMaxPacketSize; /*!< maximum packet size this endpoint is capable of sending or receiving */
+ uint8_t bInterval; /*!< left to the designer's discretion */
+ uint8_t bRefresh; /*!< reset to 0 */
+ uint8_t bSynchAddress; /*!< reset to 0 */
+} usb_desc_std_ep;
+
+typedef struct {
+ usb_desc_header header; /*!< descriptor header, including type and size */
+ uint8_t bDescriptorSubtype; /*!< EP_GENERAL descriptor subtype */
+ uint8_t bmAttributes; /*!< transfer type and synchronization type */
+ uint8_t bLockDelayUnits; /*!< indicates the units used for the wLockDelay field */
+ uint16_t wLockDelay; /*!< indicates the time it takes this endpoint to reliably lock its internal clock recovery circuitry */
+} usb_desc_AS_ep;
+
+#pragma pack()
+
+/* USB configuration descriptor structure */
+typedef struct {
+ usb_desc_config config;
+ usb_desc_itf std_itf;
+ usb_desc_AC_itf ac_itf;
+
+#ifdef USE_USB_AUDIO_MICPHONE
+ usb_desc_input_terminal mic_in_terminal;
+ usb_desc_mono_feature_unit mic_feature_unit;
+ usb_desc_output_terminal mic_out_terminal;
+#endif
+
+#ifdef USE_USB_AUDIO_SPEAKER
+ usb_desc_input_terminal speak_in_terminal;
+ usb_desc_mono_feature_unit speak_feature_unit;
+ usb_desc_output_terminal speak_out_terminal;
+#endif
+
+#ifdef USE_USB_AUDIO_MICPHONE
+ usb_desc_itf mic_std_as_itf_zeroband;
+ usb_desc_itf mic_std_as_itf_opera;
+ usb_desc_AS_itf mic_as_itf;
+ usb_desc_format_type mic_format_typeI;
+ usb_desc_std_ep mic_std_endpoint;
+ usb_desc_AS_ep mic_as_endpoint;
+#endif
+
+#ifdef USE_USB_AUDIO_SPEAKER
+ usb_desc_itf speak_std_as_itf_zeroband;
+ usb_desc_itf speak_std_as_itf_opera;
+ usb_desc_AS_itf speak_as_itf;
+ usb_desc_format_type speak_format_typeI;
+ usb_desc_std_ep speak_std_endpoint;
+ usb_desc_AS_ep speak_as_endpoint;
+#endif
+} usb_desc_config_set;
+
+typedef struct {
+ /* main buffer for audio data out transfers and its relative pointers */
+ uint8_t isoc_out_buff[TOTAL_OUT_BUF_SIZE * 2U];
+ uint8_t *isoc_out_wrptr;
+ uint8_t *isoc_out_rdptr;
+
+ /* main buffer for audio control requests transfers and its relative variables */
+ uint8_t audioctl[64];
+ uint8_t audioctl_unit;
+ uint32_t audioctl_len;
+
+#ifdef USE_USB_AUDIO_SPEAKER
+ uint32_t play_flag;
+#endif /* USE_USB_AUDIO_SPEAKER */
+} usbd_audio_handler;
+
+extern usb_desc audio_desc;
+extern usb_class_core usbd_audio_cb;
+
+#endif /* __AUDIO_CORE_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/audio/Include/audio_out_itf.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/audio/Include/audio_out_itf.h
new file mode 100644
index 00000000..8ef971fc
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/audio/Include/audio_out_itf.h
@@ -0,0 +1,75 @@
+/*!
+ \file audio_out_itf.h
+ \brief audio OUT (playback) interface header file
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __AUDIO_OUT_ITF_H
+#define __AUDIO_OUT_ITF_H
+
+#include "usbd_conf.h"
+
+/* audio commands enumeration */
+typedef enum {
+ AUDIO_CMD_PLAY = 1U,
+ AUDIO_CMD_PAUSE,
+ AUDIO_CMD_STOP,
+} audio_cmd_enum;
+
+/* mute commands */
+#define AUDIO_MUTE 0x01U
+#define AUDIO_UNMUTE 0x00U
+
+/* functions return value */
+#define AUDIO_OK 0x00U
+#define AUDIO_FAIL 0xFFU
+
+/* audio machine states */
+#define AUDIO_STATE_INACTIVE 0x00U
+#define AUDIO_STATE_ACTIVE 0x01U
+#define AUDIO_STATE_PLAYING 0x02U
+#define AUDIO_STATE_PAUSED 0x03U
+#define AUDIO_STATE_STOPPED 0x04U
+#define AUDIO_STATE_ERROR 0x05U
+
+typedef struct {
+ uint8_t (*audio_init)(uint32_t audio_freq, uint32_t volume, uint32_t options);
+ uint8_t (*audio_deinit)(uint32_t options);
+ uint8_t (*audio_cmd)(uint8_t *pbuf, uint32_t size, uint8_t cmd);
+ uint8_t (*audio_volume_ctl)(uint8_t vol);
+ uint8_t (*audio_mute_ctl)(uint8_t cmd);
+ uint8_t (*audio_periodic_tc)(uint8_t cmd);
+ uint8_t (*audio_state_get)(void);
+} audio_fops_struct;
+
+extern audio_fops_struct audio_out_fops;
+
+#endif /* __AUDIO_OUT_ITF_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/audio/Source/audio_core.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/audio/Source/audio_core.c
new file mode 100644
index 00000000..e262cfa6
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/audio/Source/audio_core.c
@@ -0,0 +1,803 @@
+/*!
+ \file audio_core.c
+ \brief USB audio device class core functions
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+ \version 2020-12-07, V3.0.1, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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.
+*/
+
+#include "audio_out_itf.h"
+#include "audio_core.h"
+#include
+
+#define USBD_VID 0x28E9U
+#define USBD_PID 0x9574U
+
+#ifdef USE_USB_AUDIO_MICPHONE
+extern volatile uint32_t count_data;
+extern const char wavetestdata[];
+#define LENGTH_DATA (1747 * 32)
+#endif
+
+/* local function prototypes ('static') */
+static uint8_t audio_init(usb_dev *udev, uint8_t config_index);
+static uint8_t audio_deinit(usb_dev *udev, uint8_t config_index);
+static uint8_t audio_req_handler(usb_dev *udev, usb_req *req);
+static uint8_t audio_set_intf(usb_dev *udev, usb_req *req);
+static uint8_t audio_ctlx_out(usb_dev *udev);
+static uint8_t audio_data_in(usb_dev *udev, uint8_t ep_num);
+static uint8_t audio_data_out(usb_dev *udev, uint8_t ep_num);
+static uint8_t usbd_audio_sof(usb_dev *udev);
+
+usb_class_core usbd_audio_cb = {
+ .init = audio_init,
+ .deinit = audio_deinit,
+ .req_proc = audio_req_handler,
+ .set_intf = audio_set_intf,
+ .ctlx_out = audio_ctlx_out,
+ .data_in = audio_data_in,
+ .data_out = audio_data_out,
+ .SOF = usbd_audio_sof
+};
+
+#define VOL_MIN 0U /* Volume Minimum Value */
+#define VOL_MAX 100U /* Volume Maximum Value */
+#define VOL_RES 1U /* Volume Resolution */
+#define VOL_0dB 70U /* 0dB is in the middle of VOL_MIN and VOL_MAX */
+
+/* note:it should use the c99 standard when compiling the below codes */
+/* USB standard device descriptor */
+const usb_desc_dev audio_dev_desc = {
+ .header =
+ {
+ .bLength = USB_DEV_DESC_LEN,
+ .bDescriptorType = USB_DESCTYPE_DEV
+ },
+ .bcdUSB = 0x0200U,
+ .bDeviceClass = 0x00U,
+ .bDeviceSubClass = 0x00U,
+ .bDeviceProtocol = 0x00U,
+ .bMaxPacketSize0 = USB_FS_EP0_MAX_LEN,
+ .idVendor = USBD_VID,
+ .idProduct = USBD_PID,
+ .bcdDevice = 0x0100U,
+ .iManufacturer = STR_IDX_MFC,
+ .iProduct = STR_IDX_PRODUCT,
+ .iSerialNumber = STR_IDX_SERIAL,
+ .bNumberConfigurations = USBD_CFG_MAX_NUM
+};
+
+/* USB device configuration descriptor */
+const usb_desc_config_set audio_config_set = {
+ .config =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_config),
+ .bDescriptorType = USB_DESCTYPE_CONFIG
+ },
+ .wTotalLength = AUDIO_CONFIG_DESC_SET_LEN,
+ .bNumInterfaces = 0x01U + CONFIG_DESC_AS_ITF_COUNT,
+ .bConfigurationValue = 0x01U,
+ .iConfiguration = 0x00U,
+ .bmAttributes = 0xC0U,
+ .bMaxPower = 0x32U
+ },
+
+ .std_itf =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_itf),
+ .bDescriptorType = USB_DESCTYPE_ITF
+ },
+ .bInterfaceNumber = 0x00U,
+ .bAlternateSetting = 0x00U,
+ .bNumEndpoints = 0x00U,
+ .bInterfaceClass = USB_CLASS_AUDIO,
+ .bInterfaceSubClass = AUDIO_SUBCLASS_CONTROL,
+ .bInterfaceProtocol = AUDIO_PROTOCOL_UNDEFINED,
+ .iInterface = 0x00U
+ },
+
+ .ac_itf =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_AC_itf),
+ .bDescriptorType = AUDIO_DESCTYPE_INTERFACE
+ },
+ .bDescriptorSubtype = 0x01U,
+ .bcdADC = 0x0100U,
+ .wTotalLength = AC_ITF_TOTAL_LEN,
+ .bInCollection = CONFIG_DESC_AS_ITF_COUNT,
+#ifdef USE_USB_AUDIO_MICPHONE
+ .baInterfaceNr0 = 0x01U,
+#endif
+#ifdef USE_USB_AUDIO_SPEAKER
+ .baInterfaceNr1 = 0x02U
+#endif
+ },
+
+#ifdef USE_USB_AUDIO_MICPHONE
+ .mic_in_terminal =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_input_terminal),
+ .bDescriptorType = AUDIO_DESCTYPE_INTERFACE
+ },
+ .bDescriptorSubtype = 0x02U,
+ .bTerminalID = 0x01U,
+ .wTerminalType = 0x0201U,
+ .bAssocTerminal = 0x00U,
+ .bNrChannels = 0x02U,
+ .wChannelConfig = 0x0003U,
+ .iChannelNames = 0x00U,
+ .iTerminal = 0x00U
+ },
+
+ .mic_feature_unit =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_mono_feature_unit),
+ .bDescriptorType = AUDIO_DESCTYPE_INTERFACE
+ },
+ .bDescriptorSubtype = AUDIO_CONTROL_FEATURE_UNIT,
+ .bUnitID = AUDIO_IN_STREAMING_CTRL,
+ .bSourceID = 0x01U,
+ .bControlSize = 0x01U,
+ .bmaControls0 = AUDIO_CONTROL_MUTE,
+ .bmaControls1 = AUDIO_CONTROL_VOLUME,
+ .iFeature = 0x00U
+ },
+
+ .mic_out_terminal =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_output_terminal),
+ .bDescriptorType = AUDIO_DESCTYPE_INTERFACE
+ },
+ .bDescriptorSubtype = AUDIO_CONTROL_OUTPUT_TERMINAL,
+ .bTerminalID = 0x03U,
+ .wTerminalType = 0x0101U,
+ .bAssocTerminal = 0x00U,
+ .bSourceID = 0x02U,
+ .iTerminal = 0x00U
+ },
+#endif
+
+#ifdef USE_USB_AUDIO_SPEAKER
+ .speak_in_terminal =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_input_terminal),
+ .bDescriptorType = AUDIO_DESCTYPE_INTERFACE
+ },
+ .bDescriptorSubtype = AUDIO_CONTROL_INPUT_TERMINAL,
+ .bTerminalID = 0x04U,
+ .wTerminalType = 0x0101U,
+ .bAssocTerminal = 0x00U,
+ .bNrChannels = 0x02U,
+ .wChannelConfig = 0x0003U,
+ .iChannelNames = 0x00U,
+ .iTerminal = 0x00U
+ },
+
+ .speak_feature_unit =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_mono_feature_unit),
+ .bDescriptorType = AUDIO_DESCTYPE_INTERFACE
+ },
+ .bDescriptorSubtype = AUDIO_CONTROL_FEATURE_UNIT,
+ .bUnitID = AUDIO_OUT_STREAMING_CTRL,
+ .bSourceID = 0x04U,
+ .bControlSize = 0x01U,
+ .bmaControls0 = AUDIO_CONTROL_MUTE,
+ .bmaControls1 = AUDIO_CONTROL_VOLUME,
+ .iFeature = 0x00U
+ },
+
+ .speak_out_terminal =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_output_terminal),
+ .bDescriptorType = AUDIO_DESCTYPE_INTERFACE
+ },
+ .bDescriptorSubtype = AUDIO_CONTROL_OUTPUT_TERMINAL,
+ .bTerminalID = 0x06U,
+ .wTerminalType = 0x0301U,
+ .bAssocTerminal = 0x00U,
+ .bSourceID = 0x05U,
+ .iTerminal = 0x00U
+ },
+#endif
+
+#ifdef USE_USB_AUDIO_MICPHONE
+ .mic_std_as_itf_zeroband =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_itf),
+ .bDescriptorType = USB_DESCTYPE_ITF
+ },
+ .bInterfaceNumber = 0x01U,
+ .bAlternateSetting = 0x00U,
+ .bNumEndpoints = 0x00U,
+ .bInterfaceClass = USB_CLASS_AUDIO,
+ .bInterfaceSubClass = AUDIO_SUBCLASS_AUDIOSTREAMING,
+ .bInterfaceProtocol = AUDIO_PROTOCOL_UNDEFINED,
+ .iInterface = 0x00U
+ },
+
+ .mic_std_as_itf_opera =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_itf),
+ .bDescriptorType = USB_DESCTYPE_ITF
+ },
+ .bInterfaceNumber = 0x01U,
+ .bAlternateSetting = 0x01U,
+ .bNumEndpoints = 0x01U,
+ .bInterfaceClass = USB_CLASS_AUDIO,
+ .bInterfaceSubClass = AUDIO_SUBCLASS_AUDIOSTREAMING,
+ .bInterfaceProtocol = AUDIO_PROTOCOL_UNDEFINED,
+ .iInterface = 0x00U
+ },
+
+ .mic_as_itf =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_AS_itf),
+ .bDescriptorType = AUDIO_DESCTYPE_INTERFACE
+ },
+ .bDescriptorSubtype = AUDIO_STREAMING_GENERAL,
+ .bTerminalLink = 0x03U,
+ .bDelay = 0x01U,
+ .wFormatTag = 0x0001U,
+ },
+
+ .mic_format_typeI =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_format_type),
+ .bDescriptorType = AUDIO_DESCTYPE_INTERFACE
+ },
+ .bDescriptorSubtype = AUDIO_STREAMING_FORMAT_TYPE,
+ .bFormatType = AUDIO_FORMAT_TYPE_I,
+ .bNrChannels = MIC_IN_CHANNEL_NBR,
+ .bSubFrameSize = 0x02U,
+ .bBitResolution = MIC_IN_BIT_RESOLUTION,
+ .bSamFreqType = 0x01U,
+ .bSamFreq[0] = (uint8_t)USBD_MIC_FREQ,
+ .bSamFreq[1] = USBD_MIC_FREQ >> 8U,
+ .bSamFreq[2] = USBD_MIC_FREQ >> 16U
+ },
+
+ .mic_std_endpoint =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_std_ep),
+ .bDescriptorType = USB_DESCTYPE_EP
+ },
+ .bEndpointAddress = AUDIO_IN_EP,
+ .bmAttributes = USB_ENDPOINT_TYPE_ISOCHRONOUS,
+ .wMaxPacketSize = MIC_IN_PACKET,
+ .bInterval = 0x01U,
+ .bRefresh = 0x00U,
+ .bSynchAddress = 0x00U
+ },
+
+ .mic_as_endpoint =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_AS_ep),
+ .bDescriptorType = AUDIO_DESCTYPE_ENDPOINT
+ },
+ .bDescriptorSubtype = AUDIO_ENDPOINT_GENERAL,
+ .bmAttributes = 0x00U,
+ .bLockDelayUnits = 0x00U,
+ .wLockDelay = 0x0000U,
+ },
+#endif
+
+#ifdef USE_USB_AUDIO_SPEAKER
+ .speak_std_as_itf_zeroband =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_itf),
+ .bDescriptorType = USB_DESCTYPE_ITF
+ },
+ .bInterfaceNumber = 0x02U,
+ .bAlternateSetting = 0x00U,
+ .bNumEndpoints = 0x00U,
+ .bInterfaceClass = USB_CLASS_AUDIO,
+ .bInterfaceSubClass = AUDIO_SUBCLASS_AUDIOSTREAMING,
+ .bInterfaceProtocol = AUDIO_PROTOCOL_UNDEFINED,
+ .iInterface = 0x00U
+ },
+
+ .speak_std_as_itf_opera =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_itf),
+ .bDescriptorType = USB_DESCTYPE_ITF
+ },
+ .bInterfaceNumber = 0x02U,
+ .bAlternateSetting = 0x01U,
+ .bNumEndpoints = 0x01U,
+ .bInterfaceClass = USB_CLASS_AUDIO,
+ .bInterfaceSubClass = AUDIO_SUBCLASS_AUDIOSTREAMING,
+ .bInterfaceProtocol = AUDIO_PROTOCOL_UNDEFINED,
+ .iInterface = 0x00U
+ },
+
+ .speak_as_itf =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_AS_itf),
+ .bDescriptorType = AUDIO_DESCTYPE_INTERFACE
+ },
+ .bDescriptorSubtype = AUDIO_STREAMING_GENERAL,
+ .bTerminalLink = 0x04U,
+ .bDelay = 0x01U,
+ .wFormatTag = 0x0001U,
+ },
+
+ .speak_format_typeI =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_format_type),
+ .bDescriptorType = AUDIO_DESCTYPE_INTERFACE
+ },
+ .bDescriptorSubtype = AUDIO_STREAMING_FORMAT_TYPE,
+ .bFormatType = AUDIO_FORMAT_TYPE_I,
+ .bNrChannels = SPEAKER_OUT_CHANNEL_NBR,
+ .bSubFrameSize = 0x02U,
+ .bBitResolution = SPEAKER_OUT_BIT_RESOLUTION,
+ .bSamFreqType = 0x01U,
+ .bSamFreq[0] = (uint8_t)USBD_SPEAKER_FREQ,
+ .bSamFreq[1] = USBD_SPEAKER_FREQ >> 8U,
+ .bSamFreq[2] = USBD_SPEAKER_FREQ >> 16U
+ },
+
+ .speak_std_endpoint =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_std_ep),
+ .bDescriptorType = USB_DESCTYPE_EP
+ },
+ .bEndpointAddress = AUDIO_OUT_EP,
+ .bmAttributes = USB_ENDPOINT_TYPE_ISOCHRONOUS,
+ .wMaxPacketSize = SPEAKER_OUT_PACKET,
+ .bInterval = 0x01U,
+ .bRefresh = 0x00U,
+ .bSynchAddress = 0x00U
+ },
+
+ .speak_as_endpoint =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_AS_ep),
+ .bDescriptorType = AUDIO_DESCTYPE_ENDPOINT
+ },
+ .bDescriptorSubtype = AUDIO_ENDPOINT_GENERAL,
+ .bmAttributes = 0x00U,
+ .bLockDelayUnits = 0x00U,
+ .wLockDelay = 0x0000U,
+ }
+#endif
+};
+
+/* USB language ID descriptor */
+static const usb_desc_LANGID usbd_language_id_desc = {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_LANGID),
+ .bDescriptorType = USB_DESCTYPE_STR
+ },
+
+ .wLANGID = ENG_LANGID
+};
+
+/* USB manufacture string */
+static const usb_desc_str manufacturer_string = {
+ .header =
+ {
+ .bLength = USB_STRING_LEN(10),
+ .bDescriptorType = USB_DESCTYPE_STR,
+ },
+ .unicode_string = {'G', 'i', 'g', 'a', 'D', 'e', 'v', 'i', 'c', 'e'}
+};
+
+/* USB product string */
+static const usb_desc_str product_string = {
+ .header =
+ {
+ .bLength = USB_STRING_LEN(14),
+ .bDescriptorType = USB_DESCTYPE_STR,
+ },
+ .unicode_string = {'G', 'D', '3', '2', '-', 'U', 'S', 'B', '_', 'A', 'u', 'd', 'i', 'o'}
+};
+
+/* USBD serial string */
+static usb_desc_str serial_string = {
+ .header =
+ {
+ .bLength = USB_STRING_LEN(12),
+ .bDescriptorType = USB_DESCTYPE_STR,
+ }
+};
+
+/* USB string descriptor */
+void *const usbd_audio_strings[] = {
+ [STR_IDX_LANGID] = (uint8_t *) &usbd_language_id_desc,
+ [STR_IDX_MFC] = (uint8_t *) &manufacturer_string,
+ [STR_IDX_PRODUCT] = (uint8_t *) &product_string,
+ [STR_IDX_SERIAL] = (uint8_t *) &serial_string
+};
+
+usb_desc audio_desc = {
+ .dev_desc = (uint8_t *) &audio_dev_desc,
+ .config_desc = (uint8_t *) &audio_config_set,
+ .strings = usbd_audio_strings
+};
+
+/*!
+ \brief initialize the AUDIO device
+ \param[in] udev: pointer to USB device instance
+ \param[in] config_index: configuration index
+ \param[out] none
+ \retval USB device operation status
+*/
+static uint8_t audio_init(usb_dev *udev, uint8_t config_index)
+{
+ static usbd_audio_handler audio_handler;
+
+ memset((void *)&audio_handler, 0, sizeof(usbd_audio_handler));
+
+#ifdef USE_USB_AUDIO_MICPHONE
+ {
+ usb_desc_std_ep std_ep = audio_config_set.mic_std_endpoint;
+
+ usb_desc_ep ep = {
+ .header = std_ep.header,
+ .bEndpointAddress = std_ep.bEndpointAddress,
+ .bmAttributes = std_ep.bmAttributes,
+ .wMaxPacketSize = std_ep.wMaxPacketSize,
+ .bInterval = std_ep.bInterval
+ };
+
+ /* initialize Tx endpoint */
+ usbd_ep_setup(udev, &ep);
+ }
+#endif
+
+#ifdef USE_USB_AUDIO_SPEAKER
+ {
+ audio_handler.isoc_out_rdptr = audio_handler.isoc_out_buff;
+ audio_handler.isoc_out_wrptr = audio_handler.isoc_out_buff;
+
+ usb_desc_std_ep std_ep = audio_config_set.speak_std_endpoint;
+
+ usb_desc_ep ep = {
+ .header = std_ep.header,
+ .bEndpointAddress = std_ep.bEndpointAddress,
+ .bmAttributes = std_ep.bmAttributes,
+ .wMaxPacketSize = std_ep.wMaxPacketSize,
+ .bInterval = std_ep.bInterval
+ };
+
+ /* initialize Rx endpoint */
+ usbd_ep_setup(udev, &ep);
+
+ /* initialize the audio output hardware layer */
+ if(USBD_OK != audio_out_fops.audio_init(USBD_AUDIO_FREQ_16K, DEFAULT_VOLUME, 0U)) {
+ return USBD_FAIL;
+ }
+
+ /* prepare OUT endpoint to receive audio data */
+ usbd_ep_recev(udev, AUDIO_OUT_EP, (uint8_t *)audio_handler.isoc_out_buff, SPEAKER_OUT_PACKET);
+ }
+#endif
+
+ udev->dev.class_data[USBD_AUDIO_INTERFACE] = (void *)&audio_handler;
+
+ return USBD_OK;
+}
+
+/*!
+ \brief de-initialize the AUDIO device
+ \param[in] udev: pointer to USB device instance
+ \param[in] config_index: configuration index
+ \param[out] none
+ \retval USB device operation status
+*/
+static uint8_t audio_deinit(usb_dev *udev, uint8_t config_index)
+{
+#ifdef USE_USB_AUDIO_MICPHONE
+ /* deinitialize AUDIO endpoints */
+ usbd_ep_clear(udev, AUDIO_IN_EP);
+#endif
+
+#ifdef USE_USB_AUDIO_SPEAKER
+ /* deinitialize AUDIO endpoints */
+ usbd_ep_clear(udev, AUDIO_OUT_EP);
+
+ /* deinitialize the audio output hardware layer */
+ if(USBD_OK != audio_out_fops.audio_deinit(0U)) {
+ return USBD_FAIL;
+ }
+#endif
+
+ return USBD_OK;
+}
+
+/*!
+ \brief handle the AUDIO class-specific requests
+ \param[in] udev: pointer to USB device instance
+ \param[in] req: device class-specific request
+ \param[out] none
+ \retval USB device operation status
+*/
+static uint8_t audio_req_handler(usb_dev *udev, usb_req *req)
+{
+ uint8_t status = REQ_NOTSUPP;
+
+ usbd_audio_handler *audio = (usbd_audio_handler *)udev->dev.class_data[USBD_AUDIO_INTERFACE];
+
+ usb_transc *transc_in = &udev->dev.transc_in[0];
+ usb_transc *transc_out = &udev->dev.transc_out[0];
+
+ switch(req->bRequest) {
+ case AUDIO_REQ_GET_CUR:
+ transc_in->xfer_buf = audio->audioctl;
+ transc_in->remain_len = req->wLength;
+
+ status = REQ_SUPP;
+ break;
+
+ case AUDIO_REQ_SET_CUR:
+ if(req->wLength) {
+ transc_out->xfer_buf = audio->audioctl;
+ transc_out->remain_len = req->wLength;
+
+ udev->dev.class_core->command = AUDIO_REQ_SET_CUR;
+
+ audio->audioctl_len = req->wLength;
+ audio->audioctl_unit = BYTE_HIGH(req->wIndex);
+
+ status = REQ_SUPP;
+ }
+ break;
+
+ case AUDIO_REQ_GET_MIN:
+ *((uint16_t *)audio->audioctl) = VOL_MIN;
+ transc_in->xfer_buf = audio->audioctl;
+ transc_in->remain_len = req->wLength;
+ status = REQ_SUPP;
+ break;
+
+ case AUDIO_REQ_GET_MAX:
+ *((uint16_t *)audio->audioctl) = VOL_MAX;
+ transc_in->xfer_buf = audio->audioctl;
+ transc_in->remain_len = req->wLength;
+ status = REQ_SUPP;
+ break;
+
+ case AUDIO_REQ_GET_RES:
+ *((uint16_t *)audio->audioctl) = VOL_RES;
+ transc_in->xfer_buf = audio->audioctl;
+ transc_in->remain_len = req->wLength;
+ status = REQ_SUPP;
+ break;
+
+ default:
+ break;
+ }
+
+ return status;
+}
+
+/*!
+ \brief handle the AUDIO set interface requests
+ \param[in] udev: pointer to USB device instance
+ \param[in] req: device class-specific request
+ \param[out] none
+ \retval USB device operation status
+*/
+static uint8_t audio_set_intf(usb_dev *udev, usb_req *req)
+{
+ udev->dev.class_core->alter_set = req->wValue;
+
+ return USBD_OK;
+}
+
+/*!
+ \brief handles the control transfer OUT callback
+ \param[in] udev: pointer to USB device instance
+ \param[out] none
+ \retval USB device operation status
+*/
+static uint8_t audio_ctlx_out(usb_dev *udev)
+{
+#ifdef USE_USB_AUDIO_SPEAKER
+ usbd_audio_handler *audio = (usbd_audio_handler *)udev->dev.class_data[USBD_AUDIO_INTERFACE];
+
+ /* handles audio control requests data */
+ /* check if an audio_control request has been issued */
+ if(AUDIO_REQ_SET_CUR == udev->dev.class_core->command) {
+ /* in this driver, to simplify code, only SET_CUR request is managed */
+
+ /* check for which addressed unit the audio_control request has been issued */
+ if(AUDIO_OUT_STREAMING_CTRL == audio->audioctl_unit) {
+ /* in this driver, to simplify code, only one unit is manage */
+
+ /* call the audio interface mute function */
+ audio_out_fops.audio_mute_ctl(audio->audioctl[0]);
+
+ /* reset the audioctl_cmd variable to prevent re-entering this function */
+ udev->dev.class_core->command = 0U;
+
+ audio->audioctl_len = 0U;
+ }
+ }
+#endif
+
+ return USBD_OK;
+}
+
+
+/*!
+ \brief handles the audio IN data stage
+ \param[in] udev: pointer to USB device instance
+ \param[in] ep_num: endpoint number
+ \param[out] none
+ \retval USB device operation status
+*/
+static uint8_t audio_data_in(usb_dev *udev, uint8_t ep_num)
+{
+#ifdef USE_USB_AUDIO_MICPHONE
+ if(count_data < LENGTH_DATA) {
+ /* Prepare next buffer to be sent: dummy data */
+ usbd_ep_send(udev, AUDIO_IN_EP, (uint8_t *)&wavetestdata[count_data], MIC_IN_PACKET);
+ count_data += MIC_IN_PACKET;
+ } else {
+ usbd_ep_send(udev, AUDIO_IN_EP, (uint8_t *)wavetestdata, MIC_IN_PACKET);
+ count_data = MIC_IN_PACKET;
+ }
+#endif
+
+ return USBD_OK;
+}
+
+/*!
+ \brief handles the audio OUT data stage
+ \param[in] udev: pointer to USB device instance
+ \param[in] ep_num: endpoint number
+ \param[out] none
+ \retval USB device operation status
+*/
+static uint8_t audio_data_out(usb_dev *udev, uint8_t ep_num)
+{
+#ifdef USE_USB_AUDIO_SPEAKER
+ usbd_audio_handler *audio = (usbd_audio_handler *)udev->dev.class_data[USBD_AUDIO_INTERFACE];
+
+ /* increment the Buffer pointer or roll it back when all buffers are full */
+ if(audio->isoc_out_wrptr >= (audio->isoc_out_buff + (SPEAKER_OUT_PACKET * OUT_PACKET_NUM))) {
+ /* all buffers are full: roll back */
+ audio->isoc_out_wrptr = audio->isoc_out_buff;
+ } else {
+ /* increment the buffer pointer */
+ audio->isoc_out_wrptr += SPEAKER_OUT_PACKET;
+ }
+
+ /* Toggle the frame index */
+ udev->dev.transc_out[ep_num].frame_num =
+ (udev->dev.transc_out[ep_num].frame_num) ? 0U : 1U;
+
+ /* prepare out endpoint to receive next audio packet */
+ usbd_ep_recev(udev, AUDIO_OUT_EP, (uint8_t *)(audio->isoc_out_wrptr), SPEAKER_OUT_PACKET);
+
+ /* trigger the start of streaming only when half buffer is full */
+ if((0U == audio->play_flag) && (audio->isoc_out_wrptr >= (audio->isoc_out_buff + ((SPEAKER_OUT_PACKET * OUT_PACKET_NUM) / 2U)))) {
+ /* enable start of streaming */
+ audio->play_flag = 1U;
+ }
+#endif
+
+ return USBD_OK;
+}
+
+/*!
+ \brief handles the SOF event (data buffer update and synchronization)
+ \param[in] udev: pointer to USB device instance
+ \param[out] none
+ \retval USB device operation status
+*/
+static uint8_t usbd_audio_sof(usb_dev *udev)
+{
+#ifdef USE_USB_AUDIO_SPEAKER
+ usbd_audio_handler *audio = (usbd_audio_handler *)udev->dev.class_data[USBD_AUDIO_INTERFACE];
+
+ /* check if there are available data in stream buffer.
+ in this function, a single variable (play_flag) is used to avoid software delays.
+ the play operation must be executed as soon as possible after the SOF detection. */
+ if(audio->play_flag) {
+ /* start playing received packet */
+ audio_out_fops.audio_cmd((uint8_t *)(audio->isoc_out_rdptr), /* samples buffer pointer */
+ SPEAKER_OUT_PACKET, /* number of samples in Bytes */
+ AUDIO_CMD_PLAY); /* command to be processed */
+
+ /* increment the Buffer pointer or roll it back when all buffers all full */
+ if(audio->isoc_out_rdptr >= (audio->isoc_out_buff + (SPEAKER_OUT_PACKET * OUT_PACKET_NUM))) {
+ /* roll back to the start of buffer */
+ audio->isoc_out_rdptr = audio->isoc_out_buff;
+ } else {
+ /* increment to the next sub-buffer */
+ audio->isoc_out_rdptr += SPEAKER_OUT_PACKET;
+ }
+
+ /* if all available buffers have been consumed, stop playing */
+ if(audio->isoc_out_rdptr == audio->isoc_out_wrptr) {
+ /* Pause the audio stream */
+ audio_out_fops.audio_cmd((uint8_t *)(audio->isoc_out_buff), /* samples buffer pointer */
+ SPEAKER_OUT_PACKET, /* number of samples in Bytes */
+ AUDIO_CMD_PAUSE); /* command to be processed */
+
+ /* stop entering play loop */
+ audio->play_flag = 0U;
+
+ /* reset buffer pointers */
+ audio->isoc_out_rdptr = audio->isoc_out_buff;
+ audio->isoc_out_wrptr = audio->isoc_out_buff;
+ }
+ }
+#endif
+
+ return USBD_OK;
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/audio/Source/audio_out_itf.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/audio/Source/audio_out_itf.c
new file mode 100644
index 00000000..0752ef2e
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/audio/Source/audio_out_itf.c
@@ -0,0 +1,228 @@
+/*!
+ \file audio_out_itf.c
+ \brief audio OUT (playback) interface functions
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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.
+*/
+
+#include "audio_core.h"
+#include "audio_out_itf.h"
+
+/* local function prototypes ('static') */
+static uint8_t init(uint32_t audiofreq, uint32_t volume, uint32_t options);
+static uint8_t deinit(uint32_t options);
+static uint8_t audio_cmd(uint8_t *pbuf, uint32_t size, uint8_t cmd);
+static uint8_t volume_ctl(uint8_t vol);
+static uint8_t mute_ctl(uint8_t cmd);
+static uint8_t periodic_tc(uint8_t cmd);
+static uint8_t get_state(void);
+
+audio_fops_struct audio_out_fops = {
+ init,
+ deinit,
+ audio_cmd,
+ volume_ctl,
+ mute_ctl,
+ periodic_tc,
+ get_state
+};
+
+static uint8_t audio_state = AUDIO_STATE_INACTIVE;
+
+/*!
+ \brief initialize and configures all required resources for audio play function
+ \param[in] audio_freq: statrt_up audio frequency
+ \param[in] volume: start_up volume to be set
+ \param[in] options: specific options passed to low layer function
+ \param[out] none
+ \retval AUDIO_OK if all operations succeed, AUDIO_FAIL else
+*/
+static uint8_t init(uint32_t audio_freq, uint32_t volume, uint32_t options)
+{
+ static uint32_t initialized = 0U;
+
+ /* check if the low layer has already been initialized */
+ if(0U == initialized) {
+ /* call low layer function */
+ if(0U != eval_audio_init(OUTPUT_DEVICE_AUTO, (uint8_t)volume, audio_freq)) {
+ audio_state = AUDIO_STATE_ERROR;
+
+ return AUDIO_FAIL;
+ }
+
+ /* set the initialization flag to prevent reinitializing the interface again */
+ initialized = 1U;
+ }
+
+ /* update the audio state machine */
+ audio_state = AUDIO_STATE_ACTIVE;
+
+ return AUDIO_OK;
+}
+
+/*!
+ \brief free all resources used by low layer and stops audio-play function
+ \param[in] options: specific options passed to low layer function
+ \param[out] none
+ \retval AUDIO_OK if all operations succeed, AUDIO_FAIL else
+*/
+static uint8_t deinit(uint32_t options)
+{
+ /* update the audio state machine */
+ audio_state = AUDIO_STATE_INACTIVE;
+
+ return AUDIO_OK;
+}
+
+/*!
+ \brief play, stop, pause or resume current file
+ \param[in] pbuf: address from which file should be played
+ \param[in] size: size of the current buffer/file
+ \param[in] cmd: command to be executed, can be:
+ \arg AUDIO_CMD_PLAY
+ \arg AUDIO_CMD_PAUSE
+ \arg AUDIO_CMD_RESUME
+ \arg AUDIO_CMD_STOP
+ \param[out] none
+ \retval AUDIO_OK if all operations succeed, AUDIO_FAIL else
+*/
+static uint8_t audio_cmd(uint8_t *pbuf, uint32_t size, uint8_t cmd)
+{
+ /* check the current state */
+ if((AUDIO_STATE_INACTIVE == audio_state) || (AUDIO_STATE_ERROR == audio_state)) {
+ audio_state = AUDIO_STATE_ERROR;
+
+ return AUDIO_FAIL;
+ }
+
+ switch(cmd) {
+ /* process the play command */
+ case AUDIO_CMD_PLAY:
+ /* if current state is active or stopped */
+ if((AUDIO_STATE_ACTIVE == audio_state) || \
+ (AUDIO_STATE_STOPPED == audio_state) || \
+ (AUDIO_STATE_PLAYING == audio_state)) {
+ audio_mal_play((uint32_t)pbuf, size);
+ audio_state = AUDIO_STATE_PLAYING;
+
+ return AUDIO_OK;
+ } else if(AUDIO_STATE_PAUSED == audio_state) {
+ if(eval_audio_pause_resume(AUDIO_RESUME, (uint32_t)pbuf, (size / 2U))) {
+ audio_state = AUDIO_STATE_ERROR;
+
+ return AUDIO_FAIL;
+ } else {
+ audio_state = AUDIO_STATE_PLAYING;
+
+ return AUDIO_OK;
+ }
+ } else {
+ return AUDIO_FAIL;
+ }
+
+ /* process the stop command */
+ case AUDIO_CMD_STOP:
+ if(AUDIO_STATE_PLAYING != audio_state) {
+ /* unsupported command */
+ return AUDIO_FAIL;
+ } else if(eval_audio_stop(CODEC_PDWN_SW)) {
+ audio_state = AUDIO_STATE_ERROR;
+
+ return AUDIO_FAIL;
+ } else {
+ audio_state = AUDIO_STATE_STOPPED;
+
+ return AUDIO_OK;
+ }
+
+ /* process the pause command */
+ case AUDIO_CMD_PAUSE:
+ if(AUDIO_STATE_PLAYING != audio_state) {
+ /* unsupported command */
+ return AUDIO_FAIL;
+ } else if(eval_audio_pause_resume(AUDIO_PAUSE, (uint32_t)pbuf, (size / 2U))) {
+ audio_state = AUDIO_STATE_ERROR;
+
+ return AUDIO_FAIL;
+ } else {
+ audio_state = AUDIO_STATE_PAUSED;
+
+ return AUDIO_OK;
+ }
+
+ /* unsupported command */
+ default:
+ return AUDIO_FAIL;
+ }
+}
+
+/*!
+ \brief set the volume level
+ \param[in] vol: volume level to be set in % (from 0% to 100%)
+ \param[out] none
+ \retval AUDIO_OK if all operations succeed, AUDIO_FAIL else
+*/
+static uint8_t volume_ctl(uint8_t vol)
+{
+ return AUDIO_OK;
+}
+
+/*!
+ \brief mute or unmute the audio current output
+ \param[in] cmd: can be 0 to unmute, or 1 to mute
+ \param[out] none
+ \retval AUDIO_OK if all operations succeed, AUDIO_FAIL else
+*/
+static uint8_t mute_ctl(uint8_t cmd)
+{
+ return AUDIO_OK;
+}
+
+/*!
+ \brief periodic transfer control
+ \param[in] cmd: command
+ \param[out] none
+ \retval AUDIO_OK if all operations succeed, AUDIO_FAIL else
+*/
+static uint8_t periodic_tc(uint8_t cmd)
+{
+ return AUDIO_OK;
+}
+
+/*!
+ \brief return the current state of the audio machine
+ \param[in] none
+ \param[out] none
+ \retval AUDIO_OK if all operations succeed, AUDIO_FAIL else
+*/
+static uint8_t get_state(void)
+{
+ return audio_state;
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/cdc/Include/cdc_acm_core.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/cdc/Include/cdc_acm_core.h
new file mode 100644
index 00000000..11828445
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/cdc/Include/cdc_acm_core.h
@@ -0,0 +1,66 @@
+/*!
+ \file cdc_acm_core.h
+ \brief the header file of cdc acm driver
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __CDC_ACM_CORE_H
+#define __CDC_ACM_CORE_H
+
+#include "usbd_enum.h"
+#include "usb_cdc.h"
+
+#define USB_CDC_RX_LEN 64
+
+typedef struct {
+ uint8_t packet_sent;
+ uint8_t packet_receive;
+
+ uint8_t data[USB_CDC_RX_LEN];
+ uint8_t cmd[USB_CDC_CMD_PACKET_SIZE];
+
+ uint32_t receive_length;
+
+ acm_line line_coding;
+} usb_cdc_handler;
+
+extern usb_desc cdc_desc;
+extern usb_class_core cdc_class;
+
+/* function declarations */
+/* check cdc acm is ready for data transfer */
+uint8_t cdc_acm_check_ready(usb_dev *udev);
+/* send CDC ACM data */
+void cdc_acm_data_send(usb_dev *udev);
+/* receive CDC ACM data */
+void cdc_acm_data_receive(usb_dev *udev);
+
+#endif /* __CDC_ACM_CORE_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/cdc/Source/cdc_acm_core.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/cdc/Source/cdc_acm_core.c
new file mode 100644
index 00000000..92ae2324
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/cdc/Source/cdc_acm_core.c
@@ -0,0 +1,516 @@
+/*!
+ \file cdc_acm_core.c
+ \brief CDC ACM driver
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+ \version 2020-12-07, V3.0.1, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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.
+*/
+
+#include "cdc_acm_core.h"
+
+#define USBD_VID 0x28E9U
+#define USBD_PID 0x018AU
+
+/* note:it should use the C99 standard when compiling the below codes */
+/* USB standard device descriptor */
+const usb_desc_dev cdc_dev_desc = {
+ .header =
+ {
+ .bLength = USB_DEV_DESC_LEN,
+ .bDescriptorType = USB_DESCTYPE_DEV,
+ },
+ .bcdUSB = 0x0200U,
+ .bDeviceClass = USB_CLASS_CDC,
+ .bDeviceSubClass = 0x00U,
+ .bDeviceProtocol = 0x00U,
+ .bMaxPacketSize0 = USB_FS_EP0_MAX_LEN,
+ .idVendor = USBD_VID,
+ .idProduct = USBD_PID,
+ .bcdDevice = 0x0100U,
+ .iManufacturer = STR_IDX_MFC,
+ .iProduct = STR_IDX_PRODUCT,
+ .iSerialNumber = STR_IDX_SERIAL,
+ .bNumberConfigurations = USBD_CFG_MAX_NUM,
+};
+
+/* USB device configuration descriptor */
+const usb_cdc_desc_config_set cdc_config_desc = {
+ .config =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_config),
+ .bDescriptorType = USB_DESCTYPE_CONFIG,
+ },
+ .wTotalLength = USB_CDC_ACM_CONFIG_DESC_SIZE,
+ .bNumInterfaces = 0x02U,
+ .bConfigurationValue = 0x01U,
+ .iConfiguration = 0x00U,
+ .bmAttributes = 0x80U,
+ .bMaxPower = 0x32U
+ },
+
+ .cmd_itf =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_itf),
+ .bDescriptorType = USB_DESCTYPE_ITF
+ },
+ .bInterfaceNumber = 0x00U,
+ .bAlternateSetting = 0x00U,
+ .bNumEndpoints = 0x01U,
+ .bInterfaceClass = USB_CLASS_CDC,
+ .bInterfaceSubClass = USB_CDC_SUBCLASS_ACM,
+ .bInterfaceProtocol = USB_CDC_PROTOCOL_AT,
+ .iInterface = 0x00U
+ },
+
+ .cdc_header =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_header_func),
+ .bDescriptorType = USB_DESCTYPE_CS_INTERFACE
+ },
+ .bDescriptorSubtype = 0x00U,
+ .bcdCDC = 0x0110U
+ },
+
+ .cdc_call_managment =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_call_managment_func),
+ .bDescriptorType = USB_DESCTYPE_CS_INTERFACE
+ },
+ .bDescriptorSubtype = 0x01U,
+ .bmCapabilities = 0x00U,
+ .bDataInterface = 0x01U
+ },
+
+ .cdc_acm =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_acm_func),
+ .bDescriptorType = USB_DESCTYPE_CS_INTERFACE
+ },
+ .bDescriptorSubtype = 0x02U,
+ .bmCapabilities = 0x02U,
+ },
+
+ .cdc_union =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_union_func),
+ .bDescriptorType = USB_DESCTYPE_CS_INTERFACE
+ },
+ .bDescriptorSubtype = 0x06U,
+ .bMasterInterface = 0x00U,
+ .bSlaveInterface0 = 0x01U,
+ },
+
+ .cdc_cmd_endpoint =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_ep),
+ .bDescriptorType = USB_DESCTYPE_EP,
+ },
+ .bEndpointAddress = CDC_CMD_EP,
+ .bmAttributes = USB_EP_ATTR_INT,
+ .wMaxPacketSize = USB_CDC_CMD_PACKET_SIZE,
+ .bInterval = 0x0AU
+ },
+
+ .cdc_data_interface =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_itf),
+ .bDescriptorType = USB_DESCTYPE_ITF,
+ },
+ .bInterfaceNumber = 0x01U,
+ .bAlternateSetting = 0x00U,
+ .bNumEndpoints = 0x02U,
+ .bInterfaceClass = USB_CLASS_DATA,
+ .bInterfaceSubClass = 0x00U,
+ .bInterfaceProtocol = USB_CDC_PROTOCOL_NONE,
+ .iInterface = 0x00U
+ },
+
+ .cdc_out_endpoint =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_ep),
+ .bDescriptorType = USB_DESCTYPE_EP,
+ },
+ .bEndpointAddress = CDC_DATA_OUT_EP,
+ .bmAttributes = USB_EP_ATTR_BULK,
+ .wMaxPacketSize = USB_CDC_DATA_PACKET_SIZE,
+ .bInterval = 0x00U
+ },
+
+ .cdc_in_endpoint =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_ep),
+ .bDescriptorType = USB_DESCTYPE_EP
+ },
+ .bEndpointAddress = CDC_DATA_IN_EP,
+ .bmAttributes = USB_EP_ATTR_BULK,
+ .wMaxPacketSize = USB_CDC_DATA_PACKET_SIZE,
+ .bInterval = 0x00U
+ }
+};
+
+/* USB language ID Descriptor */
+static const usb_desc_LANGID usbd_language_id_desc = {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_LANGID),
+ .bDescriptorType = USB_DESCTYPE_STR,
+ },
+ .wLANGID = ENG_LANGID
+};
+
+/* USB manufacture string */
+static const usb_desc_str manufacturer_string = {
+ .header =
+ {
+ .bLength = USB_STRING_LEN(10),
+ .bDescriptorType = USB_DESCTYPE_STR,
+ },
+ .unicode_string = {'G', 'i', 'g', 'a', 'D', 'e', 'v', 'i', 'c', 'e'}
+};
+
+/* USB product string */
+static const usb_desc_str product_string = {
+ .header =
+ {
+ .bLength = USB_STRING_LEN(12),
+ .bDescriptorType = USB_DESCTYPE_STR,
+ },
+ .unicode_string = {'G', 'D', '3', '2', '-', 'C', 'D', 'C', '_', 'A', 'C', 'M'}
+};
+
+/* USBD serial string */
+static usb_desc_str serial_string = {
+ .header =
+ {
+ .bLength = USB_STRING_LEN(12),
+ .bDescriptorType = USB_DESCTYPE_STR,
+ }
+};
+
+/* USB string descriptor set */
+void *const usbd_cdc_strings[] = {
+ [STR_IDX_LANGID] = (uint8_t *) &usbd_language_id_desc,
+ [STR_IDX_MFC] = (uint8_t *) &manufacturer_string,
+ [STR_IDX_PRODUCT] = (uint8_t *) &product_string,
+ [STR_IDX_SERIAL] = (uint8_t *) &serial_string
+};
+
+usb_desc cdc_desc = {
+ .dev_desc = (uint8_t *) &cdc_dev_desc,
+ .config_desc = (uint8_t *) &cdc_config_desc,
+ .strings = usbd_cdc_strings
+};
+
+/* local function prototypes ('static') */
+static uint8_t cdc_acm_init(usb_dev *udev, uint8_t config_index);
+static uint8_t cdc_acm_deinit(usb_dev *udev, uint8_t config_index);
+static uint8_t cdc_acm_req(usb_dev *udev, usb_req *req);
+static uint8_t cdc_ctlx_out(usb_dev *udev);
+static uint8_t cdc_acm_in(usb_dev *udev, uint8_t ep_num);
+static uint8_t cdc_acm_out(usb_dev *udev, uint8_t ep_num);
+
+/* USB CDC device class callbacks structure */
+usb_class_core cdc_class = {
+ .command = NO_CMD,
+ .alter_set = 0U,
+
+ .init = cdc_acm_init,
+ .deinit = cdc_acm_deinit,
+
+ .req_proc = cdc_acm_req,
+ .ctlx_out = cdc_ctlx_out,
+
+ .data_in = cdc_acm_in,
+ .data_out = cdc_acm_out
+};
+
+/*!
+ \brief check cdc acm is ready for data transfer
+ \param[in] udev: pointer to USB device instance
+ \param[out] none
+ \retval 0 if cdc is ready, 5 else
+*/
+uint8_t cdc_acm_check_ready(usb_dev *udev)
+{
+ if(udev->dev.class_data[CDC_COM_INTERFACE] != NULL) {
+ usb_cdc_handler *cdc = (usb_cdc_handler *)udev->dev.class_data[CDC_COM_INTERFACE];
+
+ if((1U == cdc->packet_receive) && (1U == cdc->packet_sent)) {
+ return 0U;
+ }
+ }
+
+ return 1U;
+}
+
+/*!
+ \brief send CDC ACM data
+ \param[in] udev: pointer to USB device instance
+ \param[out] none
+ \retval USB device operation status
+*/
+void cdc_acm_data_send(usb_dev *udev)
+{
+ usb_cdc_handler *cdc = (usb_cdc_handler *)udev->dev.class_data[CDC_COM_INTERFACE];
+
+ if(0U != cdc->receive_length) {
+ cdc->packet_sent = 0U;
+
+ usbd_ep_send(udev, CDC_DATA_IN_EP, (uint8_t *)(cdc->data), cdc->receive_length);
+
+ cdc->receive_length = 0U;
+ }
+}
+
+/*!
+ \brief receive CDC ACM data
+ \param[in] udev: pointer to USB device instance
+ \param[out] none
+ \retval USB device operation status
+*/
+void cdc_acm_data_receive(usb_dev *udev)
+{
+ usb_cdc_handler *cdc = (usb_cdc_handler *)udev->dev.class_data[CDC_COM_INTERFACE];
+
+ cdc->packet_receive = 0U;
+ cdc->packet_sent = 0U;
+
+ usbd_ep_recev(udev, CDC_DATA_OUT_EP, (uint8_t *)(cdc->data), USB_CDC_DATA_PACKET_SIZE);
+}
+
+/*!
+ \brief initialize the CDC ACM device
+ \param[in] udev: pointer to USB device instance
+ \param[in] config_index: configuration index
+ \param[out] none
+ \retval USB device operation status
+*/
+static uint8_t cdc_acm_init(usb_dev *udev, uint8_t config_index)
+{
+ static usb_cdc_handler cdc_handler;
+
+ /* initialize the data Tx endpoint */
+ usbd_ep_setup(udev, &(cdc_config_desc.cdc_in_endpoint));
+
+ /* initialize the data Rx endpoint */
+ usbd_ep_setup(udev, &(cdc_config_desc.cdc_out_endpoint));
+
+ /* initialize the command Tx endpoint */
+ usbd_ep_setup(udev, &(cdc_config_desc.cdc_cmd_endpoint));
+
+ /* initialize cdc handler structure */
+ cdc_handler.packet_receive = 1U;
+ cdc_handler.packet_sent = 1U;
+ cdc_handler.receive_length = 0U;
+
+ cdc_handler.line_coding = (acm_line) {
+ .dwDTERate = 115200,
+ .bCharFormat = 0,
+ .bParityType = 0,
+ .bDataBits = 0x08
+ };
+
+ udev->dev.class_data[CDC_COM_INTERFACE] = (void *)&cdc_handler;
+
+ return USBD_OK;
+}
+
+/*!
+ \brief de-initialize the CDC ACM device
+ \param[in] udev: pointer to USB device instance
+ \param[in] config_index: configuration index
+ \param[out] none
+ \retval USB device operation status
+*/
+static uint8_t cdc_acm_deinit(usb_dev *udev, uint8_t config_index)
+{
+ /* deinitialize the data Tx/Rx endpoint */
+ usbd_ep_clear(udev, CDC_DATA_IN_EP);
+ usbd_ep_clear(udev, CDC_DATA_OUT_EP);
+
+ /* deinitialize the command Tx endpoint */
+ usbd_ep_clear(udev, CDC_CMD_EP);
+
+ return USBD_OK;
+}
+
+/*!
+ \brief handle the CDC ACM class-specific requests
+ \param[in] udev: pointer to USB device instance
+ \param[in] req: device class-specific request
+ \param[out] none
+ \retval USB device operation status
+*/
+static uint8_t cdc_acm_req(usb_dev *udev, usb_req *req)
+{
+ usb_cdc_handler *cdc = (usb_cdc_handler *)udev->dev.class_data[CDC_COM_INTERFACE];
+
+ usb_transc *transc = NULL;
+
+ switch(req->bRequest) {
+ case SEND_ENCAPSULATED_COMMAND:
+ /* no operation for this driver */
+ break;
+
+ case GET_ENCAPSULATED_RESPONSE:
+ /* no operation for this driver */
+ break;
+
+ case SET_COMM_FEATURE:
+ /* no operation for this driver */
+ break;
+
+ case GET_COMM_FEATURE:
+ /* no operation for this driver */
+ break;
+
+ case CLEAR_COMM_FEATURE:
+ /* no operation for this driver */
+ break;
+
+ case SET_LINE_CODING:
+ transc = &udev->dev.transc_out[0];
+ /* set the value of the current command to be processed */
+ udev->dev.class_core->alter_set = req->bRequest;
+
+ /* enable EP0 prepare to receive command data packet */
+ transc->remain_len = req->wLength;
+ transc->xfer_buf = cdc->cmd;
+ break;
+
+ case GET_LINE_CODING:
+ transc = &udev->dev.transc_in[0];
+
+ cdc->cmd[0] = (uint8_t)(cdc->line_coding.dwDTERate);
+ cdc->cmd[1] = (uint8_t)(cdc->line_coding.dwDTERate >> 8);
+ cdc->cmd[2] = (uint8_t)(cdc->line_coding.dwDTERate >> 16);
+ cdc->cmd[3] = (uint8_t)(cdc->line_coding.dwDTERate >> 24);
+ cdc->cmd[4] = cdc->line_coding.bCharFormat;
+ cdc->cmd[5] = cdc->line_coding.bParityType;
+ cdc->cmd[6] = cdc->line_coding.bDataBits;
+
+ transc->xfer_buf = cdc->cmd;
+ transc->remain_len = 7U;
+ break;
+
+ case SET_CONTROL_LINE_STATE:
+ /* no operation for this driver */
+ break;
+
+ case SEND_BREAK:
+ /* no operation for this driver */
+ break;
+
+ default:
+ break;
+ }
+
+ return USBD_OK;
+}
+
+
+static uint8_t cdc_ctlx_out(usb_dev *udev)
+{
+ usb_cdc_handler *cdc = (usb_cdc_handler *)udev->dev.class_data[CDC_COM_INTERFACE];
+
+ if(udev->dev.class_core->alter_set != NO_CMD) {
+ /* process the command data */
+ cdc->line_coding.dwDTERate = (uint32_t)((uint32_t)cdc->cmd[0] |
+ ((uint32_t)cdc->cmd[1] << 8U) |
+ ((uint32_t)cdc->cmd[2] << 16U) |
+ ((uint32_t)cdc->cmd[3] << 24U));
+
+ cdc->line_coding.bCharFormat = cdc->cmd[4];
+ cdc->line_coding.bParityType = cdc->cmd[5];
+ cdc->line_coding.bDataBits = cdc->cmd[6];
+
+ udev->dev.class_core->alter_set = NO_CMD;
+ }
+ return USBD_OK;
+}
+
+/*!
+ \brief handle CDC ACM data
+ \param[in] udev: pointer to USB device instance
+ \param[in] ep_num: endpoint identifier
+ \param[out] none
+ \retval USB device operation status
+*/
+static uint8_t cdc_acm_in(usb_dev *udev, uint8_t ep_num)
+{
+ usb_transc *transc = &udev->dev.transc_in[EP_ID(ep_num)];
+
+ usb_cdc_handler *cdc = (usb_cdc_handler *)udev->dev.class_data[CDC_COM_INTERFACE];
+
+ if((0U == transc->xfer_len % transc->max_len) && (0U != transc->xfer_len)) {
+ usbd_ep_send(udev, ep_num, NULL, 0U);
+ } else {
+ cdc->packet_sent = 1U;
+ }
+
+ return USBD_OK;
+}
+
+/*!
+ \brief handle CDC ACM data
+ \param[in] udev: pointer to USB device instance
+ \param[in] ep_num: endpoint identifier
+ \param[out] none
+ \retval USB device operation status
+*/
+static uint8_t cdc_acm_out(usb_dev *udev, uint8_t ep_num)
+{
+ usb_cdc_handler *cdc = (usb_cdc_handler *)udev->dev.class_data[CDC_COM_INTERFACE];
+
+ cdc->packet_receive = 1U;
+ cdc->receive_length = ((usb_core_driver *)udev)->dev.transc_out[ep_num].xfer_count;
+
+ return USBD_OK;
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/dfu/Include/dfu_core.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/dfu/Include/dfu_core.h
new file mode 100644
index 00000000..4c58601e
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/dfu/Include/dfu_core.h
@@ -0,0 +1,173 @@
+/*!
+ \file dfu_core.h
+ \brief the header file of USB DFU device class core functions
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __DFU_CORE_H
+#define __DFU_CORE_H
+
+#include "usbd_enum.h"
+
+/* DFU class code */
+#define USB_DFU_CLASS 0xFEU
+
+/* DFU subclass code */
+#define USB_DFU_SUBCLASS_UPGRADE 0x01U
+
+/* DFU protocl code */
+#define USB_DFU_PROTOCL_RUNTIME 0x01U
+#define USB_DFU_PROTOCL_DFU 0x02U
+
+/* manifestation state */
+#define MANIFEST_COMPLETE 0x00U
+#define MANIFEST_IN_PROGRESS 0x01U
+
+/* DFU attributes code */
+#define USB_DFU_CAN_DOWNLOAD 0x01U
+#define USB_DFU_CAN_UPLOAD 0x02U
+#define USB_DFU_MANIFEST_TOLERANT 0x04U
+#define USB_DFU_WILL_DETACH 0x08U
+
+/* special commands with download request */
+#define GET_COMMANDS 0x00U
+#define SET_ADDRESS_POINTER 0x21U
+#define ERASE 0x41U
+
+/* memory operation command */
+#define CMD_ERASE 0U
+#define CMD_WRITE 1U
+
+#define _BYTE1(x) (uint8_t)((x) & 0xFFU) /*!< addressing cycle 1st byte */
+#define _BYTE2(x) (uint8_t)(((x) & 0xFF00U) >> 8U) /*!< addressing cycle 2nd byte */
+#define _BYTE3(x) (uint8_t)(((x) & 0xFF0000U) >> 16U) /*!< addressing cycle 3rd byte */
+
+#define FLASH_ERASE_TIMEOUT 60U
+#define FLASH_WRITE_TIMEOUT 80U
+
+/* bit detach capable = bit 3 in bmAttributes field */
+#define DFU_DETACH_MASK (uint8_t)(0x10U)
+
+#define USB_SERIAL_STR_LEN 0x06U
+
+#define USB_DFU_CONFIG_DESC_SIZE 27U
+
+#define DFU_DESC_TYPE 0x21U
+
+/* DFU device state defines */
+typedef enum {
+ STATE_APP_IDLE = 0x00U,
+ STATE_APP_DETACH,
+ STATE_DFU_IDLE,
+ STATE_DFU_DNLOAD_SYNC,
+ STATE_DFU_DNBUSY,
+ STATE_DFU_DNLOAD_IDLE,
+ STATE_DFU_MANIFEST_SYNC,
+ STATE_DFU_MANIFEST,
+ STATE_DFU_MANIFEST_WAIT_RESET,
+ STATE_DFU_UPLOAD_IDLE,
+ STATE_DFU_ERROR
+} dfu_state;
+
+/* DFU device status defines */
+typedef enum {
+ STATUS_OK = 0x00U,
+ STATUS_ERR_TARGET,
+ STATUS_ERR_FILE,
+ STATUS_ERR_WRITE,
+ STATUS_ERR_ERASE,
+ STATUS_ERR_CHECK_ERASED,
+ STATUS_ERR_PROG,
+ STATUS_ERR_VERIFY,
+ STATUS_ERR_ADDRESS,
+ STATUS_ERR_NOTDONE,
+ STATUS_ERR_FIRMWARE,
+ STATUS_ERR_VENDOR,
+ STATUS_ERR_USBR,
+ STATUS_ERR_POR,
+ STATUS_ERR_UNKNOWN,
+ STATUS_ERR_STALLEDPKT
+} dfu_status;
+
+/* DFU class-specific requests */
+typedef enum {
+ DFU_DETACH = 0U,
+ DFU_DNLOAD,
+ DFU_UPLOAD,
+ DFU_GETSTATUS,
+ DFU_CLRSTATUS,
+ DFU_GETSTATE,
+ DFU_ABORT,
+ DFU_REQ_MAX
+} dfu_requests;
+
+#pragma pack(1)
+
+/* USB dfu function descriptor structure */
+typedef struct {
+ usb_desc_header header; /*!< descriptor header, including type and size */
+ uint8_t bmAttributes; /*!< DFU attributes */
+ uint16_t wDetachTimeOut; /*!< time, in milliseconds, that the device will wait after receipt of the DFU_DETACH request. If */
+ uint16_t wTransferSize; /*!< maximum number of bytes that the device can accept per control-write transaction */
+ uint16_t bcdDFUVersion; /*!< numeric expression identifying the version of the DFU Specification release. */
+} usb_desc_dfu_func;
+
+#pragma pack()
+
+/* USB configuration descriptor structure */
+typedef struct {
+ usb_desc_config config;
+ usb_desc_itf dfu_itf;
+ usb_desc_dfu_func dfu_func;
+} usb_dfu_desc_config_set;
+
+typedef struct {
+ uint8_t bStatus;
+ uint8_t bwPollTimeout0;
+ uint8_t bwPollTimeout1;
+ uint8_t bwPollTimeout2;
+ uint8_t bState;
+ uint8_t iString;
+
+ uint8_t manifest_state;
+ uint32_t data_len;
+ uint16_t block_num;
+ uint32_t base_addr;
+
+ uint8_t buf[TRANSFER_SIZE];
+} usbd_dfu_handler;
+
+typedef void (*app_func)(void);
+
+extern usb_desc dfu_desc;
+extern usb_class_core dfu_class;
+
+#endif /* DFU_CORE_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/dfu/Include/dfu_mal.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/dfu/Include/dfu_mal.h
new file mode 100644
index 00000000..bd1ee738
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/dfu/Include/dfu_mal.h
@@ -0,0 +1,82 @@
+/*!
+ \file dfu_mal.h
+ \brief USB DFU device media access layer header file
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __DFU_MAL_H
+#define __DFU_MAL_H
+
+#include "usbd_conf.h"
+
+typedef struct _dfu_mal_prop {
+ const uint8_t *pstr_desc;
+
+ uint8_t (*mal_init)(void);
+ uint8_t (*mal_deinit)(void);
+ uint8_t (*mal_erase)(uint32_t addr);
+ uint8_t (*mal_write)(uint8_t *buf, uint32_t addr, uint32_t len);
+ uint8_t *(*mal_read)(uint8_t *buf, uint32_t addr, uint32_t len);
+ uint8_t (*mal_checkaddr)(uint32_t addr);
+
+ const uint32_t erase_timeout;
+ const uint32_t write_timeout;
+} dfu_mal_prop;
+
+typedef enum {
+ MAL_OK = 0,
+ MAL_FAIL
+} MAL_Status;
+
+#define _1st_BYTE(x) (uint8_t)((x) & 0xFF) /*!< addressing cycle 1st byte */
+#define _2nd_BYTE(x) (uint8_t)(((x) & 0xFF00) >> 8) /*!< addressing cycle 2nd byte */
+#define _3rd_BYTE(x) (uint8_t)(((x) & 0xFF0000) >> 16) /*!< addressing cycle 3rd byte */
+
+#define SET_POLLING_TIMEOUT(x) buffer[0] = _1st_BYTE(x);\
+ buffer[1] = _2nd_BYTE(x);\
+ buffer[2] = _3rd_BYTE(x);
+
+/* function declarations */
+/* initialize the memory media on the GD32 */
+uint8_t dfu_mal_init(void);
+/* deinitialize the memory media on the GD32 */
+uint8_t dfu_mal_deinit(void);
+/* erase a memory sector */
+uint8_t dfu_mal_erase(uint32_t addr);
+/* write data to sectors of memory */
+uint8_t dfu_mal_write(uint8_t *buf, uint32_t addr, uint32_t len);
+/* read data from sectors of memory */
+uint8_t *dfu_mal_read(uint8_t *buf, uint32_t addr, uint32_t len);
+/* get the status of a given memory and store in buffer */
+uint8_t dfu_mal_getstatus(uint32_t addr, uint8_t cmd, uint8_t *buffer);
+
+#endif /* __DFU_MAL_H */
+
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/dfu/Source/dfu_core.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/dfu/Source/dfu_core.c
new file mode 100644
index 00000000..1a3d2a4a
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/dfu/Source/dfu_core.c
@@ -0,0 +1,643 @@
+/*!
+ \file dfu_core.c
+ \brief USB DFU device class core functions
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+ \version 2020-12-07, V3.0.1, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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.
+*/
+
+#include "dfu_core.h"
+#include "drv_usb_hw.h"
+#include "dfu_mal.h"
+#include "flash_if.h"
+#include
+
+#define USBD_VID 0x28E9U
+#define USBD_PID 0x0189U
+
+/* local function prototypes ('static') */
+static uint8_t dfu_init(usb_dev *udev, uint8_t config_index);
+static uint8_t dfu_deinit(usb_dev *udev, uint8_t config_index);
+static uint8_t dfu_req_handler(usb_dev *udev, usb_req *req);
+static uint8_t dfu_ctlx_in(usb_dev *udev);
+static void dfu_detach(usb_dev *udev, usb_req *req);
+static void dfu_dnload(usb_dev *udev, usb_req *req);
+static void dfu_upload(usb_dev *udev, usb_req *req);
+static void dfu_getstatus(usb_dev *udev, usb_req *req);
+static void dfu_clrstatus(usb_dev *udev, usb_req *req);
+static void dfu_getstate(usb_dev *udev, usb_req *req);
+static void dfu_abort(usb_dev *udev, usb_req *req);
+static void dfu_mode_leave(usb_dev *udev);
+static uint8_t dfu_getstatus_complete(usb_dev *udev);
+
+static void (*dfu_request_process[])(usb_dev *udev, usb_req *req) = {
+ [DFU_DETACH] = dfu_detach,
+ [DFU_DNLOAD] = dfu_dnload,
+ [DFU_UPLOAD] = dfu_upload,
+ [DFU_GETSTATUS] = dfu_getstatus,
+ [DFU_CLRSTATUS] = dfu_clrstatus,
+ [DFU_GETSTATE] = dfu_getstate,
+ [DFU_ABORT] = dfu_abort
+};
+
+/* note:it should use the c99 standard when compiling the below codes */
+/* USB standard device descriptor */
+const usb_desc_dev dfu_dev_desc = {
+ .header =
+ {
+ .bLength = USB_DEV_DESC_LEN,
+ .bDescriptorType = USB_DESCTYPE_DEV
+ },
+ .bcdUSB = 0x0200U,
+ .bDeviceClass = 0x00U,
+ .bDeviceSubClass = 0x00U,
+ .bDeviceProtocol = 0x00U,
+ .bMaxPacketSize0 = USB_FS_EP0_MAX_LEN,
+ .idVendor = USBD_VID,
+ .idProduct = USBD_PID,
+ .bcdDevice = 0x0100U,
+ .iManufacturer = STR_IDX_MFC,
+ .iProduct = STR_IDX_PRODUCT,
+ .iSerialNumber = STR_IDX_SERIAL,
+ .bNumberConfigurations = USBD_CFG_MAX_NUM
+};
+
+/* USB device configuration descriptor */
+const usb_dfu_desc_config_set dfu_config_desc = {
+ .config =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_config),
+ .bDescriptorType = USB_DESCTYPE_CONFIG
+ },
+ .wTotalLength = USB_DFU_CONFIG_DESC_SIZE,
+ .bNumInterfaces = 0x01U,
+ .bConfigurationValue = 0x01U,
+ .iConfiguration = 0x00U,
+ .bmAttributes = 0x80U,
+ .bMaxPower = 0x32U
+ },
+
+ .dfu_itf =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_itf),
+ .bDescriptorType = USB_DESCTYPE_ITF
+ },
+ .bInterfaceNumber = 0x00U,
+ .bAlternateSetting = 0x00U,
+ .bNumEndpoints = 0x00U,
+ .bInterfaceClass = USB_DFU_CLASS,
+ .bInterfaceSubClass = USB_DFU_SUBCLASS_UPGRADE,
+ .bInterfaceProtocol = USB_DFU_PROTOCL_DFU,
+ .iInterface = 0x05U
+ },
+
+ .dfu_func =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_dfu_func),
+ .bDescriptorType = DFU_DESC_TYPE
+ },
+ .bmAttributes = USB_DFU_CAN_DOWNLOAD | USB_DFU_CAN_UPLOAD | USB_DFU_WILL_DETACH,
+ .wDetachTimeOut = 0x00FFU,
+ .wTransferSize = TRANSFER_SIZE,
+ .bcdDFUVersion = 0x011AU,
+ },
+};
+
+/* USB language ID Descriptor */
+static const usb_desc_LANGID usbd_language_id_desc = {
+ .header = {
+ .bLength = sizeof(usb_desc_LANGID),
+ .bDescriptorType = USB_DESCTYPE_STR
+ },
+ .wLANGID = ENG_LANGID
+};
+
+/* USB manufacture string */
+static const usb_desc_str manufacturer_string = {
+ .header =
+ {
+ .bLength = USB_STRING_LEN(10U),
+ .bDescriptorType = USB_DESCTYPE_STR,
+ },
+ .unicode_string = {'G', 'i', 'g', 'a', 'D', 'e', 'v', 'i', 'c', 'e'}
+};
+
+/* USB product string */
+static const usb_desc_str product_string = {
+ .header =
+ {
+ .bLength = USB_STRING_LEN(12U),
+ .bDescriptorType = USB_DESCTYPE_STR,
+ },
+ .unicode_string = {'G', 'D', '3', '2', '-', 'U', 'S', 'B', '_', 'D', 'F', 'U'}
+};
+
+/* USBD serial string */
+static usb_desc_str serial_string = {
+ .header =
+ {
+ .bLength = USB_STRING_LEN(2U),
+ .bDescriptorType = USB_DESCTYPE_STR,
+ }
+};
+
+/* USB configure string */
+static const usb_desc_str config_string = {
+ .header =
+ {
+ .bLength = USB_STRING_LEN(15U),
+ .bDescriptorType = USB_DESCTYPE_STR,
+ },
+ .unicode_string = {'G', 'D', '3', '2', ' ', 'U', 'S', 'B', ' ', 'C', 'O', 'N', 'F', 'I', 'G'}
+};
+
+static const usb_desc_str interface_string = {
+ .header =
+ {
+ .bLength = USB_STRING_LEN(44U),
+ .bDescriptorType = USB_DESCTYPE_STR,
+ },
+ .unicode_string = {'@', 'I', 'n', 't', 'e', 'r', 'n', 'a', 'l', 'F', 'l', 'a', 's', 'h', ' ', '/', '0', 'x', '0', '8', '0', '0',
+ '0', '0', '0', '0', '/', '1', '6', '*', '0', '0', '1', 'K', 'a', ',', '4', '8', '*', '0', '0', '1', 'K', 'g'
+ }
+};
+
+void *const usbd_dfu_strings[] = {
+ [STR_IDX_LANGID] = (uint8_t *) &usbd_language_id_desc,
+ [STR_IDX_MFC] = (uint8_t *) &manufacturer_string,
+ [STR_IDX_PRODUCT] = (uint8_t *) &product_string,
+ [STR_IDX_SERIAL] = (uint8_t *) &serial_string,
+ [STR_IDX_CONFIG] = (uint8_t *) &config_string,
+ [STR_IDX_ITF] = (uint8_t *) &interface_string
+};
+
+usb_desc dfu_desc = {
+ .dev_desc = (uint8_t *) &dfu_dev_desc,
+ .config_desc = (uint8_t *) &dfu_config_desc,
+ .strings = usbd_dfu_strings
+};
+
+usb_class_core dfu_class = {
+ .init = dfu_init,
+ .deinit = dfu_deinit,
+ .req_proc = dfu_req_handler,
+ .ctlx_in = dfu_ctlx_in
+};
+
+/*!
+ \brief initialize the DFU device
+ \param[in] udev: pointer to USB device instance
+ \param[in] config_index: configuration index
+ \param[out] none
+ \retval USB device operation status
+*/
+static uint8_t dfu_init(usb_dev *udev, uint8_t config_index)
+{
+ static usbd_dfu_handler dfu_handler;
+
+ /* unlock the internal flash */
+ dfu_mal_init();
+
+ memset((void *)&dfu_handler, 0, sizeof(usbd_dfu_handler));
+
+ dfu_handler.base_addr = APP_LOADED_ADDR;
+ dfu_handler.manifest_state = MANIFEST_COMPLETE;
+ dfu_handler.bState = STATE_DFU_IDLE;
+ dfu_handler.bStatus = STATUS_OK;
+
+ udev->dev.class_data[USBD_DFU_INTERFACE] = (void *)&dfu_handler;
+
+ return USBD_OK;
+}
+
+/*!
+ \brief de-initialize the DFU device
+ \param[in] udev: pointer to USB device instance
+ \param[in] config_index: configuration index
+ \param[out] none
+ \retval USB device operation status
+*/
+static uint8_t dfu_deinit(usb_dev *udev, uint8_t config_index)
+{
+ usbd_dfu_handler *dfu = (usbd_dfu_handler *)udev->dev.class_data[USBD_DFU_INTERFACE];
+
+ /* restore device default state */
+ memset(udev->dev.class_data[USBD_DFU_INTERFACE], 0, sizeof(usbd_dfu_handler));
+
+ dfu->bState = STATE_DFU_IDLE;
+ dfu->bStatus = STATUS_OK;
+
+ /* lock the internal flash */
+ dfu_mal_deinit();
+
+ return USBD_OK;
+}
+
+/*!
+ \brief handle the DFU class-specific requests
+ \param[in] udev: pointer to USB device instance
+ \param[in] req: device class-specific request
+ \param[out] none
+ \retval USB device operation status
+*/
+static uint8_t dfu_req_handler(usb_dev *udev, usb_req *req)
+{
+ if(req->bRequest < DFU_REQ_MAX) {
+ dfu_request_process[req->bRequest](udev, req);
+ } else {
+ return USBD_FAIL;
+ }
+
+ return USBD_OK;
+}
+
+/*!
+ \brief handle data Stage
+ \param[in] udev: pointer to USB device instance
+ \param[in] ep_num: the endpoint number
+ \param[out] none
+ \retval USB device operation status
+*/
+static uint8_t dfu_ctlx_in(usb_dev *udev)
+{
+ dfu_getstatus_complete(udev);
+
+ return USBD_OK;
+}
+
+/*!
+ \brief leave DFU mode and reset device to jump to user loaded code
+ \param[in] udev: pointer to USB device instance
+ \param[out] none
+ \retval none
+*/
+static void dfu_mode_leave(usb_dev *udev)
+{
+ usbd_dfu_handler *dfu = (usbd_dfu_handler *)udev->dev.class_data[USBD_DFU_INTERFACE];
+
+ dfu->manifest_state = MANIFEST_COMPLETE;
+
+ if(dfu_config_desc.dfu_func.bmAttributes & 0x04U) {
+ dfu->bState = STATE_DFU_MANIFEST_SYNC;
+ } else {
+ dfu->bState = STATE_DFU_MANIFEST_WAIT_RESET;
+
+ /* lock the internal flash */
+ dfu_mal_deinit();
+
+ /* generate system reset to allow jumping to the user code */
+ NVIC_SystemReset();
+ }
+}
+
+/*!
+ \brief handle data IN stage in control endpoint 0
+ \param[in] udev: pointer to usb device instance
+ \param[out] none
+ \retval usb device operation status
+ */
+static uint8_t dfu_getstatus_complete(usb_dev *udev)
+{
+ uint32_t addr;
+
+ usbd_dfu_handler *dfu = (usbd_dfu_handler *)udev->dev.class_data[USBD_DFU_INTERFACE];
+
+ if(STATE_DFU_DNBUSY == dfu->bState) {
+ /* decode the special command */
+ if(0U == dfu->block_num) {
+ if(1U == dfu->data_len) {
+ if(GET_COMMANDS == dfu->buf[0]) {
+ /* no operation */
+ }
+ } else if(5U == dfu->data_len) {
+ if(SET_ADDRESS_POINTER == dfu->buf[0]) {
+ /* set flash operation address */
+ dfu->base_addr = *(uint32_t *)(dfu->buf + 1U);
+ } else if(ERASE == dfu->buf[0]) {
+ dfu->base_addr = *(uint32_t *)(dfu->buf + 1U);
+
+ dfu_mal_erase(dfu->base_addr);
+ } else {
+ /* no operation */
+ }
+ } else {
+ /* no operation */
+ }
+ } else if(dfu->block_num > 1U) { /* regular download command */
+ /* decode the required address */
+ addr = (dfu->block_num - 2U) * TRANSFER_SIZE + dfu->base_addr;
+
+ dfu_mal_write(dfu->buf, addr, dfu->data_len);
+
+ dfu->block_num = 0U;
+ } else {
+ /* no operation */
+ }
+
+ dfu->data_len = 0U;
+
+ /* update the device state and poll timeout */
+ dfu->bState = STATE_DFU_DNLOAD_SYNC;
+
+ return USBD_OK;
+ } else if(dfu->bState == STATE_DFU_MANIFEST) { /* manifestation in progress */
+ /* start leaving DFU mode */
+ dfu_mode_leave(udev);
+ } else {
+ /* no operation */
+ }
+
+ return USBD_OK;
+}
+
+/*!
+ \brief handle the DFU_DETACH request
+ \param[in] udev: pointer to usb device instance
+ \param[in] req: DFU class request
+ \param[out] none
+ \retval none.
+*/
+static void dfu_detach(usb_dev *udev, usb_req *req)
+{
+ usbd_dfu_handler *dfu = (usbd_dfu_handler *)udev->dev.class_data[USBD_DFU_INTERFACE];
+
+ switch(dfu->bState) {
+ case STATE_DFU_IDLE:
+ case STATE_DFU_DNLOAD_SYNC:
+ case STATE_DFU_DNLOAD_IDLE:
+ case STATE_DFU_MANIFEST_SYNC:
+ case STATE_DFU_UPLOAD_IDLE:
+ dfu->bStatus = STATUS_OK;
+ dfu->bState = STATE_DFU_IDLE;
+ dfu->iString = 0U; /* iString */
+
+ dfu->block_num = 0U;
+ dfu->data_len = 0U;
+ break;
+
+ default:
+ break;
+ }
+
+ /* check the detach capability in the DFU functional descriptor */
+ if(dfu_config_desc.dfu_func.wDetachTimeOut & DFU_DETACH_MASK) {
+ usbd_disconnect(udev);
+
+ usbd_connect(udev);
+ } else {
+ /* wait for the period of time specified in detach request */
+ usb_mdelay(4U);
+ }
+}
+
+/*!
+ \brief handle the DFU_DNLOAD request
+ \param[in] udev: pointer to usb device instance
+ \param[in] req: DFU class request
+ \param[out] none
+ \retval none
+*/
+static void dfu_dnload(usb_dev *udev, usb_req *req)
+{
+ usb_transc *transc = &udev->dev.transc_out[0];
+ usbd_dfu_handler *dfu = (usbd_dfu_handler *)udev->dev.class_data[USBD_DFU_INTERFACE];
+
+ switch(dfu->bState) {
+ case STATE_DFU_IDLE:
+ case STATE_DFU_DNLOAD_IDLE:
+ if(req->wLength > 0U) {
+ /* update the global length and block number */
+ dfu->block_num = req->wValue;
+ dfu->data_len = req->wLength;
+
+ dfu->bState = STATE_DFU_DNLOAD_SYNC;
+
+ transc->remain_len = dfu->data_len;
+ transc->xfer_buf = dfu->buf;
+ } else {
+ dfu->manifest_state = MANIFEST_IN_PROGRESS;
+ dfu->bState = STATE_DFU_MANIFEST_SYNC;
+ }
+ break;
+
+ default:
+ break;
+ }
+}
+
+/*!
+ \brief handles the DFU UPLOAD request.
+ \param[in] udev: pointer to usb device instance
+ \param[in] req: DFU class request
+ \param[out] none
+ \retval none
+*/
+static void dfu_upload(usb_dev *udev, usb_req *req)
+{
+ uint8_t *phy_addr = NULL;
+ uint32_t addr = 0U;
+ usbd_dfu_handler *dfu = (usbd_dfu_handler *)udev->dev.class_data[USBD_DFU_INTERFACE];
+
+ usb_transc *transc = &udev->dev.transc_in[0];
+
+ if(req->wLength <= 0U) {
+ dfu->bState = STATE_DFU_IDLE;
+ return;
+ }
+
+ switch(dfu->bState) {
+ case STATE_DFU_IDLE:
+ case STATE_DFU_UPLOAD_IDLE:
+ /* update the global length and block number */
+ dfu->block_num = req->wValue;
+ dfu->data_len = req->wLength;
+
+ /* DFU get command */
+ if(0U == dfu->block_num) {
+ /* update the state machine */
+ dfu->bState = (dfu->data_len > 3U) ? STATE_DFU_IDLE : STATE_DFU_UPLOAD_IDLE;
+
+ /* store the values of all supported commands */
+ dfu->buf[0] = GET_COMMANDS;
+ dfu->buf[1] = SET_ADDRESS_POINTER;
+ dfu->buf[2] = ERASE;
+
+ /* send the status data over EP0 */
+ transc->xfer_buf = &(dfu->buf[0]);
+ transc->remain_len = 3U;
+ } else if(dfu->block_num > 1U) {
+ dfu->bState = STATE_DFU_UPLOAD_IDLE;
+
+ /* change is accelerated */
+ addr = (dfu->block_num - 2U) * TRANSFER_SIZE + dfu->base_addr;
+
+ /* return the physical address where data are stored */
+ phy_addr = dfu_mal_read(dfu->buf, addr, dfu->data_len);
+
+ /* send the status data over EP0 */
+ transc->xfer_buf = phy_addr;
+ transc->remain_len = dfu->data_len;
+ } else {
+ dfu->bState = STATUS_ERR_STALLEDPKT;
+ }
+ break;
+
+ default:
+ dfu->data_len = 0U;
+ dfu->block_num = 0U;
+ break;
+ }
+}
+
+/*!
+ \brief handle the DFU_GETSTATUS request
+ \param[in] udev: pointer to usb device instance
+ \param[in] req: DFU class request
+ \param[out] none
+ \retval none
+*/
+static void dfu_getstatus(usb_dev *udev, usb_req *req)
+{
+ usbd_dfu_handler *dfu = (usbd_dfu_handler *)udev->dev.class_data[USBD_DFU_INTERFACE];
+
+ usb_transc *transc = &udev->dev.transc_in[0];
+
+ switch(dfu->bState) {
+ case STATE_DFU_DNLOAD_SYNC:
+ if(0U != dfu->data_len) {
+ dfu->bState = STATE_DFU_DNBUSY;
+
+ if(0U == dfu->block_num) {
+ if(ERASE == dfu->buf[0]) {
+ dfu_mal_getstatus(dfu->base_addr, CMD_ERASE, (uint8_t *)&dfu->bwPollTimeout0);
+ } else {
+ dfu_mal_getstatus(dfu->base_addr, CMD_WRITE, (uint8_t *)&dfu->bwPollTimeout0);
+ }
+ }
+ } else {
+ dfu->bState = STATE_DFU_DNLOAD_IDLE;
+ }
+ break;
+
+ case STATE_DFU_MANIFEST_SYNC:
+ if(MANIFEST_IN_PROGRESS == dfu->manifest_state) {
+ dfu->bState = STATE_DFU_MANIFEST;
+ dfu->bwPollTimeout0 = 1U;
+ } else if((MANIFEST_COMPLETE == dfu->manifest_state) && \
+ (dfu_config_desc.dfu_func.bmAttributes & 0x04U)) {
+ dfu->bState = STATE_DFU_IDLE;
+ dfu->bwPollTimeout0 = 0U;
+ } else {
+ /* no operation */
+ }
+ break;
+
+ default:
+ break;
+ }
+
+ /* send the status data of DFU interface to host over EP0 */
+ transc->xfer_buf = (uint8_t *) & (dfu->bStatus);
+ transc->remain_len = 6U;
+}
+
+/*!
+ \brief handle the DFU_CLRSTATUS request
+ \param udev: pointer to usb device instance
+ \param[out] none
+ \retval none
+*/
+static void dfu_clrstatus(usb_dev *udev, usb_req *req)
+{
+ usbd_dfu_handler *dfu = (usbd_dfu_handler *)udev->dev.class_data[USBD_DFU_INTERFACE];
+
+ if(STATE_DFU_ERROR == dfu->bState) {
+ dfu->bStatus = STATUS_OK;
+ dfu->bState = STATE_DFU_IDLE;
+ } else {
+ /* state error */
+ dfu->bStatus = STATUS_ERR_UNKNOWN;
+ dfu->bState = STATE_DFU_ERROR;
+ }
+
+ dfu->iString = 0U; /* iString: index = 0 */
+}
+
+/*!
+ \brief handle the DFU_GETSTATE request
+ \param[in] udev: pointer to usb device instance
+ \param[out] none
+ \retval none
+*/
+static void dfu_getstate(usb_dev *udev, usb_req *req)
+{
+ usbd_dfu_handler *dfu = (usbd_dfu_handler *)udev->dev.class_data[USBD_DFU_INTERFACE];
+
+ usb_transc *transc = &udev->dev.transc_in[0];
+
+ /* send the current state of the DFU interface to host */
+ transc->xfer_buf = &(dfu->bState);
+ transc->remain_len = 1U;
+}
+
+/*!
+ \brief handle the DFU_ABORT request
+ \param[in] udev: pointer to usb device instance
+ \param[out] none
+ \retval none
+*/
+static void dfu_abort(usb_dev *udev, usb_req *req)
+{
+ usbd_dfu_handler *dfu = (usbd_dfu_handler *)udev->dev.class_data[USBD_DFU_INTERFACE];
+
+ switch(dfu->bState) {
+ case STATE_DFU_IDLE:
+ case STATE_DFU_DNLOAD_SYNC:
+ case STATE_DFU_DNLOAD_IDLE:
+ case STATE_DFU_MANIFEST_SYNC:
+ case STATE_DFU_UPLOAD_IDLE:
+ dfu->bStatus = STATUS_OK;
+ dfu->bState = STATE_DFU_IDLE;
+ dfu->iString = 0U; /* iString: index = 0 */
+
+ dfu->block_num = 0U;
+ dfu->data_len = 0U;
+ break;
+
+ default:
+ break;
+ }
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/dfu/Source/dfu_mal.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/dfu/Source/dfu_mal.c
new file mode 100644
index 00000000..69394761
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/dfu/Source/dfu_mal.c
@@ -0,0 +1,232 @@
+/*!
+ \file dfu_mal.c
+ \brief USB DFU device media access layer functions
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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.
+*/
+
+#include "dfu_mal.h"
+#include "flash_if.h"
+#include "drv_usb_hw.h"
+#include "usbd_transc.h"
+
+extern usb_core_driver usb_dfu_dev;
+
+extern struct {
+ uint8_t buf[TRANSFER_SIZE];
+ uint16_t data_len;
+ uint16_t block_num;
+ uint32_t base_addr;
+} prog;
+
+dfu_mal_prop *tMALTab[MAX_USED_MEMORY_MEDIA] = {
+ &DFU_Flash_cb
+};
+
+/* The list of memory interface string descriptor pointers. This list
+ can be updated whenever a memory has to be added or removed */
+const uint8_t *USBD_DFU_StringDesc[MAX_USED_MEMORY_MEDIA] = {
+ (const uint8_t *)FLASH_IF_STRING
+};
+
+static uint8_t dfu_mal_checkaddr(uint32_t addr);
+
+/*!
+ \brief initialize the memory media on the GD32
+ \param[in] none
+ \param[out] none
+ \retval MAL_OK
+*/
+uint8_t dfu_mal_init(void)
+{
+ uint32_t mem_index = 0U;
+
+ /* initialize all supported memory medias */
+ for(mem_index = 0U; mem_index < MAX_USED_MEMORY_MEDIA; mem_index++) {
+ /* check if the memory media exists */
+ if(NULL != tMALTab[mem_index]->mal_init) {
+ tMALTab[mem_index]->mal_init();
+ }
+ }
+
+ return MAL_OK;
+}
+
+/*!
+ \brief deinitialize the memory media on the GD32
+ \param[in] none
+ \param[out] none
+ \retval MAL_OK
+*/
+uint8_t dfu_mal_deinit(void)
+{
+ uint32_t mem_index = 0U;
+
+ /* deinitializes all supported memory medias */
+ for(mem_index = 0U; mem_index < MAX_USED_MEMORY_MEDIA; mem_index++) {
+ /* check if the memory media exists */
+ if(NULL != tMALTab[mem_index]->mal_deinit) {
+ tMALTab[mem_index]->mal_deinit();
+ }
+ }
+
+ return MAL_OK;
+}
+
+/*!
+ \brief erase a memory sector
+ \param[in] addr: memory sector address/code
+ \param[out] none
+ \retval MAL_OK
+*/
+uint8_t dfu_mal_erase(uint32_t addr)
+{
+ uint32_t mem_index = dfu_mal_checkaddr(addr);
+
+ /* check if the address is in protected area */
+ if(IS_PROTECTED_AREA(addr)) {
+ return MAL_FAIL;
+ }
+
+ if(mem_index < MAX_USED_MEMORY_MEDIA) {
+ /* check if the operation is supported */
+ if(NULL != tMALTab[mem_index]->mal_erase) {
+ return tMALTab[mem_index]->mal_erase(addr);
+ } else {
+ return MAL_FAIL;
+ }
+ } else {
+ return MAL_FAIL;
+ }
+}
+
+/*!
+ \brief write data to sectors of memory
+ \param[in] buf: the data buffer to be write
+ \param[in] addr: memory sector address/code
+ \param[in] len: data length
+ \param[out] none
+ \retval MAL_OK
+*/
+uint8_t dfu_mal_write(uint8_t *buf, uint32_t addr, uint32_t len)
+{
+ uint32_t mem_index = dfu_mal_checkaddr(addr);
+
+ /* check if the address is in protected area */
+ if(IS_PROTECTED_AREA(addr)) {
+ return MAL_FAIL;
+ }
+
+ if(mem_index < MAX_USED_MEMORY_MEDIA) {
+ /* check if the operation is supported */
+ if(NULL != tMALTab[mem_index]->mal_write) {
+ return tMALTab[mem_index]->mal_write(buf, addr, len);
+ } else {
+ return MAL_FAIL;
+ }
+ } else {
+ return MAL_FAIL;
+ }
+}
+
+/*!
+ \brief read data from sectors of memory
+ \param[in] buf: the data buffer to be write
+ \param[in] addr: memory sector address/code
+ \param[in] len: data length
+ \param[out] none
+ \retval pointer to buffer
+*/
+uint8_t *dfu_mal_read(uint8_t *buf, uint32_t addr, uint32_t len)
+{
+ uint32_t mem_index = 0U;
+
+ if(OB_RDPT != addr) {
+ mem_index = dfu_mal_checkaddr(addr);
+ }
+
+ if(mem_index < MAX_USED_MEMORY_MEDIA) {
+ /* check if the operation is supported */
+ if(NULL != tMALTab[mem_index]->mal_read) {
+ return tMALTab[mem_index]->mal_read(buf, addr, len);
+ } else {
+ return buf;
+ }
+ } else {
+ return buf;
+ }
+}
+
+/*!
+ \brief get the status of a given memory and store in buffer
+ \param[in] addr: memory sector address/code
+ \param[in] cmd: 0 for erase and 1 for write
+ \param[in] buffer: pointer to the buffer where the status data will be stored
+ \param[out] none
+ \retval MAL_OK if all operations are OK, MAL_FAIL else
+*/
+uint8_t dfu_mal_getstatus(uint32_t addr, uint8_t cmd, uint8_t *buffer)
+{
+ uint32_t mem_index = dfu_mal_checkaddr(addr);
+
+ if(mem_index < MAX_USED_MEMORY_MEDIA) {
+ if(cmd & 0x01U) {
+ SET_POLLING_TIMEOUT(tMALTab[mem_index]->write_timeout);
+ } else {
+ SET_POLLING_TIMEOUT(tMALTab[mem_index]->erase_timeout);
+ }
+
+ return MAL_OK;
+ } else {
+ return MAL_FAIL;
+ }
+}
+
+/*!
+ \brief check the address is supported
+ \param[in] addr: memory sector address/code
+ \param[out] none
+ \retval index of the addressed memory
+*/
+static uint8_t dfu_mal_checkaddr(uint32_t addr)
+{
+ uint8_t mem_index = 0U;
+
+ /* check with all supported memories */
+ for(mem_index = 0U; mem_index < MAX_USED_MEMORY_MEDIA; mem_index++) {
+ /* if the check address is supported, return the memory index */
+ if(MAL_OK == tMALTab[mem_index]->mal_checkaddr(addr)) {
+ return mem_index;
+ }
+ }
+
+ /* if there is no memory found, return MAX_USED_MEMORY_MEDIA */
+ return (MAX_USED_MEMORY_MEDIA);
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/hid/Include/custom_hid_core.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/hid/Include/custom_hid_core.h
new file mode 100644
index 00000000..59c03920
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/hid/Include/custom_hid_core.h
@@ -0,0 +1,69 @@
+/*!
+ \file custom_hid_core.h
+ \brief definitions for HID core
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __CUSTOM_HID_CORE_H
+#define __CUSTOM_HID_CORE_H
+
+#include "usbd_enum.h"
+#include "usb_hid.h"
+
+#define DESC_LEN_REPORT 96U
+#define DESC_LEN_CONFIG 41U
+
+#define NO_CMD 0xFFU
+
+#define MAX_PERIPH_NUM 4U
+
+typedef struct {
+ uint8_t data[2];
+
+ uint8_t reportID;
+ uint8_t idlestate;
+ uint8_t protocol;
+} custom_hid_handler;
+
+typedef struct {
+ void (*periph_config[MAX_PERIPH_NUM])(void);
+} hid_fop_handler;
+
+extern usb_desc custom_hid_desc;
+extern usb_class_core usbd_custom_hid_cb;
+
+/* function declarations */
+/* register HID interface operation functions */
+uint8_t custom_hid_itfop_register(usb_dev *udev, hid_fop_handler *hid_fop);
+/* send custom HID report */
+uint8_t custom_hid_report_send(usb_dev *udev, uint8_t *report, uint32_t len);
+
+#endif /* __CUSTOM_HID_CORE_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/hid/Include/standard_hid_core.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/hid/Include/standard_hid_core.h
new file mode 100644
index 00000000..003ac00c
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/hid/Include/standard_hid_core.h
@@ -0,0 +1,68 @@
+/*!
+ \file standard_hid_core.h
+ \brief definitions for HID core
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __STANDARD_HID_CORE_H
+#define __STANDARD_HID_CORE_H
+
+#include "usbd_enum.h"
+#include "usb_hid.h"
+
+#define USB_HID_CONFIG_DESC_LEN 0x22U
+#define USB_HID_REPORT_DESC_LEN 0x2EU
+
+#define NO_CMD 0xFFU
+
+typedef struct {
+ uint32_t protocol;
+ uint32_t idle_state;
+
+ uint8_t data[HID_IN_PACKET];
+ __IO uint8_t prev_transfer_complete;
+} standard_hid_handler;
+
+typedef struct {
+ void (*hid_itf_config)(void);
+ void (*hid_itf_data_process)(usb_dev *udev);
+} hid_fop_handler;
+
+extern usb_desc hid_desc;
+extern usb_class_core usbd_hid_cb;
+
+/* function declarations */
+/* register HID interface operation functions */
+uint8_t hid_itfop_register(usb_dev *udev, hid_fop_handler *hid_fop);
+/* send keyboard report */
+uint8_t hid_report_send(usb_dev *pudev, uint8_t *report, uint32_t len);
+
+#endif /* __STANDARD_HID_CORE_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/hid/Source/custom_hid_core.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/hid/Source/custom_hid_core.c
new file mode 100644
index 00000000..9195c559
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/hid/Source/custom_hid_core.c
@@ -0,0 +1,480 @@
+/*!
+ \file custom_hid_core.c
+ \brief custom HID class driver
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+ \version 2020-12-07, V3.0.1, firmware for GD32F3x0
+ \version 2021-06-22, V3.0.2, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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.
+*/
+
+#include "custom_hid_core.h"
+#include "usbd_enum.h"
+#include
+
+#define USBD_VID 0x28E9U
+#define USBD_PID 0x028AU
+
+/* Note:it should use the C99 standard when compiling the below codes */
+/* USB standard device descriptor */
+const usb_desc_dev custom_hid_dev_desc = {
+ .header =
+ {
+ .bLength = USB_DEV_DESC_LEN,
+ .bDescriptorType = USB_DESCTYPE_DEV,
+ },
+ .bcdUSB = 0x0200U,
+ .bDeviceClass = 0x00U,
+ .bDeviceSubClass = 0x00U,
+ .bDeviceProtocol = 0x00U,
+ .bMaxPacketSize0 = USB_FS_EP0_MAX_LEN,
+ .idVendor = USBD_VID,
+ .idProduct = USBD_PID,
+ .bcdDevice = 0x0100U,
+ .iManufacturer = STR_IDX_MFC,
+ .iProduct = STR_IDX_PRODUCT,
+ .iSerialNumber = STR_IDX_SERIAL,
+ .bNumberConfigurations = USBD_CFG_MAX_NUM,
+};
+
+/* USB device configuration descriptor */
+const usb_hid_desc_config_set custom_hid_config_desc = {
+ .config =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_config),
+ .bDescriptorType = USB_DESCTYPE_CONFIG
+ },
+ .wTotalLength = DESC_LEN_CONFIG,
+ .bNumInterfaces = 0x01U,
+ .bConfigurationValue = 0x01U,
+ .iConfiguration = 0x00U,
+ .bmAttributes = 0x80U,
+ .bMaxPower = 0x32U
+ },
+
+ .hid_itf =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_itf),
+ .bDescriptorType = USB_DESCTYPE_ITF
+ },
+ .bInterfaceNumber = 0x00U,
+ .bAlternateSetting = 0x00U,
+ .bNumEndpoints = 0x02U,
+ .bInterfaceClass = USB_HID_CLASS,
+ .bInterfaceSubClass = 0x00U,
+ .bInterfaceProtocol = 0x00U,
+ .iInterface = 0x00U
+ },
+
+ .hid_vendor =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_hid),
+ .bDescriptorType = USB_DESCTYPE_HID
+ },
+ .bcdHID = 0x0111U,
+ .bCountryCode = 0x00U,
+ .bNumDescriptors = 0x01U,
+ .bDescriptorType = USB_DESCTYPE_REPORT,
+ .wDescriptorLength = DESC_LEN_REPORT,
+ },
+
+ .hid_epin =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_ep),
+ .bDescriptorType = USB_DESCTYPE_EP
+ },
+ .bEndpointAddress = CUSTOMHID_IN_EP,
+ .bmAttributes = USB_EP_ATTR_INT,
+ .wMaxPacketSize = CUSTOMHID_IN_PACKET,
+ .bInterval = 0x20U
+ },
+
+ .hid_epout =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_ep),
+ .bDescriptorType = USB_DESCTYPE_EP
+ },
+ .bEndpointAddress = CUSTOMHID_OUT_EP,
+ .bmAttributes = USB_EP_ATTR_INT,
+ .wMaxPacketSize = CUSTOMHID_OUT_PACKET,
+ .bInterval = 0x20U
+ }
+};
+
+/* USB language ID descriptor */
+static const usb_desc_LANGID usbd_language_id_desc = {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_LANGID),
+ .bDescriptorType = USB_DESCTYPE_STR
+ },
+ .wLANGID = ENG_LANGID
+};
+
+/* USB manufacture string */
+static const usb_desc_str manufacturer_string = {
+ .header =
+ {
+ .bLength = USB_STRING_LEN(10U),
+ .bDescriptorType = USB_DESCTYPE_STR,
+ },
+ .unicode_string = {'G', 'i', 'g', 'a', 'D', 'e', 'v', 'i', 'c', 'e'}
+};
+
+/* USB product string */
+static const usb_desc_str product_string = {
+ .header =
+ {
+ .bLength = USB_STRING_LEN(14U),
+ .bDescriptorType = USB_DESCTYPE_STR,
+ },
+ .unicode_string = {'G', 'D', '3', '2', '-', 'C', 'u', 's', 't', 'o', 'm', 'H', 'I', 'D'}
+};
+
+/* USBD serial string */
+static usb_desc_str serial_string = {
+ .header =
+ {
+ .bLength = USB_STRING_LEN(12U),
+ .bDescriptorType = USB_DESCTYPE_STR,
+ }
+};
+
+/* USB string descriptor set */
+void *const usbd_hid_strings[] = {
+ [STR_IDX_LANGID] = (uint8_t *) &usbd_language_id_desc,
+ [STR_IDX_MFC] = (uint8_t *) &manufacturer_string,
+ [STR_IDX_PRODUCT] = (uint8_t *) &product_string,
+ [STR_IDX_SERIAL] = (uint8_t *) &serial_string
+};
+
+usb_desc custom_hid_desc = {
+ .dev_desc = (uint8_t *) &custom_hid_dev_desc,
+ .config_desc = (uint8_t *) &custom_hid_config_desc,
+ .strings = usbd_hid_strings
+};
+
+const uint8_t customhid_report_descriptor[DESC_LEN_REPORT] = {
+ 0x06, 0x00, 0xFF, /* USAGE_PAGE (Vendor Defined: 0xFF00) */
+ 0x09, 0x00, /* USAGE (Custom Device) */
+ 0xa1, 0x01, /* COLLECTION (Application) */
+
+ /* led 1 */
+ 0x85, 0x11, /* REPORT_ID (0x11) */
+ 0x09, 0x01, /* USAGE (LED 1) */
+ 0x15, 0x00, /* LOGICAL_MINIMUM (0) */
+ 0x25, 0x01, /* LOGICAL_MAXIMUM (1) */
+ 0x75, 0x08, /* REPORT_SIZE (8) */
+ 0x95, 0x01, /* REPORT_COUNT (1) */
+ 0x91, 0x82, /* OUTPUT (Data,Var,Abs,Vol) */
+
+ /* led 2 */
+ 0x85, 0x12, /* REPORT_ID (0x12) */
+ 0x09, 0x02, /* USAGE (LED 2) */
+ 0x15, 0x00, /* LOGICAL_MINIMUM (0) */
+ 0x25, 0x01, /* LOGICAL_MAXIMUM (1) */
+ 0x75, 0x08, /* REPORT_SIZE (8) */
+ 0x95, 0x01, /* REPORT_COUNT (1) */
+ 0x91, 0x82, /* OUTPUT (Data,Var,Abs,Vol) */
+
+ /* led 3 */
+ 0x85, 0x13, /* REPORT_ID (0x13) */
+ 0x09, 0x03, /* USAGE (LED 3) */
+ 0x15, 0x00, /* LOGICAL_MINIMUM (0) */
+ 0x25, 0x01, /* LOGICAL_MAXIMUM (1) */
+ 0x75, 0x08, /* REPORT_SIZE (8) */
+ 0x95, 0x01, /* REPORT_COUNT (1) */
+ 0x91, 0x82, /* OUTPUT (Data,Var,Abs,Vol) */
+
+ /* led 4 */
+ 0x85, 0x14, /* REPORT_ID (0x14) */
+ 0x09, 0x04, /* USAGE (LED 4) */
+ 0x15, 0x00, /* LOGICAL_MINIMUM (0) */
+ 0x25, 0x01, /* LOGICAL_MAXIMUM (1) */
+ 0x75, 0x08, /* REPORT_SIZE (8) */
+ 0x95, 0x01, /* REPORT_COUNT (1) */
+ 0x91, 0x82, /* OUTPUT (Data,Var,Abs,Vol) */
+
+ /* wakeup key */
+ 0x85, 0x15, /* REPORT_ID (0x15) */
+ 0x09, 0x05, /* USAGE (Push Button) */
+ 0x15, 0x00, /* LOGICAL_MINIMUM (0) */
+ 0x25, 0x01, /* LOGICAL_MAXIMUM (1) */
+ 0x75, 0x01, /* REPORT_SIZE (1) */
+ 0x81, 0x02, /* INPUT (Data,Var,Abs,Vol) */
+
+ 0x75, 0x07, /* REPORT_SIZE (7) */
+ 0x81, 0x03, /* INPUT (Cnst,Var,Abs,Vol) */
+
+ /* tamper key */
+ 0x85, 0x16, /* REPORT_ID (0x16) */
+ 0x09, 0x06, /* USAGE (Push Button) */
+ 0x15, 0x00, /* LOGICAL_MINIMUM (0) */
+ 0x25, 0x01, /* LOGICAL_MAXIMUM (1) */
+ 0x75, 0x01, /* REPORT_SIZE (1) */
+ 0x81, 0x02, /* INPUT (Data,Var,Abs,Vol) */
+
+ 0x75, 0x07, /* REPORT_SIZE (7) */
+ 0x81, 0x03, /* INPUT (Cnst,Var,Abs,Vol) */
+
+ 0xc0 /* END_COLLECTION */
+};
+
+/* local function prototypes ('static') */
+static uint8_t custom_hid_init(usb_dev *udev, uint8_t config_index);
+static uint8_t custom_hid_deinit(usb_dev *udev, uint8_t config_index);
+static uint8_t custom_hid_req_handler(usb_dev *udev, usb_req *req);
+static uint8_t custom_hid_data_in(usb_dev *udev, uint8_t ep_num);
+static uint8_t custom_hid_data_out(usb_dev *udev, uint8_t ep_num);
+
+usb_class_core usbd_custom_hid_cb = {
+ .command = NO_CMD,
+ .alter_set = 0U,
+
+ .init = custom_hid_init,
+ .deinit = custom_hid_deinit,
+
+ .req_proc = custom_hid_req_handler,
+
+ .data_in = custom_hid_data_in,
+ .data_out = custom_hid_data_out
+};
+
+/*!
+ \brief register HID interface operation functions
+ \param[in] udev: pointer to USB device instance
+ \param[in] hid_fop: HID operation functions structure
+ \param[out] none
+ \retval USB device operation status
+*/
+uint8_t custom_hid_itfop_register(usb_dev *udev, hid_fop_handler *hid_fop)
+{
+ if(NULL != hid_fop) {
+ udev->dev.user_data = hid_fop;
+
+ return USBD_OK;
+ }
+
+ return USBD_FAIL;
+}
+
+/*!
+ \brief send custom HID report
+ \param[in] udev: pointer to USB device instance
+ \param[in] report: pointer to HID report
+ \param[in] len: data length
+ \param[out] none
+ \retval USB device operation status
+*/
+uint8_t custom_hid_report_send(usb_dev *udev, uint8_t *report, uint32_t len)
+{
+ usbd_ep_send(udev, CUSTOMHID_IN_EP, report, len);
+
+ return USBD_OK;
+}
+
+/*!
+ \brief initialize the HID device
+ \param[in] udev: pointer to USB device instance
+ \param[in] config_index: configuration index
+ \param[out] none
+ \retval USB device operation status
+*/
+static uint8_t custom_hid_init(usb_dev *udev, uint8_t config_index)
+{
+ static custom_hid_handler hid_handler;
+
+ memset((void *)&hid_handler, 0U, sizeof(custom_hid_handler));
+
+ /* Initialize the data Tx endpoint */
+ usbd_ep_setup(udev, &(custom_hid_config_desc.hid_epin));
+
+ /* Initialize the data Rx endpoint */
+ usbd_ep_setup(udev, &(custom_hid_config_desc.hid_epout));
+
+ /* prepare receive data */
+ usbd_ep_recev(udev, CUSTOMHID_OUT_EP, hid_handler.data, 2U);
+
+ udev->dev.class_data[CUSTOM_HID_INTERFACE] = (void *)&hid_handler;
+
+ if(udev->dev.user_data != NULL) {
+ for(uint8_t i = 0U; i < MAX_PERIPH_NUM; i++) {
+ if(((hid_fop_handler *)udev->dev.user_data)->periph_config[i] != NULL) {
+ ((hid_fop_handler *)udev->dev.user_data)->periph_config[i]();
+ }
+ }
+ }
+
+ return USBD_OK;
+}
+
+/*!
+ \brief de-initialize the HID device
+ \param[in] udev: pointer to USB device instance
+ \param[in] config_index: configuration index
+ \param[out] none
+ \retval USB device operation status
+*/
+static uint8_t custom_hid_deinit(usb_dev *udev, uint8_t config_index)
+{
+ /* deinitialize HID endpoints */
+ usbd_ep_clear(udev, CUSTOMHID_IN_EP);
+ usbd_ep_clear(udev, CUSTOMHID_OUT_EP);
+
+ return USBD_OK;
+}
+
+/*!
+ \brief handle the HID class-specific requests
+ \param[in] udev: pointer to USB device instance
+ \param[in] req: device class-specific request
+ \param[out] none
+ \retval USB device operation status
+*/
+static uint8_t custom_hid_req_handler(usb_dev *udev, usb_req *req)
+{
+ usb_transc *transc = &udev->dev.transc_in[0];
+
+ custom_hid_handler *hid = (custom_hid_handler *)udev->dev.class_data[CUSTOM_HID_INTERFACE];
+
+ switch(req->bRequest) {
+ case GET_REPORT:
+ break;
+
+ case GET_IDLE:
+ transc->xfer_buf = (uint8_t *)&hid->idlestate;
+ transc->remain_len = 1U;
+ break;
+
+ case GET_PROTOCOL:
+ transc->xfer_buf = (uint8_t *)&hid->protocol;
+ transc->remain_len = 1U;
+ break;
+
+ case SET_REPORT:
+ hid->reportID = (uint8_t)(req->wValue);
+ break;
+
+ case SET_IDLE:
+ hid->idlestate = (uint8_t)(req->wValue >> 8U);
+ break;
+
+ case SET_PROTOCOL:
+ hid->protocol = (uint8_t)(req->wValue);
+ break;
+
+ case USB_GET_DESCRIPTOR:
+ if(USB_DESCTYPE_REPORT == (req->wValue >> 8U)) {
+ transc->remain_len = USB_MIN(DESC_LEN_REPORT, req->wLength);
+ transc->xfer_buf = (uint8_t *)customhid_report_descriptor;
+ }
+ break;
+
+ default:
+ return USBD_FAIL;
+ }
+
+ return USBD_OK;
+}
+
+/*!
+ \brief handle custom HID data
+ \param[in] udev: pointer to USB device instance
+ \param[in] ep_num: endpoint identifier
+ \param[out] none
+ \retval USB device operation status
+*/
+static uint8_t custom_hid_data_in(usb_dev *udev, uint8_t ep_num)
+{
+ return USBD_OK;
+}
+
+/*!
+ \brief handle custom HID data
+ \param[in] udev: pointer to USB device instance
+ \param[in] ep_num: endpoint identifier
+ \param[out] none
+ \retval USB device operation status
+*/
+static uint8_t custom_hid_data_out(usb_dev *udev, uint8_t ep_num)
+{
+ custom_hid_handler *hid = (custom_hid_handler *)udev->dev.class_data[CUSTOM_HID_INTERFACE];
+
+ switch(hid->data[0]) {
+ case 0x11U:
+ if(RESET != hid->data[1]) {
+ gd_eval_led_on(LED1);
+ } else {
+ gd_eval_led_off(LED1);
+ }
+ break;
+
+ case 0x12U:
+ if(RESET != hid->data[1]) {
+ gd_eval_led_on(LED2);
+ } else {
+ gd_eval_led_off(LED2);
+ }
+ break;
+
+ case 0x13U:
+ if(RESET != hid->data[1]) {
+ gd_eval_led_on(LED3);
+ } else {
+ gd_eval_led_off(LED3);
+ }
+ break;
+
+ case 0x14U:
+ if(RESET != hid->data[1]) {
+ gd_eval_led_on(LED4);
+ } else {
+ gd_eval_led_off(LED4);
+ }
+ break;
+
+
+ default:
+ break;
+ }
+
+ usbd_ep_recev(udev, CUSTOMHID_OUT_EP, hid->data, 2U);
+
+ return USBD_OK;
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/hid/Source/standard_hid_core.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/hid/Source/standard_hid_core.c
new file mode 100644
index 00000000..29199525
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/hid/Source/standard_hid_core.c
@@ -0,0 +1,382 @@
+/*!
+ \file standard_hid_core.c
+ \brief HID class driver
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+ \version 2020-12-07, V3.0.1, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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.
+*/
+
+#include "standard_hid_core.h"
+#include
+
+#define USBD_VID 0x28e9U
+#define USBD_PID 0x0380U
+
+/* Note:it should use the C99 standard when compiling the below codes */
+/* USB standard device descriptor */
+const usb_desc_dev hid_dev_desc = {
+ .header =
+ {
+ .bLength = USB_DEV_DESC_LEN,
+ .bDescriptorType = USB_DESCTYPE_DEV
+ },
+ .bcdUSB = 0x0200U,
+ .bDeviceClass = 0x00U,
+ .bDeviceSubClass = 0x00U,
+ .bDeviceProtocol = 0x00U,
+ .bMaxPacketSize0 = USB_FS_EP0_MAX_LEN,
+ .idVendor = USBD_VID,
+ .idProduct = USBD_PID,
+ .bcdDevice = 0x0100U,
+ .iManufacturer = STR_IDX_MFC,
+ .iProduct = STR_IDX_PRODUCT,
+ .iSerialNumber = STR_IDX_SERIAL,
+ .bNumberConfigurations = USBD_CFG_MAX_NUM
+};
+
+const usb_hid_desc_config_set hid_config_desc = {
+ .config =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_config),
+ .bDescriptorType = USB_DESCTYPE_CONFIG
+ },
+ .wTotalLength = USB_HID_CONFIG_DESC_LEN,
+ .bNumInterfaces = 0x01U,
+ .bConfigurationValue = 0x01U,
+ .iConfiguration = 0x00U,
+ .bmAttributes = 0xA0U,
+ .bMaxPower = 0x32U
+ },
+
+ .hid_itf =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_itf),
+ .bDescriptorType = USB_DESCTYPE_ITF
+ },
+ .bInterfaceNumber = 0x00U,
+ .bAlternateSetting = 0x00U,
+ .bNumEndpoints = 0x01U,
+ .bInterfaceClass = USB_HID_CLASS,
+ .bInterfaceSubClass = USB_HID_SUBCLASS_BOOT_ITF,
+ .bInterfaceProtocol = USB_HID_PROTOCOL_KEYBOARD,
+ .iInterface = 0x00U
+ },
+
+ .hid_vendor =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_hid),
+ .bDescriptorType = USB_DESCTYPE_HID
+ },
+ .bcdHID = 0x0111U,
+ .bCountryCode = 0x00U,
+ .bNumDescriptors = 0x01U,
+ .bDescriptorType = USB_DESCTYPE_REPORT,
+ .wDescriptorLength = USB_HID_REPORT_DESC_LEN,
+ },
+
+ .hid_epin =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_ep),
+ .bDescriptorType = USB_DESCTYPE_EP
+ },
+ .bEndpointAddress = HID_IN_EP,
+ .bmAttributes = USB_EP_ATTR_INT,
+ .wMaxPacketSize = HID_IN_PACKET,
+ .bInterval = 0x40U
+ }
+};
+
+/* USB language ID Descriptor */
+const usb_desc_LANGID usbd_language_id_desc = {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_LANGID),
+ .bDescriptorType = USB_DESCTYPE_STR
+ },
+ .wLANGID = ENG_LANGID
+};
+
+/* USB manufacture string */
+static const usb_desc_str manufacturer_string = {
+ .header =
+ {
+ .bLength = USB_STRING_LEN(10U),
+ .bDescriptorType = USB_DESCTYPE_STR,
+ },
+ .unicode_string = {'G', 'i', 'g', 'a', 'D', 'e', 'v', 'i', 'c', 'e'}
+};
+
+/* USB product string */
+static const usb_desc_str product_string = {
+ .header =
+ {
+ .bLength = USB_STRING_LEN(17U),
+ .bDescriptorType = USB_DESCTYPE_STR,
+ },
+ .unicode_string = {'G', 'D', '3', '2', '-', 'U', 'S', 'B', '_', 'K', 'e', 'y', 'b', 'o', 'a', 'r', 'd'}
+};
+
+/* USBD serial string */
+static usb_desc_str serial_string = {
+ .header =
+ {
+ .bLength = USB_STRING_LEN(12U),
+ .bDescriptorType = USB_DESCTYPE_STR,
+ }
+};
+
+void *const usbd_hid_strings[] = {
+ [STR_IDX_LANGID] = (uint8_t *) &usbd_language_id_desc,
+ [STR_IDX_MFC] = (uint8_t *) &manufacturer_string,
+ [STR_IDX_PRODUCT] = (uint8_t *) &product_string,
+ [STR_IDX_SERIAL] = (uint8_t *) &serial_string
+};
+
+usb_desc hid_desc = {
+ .dev_desc = (uint8_t *) &hid_dev_desc,
+ .config_desc = (uint8_t *) &hid_config_desc,
+ .strings = usbd_hid_strings
+};
+
+const uint8_t hid_report_desc[USB_HID_REPORT_DESC_LEN] = {
+ 0x05, 0x01, /* USAGE_PAGE (Generic Desktop) */
+ 0x09, 0x06, /* USAGE (Keyboard) */
+ 0xa1, 0x01, /* COLLECTION (Application) */
+
+ 0x05, 0x07, /* USAGE_PAGE (Keyboard/Keypad) */
+ 0x19, 0xe0, /* USAGE_MINIMUM (Keyboard LeftControl) */
+ 0x29, 0xe7, /* USAGE_MAXIMUM (Keyboard Right GUI) */
+ 0x15, 0x00, /* LOGICAL_MINIMUM (0) */
+ 0x25, 0x01, /* LOGICAL_MAXIMUM (1) */
+ 0x95, 0x08, /* REPORT_COUNT (8) */
+ 0x75, 0x01, /* REPORT_SIZE (1) */
+ 0x81, 0x02, /* INPUT (Data,Var,Abs) */
+
+ 0x95, 0x01, /* REPORT_COUNT (1) */
+ 0x75, 0x08, /* REPORT_SIZE (8) */
+ 0x81, 0x03, /* INPUT (Cnst,Var,Abs) */
+
+ 0x95, 0x06, /* REPORT_COUNT (6) */
+ 0x75, 0x08, /* REPORT_SIZE (8) */
+ 0x15, 0x00, /* LOGICAL_MINIMUM (0) */
+ 0x26, 0xFF, 0x00, /* LOGICAL_MAXIMUM (255) */
+ 0x05, 0x07, /* USAGE_PAGE (Keyboard/Keypad) */
+ 0x19, 0x00, /* USAGE_MINIMUM (Reserved (no event indicated)) */
+ 0x29, 0x65, /* USAGE_MAXIMUM (Keyboard Application) */
+ 0x81, 0x00, /* INPUT (Data,Ary,Abs) */
+
+ 0xc0 /* END_COLLECTION */
+};
+
+/* local function prototypes ('static') */
+static uint8_t hid_init(usb_dev *udev, uint8_t config_index);
+static uint8_t hid_deinit(usb_dev *udev, uint8_t config_index);
+static uint8_t hid_req(usb_dev *udev, usb_req *req);
+static uint8_t hid_data_in(usb_dev *udev, uint8_t ep_num);
+
+usb_class_core usbd_hid_cb = {
+ .command = NO_CMD,
+ .alter_set = 0U,
+
+ .init = hid_init,
+ .deinit = hid_deinit,
+ .req_proc = hid_req,
+ .data_in = hid_data_in
+};
+
+/*!
+ \brief register HID interface operation functions
+ \param[in] udev: pointer to USB device instance
+ \param[in] hid_fop: HID operation functions structure
+ \param[out] none
+ \retval USB device operation status
+*/
+uint8_t hid_itfop_register(usb_dev *udev, hid_fop_handler *hid_fop)
+{
+ if(NULL != hid_fop) {
+ udev->dev.user_data = (void *)hid_fop;
+
+ return USBD_OK;
+ }
+
+ return USBD_FAIL;
+}
+
+/*!
+ \brief send keyboard report
+ \param[in] udev: pointer to USB device instance
+ \param[in] report: pointer to HID report
+ \param[in] len: data length
+ \param[out] none
+ \retval USB device operation status
+*/
+uint8_t hid_report_send(usb_dev *udev, uint8_t *report, uint32_t len)
+{
+ standard_hid_handler *hid = (standard_hid_handler *)udev->dev.class_data[USBD_HID_INTERFACE];
+
+ hid->prev_transfer_complete = 0U;
+
+ usbd_ep_send(udev, HID_IN_EP, report, len);
+
+ return USBD_OK;
+}
+
+/*!
+ \brief initialize the HID device
+ \param[in] udev: pointer to USB device instance
+ \param[in] config_index: configuration index
+ \param[out] none
+ \retval USB device operation status
+*/
+static uint8_t hid_init(usb_dev *udev, uint8_t config_index)
+{
+ static standard_hid_handler hid_handler;
+
+ memset((void *)&hid_handler, 0U, sizeof(standard_hid_handler));
+
+ /* Initialize the data Tx endpoint */
+ usbd_ep_setup(udev, &(hid_config_desc.hid_epin));
+
+ hid_handler.prev_transfer_complete = 1U;
+
+ udev->dev.class_data[USBD_HID_INTERFACE] = (void *)&hid_handler;
+
+ if(NULL != udev->dev.user_data) {
+ ((hid_fop_handler *)udev->dev.user_data)->hid_itf_config();
+ }
+
+ return USBD_OK;
+}
+
+/*!
+ \brief de-initialize the HID device
+ \param[in] udev: pointer to USB device instance
+ \param[in] config_index: configuration index
+ \param[out] none
+ \retval USB device operation status
+*/
+static uint8_t hid_deinit(usb_dev *udev, uint8_t config_index)
+{
+ /* deinitialize HID endpoints */
+ usbd_ep_clear(udev, HID_IN_EP);
+
+ return USBD_OK;
+}
+
+/*!
+ \brief handle the HID class-specific requests
+ \param[in] udev: pointer to USB device instance
+ \param[in] req: device class-specific request
+ \param[out] none
+ \retval USB device operation status
+*/
+static uint8_t hid_req(usb_dev *udev, usb_req *req)
+{
+ usb_transc *transc = &udev->dev.transc_in[0];
+
+ standard_hid_handler *hid = (standard_hid_handler *)udev->dev.class_data[USBD_HID_INTERFACE];
+
+ switch(req->bRequest) {
+ case GET_REPORT:
+ /* no use for this driver */
+ break;
+
+ case GET_IDLE:
+ transc->xfer_buf = (uint8_t *)&hid->idle_state;
+
+ transc->remain_len = 1U;
+ break;
+
+ case GET_PROTOCOL:
+ transc->xfer_buf = (uint8_t *)&hid->protocol;
+
+ transc->remain_len = 1U;
+ break;
+
+ case SET_REPORT:
+ /* no use for this driver */
+ break;
+
+ case SET_IDLE:
+ hid->idle_state = (uint8_t)(req->wValue >> 8U);
+ break;
+
+ case SET_PROTOCOL:
+ hid->protocol = (uint8_t)(req->wValue);
+ break;
+
+ case USB_GET_DESCRIPTOR:
+ if(USB_DESCTYPE_REPORT == (req->wValue >> 8U)) {
+ transc->remain_len = USB_MIN(USB_HID_REPORT_DESC_LEN, req->wLength);
+ transc->xfer_buf = (uint8_t *)hid_report_desc;
+
+ return REQ_SUPP;
+ } else if(USB_DESCTYPE_HID == (req->wValue >> 8U)) {
+ transc->remain_len = USB_MIN(9U, req->wLength);
+ transc->xfer_buf = (uint8_t *)(&(hid_config_desc.hid_vendor));
+ }
+ break;
+
+ default:
+ break;
+ }
+
+ return USBD_OK;
+}
+
+/*!
+ \brief handle data stage
+ \param[in] udev: pointer to USB device instance
+ \param[in] ep_num: endpoint identifier
+ \param[out] none
+ \retval USB device operation status
+*/
+static uint8_t hid_data_in(usb_dev *udev, uint8_t ep_num)
+{
+ standard_hid_handler *hid = (standard_hid_handler *)udev->dev.class_data[USBD_HID_INTERFACE];
+
+ if(0U != hid->data[2]) {
+ hid->data[2] = 0x00U;
+
+ usbd_ep_send(udev, HID_IN_EP, hid->data, HID_IN_PACKET);
+ } else {
+ hid->prev_transfer_complete = 1U;
+ }
+
+ return USBD_OK;
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/iap/Include/usb_iap_core.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/iap/Include/usb_iap_core.h
new file mode 100644
index 00000000..72755c7d
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/iap/Include/usb_iap_core.h
@@ -0,0 +1,86 @@
+/*!
+ \file usb_iap_core.h
+ \brief the header file of IAP driver
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __USB_IAP_CORE_H
+#define __USB_IAP_CORE_H
+
+#include "usbd_enum.h"
+#include "usb_hid.h"
+
+#define USB_SERIAL_STRING_SIZE 0x06U
+
+#ifdef USE_USB_FS
+#define USB_DESC_LEN_IAP_REPORT 35U
+#endif
+#define USB_DESC_LEN_IAP_CONFIG_SET 41U
+
+/* special commands with download request */
+#define IAP_OPTION_BYTE1 0x01U
+#define IAP_ERASE 0x02U
+#define IAP_DNLOAD 0x03U
+#define IAP_LEAVE 0x04U
+#define IAP_GETBIN_ADDRESS 0x05U
+#define IAP_OPTION_BYTE2 0x06U
+
+typedef struct {
+ uint8_t report_buf[IAP_OUT_PACKET + 1U];
+ uint8_t option_byte[IAP_IN_PACKET];
+
+ /* state machine variables */
+ uint8_t dev_status[IAP_IN_PACKET];
+ uint8_t bin_addr[IAP_IN_PACKET];
+
+ uint8_t reportID;
+ uint8_t flag;
+
+ uint32_t protocol;
+ uint32_t idlestate;
+
+ uint16_t transfer_times;
+ uint16_t page_count;
+ uint16_t lps; /* last packet size */
+ uint32_t file_length;
+ uint32_t base_address;
+} usbd_iap_handler;
+
+typedef void (*app_func)(void);
+
+extern usb_desc iap_desc;
+extern usb_class_core iap_class;
+
+/* function declarations */
+/* send iap report */
+uint8_t iap_report_send(usb_dev *udev, uint8_t *report, uint32_t len);
+
+#endif /* __USB_IAP_CORE_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/iap/Source/usb_iap_core.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/iap/Source/usb_iap_core.c
new file mode 100644
index 00000000..299788ce
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/iap/Source/usb_iap_core.c
@@ -0,0 +1,554 @@
+/*!
+ \file usb_iap_core.c
+ \brief IAP driver
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+ \version 2020-12-07, V3.0.1, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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.
+*/
+
+#include "usb_iap_core.h"
+#include "flash_operation.h"
+#include
+
+#define USBD_VID 0x28E9U
+#define USBD_PID 0x0228U
+
+/* Note:it should use the C99 standard when compiling the below codes */
+/* USB standard device descriptor */
+__ALIGN_BEGIN const usb_desc_dev iap_dev_desc __ALIGN_END = {
+ .header =
+ {
+ .bLength = USB_DEV_DESC_LEN,
+ .bDescriptorType = USB_DESCTYPE_DEV
+ },
+ .bcdUSB = 0x0200U,
+ .bDeviceClass = 0x00U,
+ .bDeviceSubClass = 0x00U,
+ .bDeviceProtocol = 0x00U,
+ .bMaxPacketSize0 = USB_FS_EP0_MAX_LEN,
+ .idVendor = USBD_VID,
+ .idProduct = USBD_PID,
+ .bcdDevice = 0x0100U,
+ .iManufacturer = STR_IDX_MFC,
+ .iProduct = STR_IDX_PRODUCT,
+ .iSerialNumber = STR_IDX_SERIAL,
+ .bNumberConfigurations = USBD_CFG_MAX_NUM
+};
+
+__ALIGN_BEGIN const usb_hid_desc_config_set iap_config_desc __ALIGN_END = {
+ .config =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_config),
+ .bDescriptorType = USB_DESCTYPE_CONFIG
+ },
+ .wTotalLength = USB_DESC_LEN_IAP_CONFIG_SET,
+ .bNumInterfaces = 0x01U,
+ .bConfigurationValue = 0x01U,
+ .iConfiguration = 0x00U,
+ .bmAttributes = 0x80U,
+ .bMaxPower = 0x32U
+ },
+
+ .hid_itf =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_itf),
+ .bDescriptorType = USB_DESCTYPE_ITF
+ },
+ .bInterfaceNumber = 0x00U,
+ .bAlternateSetting = 0x00U,
+ .bNumEndpoints = 0x02U,
+ .bInterfaceClass = USB_HID_CLASS,
+ .bInterfaceSubClass = 0x00U,
+ .bInterfaceProtocol = 0x00U,
+ .iInterface = 0x00U
+ },
+
+ .hid_vendor =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_hid),
+ .bDescriptorType = USB_DESCTYPE_HID
+ },
+ .bcdHID = 0x0111U,
+ .bCountryCode = 0x00U,
+ .bNumDescriptors = 0x01U,
+ .bDescriptorType = USB_DESCTYPE_REPORT,
+ .wDescriptorLength = USB_DESC_LEN_IAP_REPORT,
+ },
+
+ .hid_epin =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_ep),
+ .bDescriptorType = USB_DESCTYPE_EP
+ },
+ .bEndpointAddress = IAP_IN_EP,
+ .bmAttributes = USB_EP_ATTR_INT,
+ .wMaxPacketSize = IAP_IN_PACKET,
+ .bInterval = 0x01U
+ },
+
+ .hid_epout =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_ep),
+ .bDescriptorType = USB_DESCTYPE_EP
+ },
+ .bEndpointAddress = IAP_OUT_EP,
+ .bmAttributes = USB_EP_ATTR_INT,
+ .wMaxPacketSize = IAP_OUT_PACKET,
+ .bInterval = 0x01U
+ }
+};
+
+/* USB language ID Descriptor */
+static __ALIGN_BEGIN const usb_desc_LANGID usbd_language_id_desc __ALIGN_END = {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_LANGID),
+ .bDescriptorType = USB_DESCTYPE_STR
+ },
+ .wLANGID = ENG_LANGID
+};
+
+/* USB manufacture string */
+static __ALIGN_BEGIN const usb_desc_str manufacturer_string __ALIGN_END = {
+ .header =
+ {
+ .bLength = USB_STRING_LEN(10U),
+ .bDescriptorType = USB_DESCTYPE_STR,
+ },
+ .unicode_string = {'G', 'i', 'g', 'a', 'D', 'e', 'v', 'i', 'c', 'e'}
+};
+
+/* USB product string */
+static __ALIGN_BEGIN const usb_desc_str product_string __ALIGN_END = {
+ .header =
+ {
+ .bLength = USB_STRING_LEN(12U),
+ .bDescriptorType = USB_DESCTYPE_STR,
+ },
+ .unicode_string = {'G', 'D', '3', '2', '-', 'U', 'S', 'B', '_', 'I', 'A', 'P'}
+};
+
+/* USBD serial string */
+static __ALIGN_BEGIN usb_desc_str serial_string __ALIGN_END = {
+ .header =
+ {
+ .bLength = USB_STRING_LEN(2U),
+ .bDescriptorType = USB_DESCTYPE_STR,
+ }
+};
+
+void *const usbd_iap_strings[] = {
+ [STR_IDX_LANGID] = (uint8_t *) &usbd_language_id_desc,
+ [STR_IDX_MFC] = (uint8_t *) &manufacturer_string,
+ [STR_IDX_PRODUCT] = (uint8_t *) &product_string,
+ [STR_IDX_SERIAL] = (uint8_t *) &serial_string
+};
+
+usb_desc iap_desc = {
+ .dev_desc = (uint8_t *) &iap_dev_desc,
+ .config_desc = (uint8_t *) &iap_config_desc,
+ .strings = usbd_iap_strings
+};
+
+/* local function prototypes ('static') */
+static uint8_t iap_init(usb_dev *udev, uint8_t config_index);
+static uint8_t iap_deinit(usb_dev *udev, uint8_t config_index);
+static uint8_t iap_req_handler(usb_dev *udev, usb_req *req);
+static uint8_t iap_data_out(usb_dev *udev, uint8_t ep_num);
+
+/* IAP requests management functions */
+static void iap_req_erase(usb_dev *udev);
+static void iap_req_dnload(usb_dev *udev);
+static void iap_req_optionbyte(usb_dev *udev, uint8_t option_num);
+static void iap_req_leave(usb_dev *udev);
+static void iap_address_send(usb_dev *udev);
+
+usb_class_core iap_class = {
+ .init = iap_init,
+ .deinit = iap_deinit,
+ .req_proc = iap_req_handler,
+ .data_out = iap_data_out
+};
+
+/* USB custom HID device report descriptor */
+__ALIGN_BEGIN const uint8_t iap_report_desc[USB_DESC_LEN_IAP_REPORT] __ALIGN_END = {
+ 0x05, 0x01, /* USAGE_PAGE (Generic Desktop) */
+ 0x09, 0x00, /* USAGE (Custom Device) */
+ 0xa1, 0x01, /* COLLECTION (Application) */
+
+ /* IAP command and data */
+ 0x85, 0x01, /* REPORT_ID (0x01) */
+ 0x09, 0x01, /* USAGE (IAP command) */
+ 0x15, 0x00, /* LOGICAL_MINIMUM (0) */
+ 0x25, 0xff, /* LOGICAL_MAXIMUM (255) */
+ 0x75, 0x08, /* REPORT_SIZE (8) */
+ 0x95, REPORT_OUT_COUNT,
+ 0x91, 0x82, /* OUTPUT (Data,Var,Abs,Vol) */
+
+ /* device status and option byte */
+ 0x85, 0x02, /* REPORT_ID (0x02) */
+ 0x09, 0x02, /* USAGE (Status and option byte) */
+ 0x15, 0x00, /* LOGICAL_MINIMUM (0) */
+ 0x25, 0xff, /* LOGICAL_MAXIMUM (255) */
+ 0x75, 0x08, /* REPORT_SIZE (8) */
+ 0x95, REPORT_IN_COUNT, /* REPORT_COUNT (23) */
+ 0x81, 0x82, /* INPUT (Data,Var,Abs,Vol) */
+
+ 0xc0 /* END_COLLECTION */
+};
+
+/*!
+ \brief send iap report
+ \param[in] udev: pointer to USB device instance
+ \param[in] report: pointer to HID report
+ \param[in] len: data length
+ \param[out] none
+ \retval USB device operation status
+*/
+uint8_t iap_report_send(usb_dev *udev, uint8_t *report, uint32_t len)
+{
+ usbd_ep_send(udev, IAP_IN_EP, report, len);
+
+ return USBD_OK;
+}
+
+/*!
+ \brief initialize the IAP device
+ \param[in] udev: pointer to USB device instance
+ \param[in] config_index: configuration index
+ \param[out] none
+ \retval USB device operation status
+*/
+static uint8_t iap_init(usb_dev *udev, uint8_t config_index)
+{
+ static __ALIGN_BEGIN usbd_iap_handler iap_handler __ALIGN_END;
+
+ /* initialize Tx endpoint */
+ usbd_ep_setup(udev, &(iap_config_desc.hid_epin));
+
+ /* initialize Rx endpoint */
+ usbd_ep_setup(udev, &(iap_config_desc.hid_epout));
+
+ /* unlock the internal flash */
+ fmc_unlock();
+
+ memset((void *)&iap_handler, 0U, sizeof(usbd_iap_handler));
+
+ /* prepare receive data */
+ usbd_ep_recev(udev, IAP_OUT_EP, iap_handler.report_buf, IAP_OUT_PACKET);
+
+ iap_handler.base_address = APP_LOADED_ADDR;
+
+ udev->dev.class_data[USBD_IAP_INTERFACE] = (void *)&iap_handler;
+
+ return USBD_OK;
+}
+
+/*!
+ \brief de-initialize the iap device
+ \param[in] udev: pointer to USB device instance
+ \param[in] config_index: configuration index
+ \param[out] none
+ \retval USB device operation status
+*/
+static uint8_t iap_deinit(usb_dev *udev, uint8_t config_index)
+{
+ /* deinitialize iap endpoints */
+ usbd_ep_clear(udev, IAP_IN_EP);
+ usbd_ep_clear(udev, IAP_OUT_EP);
+
+ /* lock the internal flash */
+ fmc_lock();
+
+ return USBD_OK;
+}
+
+/*!
+ \brief handle the iap class-specific requests
+ \param[in] udev: pointer to USB device instance
+ \param[in] req: device class-specific request
+ \param[out] none
+ \retval USB device operation status
+*/
+static uint8_t iap_req_handler(usb_dev *udev, usb_req *req)
+{
+ usb_transc *transc = &udev->dev.transc_in[0];
+
+ usbd_iap_handler *iap = (usbd_iap_handler *)udev->dev.class_data[USBD_IAP_INTERFACE];
+
+ switch(req->bRequest) {
+ case GET_REPORT:
+ /* no use for this driver */
+ break;
+
+ case GET_IDLE:
+ transc->xfer_buf = (uint8_t *)&iap->idlestate;
+ transc->remain_len = 1U;
+ break;
+
+ case GET_PROTOCOL:
+ transc->xfer_buf = (uint8_t *)&iap->protocol;
+ transc->remain_len = 1U;
+ break;
+
+ case SET_REPORT:
+ iap->reportID = (uint8_t)(req->wValue);
+ break;
+
+ case SET_IDLE:
+ iap->idlestate = (uint8_t)(req->wValue >> 8U);
+ break;
+
+ case SET_PROTOCOL:
+ iap->protocol = (uint8_t)(req->wValue);
+ break;
+
+ case USB_GET_DESCRIPTOR:
+ if(USB_DESCTYPE_REPORT == (req->wValue >> 8U)) {
+ transc->remain_len = USB_MIN(USB_DESC_LEN_IAP_REPORT, req->wLength);
+ transc->xfer_buf = (uint8_t *)iap_report_desc;
+ }
+ break;
+
+ default:
+ return USBD_FAIL;
+ }
+
+ return USBD_OK;
+}
+
+/*!
+ \brief handle data out stage
+ \param[in] udev: pointer to USB device instance
+ \param[in] ep_num: endpoint identifier
+ \param[out] none
+ \retval none
+*/
+static uint8_t iap_data_out(usb_dev *udev, uint8_t ep_num)
+{
+ usbd_iap_handler *iap = (usbd_iap_handler *)udev->dev.class_data[USBD_IAP_INTERFACE];
+
+ if(0x01U == iap->report_buf[0]) {
+ switch(iap->report_buf[1]) {
+ case IAP_DNLOAD:
+ iap_req_dnload(udev);
+ break;
+
+ case IAP_ERASE:
+ iap_req_erase(udev);
+ break;
+
+ case IAP_OPTION_BYTE1:
+ iap_req_optionbyte(udev, 0x01U);
+ break;
+
+ case IAP_LEAVE:
+ iap_req_leave(udev);
+ break;
+
+ case IAP_GETBIN_ADDRESS:
+ iap_address_send(udev);
+ break;
+
+ case IAP_OPTION_BYTE2:
+ iap_req_optionbyte(udev, 0x02U);
+ break;
+
+ default:
+ break;
+ }
+ }
+
+ usbd_ep_recev(udev, IAP_OUT_EP, iap->report_buf, IAP_OUT_PACKET);
+
+ return USBD_OK;
+}
+
+/*!
+ \brief handle the IAP_DNLOAD request
+ \param[in] udev: pointer to usb device instance
+ \param[out] none
+ \retval none
+*/
+static void iap_req_dnload(usb_dev *udev)
+{
+ usbd_iap_handler *iap = (usbd_iap_handler *)udev->dev.class_data[USBD_IAP_INTERFACE];
+
+ if(0U != iap->transfer_times) {
+ if(1U == iap->transfer_times) {
+ if(0U == iap->lps) {
+ iap_data_write(&iap->report_buf[2], iap->base_address, TRANSFER_SIZE);
+ } else {
+ iap_data_write(&iap->report_buf[2], iap->base_address, iap->file_length % TRANSFER_SIZE);
+ iap->lps = 0U;
+ }
+
+ iap->dev_status[0] = 0x02U;
+ iap->dev_status[1] = 0x02U;
+ iap_report_send(udev, iap->dev_status, IAP_IN_PACKET);
+ } else {
+ iap_data_write(&iap->report_buf[2], iap->base_address, TRANSFER_SIZE);
+
+ iap->base_address += TRANSFER_SIZE;
+ }
+
+ iap->transfer_times--;
+ }
+}
+
+/*!
+ \brief handle the IAP_ERASE request
+ \param[in] udev: pointer to usb device instance
+ \param[out] none
+ \retval none
+*/
+static void iap_req_erase(usb_dev *udev)
+{
+ uint32_t addr = 0U;
+
+ usbd_iap_handler *iap = (usbd_iap_handler *)udev->dev.class_data[USBD_IAP_INTERFACE];
+
+ /* get base address to erase */
+ iap->base_address = iap->report_buf[2];
+ iap->base_address |= iap->report_buf[3] << 8U;
+ iap->base_address |= iap->report_buf[4] << 16U;
+ iap->base_address |= iap->report_buf[5] << 24U;
+
+ /* get file length */
+ iap->file_length = iap->report_buf[7];
+ iap->file_length |= iap->report_buf[8] << 8U;
+ iap->file_length |= iap->report_buf[9] << 16U;
+ iap->file_length |= iap->report_buf[10] << 24U;
+
+ iap->lps = iap->file_length % TRANSFER_SIZE;
+ if(0U == iap->lps) {
+ iap->transfer_times = iap->file_length / TRANSFER_SIZE;
+ } else {
+ iap->transfer_times = iap->file_length / TRANSFER_SIZE + 1U;
+ }
+
+ /* check if the address is in protected area */
+ if(IS_PROTECTED_AREA(iap->base_address)) {
+ return;
+ }
+
+ addr = iap->base_address;
+
+ /* unlock the flash program erase controller */
+ fmc_unlock();
+
+ flash_erase(addr, iap->file_length, iap->report_buf);
+
+ fmc_lock();
+
+ iap->dev_status[0] = 0x02U;
+ iap->dev_status[1] = 0x01U;
+
+ usbd_ep_send(udev, IAP_IN_EP, iap->dev_status, IAP_IN_PACKET);
+}
+
+/*!
+ \brief handle the IAP_OPTION_BYTE request
+ \param[in] udev: pointer to USB device instance
+ \param[in] option_num: number of option byte
+ \param[out] none
+ \retval none
+*/
+static void iap_req_optionbyte(usb_dev *udev, uint8_t option_num)
+{
+ uint8_t i = 0U;
+ uint32_t address = 0U;
+
+ usbd_iap_handler *iap = (usbd_iap_handler *)udev->dev.class_data[USBD_IAP_INTERFACE];
+
+ iap->option_byte[0] = 0x02U;
+
+ if(0x01U == option_num) {
+ address = OPT_BYTE_ADDR1;
+#ifdef OPT_BYTE_ADDR2
+ } else if(0x02U == option_num) {
+ address = OPT_BYTE_ADDR2;
+#endif
+ } else {
+ return;
+ }
+
+ for(i = 1U; i < 17U; i++) {
+ iap->option_byte[i] = *(uint8_t *)address;
+ address++;
+ }
+
+ iap_report_send(udev, iap->option_byte, IAP_IN_PACKET);
+}
+
+/*!
+ \brief handle the IAP_LEAVE request
+ \param[in] udev: pointer to usb device instance
+ \param[out] none
+ \retval none
+*/
+static void iap_req_leave(usb_dev *udev)
+{
+ /* lock the internal flash */
+ fmc_lock();
+
+ /* generate system reset to allow jumping to the user code */
+ NVIC_SystemReset();
+}
+
+/*!
+ \brief handle the IAP_SEND_ADDRESS request
+ \param[in] udev: pointer to usb device instance
+ \param[out] none
+ \retval none
+*/
+static void iap_address_send(usb_dev *udev)
+{
+ usbd_iap_handler *iap = (usbd_iap_handler *)udev->dev.class_data[USBD_IAP_INTERFACE];
+
+ iap->bin_addr[0] = 0x02U;
+
+ iap->bin_addr[1] = (uint8_t)(APP_LOADED_ADDR);
+ iap->bin_addr[2] = (uint8_t)(APP_LOADED_ADDR >> 8U);
+ iap->bin_addr[3] = (uint8_t)(APP_LOADED_ADDR >> 16U);
+ iap->bin_addr[4] = (uint8_t)(APP_LOADED_ADDR >> 24U);
+
+ iap_report_send(udev, iap->bin_addr, IAP_IN_PACKET);
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/msc/Include/usbd_msc_bbb.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/msc/Include/usbd_msc_bbb.h
new file mode 100644
index 00000000..c260c56d
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/msc/Include/usbd_msc_bbb.h
@@ -0,0 +1,100 @@
+/*!
+ \file usbd_msc_bbb.h
+ \brief the header file of the usbd_msc_bot.c file
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __USBD_MSC_BBB_H
+#define __USBD_MSC_BBB_H
+
+#include "usbd_core.h"
+#include "msc_bbb.h"
+#include "usbd_msc_mem.h"
+#include "usbd_msc_scsi.h"
+
+/* MSC BBB state */
+enum msc_bbb_state {
+ BBB_IDLE = 0U, /*!< idle state */
+ BBB_DATA_OUT, /*!< data OUT state */
+ BBB_DATA_IN, /*!< data IN state */
+ BBB_LAST_DATA_IN, /*!< last data IN state */
+ BBB_SEND_DATA /*!< send immediate data state */
+};
+
+/* MSC BBB status */
+enum msc_bbb_status {
+ BBB_STATUS_NORMAL = 0U, /*!< normal status */
+ BBB_STATUS_RECOVERY, /*!< recovery status*/
+ BBB_STATUS_ERROR /*!< error status */
+};
+
+typedef struct {
+ uint8_t bbb_data[MSC_MEDIA_PACKET_SIZE];
+
+ uint8_t max_lun;
+ uint8_t bbb_state;
+ uint8_t bbb_status;
+
+ uint32_t bbb_datalen;
+
+ msc_bbb_cbw bbb_cbw;
+ msc_bbb_csw bbb_csw;
+
+ uint8_t scsi_sense_head;
+ uint8_t scsi_sense_tail;
+
+ uint32_t scsi_blk_size[MEM_LUN_NUM];
+ uint32_t scsi_blk_nbr[MEM_LUN_NUM];
+
+ uint32_t scsi_blk_addr;
+ uint32_t scsi_blk_len;
+ uint32_t scsi_disk_pop;
+
+ msc_scsi_sense scsi_sense[SENSE_LIST_DEEPTH];
+} usbd_msc_handler;
+
+/* function declarations */
+/* initialize the bbb process */
+void msc_bbb_init(usb_core_driver *pudev);
+/* reset the BBB machine */
+void msc_bbb_reset(usb_core_driver *pudev);
+/* de-initialize the BBB machine */
+void msc_bbb_deinit(usb_core_driver *pudev);
+/* handle BBB data IN stage */
+void msc_bbb_data_in(usb_core_driver *pudev, uint8_t ep_num);
+/* handle BBB data OUT stage */
+void msc_bbb_data_out(usb_core_driver *pudev, uint8_t ep_num);
+/* send the CSW(command status wrapper) */
+void msc_bbb_csw_send(usb_core_driver *pudev, uint8_t csw_status);
+/* complete the clear feature request */
+void msc_bbb_clrfeature(usb_core_driver *pudev, uint8_t ep_num);
+
+#endif /* __USBD_MSC_BBB_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/msc/Include/usbd_msc_core.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/msc/Include/usbd_msc_core.h
new file mode 100644
index 00000000..52dfe975
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/msc/Include/usbd_msc_core.h
@@ -0,0 +1,58 @@
+/*!
+ \file usbd_msc_core.h
+ \brief the header file of USB MSC device class core functions
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __USBD_MSC_CORE_H
+#define __USBD_MSC_CORE_H
+
+#include "usbd_core.h"
+#include "usb_msc.h"
+
+#define USB_MSC_CONFIG_DESC_SIZE 32U
+
+#define MSC_EPIN_SIZE MSC_DATA_PACKET_SIZE
+#define MSC_EPOUT_SIZE MSC_DATA_PACKET_SIZE
+
+/* USB configuration descriptor structure */
+typedef struct {
+ usb_desc_config config;
+
+ usb_desc_itf msc_itf;
+ usb_desc_ep msc_epin;
+ usb_desc_ep msc_epout;
+} usb_desc_config_set;
+
+extern usb_desc msc_desc;
+extern usb_class_core msc_class;
+
+#endif /* __USBD_MSC_CORE_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/msc/Include/usbd_msc_data.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/msc/Include/usbd_msc_data.h
new file mode 100644
index 00000000..ae0abf62
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/msc/Include/usbd_msc_data.h
@@ -0,0 +1,49 @@
+/*!
+ \file usbd_msc_data.h
+ \brief the header file of the usbd_msc_data.c file
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __USBD_MSC_DATA_H
+#define __USBD_MSC_DATA_H
+
+#include "usbd_conf.h"
+
+#define MODE_SENSE6_LENGTH 8U
+#define MODE_SENSE10_LENGTH 8U
+#define INQUIRY_PAGE00_LENGTH 96U
+#define FORMAT_CAPACITIES_LENGTH 20U
+
+extern const uint8_t msc_page00_inquiry_data[];
+extern const uint8_t msc_mode_sense6_data[];
+extern const uint8_t msc_mode_sense10_data[];
+
+#endif /* __USBD_MSC_DATA_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/msc/Include/usbd_msc_mem.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/msc/Include/usbd_msc_mem.h
new file mode 100644
index 00000000..758b7955
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/msc/Include/usbd_msc_mem.h
@@ -0,0 +1,58 @@
+/*!
+ \file usbd_msc_mem.h
+ \brief header file for storage memory
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __USBD_MSC_MEM_H
+#define __USBD_MSC_MEM_H
+
+#include "usbd_conf.h"
+
+#define USBD_STD_INQUIRY_LENGTH 36U
+
+typedef struct {
+ int8_t (*mem_init)(uint8_t lun);
+ int8_t (*mem_ready)(uint8_t lun);
+ int8_t (*mem_protected)(uint8_t lun);
+ int8_t (*mem_read)(uint8_t lun, uint8_t *buf, uint32_t block_addr, uint16_t block_len);
+ int8_t (*mem_write)(uint8_t lun, uint8_t *buf, uint32_t block_addr, uint16_t block_len);
+ int8_t (*mem_maxlun)(void);
+
+ uint8_t *mem_toc_data;
+ uint8_t *mem_inquiry_data[MEM_LUN_NUM];
+ uint32_t mem_block_size[MEM_LUN_NUM];
+ uint32_t mem_block_len[MEM_LUN_NUM];
+} usbd_mem_cb;
+
+extern usbd_mem_cb *usbd_mem_fops;
+
+#endif /* __USBD_MSC_MEM_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/msc/Include/usbd_msc_scsi.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/msc/Include/usbd_msc_scsi.h
new file mode 100644
index 00000000..762c1cc7
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/msc/Include/usbd_msc_scsi.h
@@ -0,0 +1,50 @@
+/*!
+ \file usbd_msc_scsi.h
+ \brief the header file of the usbd_msc_scsi.c file
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __USBD_MSC_SCSI_H
+#define __USBD_MSC_SCSI_H
+
+#include "usbd_msc_data.h"
+#include "usbd_msc_bbb.h"
+#include "msc_scsi.h"
+
+#define SENSE_LIST_DEEPTH 4U
+
+/* function declarations */
+/* process SCSI commands */
+int8_t scsi_process_cmd(usb_core_driver *pudev, uint8_t lun, uint8_t *cmd);
+/* load the last error code in the error list */
+void scsi_sense_code(usb_core_driver *pudev, uint8_t lun, uint8_t skey, uint8_t asc);
+
+#endif /* __USBD_MSC_SCSI_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/msc/Source/usbd_msc_bbb.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/msc/Source/usbd_msc_bbb.c
new file mode 100644
index 00000000..ad950297
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/msc/Source/usbd_msc_bbb.c
@@ -0,0 +1,287 @@
+/*!
+ \file usbd_msc_bbb.c
+ \brief USB BBB(Bulk/Bulk/Bulk) protocol core functions
+ \note BBB means Bulk-only transport protocol for USB MSC
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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.
+*/
+
+#include "usbd_enum.h"
+#include "usbd_msc_bbb.h"
+
+/* local function prototypes ('static') */
+static void msc_bbb_cbw_decode(usb_core_driver *pudev);
+static void msc_bbb_data_send(usb_core_driver *pudev, uint8_t *pbuf, uint32_t Len);
+static void msc_bbb_abort(usb_core_driver *pudev);
+
+/*!
+ \brief initialize the bbb process
+ \param[in] pudev: pointer to USB device instance
+ \param[out] none
+ \retval none
+*/
+void msc_bbb_init(usb_core_driver *pudev)
+{
+ uint8_t lun_num;
+
+ usbd_msc_handler *msc = (usbd_msc_handler *)pudev->dev.class_data[USBD_MSC_INTERFACE];
+
+ msc->bbb_state = BBB_IDLE;
+ msc->bbb_status = BBB_STATUS_NORMAL;
+
+ /* init the storage logic unit */
+ for(lun_num = 0U; lun_num < MEM_LUN_NUM; lun_num++) {
+ usbd_mem_fops->mem_init(lun_num);
+ }
+
+ /* flush the Rx FIFO */
+ usbd_fifo_flush(pudev, MSC_OUT_EP);
+
+ /* flush the Tx FIFO */
+ usbd_fifo_flush(pudev, MSC_IN_EP);
+
+ /* prepare endpoint to receive the first BBB CBW */
+ usbd_ep_recev(pudev, MSC_OUT_EP, (uint8_t *)&msc->bbb_cbw, BBB_CBW_LENGTH);
+}
+
+/*!
+ \brief reset the BBB machine
+ \param[in] pudev: pointer to USB device instance
+ \param[out] none
+ \retval none
+*/
+void msc_bbb_reset(usb_core_driver *pudev)
+{
+ usbd_msc_handler *msc = (usbd_msc_handler *)pudev->dev.class_data[USBD_MSC_INTERFACE];
+
+ msc->bbb_state = BBB_IDLE;
+ msc->bbb_status = BBB_STATUS_RECOVERY;
+
+ /* prepare endpoint to receive the first BBB command */
+ usbd_ep_recev(pudev, MSC_OUT_EP, (uint8_t *)&msc->bbb_cbw, BBB_CBW_LENGTH);
+}
+
+/*!
+ \brief de-initialize the BBB machine
+ \param[in] pudev: pointer to USB device instance
+ \param[out] none
+ \retval none
+*/
+void msc_bbb_deinit(usb_core_driver *pudev)
+{
+ usbd_msc_handler *msc = (usbd_msc_handler *)pudev->dev.class_data[USBD_MSC_INTERFACE];
+
+ msc->bbb_state = BBB_IDLE;
+}
+
+/*!
+ \brief handle BBB data IN stage
+ \param[in] pudev: pointer to USB device instance
+ \param[in] ep_num: endpoint number
+ \param[out] none
+ \retval none
+*/
+void msc_bbb_data_in(usb_core_driver *pudev, uint8_t ep_num)
+{
+ usbd_msc_handler *msc = (usbd_msc_handler *)pudev->dev.class_data[USBD_MSC_INTERFACE];
+
+ switch(msc->bbb_state) {
+ case BBB_DATA_IN:
+ if(scsi_process_cmd(pudev, msc->bbb_cbw.bCBWLUN, &msc->bbb_cbw.CBWCB[0]) < 0) {
+ msc_bbb_csw_send(pudev, CSW_CMD_FAILED);
+ }
+ break;
+
+ case BBB_SEND_DATA:
+ case BBB_LAST_DATA_IN:
+ msc_bbb_csw_send(pudev, CSW_CMD_PASSED);
+ break;
+
+ default:
+ break;
+ }
+}
+
+/*!
+ \brief handle BBB data OUT stage
+ \param[in] pudev: pointer to USB device instance
+ \param[in] ep_num: endpoint number
+ \param[out] none
+ \retval none
+*/
+void msc_bbb_data_out(usb_core_driver *pudev, uint8_t ep_num)
+{
+ usbd_msc_handler *msc = (usbd_msc_handler *)pudev->dev.class_data[USBD_MSC_INTERFACE];
+
+ switch(msc->bbb_state) {
+ case BBB_IDLE:
+ msc_bbb_cbw_decode(pudev);
+ break;
+
+ case BBB_DATA_OUT:
+ if(scsi_process_cmd(pudev, msc->bbb_cbw.bCBWLUN, &msc->bbb_cbw.CBWCB[0]) < 0) {
+ msc_bbb_csw_send(pudev, CSW_CMD_FAILED);
+ }
+ break;
+
+ default:
+ break;
+ }
+}
+
+/*!
+ \brief send the CSW(command status wrapper)
+ \param[in] pudev: pointer to USB device instance
+ \param[in] csw_status: CSW status
+ \param[out] none
+ \retval none
+*/
+void msc_bbb_csw_send(usb_core_driver *pudev, uint8_t csw_status)
+{
+ usbd_msc_handler *msc = (usbd_msc_handler *)pudev->dev.class_data[USBD_MSC_INTERFACE];
+
+ msc->bbb_csw.dCSWSignature = BBB_CSW_SIGNATURE;
+ msc->bbb_csw.bCSWStatus = csw_status;
+ msc->bbb_state = BBB_IDLE;
+
+ usbd_ep_send(pudev, MSC_IN_EP, (uint8_t *)&msc->bbb_csw, BBB_CSW_LENGTH);
+
+ /* prapare endpoint to receive next command */
+ usbd_ep_recev(pudev, MSC_OUT_EP, (uint8_t *)&msc->bbb_cbw, BBB_CBW_LENGTH);
+}
+
+/*!
+ \brief complete the clear feature request
+ \param[in] pudev: pointer to USB device instance
+ \param[in] ep_num: endpoint number
+ \param[out] none
+ \retval none
+*/
+void msc_bbb_clrfeature(usb_core_driver *pudev, uint8_t ep_num)
+{
+ usbd_msc_handler *msc = (usbd_msc_handler *)pudev->dev.class_data[USBD_MSC_INTERFACE];
+
+ if(msc->bbb_status == BBB_STATUS_ERROR) { /* bad CBW signature */
+ usbd_ep_stall(pudev, MSC_IN_EP);
+
+ msc->bbb_status = BBB_STATUS_NORMAL;
+ } else if(((ep_num & 0x80U) == 0x80U) && (msc->bbb_status != BBB_STATUS_RECOVERY)) {
+ msc_bbb_csw_send(pudev, CSW_CMD_FAILED);
+ } else {
+
+ }
+}
+
+/*!
+ \brief decode the CBW command and set the BBB state machine accordingly
+ \param[in] pudev: pointer to USB device instance
+ \param[out] none
+ \retval none
+*/
+static void msc_bbb_cbw_decode(usb_core_driver *pudev)
+{
+ usbd_msc_handler *msc = (usbd_msc_handler *)pudev->dev.class_data[USBD_MSC_INTERFACE];
+
+ msc->bbb_csw.dCSWTag = msc->bbb_cbw.dCBWTag;
+ msc->bbb_csw.dCSWDataResidue = msc->bbb_cbw.dCBWDataTransferLength;
+
+ if((BBB_CBW_LENGTH != usbd_rxcount_get(pudev, MSC_OUT_EP)) ||
+ (BBB_CBW_SIGNATURE != msc->bbb_cbw.dCBWSignature) ||
+ (msc->bbb_cbw.bCBWLUN > 1U) ||
+ (msc->bbb_cbw.bCBWCBLength < 1U) ||
+ (msc->bbb_cbw.bCBWCBLength > 16U)) {
+ /* illegal command handler */
+ scsi_sense_code(pudev, msc->bbb_cbw.bCBWLUN, ILLEGAL_REQUEST, INVALID_CDB);
+
+ msc->bbb_status = BBB_STATUS_ERROR;
+
+ msc_bbb_abort(pudev);
+ } else {
+ if(scsi_process_cmd(pudev, msc->bbb_cbw.bCBWLUN, &msc->bbb_cbw.CBWCB[0]) < 0) {
+ msc_bbb_abort(pudev);
+ } else if((BBB_DATA_IN != msc->bbb_state) &&
+ (BBB_DATA_OUT != msc->bbb_state) &&
+ (BBB_LAST_DATA_IN != msc->bbb_state)) { /* burst xfer handled internally */
+ if(msc->bbb_datalen > 0U) {
+ msc_bbb_data_send(pudev, msc->bbb_data, msc->bbb_datalen);
+ } else if(0U == msc->bbb_datalen) {
+ msc_bbb_csw_send(pudev, CSW_CMD_PASSED);
+ } else {
+
+ }
+ } else {
+
+ }
+ }
+}
+
+/*!
+ \brief send the requested data
+ \param[in] pudev: pointer to USB device instance
+ \param[in] buf: pointer to data buffer
+ \param[in] len: data length
+ \param[out] none
+ \retval none
+*/
+static void msc_bbb_data_send(usb_core_driver *pudev, uint8_t *buf, uint32_t len)
+{
+ usbd_msc_handler *msc = (usbd_msc_handler *)pudev->dev.class_data[USBD_MSC_INTERFACE];
+
+ len = USB_MIN(msc->bbb_cbw.dCBWDataTransferLength, len);
+
+ msc->bbb_csw.dCSWDataResidue -= len;
+ msc->bbb_csw.bCSWStatus = CSW_CMD_PASSED;
+ msc->bbb_state = BBB_SEND_DATA;
+
+ usbd_ep_send(pudev, MSC_IN_EP, buf, len);
+}
+
+/*!
+ \brief abort the current transfer
+ \param[in] pudev: pointer to USB device instance
+ \param[out] none
+ \retval none
+*/
+static void msc_bbb_abort(usb_core_driver *pudev)
+{
+ usbd_msc_handler *msc = (usbd_msc_handler *)pudev->dev.class_data[USBD_MSC_INTERFACE];
+
+ if((0U == msc->bbb_cbw.bmCBWFlags) &&
+ (0U != msc->bbb_cbw.dCBWDataTransferLength) &&
+ (BBB_STATUS_NORMAL == msc->bbb_status)) {
+ usbd_ep_stall(pudev, MSC_OUT_EP);
+ }
+
+ usbd_ep_stall(pudev, MSC_IN_EP);
+
+ if(msc->bbb_status == BBB_STATUS_ERROR) {
+ usbd_ep_recev(pudev, MSC_OUT_EP, (uint8_t *)&msc->bbb_cbw, BBB_CBW_LENGTH);
+ }
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/msc/Source/usbd_msc_core.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/msc/Source/usbd_msc_core.c
new file mode 100644
index 00000000..0c5b920c
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/msc/Source/usbd_msc_core.c
@@ -0,0 +1,311 @@
+/*!
+ \file usbd_msc_core.c
+ \brief USB MSC device class core functions
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+ \version 2020-12-07, V3.0.1, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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.
+*/
+
+#include "usbd_enum.h"
+#include "usbd_msc_bbb.h"
+#include "usbd_msc_core.h"
+#include
+
+#define USBD_VID 0x28E9U
+#define USBD_PID 0x028FU
+
+/* local function prototypes ('static') */
+static uint8_t msc_core_init(usb_dev *pudev, uint8_t config_index);
+static uint8_t msc_core_deinit(usb_dev *pudev, uint8_t config_index);
+static uint8_t msc_core_req(usb_dev *pudev, usb_req *req);
+static uint8_t msc_core_in(usb_dev *pudev, uint8_t ep_num);
+static uint8_t msc_core_out(usb_dev *pudev, uint8_t ep_num);
+
+usb_class_core msc_class = {
+ .init = msc_core_init,
+ .deinit = msc_core_deinit,
+
+ .req_proc = msc_core_req,
+
+ .data_in = msc_core_in,
+ .data_out = msc_core_out
+};
+
+/* note: it should use the C99 standard when compiling the below codes */
+/* USB standard device descriptor */
+__ALIGN_BEGIN const usb_desc_dev msc_dev_desc __ALIGN_END = {
+ .header = {
+ .bLength = USB_DEV_DESC_LEN,
+ .bDescriptorType = USB_DESCTYPE_DEV
+ },
+ .bcdUSB = 0x0200U,
+ .bDeviceClass = 0x00U,
+ .bDeviceSubClass = 0x00U,
+ .bDeviceProtocol = 0x00U,
+ .bMaxPacketSize0 = USB_FS_EP0_MAX_LEN,
+ .idVendor = USBD_VID,
+ .idProduct = USBD_PID,
+ .bcdDevice = 0x0100U,
+ .iManufacturer = STR_IDX_MFC,
+ .iProduct = STR_IDX_PRODUCT,
+ .iSerialNumber = STR_IDX_SERIAL,
+ .bNumberConfigurations = USBD_CFG_MAX_NUM
+};
+
+/* USB device configuration descriptor */
+__ALIGN_BEGIN const usb_desc_config_set msc_config_desc __ALIGN_END = {
+ .config =
+ {
+ .header = {
+ .bLength = sizeof(usb_desc_config),
+ .bDescriptorType = USB_DESCTYPE_CONFIG
+ },
+ .wTotalLength = USB_MSC_CONFIG_DESC_SIZE,
+ .bNumInterfaces = 0x01U,
+ .bConfigurationValue = 0x01U,
+ .iConfiguration = 0x00U,
+ .bmAttributes = 0xC0U,
+ .bMaxPower = 0x32U
+ },
+
+ .msc_itf =
+ {
+ .header = {
+ .bLength = sizeof(usb_desc_itf),
+ .bDescriptorType = USB_DESCTYPE_ITF
+ },
+ .bInterfaceNumber = 0x00U,
+ .bAlternateSetting = 0x00U,
+ .bNumEndpoints = 0x02U,
+ .bInterfaceClass = USB_CLASS_MSC,
+ .bInterfaceSubClass = USB_MSC_SUBCLASS_SCSI,
+ .bInterfaceProtocol = USB_MSC_PROTOCOL_BBB,
+ .iInterface = 0x00U
+ },
+
+ .msc_epin =
+ {
+ .header = {
+ .bLength = sizeof(usb_desc_ep),
+ .bDescriptorType = USB_DESCTYPE_EP
+ },
+ .bEndpointAddress = MSC_IN_EP,
+ .bmAttributes = USB_EP_ATTR_BULK,
+ .wMaxPacketSize = MSC_EPIN_SIZE,
+ .bInterval = 0x00U
+ },
+
+ .msc_epout =
+ {
+ .header = {
+ .bLength = sizeof(usb_desc_ep),
+ .bDescriptorType = USB_DESCTYPE_EP
+ },
+ .bEndpointAddress = MSC_OUT_EP,
+ .bmAttributes = USB_EP_ATTR_BULK,
+ .wMaxPacketSize = MSC_EPOUT_SIZE,
+ .bInterval = 0x00U
+ }
+};
+
+/* USB language ID descriptor */
+__ALIGN_BEGIN const usb_desc_LANGID usbd_language_id_desc __ALIGN_END = {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_LANGID),
+ .bDescriptorType = USB_DESCTYPE_STR
+ },
+ .wLANGID = ENG_LANGID
+};
+
+/* USB manufacture string */
+static __ALIGN_BEGIN const usb_desc_str manufacturer_string __ALIGN_END = {
+ .header =
+ {
+ .bLength = USB_STRING_LEN(10U),
+ .bDescriptorType = USB_DESCTYPE_STR,
+ },
+ .unicode_string = {'G', 'i', 'g', 'a', 'D', 'e', 'v', 'i', 'c', 'e'}
+};
+
+/* USB product string */
+static __ALIGN_BEGIN const usb_desc_str product_string __ALIGN_END = {
+ .header =
+ {
+ .bLength = USB_STRING_LEN(12U),
+ .bDescriptorType = USB_DESCTYPE_STR,
+ },
+ .unicode_string = {'G', 'D', '3', '2', '-', 'U', 'S', 'B', '_', 'M', 'S', 'C'}
+};
+
+/* USBD serial string */
+static __ALIGN_BEGIN usb_desc_str serial_string __ALIGN_END = {
+ .header =
+ {
+ .bLength = USB_STRING_LEN(12U),
+ .bDescriptorType = USB_DESCTYPE_STR,
+ }
+};
+
+/* USB string descriptor */
+void *const usbd_msc_strings[] = {
+ [STR_IDX_LANGID] = (uint8_t *) &usbd_language_id_desc,
+ [STR_IDX_MFC] = (uint8_t *) &manufacturer_string,
+ [STR_IDX_PRODUCT] = (uint8_t *) &product_string,
+ [STR_IDX_SERIAL] = (uint8_t *) &serial_string
+};
+
+usb_desc msc_desc = {
+ .dev_desc = (uint8_t *) &msc_dev_desc,
+ .config_desc = (uint8_t *) &msc_config_desc,
+ .strings = usbd_msc_strings
+};
+
+static __ALIGN_BEGIN uint8_t usbd_msc_maxlun = 0U __ALIGN_END;
+
+/*!
+ \brief initialize the MSC device
+ \param[in] pudev: pointer to USB device instance
+ \param[in] config_index: configuration index
+ \param[out] none
+ \retval USB device operation status
+*/
+static uint8_t msc_core_init(usb_dev *pudev, uint8_t config_index)
+{
+ static __ALIGN_BEGIN usbd_msc_handler msc_handler __ALIGN_END;
+
+ memset((void *)&msc_handler, 0U, sizeof(usbd_msc_handler));
+
+ pudev->dev.class_data[USBD_MSC_INTERFACE] = (void *)&msc_handler;
+
+ /* configure MSC Tx endpoint */
+ usbd_ep_setup(pudev, &(msc_config_desc.msc_epin));
+
+ /* configure MSC Rx endpoint */
+ usbd_ep_setup(pudev, &(msc_config_desc.msc_epout));
+
+ /* init the BBB layer */
+ msc_bbb_init(pudev);
+
+ return USBD_OK;
+}
+
+/*!
+ \brief de-initialize the MSC device
+ \param[in] pudev: pointer to USB device instance
+ \param[in] config_index: configuration index
+ \param[out] none
+ \retval USB device operation status
+*/
+static uint8_t msc_core_deinit(usb_dev *pudev, uint8_t config_index)
+{
+ /* clear MSC endpoints */
+ usbd_ep_clear(pudev, MSC_IN_EP);
+ usbd_ep_clear(pudev, MSC_OUT_EP);
+
+ /* un-init the BBB layer */
+ msc_bbb_deinit(pudev);
+
+ return USBD_OK;
+}
+
+/*!
+ \brief handle the MSC class-specific and standard requests
+ \param[in] pudev: pointer to USB device instance
+ \param[in] req: device class-specific request
+ \param[out] none
+ \retval USB device operation status
+*/
+static uint8_t msc_core_req(usb_dev *pudev, usb_req *req)
+{
+ usb_transc *transc = &pudev->dev.transc_in[0];
+
+ switch(req->bRequest) {
+ case BBB_GET_MAX_LUN :
+ if((0U == req->wValue) &&
+ (1U == req->wLength) &&
+ (0x80U == (req->bmRequestType & 0x80U))) {
+ usbd_msc_maxlun = (uint8_t)usbd_mem_fops->mem_maxlun();
+
+ transc->xfer_buf = &usbd_msc_maxlun;
+ transc->remain_len = 1U;
+ } else {
+ return USBD_FAIL;
+ }
+ break;
+
+ case BBB_RESET :
+ if((0U == req->wValue) &&
+ (0U == req->wLength) &&
+ (0x80U != (req->bmRequestType & 0x80U))) {
+ msc_bbb_reset(pudev);
+ } else {
+ return USBD_FAIL;
+ }
+ break;
+
+ case USB_CLEAR_FEATURE:
+ msc_bbb_clrfeature(pudev, (uint8_t)req->wIndex);
+ break;
+
+ default:
+ return USBD_FAIL;
+ }
+
+ return USBD_OK;
+}
+
+/*!
+ \brief handle data in stage
+ \param[in] pudev: pointer to USB device instance
+ \param[in] ep_num: the endpoint number
+ \param[out] none
+ \retval none
+*/
+static uint8_t msc_core_in(usb_dev *pudev, uint8_t ep_num)
+{
+ msc_bbb_data_in(pudev, ep_num);
+
+ return USBD_OK;
+}
+
+/*!
+ \brief handle data out stage
+ \param[in] pudev: pointer to USB device instance
+ \param[in] ep_num: the endpoint number
+ \param[out] none
+ \retval none
+*/
+static uint8_t msc_core_out(usb_dev *pudev, uint8_t ep_num)
+{
+ msc_bbb_data_out(pudev, ep_num);
+
+ return USBD_OK;
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/msc/Source/usbd_msc_data.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/msc/Source/usbd_msc_data.c
new file mode 100644
index 00000000..421e58ba
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/msc/Source/usbd_msc_data.c
@@ -0,0 +1,70 @@
+/*!
+ \file usbd_msc_data.c
+ \brief USB MSC vital inquiry pages and sense data
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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.
+*/
+
+#include "usbd_msc_data.h"
+
+/* USB mass storage page 0 inquiry data */
+const uint8_t msc_page00_inquiry_data[] = {
+ 0x00U,
+ 0x00U,
+ 0x00U,
+ 0x00U,
+ (INQUIRY_PAGE00_LENGTH - 4U),
+ 0x80U,
+ 0x83U,
+};
+
+/* USB mass storage sense 6 data */
+const uint8_t msc_mode_sense6_data[] = {
+ 0x00U,
+ 0x00U,
+ 0x00U,
+ 0x00U,
+ 0x00U,
+ 0x00U,
+ 0x00U,
+ 0x00U
+};
+
+/* USB mass storage sense 10 data */
+const uint8_t msc_mode_sense10_data[] = {
+ 0x00U,
+ 0x06U,
+ 0x00U,
+ 0x00U,
+ 0x00U,
+ 0x00U,
+ 0x00U,
+ 0x00U
+};
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/msc/Source/usbd_msc_scsi.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/msc/Source/usbd_msc_scsi.c
new file mode 100644
index 00000000..f597fb46
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/msc/Source/usbd_msc_scsi.c
@@ -0,0 +1,724 @@
+/*!
+ \file usbd_msc_scsi.c
+ \brief USB SCSI layer functions
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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.
+*/
+
+#include "usbd_enum.h"
+#include "usbd_msc_bbb.h"
+#include "usbd_msc_scsi.h"
+#include "usbd_msc_data.h"
+
+/* local function prototypes ('static') */
+static int8_t scsi_test_unit_ready(usb_core_driver *pudev, uint8_t lun, uint8_t *params);
+static int8_t scsi_mode_select6(usb_core_driver *pudev, uint8_t lun, uint8_t *params);
+static int8_t scsi_mode_select10(usb_core_driver *pudev, uint8_t lun, uint8_t *params);
+static int8_t scsi_inquiry(usb_core_driver *pudev, uint8_t lun, uint8_t *params);
+static int8_t scsi_read_format_capacity(usb_core_driver *pudev, uint8_t lun, uint8_t *params);
+static int8_t scsi_read_capacity10(usb_core_driver *pudev, uint8_t lun, uint8_t *params);
+static int8_t scsi_request_sense(usb_core_driver *pudev, uint8_t lun, uint8_t *params);
+static int8_t scsi_mode_sense6(usb_core_driver *pudev, uint8_t lun, uint8_t *params);
+static int8_t scsi_toc_cmd_read(usb_core_driver *pudev, uint8_t lun, uint8_t *params);
+static int8_t scsi_mode_sense10(usb_core_driver *pudev, uint8_t lun, uint8_t *params);
+static int8_t scsi_write10(usb_core_driver *pudev, uint8_t lun, uint8_t *params);
+static int8_t scsi_read10(usb_core_driver *pudev, uint8_t lun, uint8_t *params);
+static int8_t scsi_verify10(usb_core_driver *pudev, uint8_t lun, uint8_t *params);
+static int8_t scsi_process_read(usb_core_driver *pudev, uint8_t lun);
+static int8_t scsi_process_write(usb_core_driver *pudev, uint8_t lun);
+
+static inline int8_t scsi_check_address_range(usb_core_driver *pudev, uint8_t lun, uint32_t blk_offset, uint16_t blk_nbr);
+static inline int8_t scsi_format_cmd(usb_core_driver *pudev, uint8_t lun);
+static inline int8_t scsi_start_stop_unit(usb_core_driver *pudev, uint8_t lun, uint8_t *params);
+static inline int8_t scsi_allow_medium_removal(usb_core_driver *pudev, uint8_t lun, uint8_t *params);
+
+/*!
+ \brief process SCSI commands
+ \param[in] pudev: pointer to USB device instance
+ \param[in] lun: logical unit number
+ \param[in] params: command parameters
+ \param[out] none
+ \retval status
+*/
+int8_t scsi_process_cmd(usb_core_driver *pudev, uint8_t lun, uint8_t *params)
+{
+ switch(params[0]) {
+ case SCSI_TEST_UNIT_READY:
+ return scsi_test_unit_ready(pudev, lun, params);
+
+ case SCSI_REQUEST_SENSE:
+ return scsi_request_sense(pudev, lun, params);
+
+ case SCSI_INQUIRY:
+ return scsi_inquiry(pudev, lun, params);
+
+ case SCSI_START_STOP_UNIT:
+ return scsi_start_stop_unit(pudev, lun, params);
+
+ case SCSI_ALLOW_MEDIUM_REMOVAL:
+ return scsi_allow_medium_removal(pudev, lun, params);
+
+ case SCSI_MODE_SENSE6:
+ return scsi_mode_sense6(pudev, lun, params);
+
+ case SCSI_MODE_SENSE10:
+ return scsi_mode_sense10(pudev, lun, params);
+
+ case SCSI_READ_FORMAT_CAPACITIES:
+ return scsi_read_format_capacity(pudev, lun, params);
+
+ case SCSI_READ_CAPACITY10:
+ return scsi_read_capacity10(pudev, lun, params);
+
+ case SCSI_READ10:
+ return scsi_read10(pudev, lun, params);
+
+ case SCSI_WRITE10:
+ return scsi_write10(pudev, lun, params);
+
+ case SCSI_VERIFY10:
+ return scsi_verify10(pudev, lun, params);
+
+ case SCSI_FORMAT_UNIT:
+ return scsi_format_cmd(pudev, lun);
+
+ case SCSI_READ_TOC_DATA:
+ return scsi_toc_cmd_read(pudev, lun, params);
+
+ case SCSI_MODE_SELECT6:
+ return scsi_mode_select6(pudev, lun, params);
+
+ case SCSI_MODE_SELECT10:
+ return scsi_mode_select10(pudev, lun, params);
+
+ default:
+ scsi_sense_code(pudev, lun, ILLEGAL_REQUEST, INVALID_CDB);
+ return -1;
+ }
+}
+
+/*!
+ \brief load the last error code in the error list
+ \param[in] pudev: pointer to USB device instance
+ \param[in] lun: logical unit number
+ \param[in] skey: sense key
+ \param[in] asc: additional aense key
+ \param[out] none
+ \retval none
+*/
+void scsi_sense_code(usb_core_driver *pudev, uint8_t lun, uint8_t skey, uint8_t asc)
+{
+ usbd_msc_handler *msc = (usbd_msc_handler *)pudev->dev.class_data[USBD_MSC_INTERFACE];
+
+ msc->scsi_sense[msc->scsi_sense_tail].SenseKey = skey;
+ msc->scsi_sense[msc->scsi_sense_tail].ASC = asc << 8U;
+ msc->scsi_sense_tail++;
+
+ if(SENSE_LIST_DEEPTH == msc->scsi_sense_tail) {
+ msc->scsi_sense_tail = 0U;
+ }
+}
+
+/*!
+ \brief process SCSI Test Unit Ready command
+ \param[in] pudev: pointer to USB device instance
+ \param[in] lun: logical unit number
+ \param[in] params: command parameters
+ \param[out] none
+ \retval status
+*/
+static int8_t scsi_test_unit_ready(usb_core_driver *pudev, uint8_t lun, uint8_t *params)
+{
+ usbd_msc_handler *msc = (usbd_msc_handler *)pudev->dev.class_data[USBD_MSC_INTERFACE];
+
+ /* case 9 : Hi > D0 */
+ if(0U != msc->bbb_cbw.dCBWDataTransferLength) {
+ scsi_sense_code(pudev, msc->bbb_cbw.bCBWLUN, ILLEGAL_REQUEST, INVALID_CDB);
+
+ return -1;
+ }
+
+ if(0 != usbd_mem_fops->mem_ready(lun)) {
+ scsi_sense_code(pudev, lun, NOT_READY, MEDIUM_NOT_PRESENT);
+
+ return -1;
+ }
+
+ msc->bbb_datalen = 0U;
+
+ return 0;
+}
+
+/*!
+ \brief process Inquiry command
+ \param[in] udev: pointer to USB device instance
+ \param[in] lun: logical unit number
+ \param[in] params: command parameters
+ \param[out] none
+ \retval status
+*/
+static int8_t scsi_mode_select6(usb_core_driver *pudev, uint8_t lun, uint8_t *params)
+{
+ usbd_msc_handler *msc = (usbd_msc_handler *)pudev->dev.class_data[USBD_MSC_INTERFACE];
+
+ msc->bbb_datalen = 0U;
+
+ return 0;
+}
+
+/*!
+ \brief process Inquiry command
+ \param[in] udev: pointer to USB device instance
+ \param[in] lun: logical unit number
+ \param[in] params: command parameters
+ \param[out] none
+ \retval status
+*/
+static int8_t scsi_mode_select10(usb_core_driver *pudev, uint8_t lun, uint8_t *params)
+{
+ usbd_msc_handler *msc = (usbd_msc_handler *)pudev->dev.class_data[USBD_MSC_INTERFACE];
+
+ msc->bbb_datalen = 0U;
+
+ return 0;
+}
+
+/*!
+ \brief process Inquiry command
+ \param[in] pudev: pointer to USB device instance
+ \param[in] lun: logical unit number
+ \param[in] params: command parameters
+ \param[out] none
+ \retval status
+*/
+static int8_t scsi_inquiry(usb_core_driver *pudev, uint8_t lun, uint8_t *params)
+{
+ uint8_t *page = NULL;
+ uint16_t len = 0U;
+
+ usbd_msc_handler *msc = (usbd_msc_handler *)pudev->dev.class_data[USBD_MSC_INTERFACE];
+
+ if(params[1] & 0x01U) {
+ /* Evpd is set */
+ page = (uint8_t *)msc_page00_inquiry_data;
+
+ len = INQUIRY_PAGE00_LENGTH;
+ } else {
+ page = (uint8_t *)usbd_mem_fops->mem_inquiry_data[lun];
+
+ len = (uint16_t)(page[4] + 5U);
+
+ if(params[4] <= len) {
+ len = params[4];
+ }
+ }
+
+ msc->bbb_datalen = len;
+
+ while(len) {
+ len--;
+ msc->bbb_data[len] = page[len];
+ }
+
+ return 0;
+}
+
+/*!
+ \brief process Read Capacity 10 command
+ \param[in] pudev: pointer to USB device instance
+ \param[in] lun: logical unit number
+ \param[in] params: command parameters
+ \param[out] none
+ \retval status
+*/
+static int8_t scsi_read_capacity10(usb_core_driver *pudev, uint8_t lun, uint8_t *params)
+{
+ uint32_t blk_num = usbd_mem_fops->mem_block_len[lun] - 1U;
+ usbd_msc_handler *msc = (usbd_msc_handler *)pudev->dev.class_data[USBD_MSC_INTERFACE];
+
+ msc->scsi_blk_nbr[lun] = usbd_mem_fops->mem_block_len[lun];
+ msc->scsi_blk_size[lun] = usbd_mem_fops->mem_block_size[lun];
+
+ msc->bbb_data[0] = (uint8_t)(blk_num >> 24U);
+ msc->bbb_data[1] = (uint8_t)(blk_num >> 16U);
+ msc->bbb_data[2] = (uint8_t)(blk_num >> 8U);
+ msc->bbb_data[3] = (uint8_t)(blk_num);
+
+ msc->bbb_data[4] = (uint8_t)(msc->scsi_blk_size[lun] >> 24U);
+ msc->bbb_data[5] = (uint8_t)(msc->scsi_blk_size[lun] >> 16U);
+ msc->bbb_data[6] = (uint8_t)(msc->scsi_blk_size[lun] >> 8U);
+ msc->bbb_data[7] = (uint8_t)(msc->scsi_blk_size[lun]);
+
+ msc->bbb_datalen = 8U;
+
+ return 0;
+}
+
+/*!
+ \brief process Read Format Capacity command
+ \param[in] pudev: pointer to USB device instance
+ \param[in] lun: logical unit number
+ \param[in] params: command parameters
+ \param[out] none
+ \retval status
+*/
+static int8_t scsi_read_format_capacity(usb_core_driver *pudev, uint8_t lun, uint8_t *params)
+{
+ uint16_t i = 0U;
+ uint32_t blk_size = usbd_mem_fops->mem_block_size[lun];
+ uint32_t blk_num = usbd_mem_fops->mem_block_len[lun];
+ uint32_t blk_nbr = blk_num - 1U;
+
+ usbd_msc_handler *msc = (usbd_msc_handler *)pudev->dev.class_data[USBD_MSC_INTERFACE];
+
+ for(i = 0U; i < 12U; i++) {
+ msc->bbb_data[i] = 0U;
+ }
+
+ msc->bbb_data[3] = 0x08U;
+ msc->bbb_data[4] = (uint8_t)(blk_nbr >> 24U);
+ msc->bbb_data[5] = (uint8_t)(blk_nbr >> 16U);
+ msc->bbb_data[6] = (uint8_t)(blk_nbr >> 8U);
+ msc->bbb_data[7] = (uint8_t)(blk_nbr);
+
+ msc->bbb_data[8] = 0x02U;
+ msc->bbb_data[9] = (uint8_t)(blk_size >> 16U);
+ msc->bbb_data[10] = (uint8_t)(blk_size >> 8U);
+ msc->bbb_data[11] = (uint8_t)(blk_size);
+
+ msc->bbb_datalen = 12U;
+
+ return 0;
+}
+
+/*!
+ \brief process Mode Sense6 command
+ \param[in] pudev: pointer to USB device instance
+ \param[in] lun: logical unit number
+ \param[in] params: command parameters
+ \param[out] none
+ \retval status
+*/
+static int8_t scsi_mode_sense6(usb_core_driver *pudev, uint8_t lun, uint8_t *params)
+{
+ uint16_t len = 8U;
+ usbd_msc_handler *msc = (usbd_msc_handler *)pudev->dev.class_data[USBD_MSC_INTERFACE];
+
+ msc->bbb_datalen = len;
+
+ while(len) {
+ len--;
+ msc->bbb_data[len] = msc_mode_sense6_data[len];
+ }
+
+ return 0;
+}
+
+/*!
+ \brief process Mode Sense10 command
+ \param[in] pudev: pointer to USB device instance
+ \param[in] lun: logical unit number
+ \param[in] params: command parameters
+ \param[out] none
+ \retval status
+*/
+static int8_t scsi_mode_sense10(usb_core_driver *pudev, uint8_t lun, uint8_t *params)
+{
+ uint16_t len = 8U;
+ usbd_msc_handler *msc = (usbd_msc_handler *)pudev->dev.class_data[USBD_MSC_INTERFACE];
+
+ msc->bbb_datalen = len;
+
+ while(len) {
+ len--;
+ msc->bbb_data[len] = msc_mode_sense10_data[len];
+ }
+
+ return 0;
+}
+
+/*!
+ \brief process Request Sense command
+ \param[in] pudev: pointer to USB device instance
+ \param[in] lun: logical unit number
+ \param[in] params: command parameters
+ \param[out] none
+ \retval status
+*/
+static int8_t scsi_request_sense(usb_core_driver *pudev, uint8_t lun, uint8_t *params)
+{
+ uint8_t i = 0U;
+ usbd_msc_handler *msc = (usbd_msc_handler *)pudev->dev.class_data[USBD_MSC_INTERFACE];
+
+ for(i = 0U; i < REQUEST_SENSE_DATA_LEN; i++) {
+ msc->bbb_data[i] = 0U;
+ }
+
+ msc->bbb_data[0] = 0x70U;
+ msc->bbb_data[7] = REQUEST_SENSE_DATA_LEN - 6U;
+
+ if((msc->scsi_sense_head != msc->scsi_sense_tail)) {
+ msc->bbb_data[2] = msc->scsi_sense[msc->scsi_sense_head].SenseKey;
+ msc->bbb_data[12] = msc->scsi_sense[msc->scsi_sense_head].ASCQ;
+ msc->bbb_data[13] = msc->scsi_sense[msc->scsi_sense_head].ASC;
+ msc->scsi_sense_head++;
+
+ if(msc->scsi_sense_head == SENSE_LIST_DEEPTH) {
+ msc->scsi_sense_head = 0U;
+ }
+ }
+
+ msc->bbb_datalen = USB_MIN(REQUEST_SENSE_DATA_LEN, params[4]);
+
+ return 0;
+}
+
+/*!
+ \brief process Start Stop Unit command
+ \param[in] pudev: pointer to USB device instance
+ \param[in] lun: logical unit number
+ \param[in] params: command parameters
+ \param[out] none
+ \retval status
+*/
+static inline int8_t scsi_start_stop_unit(usb_core_driver *pudev, uint8_t lun, uint8_t *params)
+{
+ usbd_msc_handler *msc = (usbd_msc_handler *)pudev->dev.class_data[USBD_MSC_INTERFACE];
+
+ msc->bbb_datalen = 0U;
+ msc->scsi_disk_pop = 1U;
+
+ return 0;
+}
+
+/*!
+ \brief process Allow Medium Removal command
+ \param[in] pudev: pointer to USB device instance
+ \param[in] lun: logical unit number
+ \param[in] params: command parameters
+ \param[out] none
+ \retval status
+*/
+static inline int8_t scsi_allow_medium_removal(usb_core_driver *pudev, uint8_t lun, uint8_t *params)
+{
+ usbd_msc_handler *msc = (usbd_msc_handler *)pudev->dev.class_data[USBD_MSC_INTERFACE];
+
+ msc->bbb_datalen = 0U;
+
+ return 0;
+}
+
+/*!
+ \brief process Read10 command
+ \param[in] pudev: pointer to USB device instance
+ \param[in] lun: logical unit number
+ \param[in] params: command parameters
+ \param[out] none
+ \retval status
+*/
+static int8_t scsi_read10(usb_core_driver *pudev, uint8_t lun, uint8_t *params)
+{
+ usbd_msc_handler *msc = (usbd_msc_handler *)pudev->dev.class_data[USBD_MSC_INTERFACE];
+
+ if(msc->bbb_state == BBB_IDLE) {
+ /* direction is from device to host */
+ if(0x80U != (msc->bbb_cbw.bmCBWFlags & 0x80U)) {
+ scsi_sense_code(pudev, msc->bbb_cbw.bCBWLUN, ILLEGAL_REQUEST, INVALID_CDB);
+
+ return -1;
+ }
+
+ if(0 != usbd_mem_fops->mem_ready(lun)) {
+ scsi_sense_code(pudev, lun, NOT_READY, MEDIUM_NOT_PRESENT);
+
+ return -1;
+ }
+
+ msc->scsi_blk_addr = (params[2] << 24U) | (params[3] << 16U) | \
+ (params[4] << 8U) | params[5];
+
+ msc->scsi_blk_len = (params[7] << 8U) | params[8];
+
+ if(scsi_check_address_range(pudev, lun, msc->scsi_blk_addr, (uint16_t)msc->scsi_blk_len) < 0) {
+ return -1; /* error */
+ }
+
+ msc->bbb_state = BBB_DATA_IN;
+
+ msc->scsi_blk_addr *= msc->scsi_blk_size[lun];
+ msc->scsi_blk_len *= msc->scsi_blk_size[lun];
+
+ /* cases 4,5 : Hi <> Dn */
+ if(msc->bbb_cbw.dCBWDataTransferLength != msc->scsi_blk_len) {
+ scsi_sense_code(pudev, msc->bbb_cbw.bCBWLUN, ILLEGAL_REQUEST, INVALID_CDB);
+
+ return -1;
+ }
+ }
+
+ msc->bbb_datalen = MSC_MEDIA_PACKET_SIZE;
+
+ return scsi_process_read(pudev, lun);
+}
+
+/*!
+ \brief process Write10 command
+ \param[in] pudev: pointer to USB device instance
+ \param[in] lun: logical unit number
+ \param[in] params: command parameters
+ \param[out] none
+ \retval status
+*/
+static int8_t scsi_write10(usb_core_driver *pudev, uint8_t lun, uint8_t *params)
+{
+ usbd_msc_handler *msc = (usbd_msc_handler *)pudev->dev.class_data[USBD_MSC_INTERFACE];
+
+ if(BBB_IDLE == msc->bbb_state) {
+ /* case 8 : Hi <> Do */
+ if(0x80U == (msc->bbb_cbw.bmCBWFlags & 0x80U)) {
+ scsi_sense_code(pudev, msc->bbb_cbw.bCBWLUN, ILLEGAL_REQUEST, INVALID_CDB);
+
+ return -1;
+ }
+
+ /* check whether media is ready */
+ if(0 != usbd_mem_fops->mem_ready(lun)) {
+ scsi_sense_code(pudev, lun, NOT_READY, MEDIUM_NOT_PRESENT);
+
+ return -1;
+ }
+
+ /* check if media is write-protected */
+ if(0 != usbd_mem_fops->mem_protected(lun)) {
+ scsi_sense_code(pudev, lun, NOT_READY, WRITE_PROTECTED);
+
+ return -1;
+ }
+
+ msc->scsi_blk_addr = (params[2] << 24U) | (params[3] << 16U) | \
+ (params[4] << 8U) | params[5];
+
+ msc->scsi_blk_len = (params[7] << 8U) | params[8];
+
+ /* check if LBA address is in the right range */
+ if(scsi_check_address_range(pudev, lun, msc->scsi_blk_addr, (uint16_t)msc->scsi_blk_len) < 0) {
+ return -1; /* error */
+ }
+
+ msc->scsi_blk_addr *= msc->scsi_blk_size[lun];
+ msc->scsi_blk_len *= msc->scsi_blk_size[lun];
+
+ /* cases 3,11,13 : Hn,Ho <> D0 */
+ if(msc->bbb_cbw.dCBWDataTransferLength != msc->scsi_blk_len) {
+ scsi_sense_code(pudev, msc->bbb_cbw.bCBWLUN, ILLEGAL_REQUEST, INVALID_CDB);
+
+ return -1;
+ }
+
+ /* prepare endpoint to receive first data packet */
+ msc->bbb_state = BBB_DATA_OUT;
+
+ usbd_ep_recev(pudev,
+ MSC_OUT_EP,
+ msc->bbb_data,
+ USB_MIN(msc->scsi_blk_len, MSC_MEDIA_PACKET_SIZE));
+ } else { /* write process ongoing */
+ return scsi_process_write(pudev, lun);
+ }
+
+ return 0;
+}
+
+/*!
+ \brief process Verify10 command
+ \param[in] pudev: pointer to USB device instance
+ \param[in] lun: logical unit number
+ \param[in] params: command parameters
+ \param[out] none
+ \retval status
+*/
+static int8_t scsi_verify10(usb_core_driver *pudev, uint8_t lun, uint8_t *params)
+{
+ usbd_msc_handler *msc = (usbd_msc_handler *)pudev->dev.class_data[USBD_MSC_INTERFACE];
+
+ if(0x02U == (params[1] & 0x02U)) {
+ scsi_sense_code(pudev, lun, ILLEGAL_REQUEST, INVALID_FIELED_IN_COMMAND);
+
+ return -1; /* error, verify mode not supported*/
+ }
+
+ if(scsi_check_address_range(pudev, lun, msc->scsi_blk_addr, (uint16_t)msc->scsi_blk_len) < 0) {
+ return -1; /* error */
+ }
+
+ msc->bbb_datalen = 0U;
+
+ return 0;
+}
+
+/*!
+ \brief check address range
+ \param[in] pudev: pointer to USB device instance
+ \param[in] lun: logical unit number
+ \param[in] blk_offset: block offset
+ \param[in] blk_nbr: number of block to be processed
+ \param[out] none
+ \retval status
+*/
+static inline int8_t scsi_check_address_range(usb_core_driver *pudev, uint8_t lun, uint32_t blk_offset, uint16_t blk_nbr)
+{
+ usbd_msc_handler *msc = (usbd_msc_handler *)pudev->dev.class_data[USBD_MSC_INTERFACE];
+
+ if((blk_offset + blk_nbr) > msc->scsi_blk_nbr[lun]) {
+ scsi_sense_code(pudev, lun, ILLEGAL_REQUEST, ADDRESS_OUT_OF_RANGE);
+
+ return -1;
+ }
+
+ return 0;
+}
+
+/*!
+ \brief handle read process
+ \param[in] pudev: pointer to USB device instance
+ \param[in] lun: logical unit number
+ \param[out] none
+ \retval status
+*/
+static int8_t scsi_process_read(usb_core_driver *pudev, uint8_t lun)
+{
+ usbd_msc_handler *msc = (usbd_msc_handler *)pudev->dev.class_data[USBD_MSC_INTERFACE];
+
+ uint32_t len = USB_MIN(msc->scsi_blk_len, MSC_MEDIA_PACKET_SIZE);
+
+ if(usbd_mem_fops->mem_read(lun,
+ msc->bbb_data,
+ msc->scsi_blk_addr,
+ (uint16_t)(len / msc->scsi_blk_size[lun])) < 0) {
+ scsi_sense_code(pudev, lun, HARDWARE_ERROR, UNRECOVERED_READ_ERROR);
+
+ return -1;
+ }
+
+ usbd_ep_send(pudev, MSC_IN_EP, msc->bbb_data, len);
+
+ msc->scsi_blk_addr += len;
+ msc->scsi_blk_len -= len;
+
+ /* case 6 : Hi = Di */
+ msc->bbb_csw.dCSWDataResidue -= len;
+
+ if(0U == msc->scsi_blk_len) {
+ msc->bbb_state = BBB_LAST_DATA_IN;
+ }
+
+ return 0;
+}
+
+/*!
+ \brief handle write process
+ \param[in] pudev: pointer to USB device instance
+ \param[in] lun: logical unit number
+ \param[out] none
+ \retval status
+*/
+static int8_t scsi_process_write(usb_core_driver *pudev, uint8_t lun)
+{
+ usbd_msc_handler *msc = (usbd_msc_handler *)pudev->dev.class_data[USBD_MSC_INTERFACE];
+
+ uint32_t len = USB_MIN(msc->scsi_blk_len, MSC_MEDIA_PACKET_SIZE);
+
+ if(usbd_mem_fops->mem_write(lun,
+ msc->bbb_data,
+ msc->scsi_blk_addr,
+ (uint16_t)(len / msc->scsi_blk_size[lun])) < 0) {
+ scsi_sense_code(pudev, lun, HARDWARE_ERROR, WRITE_FAULT);
+
+ return -1;
+ }
+
+ msc->scsi_blk_addr += len;
+ msc->scsi_blk_len -= len;
+
+ /* case 12 : Ho = Do */
+ msc->bbb_csw.dCSWDataResidue -= len;
+
+ if(0U == msc->scsi_blk_len) {
+ msc_bbb_csw_send(pudev, CSW_CMD_PASSED);
+ } else {
+ /* prapare endpoint to receive next packet */
+ usbd_ep_recev(pudev,
+ MSC_OUT_EP,
+ msc->bbb_data,
+ USB_MIN(msc->scsi_blk_len, MSC_MEDIA_PACKET_SIZE));
+ }
+
+ return 0;
+}
+
+/*!
+ \brief process Format Unit command
+ \param[in] pudev: pointer to USB device instance
+ \param[in] lun: logical unit number
+ \param[out] none
+ \retval status
+*/
+static inline int8_t scsi_format_cmd(usb_core_driver *pudev, uint8_t lun)
+{
+ return 0;
+}
+
+/*!
+ \brief process Read_Toc command
+ \param[in] pudev: pointer to USB device instance
+ \param[in] lun: logical unit number
+ \param[in] params: command parameters
+ \param[out] none
+ \retval status
+*/
+static int8_t scsi_toc_cmd_read(usb_core_driver *pudev, uint8_t lun, uint8_t *params)
+{
+ uint8_t *pPage;
+ uint16_t len;
+
+ usbd_msc_handler *msc = (usbd_msc_handler *)pudev->dev.class_data[USBD_MSC_INTERFACE];
+
+ pPage = (uint8_t *)&usbd_mem_fops->mem_toc_data[lun * READ_TOC_CMD_LEN];
+ len = (uint16_t)pPage[1] + 2U;
+
+ msc->bbb_datalen = len;
+
+ while(len) {
+ len--;
+ msc->bbb_data[len] = pPage[len];
+ }
+
+ return 0;
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/printer/Include/printer_core.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/printer/Include/printer_core.h
new file mode 100644
index 00000000..adf18f06
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/printer/Include/printer_core.h
@@ -0,0 +1,77 @@
+/*!
+ \file printer_core.h
+ \brief the header file of USB printer device class core functions
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __PRINTER_CORE_H
+#define __PRINTER_CORE_H
+
+#include "usbd_enum.h"
+#include "usb_ch9_std.h"
+
+/* USB printing device class code */
+#define USB_CLASS_PRINTER 0x07U
+
+/* printing device subclass code */
+#define USB_SUBCLASS_PRINTER 0x01U
+
+/* printing device protocol code */
+#define PROTOCOL_UNIDIRECTIONAL_ITF 0x01U
+#define PROTOCOL_BI_DIRECTIONAL_ITF 0x02U
+#define PROTOCOL_1284_4_ITF 0x03U
+#define PROTOCOL_VENDOR 0xFFU
+
+#define DEVICE_ID_LEN 103U
+
+#define USB_PRINTER_CONFIG_DESC_LEN 32U
+
+/* printing device specific-class request */
+#define GET_DEVICE_ID 0x00U
+#define GET_PORT_STATUS 0x01U
+#define SOFT_RESET 0x02U
+
+#pragma pack(1)
+
+/* USB configuration descriptor struct */
+typedef struct {
+ usb_desc_config config;
+ usb_desc_itf printer_itf;
+ usb_desc_ep printer_epin;
+ usb_desc_ep printer_epout;
+} usb_printer_desc_config_set;
+
+#pragma pack()
+
+extern usb_desc printer_desc;
+extern usb_class_core usbd_printer_cb;
+
+#endif /* __PRINTER_CORE_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/printer/Source/printer_core.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/printer/Source/printer_core.c
new file mode 100644
index 00000000..e82d8f73
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/class/printer/Source/printer_core.c
@@ -0,0 +1,301 @@
+/*!
+ \file printer_core.c
+ \brief USB printer device class core functions
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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.
+*/
+
+#include "printer_core.h"
+
+#define USBD_VID 0x28E9U
+#define USBD_PID 0x028DU
+
+/* printer port status: paper not empty/selected/no error */
+static uint8_t g_port_status = 0x18U;
+
+uint8_t g_printer_data_buf[PRINTER_OUT_PACKET];
+
+uint8_t PRINTER_DEVICE_ID[DEVICE_ID_LEN] = {
+ 0x00, 0x67,
+ 'M', 'A', 'N', 'U', 'F', 'A', 'C', 'T', 'U', 'R', 'E', 'R', ':',
+ 'G', 'I', 'G', 'A', ' ', 'D', 'E', 'V', 'I', 'C', 'E', '-', ';',
+ 'C', 'O', 'M', 'M', 'A', 'N', 'D', ' ', 'S', 'E', 'T', ':',
+ 'P', 'C', 'L', ',', 'M', 'P', 'L', ';',
+ 'M', 'O', 'D', 'E', 'L', ':',
+ 'L', 'a', 's', 'e', 'r', 'B', 'e', 'a', 'm', '?', ';',
+ 'C', 'O', 'M', 'M', 'E', 'N', 'T', ':',
+ 'G', 'o', 'o', 'd', ' ', '!', ';',
+ 'A', 'C', 'T', 'I', 'V', 'E', ' ', 'C', 'O', 'M', 'M', 'A', 'N', 'D', ' ', 'S', 'E', 'T', ':',
+ 'P', 'C', 'L', ';'
+};
+
+/* USB standard device descriptor */
+const usb_desc_dev printer_dev_desc = {
+ .header =
+ {
+ .bLength = USB_DEV_DESC_LEN,
+ .bDescriptorType = USB_DESCTYPE_DEV,
+ },
+ .bcdUSB = 0x0200U,
+ .bDeviceClass = 0x00U,
+ .bDeviceSubClass = 0x00U,
+ .bDeviceProtocol = 0x00U,
+ .bMaxPacketSize0 = USB_FS_EP0_MAX_LEN,
+ .idVendor = USBD_VID,
+ .idProduct = USBD_PID,
+ .bcdDevice = 0x0100U,
+ .iManufacturer = STR_IDX_MFC,
+ .iProduct = STR_IDX_PRODUCT,
+ .iSerialNumber = STR_IDX_SERIAL,
+ .bNumberConfigurations = USBD_CFG_MAX_NUM,
+};
+/* USB device configuration descriptor */
+const usb_printer_desc_config_set printer_config_desc = {
+ .config =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_config),
+ .bDescriptorType = USB_DESCTYPE_CONFIG
+ },
+ .wTotalLength = USB_PRINTER_CONFIG_DESC_LEN,
+ .bNumInterfaces = 0x01U,
+ .bConfigurationValue = 0x01U,
+ .iConfiguration = 0x00U,
+ .bmAttributes = 0xA0U,
+ .bMaxPower = 0x32U
+ },
+
+ .printer_itf =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_itf),
+ .bDescriptorType = USB_DESCTYPE_ITF
+ },
+ .bInterfaceNumber = 0x00U,
+ .bAlternateSetting = 0x00U,
+ .bNumEndpoints = 0x02U,
+ .bInterfaceClass = USB_CLASS_PRINTER,
+ .bInterfaceSubClass = USB_SUBCLASS_PRINTER,
+ .bInterfaceProtocol = PROTOCOL_BI_DIRECTIONAL_ITF,
+ .iInterface = 0x00U
+ },
+
+ .printer_epin =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_ep),
+ .bDescriptorType = USB_DESCTYPE_EP
+ },
+ .bEndpointAddress = PRINTER_IN_EP,
+ .bmAttributes = USB_EP_ATTR_BULK,
+ .wMaxPacketSize = PRINTER_IN_PACKET,
+ .bInterval = 0x00U
+ },
+
+ .printer_epout =
+ {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_ep),
+ .bDescriptorType = USB_DESCTYPE_EP
+ },
+ .bEndpointAddress = PRINTER_OUT_EP,
+ .bmAttributes = USB_EP_ATTR_BULK,
+ .wMaxPacketSize = PRINTER_OUT_PACKET,
+ .bInterval = 0x00U
+ },
+};
+
+/* USB language ID Descriptor */
+static const usb_desc_LANGID usbd_language_id_desc = {
+ .header =
+ {
+ .bLength = sizeof(usb_desc_LANGID),
+ .bDescriptorType = USB_DESCTYPE_STR,
+ },
+ .wLANGID = ENG_LANGID
+};
+
+/* USB manufacture string */
+static const usb_desc_str manufacturer_string = {
+ .header =
+ {
+ .bLength = USB_STRING_LEN(10U),
+ .bDescriptorType = USB_DESCTYPE_STR,
+ },
+ .unicode_string = {'G', 'i', 'g', 'a', 'D', 'e', 'v', 'i', 'c', 'e'}
+};
+
+/* USB product string */
+static const usb_desc_str product_string = {
+ .header =
+ {
+ .bLength = USB_STRING_LEN(16U),
+ .bDescriptorType = USB_DESCTYPE_STR,
+ },
+ .unicode_string = {'G', 'D', '3', '2', '-', 'U', 'S', 'B', '_', 'P', 'r', 'i', 'n', 't', 'e', 'r'}
+};
+
+/* USBD serial string */
+static usb_desc_str serial_string = {
+ .header =
+ {
+ .bLength = USB_STRING_LEN(12U),
+ .bDescriptorType = USB_DESCTYPE_STR,
+ }
+};
+
+/* USB string descriptor */
+static void *const usbd_msc_strings[] = {
+ [STR_IDX_LANGID] = (uint8_t *) &usbd_language_id_desc,
+ [STR_IDX_MFC] = (uint8_t *) &manufacturer_string,
+ [STR_IDX_PRODUCT] = (uint8_t *) &product_string,
+ [STR_IDX_SERIAL] = (uint8_t *) &serial_string
+};
+
+usb_desc printer_desc = {
+ .dev_desc = (uint8_t *) &printer_dev_desc,
+ .config_desc = (uint8_t *) &printer_config_desc,
+ .strings = usbd_msc_strings
+};
+
+/* local function prototypes ('static') */
+static uint8_t printer_init(usb_dev *udev, uint8_t config_index);
+static uint8_t printer_deinit(usb_dev *udev, uint8_t config_index);
+static uint8_t printer_req(usb_dev *udev, usb_req *req);
+static uint8_t printer_in(usb_dev *udev, uint8_t ep_num);
+static uint8_t printer_out(usb_dev *udev, uint8_t ep_num);
+
+usb_class_core usbd_printer_cb = {
+ .init = printer_init,
+ .deinit = printer_deinit,
+
+ .req_proc = printer_req,
+
+ .data_in = printer_in,
+ .data_out = printer_out
+};
+
+/*!
+ \brief initialize the printer device
+ \param[in] udev: pointer to usb device instance
+ \param[in] config_index: configuration index
+ \param[out] none
+ \retval usb device operation status
+*/
+static uint8_t printer_init(usb_dev *udev, uint8_t config_index)
+{
+ /* initialize the data Tx endpoint */
+ usbd_ep_setup(udev, &(printer_config_desc.printer_epin));
+
+ /* initialize the data Rx endpoint */
+ usbd_ep_setup(udev, &(printer_config_desc.printer_epout));
+
+ /* prepare to receive data */
+ usbd_ep_recev(udev, PRINTER_OUT_EP, g_printer_data_buf, PRINTER_OUT_PACKET);
+
+ return USBD_OK;
+}
+
+/*!
+ \brief de-initialize the printer device
+ \param[in] udev: pointer to usb device instance
+ \param[in] config_index: configuration index
+ \param[out] none
+ \retval usb device operation status
+*/
+static uint8_t printer_deinit(usb_dev *udev, uint8_t config_index)
+{
+ /* deinitialize the data Tx/Rx endpoint */
+ usbd_ep_clear(udev, PRINTER_IN_EP);
+ usbd_ep_clear(udev, PRINTER_OUT_EP);
+
+ return USBD_OK;
+}
+
+/*!
+ \brief handle the printer class-specific requests
+ \param[in] udev: pointer to usb device instance
+ \param[in] req: device class-specific request
+ \param[out] none
+ \retval usb device operation status
+*/
+static uint8_t printer_req(usb_dev *udev, usb_req *req)
+{
+ usb_transc *transc = &udev->dev.transc_in[0];
+
+ switch(req->bRequest) {
+ case GET_DEVICE_ID:
+ transc->xfer_buf = (uint8_t *)PRINTER_DEVICE_ID;
+ transc->remain_len = DEVICE_ID_LEN;
+ break;
+
+ case GET_PORT_STATUS:
+ transc->xfer_buf = (uint8_t *)&g_port_status;
+ transc->remain_len = 1U;
+ break;
+
+ case SOFT_RESET:
+ usbd_ep_recev(udev, PRINTER_OUT_EP, g_printer_data_buf, PRINTER_OUT_PACKET);
+ break;
+
+ default:
+ return USBD_FAIL;
+ }
+
+ return USBD_OK;
+}
+
+/*!
+ \brief handle printer data
+ \param[in] udev: pointer to USB device instance
+ \param[in] ep_num: endpoint number
+ \param[out] none
+ \retval USB device operation status
+*/
+static uint8_t printer_in(usb_dev *udev, uint8_t ep_num)
+{
+ return USBD_OK;
+}
+
+/*!
+ \brief handle printer data
+ \param[in] udev: pointer to USB device instance
+ \param[in] ep_num: endpoint number
+ \param[out] none
+ \retval USB device operation status
+*/
+static uint8_t printer_out(usb_dev *udev, uint8_t ep_num)
+{
+ return USBD_OK;
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/core/Include/usbd_core.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/core/Include/usbd_core.h
new file mode 100644
index 00000000..68788433
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/core/Include/usbd_core.h
@@ -0,0 +1,102 @@
+/*!
+ \file usbd_core.h
+ \brief USB device mode core functions protype
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __USBD_CORE_H
+#define __USBD_CORE_H
+
+#include "drv_usb_core.h"
+#include "drv_usb_dev.h"
+
+typedef enum {
+ USBD_OK = 0U, /*!< status OK */
+ USBD_BUSY, /*!< status busy */
+ USBD_FAIL, /*!< status fail */
+} usbd_status;
+
+enum _usbd_status {
+ USBD_DEFAULT = 1U, /*!< default status */
+ USBD_ADDRESSED = 2U, /*!< address send status */
+ USBD_CONFIGURED = 3U, /*!< configured status */
+ USBD_SUSPENDED = 4U /*!< suspended status */
+};
+
+/* static inline function definitions */
+
+/*!
+ \brief set USB device address
+ \param[in] udev: pointer to USB core instance
+ \param[in] addr: device address to set
+ \param[out] none
+ \retval none
+*/
+__STATIC_INLINE void usbd_addr_set(usb_core_driver *udev, uint8_t addr)
+{
+ usb_devaddr_set(udev, addr);
+}
+
+/*!
+ \brief get the received data length
+ \param[in] udev: pointer to USB device instance
+ \param[in] ep_num: endpoint number
+ \param[out] none
+ \retval USB device operation cur_status
+*/
+__STATIC_INLINE uint16_t usbd_rxcount_get(usb_core_driver *udev, uint8_t ep_num)
+{
+ return (uint16_t)udev->dev.transc_out[ep_num].xfer_count;
+}
+
+/* function declarations */
+/* initializes the USB device-mode stack and load the class driver */
+void usbd_init(usb_core_driver *udev, usb_core_enum core, usb_desc *desc, usb_class_core *class_core);
+/* endpoint initialization */
+uint32_t usbd_ep_setup(usb_core_driver *udev, const usb_desc_ep *ep_desc);
+/* configure the endpoint when it is disabled */
+uint32_t usbd_ep_clear(usb_core_driver *udev, uint8_t ep_addr);
+/* endpoint prepare to receive data */
+uint32_t usbd_ep_recev(usb_core_driver *udev, uint8_t ep_addr, uint8_t *pbuf, uint32_t len);
+/* endpoint prepare to transmit data */
+uint32_t usbd_ep_send(usb_core_driver *udev, uint8_t ep_addr, uint8_t *pbuf, uint32_t len);
+/* set an endpoint to STALL status */
+uint32_t usbd_ep_stall(usb_core_driver *udev, uint8_t ep_addr);
+/* clear endpoint STALLed status */
+uint32_t usbd_ep_stall_clear(usb_core_driver *udev, uint8_t ep_addr);
+/* flush the endpoint FIFOs */
+uint32_t usbd_fifo_flush(usb_core_driver *udev, uint8_t ep_addr);
+/* device connect */
+void usbd_connect(usb_core_driver *udev);
+/* device disconnect */
+void usbd_disconnect(usb_core_driver *udev);
+
+#endif /* __USBD_CORE_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/core/Include/usbd_enum.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/core/Include/usbd_enum.h
new file mode 100644
index 00000000..6732841b
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/core/Include/usbd_enum.h
@@ -0,0 +1,103 @@
+/*!
+ \file usbd_enum.h
+ \brief USB enumeration definitions
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __USBD_ENUM_H
+#define __USBD_ENUM_H
+
+#include "usbd_core.h"
+#include "usbd_conf.h"
+#include
+
+#ifndef NULL
+#define NULL 0U
+#endif
+
+typedef enum _usb_reqsta {
+ REQ_SUPP = 0x0U, /* request support */
+ REQ_NOTSUPP = 0x1U, /* request not support */
+} usb_reqsta;
+
+/* string descriptor index */
+enum _str_index {
+ STR_IDX_LANGID = 0x0U, /* language ID string index */
+ STR_IDX_MFC = 0x1U, /* manufacturer string index */
+ STR_IDX_PRODUCT = 0x2U, /* product string index */
+ STR_IDX_SERIAL = 0x3U, /* serial string index */
+ STR_IDX_CONFIG = 0x4U, /* configuration string index */
+ STR_IDX_ITF = 0x5U, /* interface string index */
+#ifndef WINUSB_EXEMPT_DRIVER
+ STR_IDX_MAX = 0x6U, /* string maximum index */
+#else
+ STR_IDX_MAX = 0xEFU, /* string maximum index */
+#endif /* WINUSB_EXEMPT_DRIVER */
+};
+
+typedef enum _usb_pwrsta {
+ USB_PWRSTA_SELF_POWERED = 0x1U, /* USB is in self powered status */
+ USB_PWRSTA_REMOTE_WAKEUP = 0x2U, /* USB is in remote wakeup status */
+} usb_pwrsta;
+
+typedef enum _usb_feature {
+ USB_FEATURE_EP_HALT = 0x0U, /* USB has endpoint halt feature */
+ USB_FEATURE_REMOTE_WAKEUP = 0x1U, /* USB has endpoint remote wakeup feature */
+ USB_FEATURE_TEST_MODE = 0x2U, /* USB has endpoint test mode feature */
+} usb_feature;
+
+#define ENG_LANGID 0x0409U /* english language ID */
+#define CHN_LANGID 0x0804U /* chinese language ID */
+
+/* USB device exported macros */
+#define CTL_EP(ep) (((ep) == 0x00U) || ((ep) == 0x80U))
+
+#define DEVICE_ID1 (0x1FFFF7E8U) /* device ID1 */
+#define DEVICE_ID2 (0x1FFFF7ECU) /* device ID2 */
+#define DEVICE_ID3 (0x1FFFF7F0U) /* device ID3 */
+
+#define DEVICE_ID (0x40022100U)
+
+/* function declarations */
+/* handle USB standard device request */
+usb_reqsta usbd_standard_request(usb_core_driver *udev, usb_req *req);
+/* handle USB device class request */
+usb_reqsta usbd_class_request(usb_core_driver *udev, usb_req *req);
+/* handle USB vendor request */
+usb_reqsta usbd_vendor_request(usb_core_driver *udev, usb_req *req);
+/* handle USB enumeration error */
+void usbd_enum_error(usb_core_driver *udev, usb_req *req);
+/* convert hex 32bits value into unicode char */
+void int_to_unicode(uint32_t value, uint8_t *pbuf, uint8_t len);
+/* get serial string */
+void serial_string_get(uint16_t *unicode_str);
+
+#endif /* __USBD_ENUM_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/core/Include/usbd_transc.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/core/Include/usbd_transc.h
new file mode 100644
index 00000000..66764332
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/core/Include/usbd_transc.h
@@ -0,0 +1,56 @@
+/*!
+ \file usbd_transc.h
+ \brief USB transaction core functions prototype
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __USBD_TRANSC_H
+#define __USBD_TRANSC_H
+
+#include "usbd_core.h"
+
+/* function declarations */
+/* USB send data in the control transaction */
+usbd_status usbd_ctl_send(usb_core_driver *udev);
+/* USB receive data in control transaction */
+usbd_status usbd_ctl_recev(usb_core_driver *udev);
+/* USB send control transaction status */
+usbd_status usbd_ctl_status_send(usb_core_driver *udev);
+/* USB control receive status */
+usbd_status usbd_ctl_status_recev(usb_core_driver *udev);
+/* USB setup stage processing */
+uint8_t usbd_setup_transc(usb_core_driver *udev);
+/* data out stage processing */
+uint8_t usbd_out_transc(usb_core_driver *udev, uint8_t ep_num);
+/* data in stage processing */
+uint8_t usbd_in_transc(usb_core_driver *udev, uint8_t ep_num);
+
+#endif /* __USBD_TRANSC_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/core/Source/usbd_core.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/core/Source/usbd_core.c
new file mode 100644
index 00000000..f3a1eafa
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/core/Source/usbd_core.c
@@ -0,0 +1,320 @@
+/*!
+ \file usbd_core.c
+ \brief USB device mode core functions
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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.
+*/
+
+#include "usbd_core.h"
+#include "usbd_enum.h"
+#include "drv_usb_hw.h"
+
+/* endpoint type */
+const uint32_t ep_type[] = {
+ [USB_EP_ATTR_CTL] = (uint32_t)USB_EPTYPE_CTRL,
+ [USB_EP_ATTR_BULK] = (uint32_t)USB_EPTYPE_BULK,
+ [USB_EP_ATTR_INT] = (uint32_t)USB_EPTYPE_INTR,
+ [USB_EP_ATTR_ISO] = (uint32_t)USB_EPTYPE_ISOC
+};
+
+/*!
+ \brief initializes the USB device-mode stack and load the class driver
+ \param[in] udev: pointer to USB core instance
+ \param[in] core: USB core type
+ \param[in] desc: pointer to USB descriptor
+ \param[in] class_core: class driver
+ \param[out] none
+ \retval none
+*/
+void usbd_init(usb_core_driver *udev, usb_core_enum core, usb_desc *desc, usb_class_core *class_core)
+{
+ udev->dev.desc = desc;
+
+ /* class callbacks */
+ udev->dev.class_core = class_core;
+
+ /* create serial string */
+ serial_string_get(udev->dev.desc->strings[STR_IDX_SERIAL]);
+
+ /* configure USB capabilities */
+ (void)usb_basic_init(&udev->bp, &udev->regs, core);
+
+ usb_globalint_disable(&udev->regs);
+
+ /* initializes the USB core*/
+ (void)usb_core_init(udev->bp, &udev->regs);
+
+ /* set device disconnect */
+ usbd_disconnect(udev);
+
+#ifndef USE_OTG_MODE
+ usb_curmode_set(&udev->regs, DEVICE_MODE);
+#endif
+
+ /* initializes device mode */
+ (void)usb_devcore_init(udev);
+
+ usb_globalint_enable(&udev->regs);
+
+ /* set device connect */
+ usbd_connect(udev);
+
+ udev->dev.cur_status = (uint8_t)USBD_DEFAULT;
+}
+
+/*!
+ \brief endpoint initialization
+ \param[in] udev: pointer to USB core instance
+ \param[in] ep_desc: pointer to endpoint descriptor
+ \param[out] none
+ \retval none
+*/
+uint32_t usbd_ep_setup(usb_core_driver *udev, const usb_desc_ep *ep_desc)
+{
+ usb_transc *transc;
+
+ uint8_t ep_addr = ep_desc->bEndpointAddress;
+ uint16_t max_len = ep_desc->wMaxPacketSize;
+
+ /* set endpoint direction */
+ if(EP_DIR(ep_addr)) {
+ transc = &udev->dev.transc_in[EP_ID(ep_addr)];
+
+ transc->ep_addr.dir = 1U;
+ } else {
+ transc = &udev->dev.transc_out[ep_addr];
+
+ transc->ep_addr.dir = 0U;
+ }
+
+ transc->ep_addr.num = EP_ID(ep_addr);
+ transc->max_len = max_len;
+ transc->ep_type = (uint8_t)ep_type[ep_desc->bmAttributes & (uint8_t)USB_EPTYPE_MASK];
+
+ /* active USB endpoint function */
+ (void)usb_transc_active(udev, transc);
+
+ return 0U;
+}
+
+/*!
+ \brief configure the endpoint when it is disabled
+ \param[in] udev: pointer to USB core instance
+ \param[in] ep_addr: endpoint address
+ in this parameter:
+ bit0..bit6: endpoint number (0..7)
+ bit7: endpoint direction which can be IN(1) or OUT(0)
+ \param[out] none
+ \retval none
+*/
+uint32_t usbd_ep_clear(usb_core_driver *udev, uint8_t ep_addr)
+{
+ usb_transc *transc;
+
+ if(EP_DIR(ep_addr)) {
+ transc = &udev->dev.transc_in[EP_ID(ep_addr)];
+ } else {
+ transc = &udev->dev.transc_out[ep_addr];
+ }
+
+ /* deactivate USB endpoint function */
+ (void)usb_transc_deactivate(udev, transc);
+
+ return 0U;
+}
+
+/*!
+ \brief endpoint prepare to receive data
+ \param[in] udev: pointer to USB core instance
+ \param[in] ep_addr: endpoint address
+ in this parameter:
+ bit0..bit6: endpoint number (0..7)
+ bit7: endpoint direction which can be IN(1) or OUT(0)
+ \param[in] pbuf: user buffer address pointer
+ \param[in] len: buffer length
+ \param[out] none
+ \retval none
+*/
+uint32_t usbd_ep_recev(usb_core_driver *udev, uint8_t ep_addr, uint8_t *pbuf, uint32_t len)
+{
+ usb_transc *transc = &udev->dev.transc_out[EP_ID(ep_addr)];
+
+ /* setup the transfer */
+ transc->xfer_buf = pbuf;
+ transc->xfer_len = len;
+ transc->xfer_count = 0U;
+
+ if((uint8_t)USB_USE_DMA == udev->bp.transfer_mode) {
+ transc->dma_addr = (uint32_t)pbuf;
+ }
+
+ /* start the transfer */
+ (void)usb_transc_outxfer(udev, transc);
+
+ return 0U;
+}
+
+/*!
+ \brief endpoint prepare to transmit data
+ \param[in] udev: pointer to USB core instance
+ \param[in] ep_addr: endpoint address
+ in this parameter:
+ bit0..bit6: endpoint number (0..7)
+ bit7: endpoint direction which can be IN(1) or OUT(0)
+ \param[in] pbuf: transmit buffer address pointer
+ \param[in] len: buffer length
+ \param[out] none
+ \retval none
+*/
+uint32_t usbd_ep_send(usb_core_driver *udev, uint8_t ep_addr, uint8_t *pbuf, uint32_t len)
+{
+ usb_transc *transc = &udev->dev.transc_in[EP_ID(ep_addr)];
+
+ /* setup the transfer */
+ transc->xfer_buf = pbuf;
+ transc->xfer_len = len;
+ transc->xfer_count = 0U;
+
+ if((uint8_t)USB_USE_DMA == udev->bp.transfer_mode) {
+ transc->dma_addr = (uint32_t)pbuf;
+ }
+
+ /* start the transfer */
+ (void)usb_transc_inxfer(udev, transc);
+
+ return 0U;
+}
+
+/*!
+ \brief set an endpoint to STALL status
+ \param[in] udev: pointer to USB core instance
+ \param[in] ep_addr: endpoint address
+ in this parameter:
+ bit0..bit6: endpoint number (0..7)
+ bit7: endpoint direction which can be IN(1) or OUT(0)
+ \param[out] none
+ \retval none
+*/
+uint32_t usbd_ep_stall(usb_core_driver *udev, uint8_t ep_addr)
+{
+ usb_transc *transc = NULL;
+
+ if(EP_DIR(ep_addr)) {
+ transc = &udev->dev.transc_in[EP_ID(ep_addr)];
+ } else {
+ transc = &udev->dev.transc_out[ep_addr];
+ }
+
+ transc->ep_stall = 1U;
+
+ (void)usb_transc_stall(udev, transc);
+
+ return (0U);
+}
+
+/*!
+ \brief clear endpoint STALLed status
+ \param[in] udev: pointer to usb core instance
+ \param[in] ep_addr: endpoint address
+ in this parameter:
+ bit0..bit6: endpoint number (0..7)
+ bit7: endpoint direction which can be IN(1) or OUT(0)
+ \param[out] none
+ \retval none
+*/
+uint32_t usbd_ep_stall_clear(usb_core_driver *udev, uint8_t ep_addr)
+{
+ usb_transc *transc = NULL;
+
+ if(EP_DIR(ep_addr)) {
+ transc = &udev->dev.transc_in[EP_ID(ep_addr)];
+ } else {
+ transc = &udev->dev.transc_out[ep_addr];
+ }
+
+ transc->ep_stall = 0U;
+
+ (void)usb_transc_clrstall(udev, transc);
+
+ return (0U);
+}
+
+/*!
+ \brief flush the endpoint FIFOs
+ \param[in] udev: pointer to USB core instance
+ \param[in] ep_addr: endpoint address
+ in this parameter:
+ bit0..bit6: endpoint number (0..7)
+ bit7: endpoint direction which can be IN(1) or OUT(0)
+ \param[out] none
+ \retval none
+*/
+uint32_t usbd_fifo_flush(usb_core_driver *udev, uint8_t ep_addr)
+{
+ if(EP_DIR(ep_addr)) {
+ (void)usb_txfifo_flush(&udev->regs, EP_ID(ep_addr));
+ } else {
+ (void)usb_rxfifo_flush(&udev->regs);
+ }
+
+ return (0U);
+}
+
+/*!
+ \brief device connect
+ \param[in] udev: pointer to USB device instance
+ \param[out] none
+ \retval none
+*/
+void usbd_connect(usb_core_driver *udev)
+{
+#ifndef USE_OTG_MODE
+ /* connect device */
+ usb_dev_connect(udev);
+
+ usb_mdelay(3U);
+#endif /* USE_OTG_MODE */
+}
+
+/*!
+ \brief device disconnect
+ \param[in] udev: pointer to USB device instance
+ \param[out] none
+ \retval none
+*/
+void usbd_disconnect(usb_core_driver *udev)
+{
+#ifndef USE_OTG_MODE
+ /* disconnect device for 3ms */
+ usb_dev_disconnect(udev);
+
+ usb_mdelay(3U);
+#endif /* USE_OTG_MODE */
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/core/Source/usbd_enum.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/core/Source/usbd_enum.c
new file mode 100644
index 00000000..7ebe53f0
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/core/Source/usbd_enum.c
@@ -0,0 +1,764 @@
+/*!
+ \file usbd_enum.c
+ \brief USB enumeration function
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+ \version 2021-09-27, V3.0.1, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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.
+*/
+
+#include "usbd_enum.h"
+#include "usb_ch9_std.h"
+
+#ifdef WINUSB_EXEMPT_DRIVER
+
+extern usbd_status usbd_OEM_req(usb_dev *udev, usb_req *req);
+
+#endif /* WINUSB_EXEMPT_DRIVER */
+
+/* local function prototypes ('static') */
+static usb_reqsta _usb_std_reserved(usb_core_driver *udev, usb_req *req);
+static uint8_t *_usb_dev_desc_get(usb_core_driver *udev, uint8_t index, uint16_t *len);
+static uint8_t *_usb_config_desc_get(usb_core_driver *udev, uint8_t index, uint16_t *len);
+static uint8_t *_usb_bos_desc_get(usb_core_driver *udev, uint8_t index, uint16_t *len);
+static uint8_t *_usb_str_desc_get(usb_core_driver *udev, uint8_t index, uint16_t *len);
+static usb_reqsta _usb_std_getstatus(usb_core_driver *udev, usb_req *req);
+static usb_reqsta _usb_std_clearfeature(usb_core_driver *udev, usb_req *req);
+static usb_reqsta _usb_std_setfeature(usb_core_driver *udev, usb_req *req);
+static usb_reqsta _usb_std_setaddress(usb_core_driver *udev, usb_req *req);
+static usb_reqsta _usb_std_getdescriptor(usb_core_driver *udev, usb_req *req);
+static usb_reqsta _usb_std_setdescriptor(usb_core_driver *udev, usb_req *req);
+static usb_reqsta _usb_std_getconfiguration(usb_core_driver *udev, usb_req *req);
+static usb_reqsta _usb_std_setconfiguration(usb_core_driver *udev, usb_req *req);
+static usb_reqsta _usb_std_getinterface(usb_core_driver *udev, usb_req *req);
+static usb_reqsta _usb_std_setinterface(usb_core_driver *udev, usb_req *req);
+static usb_reqsta _usb_std_synchframe(usb_core_driver *udev, usb_req *req);
+
+static usb_reqsta(*_std_dev_req[])(usb_core_driver *udev, usb_req *req) = {
+ [USB_GET_STATUS] = _usb_std_getstatus,
+ [USB_CLEAR_FEATURE] = _usb_std_clearfeature,
+ [USB_RESERVED2] = _usb_std_reserved,
+ [USB_SET_FEATURE] = _usb_std_setfeature,
+ [USB_RESERVED4] = _usb_std_reserved,
+ [USB_SET_ADDRESS] = _usb_std_setaddress,
+ [USB_GET_DESCRIPTOR] = _usb_std_getdescriptor,
+ [USB_SET_DESCRIPTOR] = _usb_std_setdescriptor,
+ [USB_GET_CONFIGURATION] = _usb_std_getconfiguration,
+ [USB_SET_CONFIGURATION] = _usb_std_setconfiguration,
+ [USB_GET_INTERFACE] = _usb_std_getinterface,
+ [USB_SET_INTERFACE] = _usb_std_setinterface,
+ [USB_SYNCH_FRAME] = _usb_std_synchframe,
+};
+
+/* get standard descriptor handler */
+static uint8_t *(*std_desc_get[])(usb_core_driver *udev, uint8_t index, uint16_t *len) = {
+ [(uint8_t)USB_DESCTYPE_DEV - 1U] = _usb_dev_desc_get,
+ [(uint8_t)USB_DESCTYPE_CONFIG - 1U] = _usb_config_desc_get,
+ [(uint8_t)USB_DESCTYPE_STR - 1U] = _usb_str_desc_get
+};
+
+/*!
+ \brief handle USB standard device request
+ \param[in] udev: pointer to USB device instance
+ \param[in] req: pointer to USB device request
+ \param[out] none
+ \retval USB device request status
+*/
+usb_reqsta usbd_standard_request(usb_core_driver *udev, usb_req *req)
+{
+ return (*_std_dev_req[req->bRequest])(udev, req);
+}
+
+/*!
+ \brief handle USB device class request
+ \param[in] udev: pointer to USB device instance
+ \param[in] req: pointer to USB device class request
+ \param[out] none
+ \retval USB device request status
+*/
+usb_reqsta usbd_class_request(usb_core_driver *udev, usb_req *req)
+{
+ if((uint8_t)USBD_CONFIGURED == udev->dev.cur_status) {
+ if(BYTE_LOW(req->wIndex) <= USBD_ITF_MAX_NUM) {
+ /* call device class handle function */
+ return (usb_reqsta)udev->dev.class_core->req_proc(udev, req);
+ }
+ }
+
+ return REQ_NOTSUPP;
+}
+
+/*!
+ \brief handle USB vendor request
+ \param[in] udev: pointer to USB device instance
+ \param[in] req: pointer to USB vendor request
+ \param[out] none
+ \retval USB device request status
+*/
+usb_reqsta usbd_vendor_request(usb_core_driver *udev, usb_req *req)
+{
+ (void)udev;
+ (void)req;
+
+ /* added by user... */
+#ifdef WINUSB_EXEMPT_DRIVER
+ usbd_OEM_req(udev, req);
+#endif
+
+ return REQ_SUPP;
+}
+
+/*!
+ \brief handle USB enumeration error
+ \param[in] udev: pointer to USB device instance
+ \param[in] req: pointer to USB device request
+ \param[out] none
+ \retval none
+*/
+void usbd_enum_error(usb_core_driver *udev, usb_req *req)
+{
+ (void)req;
+
+ (void)usbd_ep_stall(udev, 0x80U);
+ (void)usbd_ep_stall(udev, 0x00U);
+
+ usb_ctlep_startout(udev);
+}
+
+/*!
+ \brief convert hex 32bits value into unicode char
+ \param[in] value: hex 32bits value
+ \param[in] pbuf: buffer pointer to store unicode char
+ \param[in] len: value length
+ \param[out] none
+ \retval none
+*/
+void int_to_unicode(uint32_t value, uint8_t *pbuf, uint8_t len)
+{
+ uint8_t index;
+
+ for(index = 0U; index < len; index++) {
+ if((value >> 28U) < 0x0AU) {
+ pbuf[2U * index] = (uint8_t)((value >> 28U) + '0');
+ } else {
+ pbuf[2U * index] = (uint8_t)((value >> 28U) + 'A' - 10U);
+ }
+
+ value = value << 4U;
+
+ pbuf[2U * index + 1U] = 0U;
+ }
+}
+
+/*!
+ \brief convert hex 32bits value into unicode char
+ \param[in] unicode_str: pointer to unicode string
+ \param[out] none
+ \retval none
+*/
+void serial_string_get(uint16_t *unicode_str)
+{
+ if((unicode_str[0] & 0x00FFU) != 6U) {
+ uint32_t DeviceSerial0, DeviceSerial1, DeviceSerial2;
+
+ DeviceSerial0 = *(uint32_t *)DEVICE_ID1;
+ DeviceSerial1 = *(uint32_t *)DEVICE_ID2;
+ DeviceSerial2 = *(uint32_t *)DEVICE_ID3;
+
+ DeviceSerial0 += DeviceSerial2;
+
+ if(0U != DeviceSerial0) {
+ int_to_unicode(DeviceSerial0, (uint8_t *) & (unicode_str[1]), 8U);
+ int_to_unicode(DeviceSerial1, (uint8_t *) & (unicode_str[9]), 4U);
+ }
+ } else {
+ uint32_t device_serial = *(uint32_t *)DEVICE_ID;
+
+ if(0U != device_serial) {
+ unicode_str[1] = (uint16_t)(device_serial & 0x0000FFFFU);
+ unicode_str[2] = (uint16_t)((device_serial & 0xFFFF0000U) >> 16U);
+
+ }
+ }
+}
+
+/*!
+ \brief no operation, just for reserved
+ \param[in] udev: pointer to USB device instance
+ \param[in] req: pointer to USB vendor request
+ \param[out] none
+ \retval USB device request status
+*/
+static usb_reqsta _usb_std_reserved(usb_core_driver *udev, usb_req *req)
+{
+ (void)udev;
+ (void)req;
+
+ /* no operation... */
+
+ return REQ_NOTSUPP;
+}
+
+/*!
+ \brief get the device descriptor
+ \param[in] udev: pointer to USB device instance
+ \param[in] index: no use
+ \param[out] len: data length pointer
+ \retval descriptor buffer pointer
+*/
+static uint8_t *_usb_dev_desc_get(usb_core_driver *udev, uint8_t index, uint16_t *len)
+{
+ (void)index;
+
+ *len = udev->dev.desc->dev_desc[0];
+
+ return udev->dev.desc->dev_desc;
+}
+
+/*!
+ \brief get the configuration descriptor
+ \brief[in] udev: pointer to USB device instance
+ \brief[in] index: no use
+ \param[out] len: data length pointer
+ \retval descriptor buffer pointer
+*/
+static uint8_t *_usb_config_desc_get(usb_core_driver *udev, uint8_t index, uint16_t *len)
+{
+ (void)index;
+
+ *len = udev->dev.desc->config_desc[2] | (udev->dev.desc->config_desc[3] << 8);
+
+ return udev->dev.desc->config_desc;
+}
+
+/*!
+ \brief get the BOS descriptor
+ \brief[in] udev: pointer to USB device instance
+ \brief[in] index: no use
+ \param[out] len: data length pointer
+ \retval descriptor buffer pointer
+*/
+static uint8_t *_usb_bos_desc_get(usb_core_driver *udev, uint8_t index, uint16_t *len)
+{
+ (void)index;
+
+ *len = udev->dev.desc->bos_desc[2];
+
+ return udev->dev.desc->bos_desc;
+}
+
+/*!
+ \brief get string descriptor
+ \param[in] udev: pointer to USB device instance
+ \param[in] index: string descriptor index
+ \param[out] len: pointer to string length
+ \retval descriptor buffer pointer
+*/
+static uint8_t *_usb_str_desc_get(usb_core_driver *udev, uint8_t index, uint16_t *len)
+{
+ uint8_t *desc = udev->dev.desc->strings[index];
+
+ *len = desc[0];
+
+ return desc;
+}
+
+/*!
+ \brief handle Get_Status request
+ \param[in] udev: pointer to USB device instance
+ \param[in] req: pointer to USB device request
+ \param[out] none
+ \retval USB device request status
+*/
+static usb_reqsta _usb_std_getstatus(usb_core_driver *udev, usb_req *req)
+{
+ uint8_t recp = BYTE_LOW(req->wIndex);
+ usb_reqsta req_status = REQ_NOTSUPP;
+ usb_transc *transc = &udev->dev.transc_in[0];
+
+ static uint8_t status[2] = {0};
+
+ switch(req->bmRequestType & (uint8_t)USB_RECPTYPE_MASK) {
+ case USB_RECPTYPE_DEV:
+ if(((uint8_t)USBD_ADDRESSED == udev->dev.cur_status) || \
+ ((uint8_t)USBD_CONFIGURED == udev->dev.cur_status)) {
+
+ if(udev->dev.pm.power_mode) {
+ status[0] = USB_STATUS_SELF_POWERED;
+ } else {
+ status[0] = 0U;
+ }
+
+ if(udev->dev.pm.dev_remote_wakeup) {
+ status[0] |= USB_STATUS_REMOTE_WAKEUP;
+ } else {
+ status[0] = 0U;
+ }
+
+ req_status = REQ_SUPP;
+ }
+ break;
+
+ case USB_RECPTYPE_ITF:
+ if(((uint8_t)USBD_CONFIGURED == udev->dev.cur_status) && (recp <= USBD_ITF_MAX_NUM)) {
+ req_status = REQ_SUPP;
+ }
+ break;
+
+ case USB_RECPTYPE_EP:
+ if((uint8_t)USBD_CONFIGURED == udev->dev.cur_status) {
+ if(0x80U == (recp & 0x80U)) {
+ status[0] = udev->dev.transc_in[EP_ID(recp)].ep_stall;
+ } else {
+ status[0] = udev->dev.transc_out[recp].ep_stall;
+ }
+
+ req_status = REQ_SUPP;
+ }
+ break;
+
+ default:
+ break;
+ }
+
+ if(REQ_SUPP == req_status) {
+ transc->xfer_buf = status;
+ transc->remain_len = 2U;
+ }
+
+ return req_status;
+}
+
+/*!
+ \brief handle USB Clear_Feature request
+ \param[in] udev: pointer to USB device instance
+ \param[in] req: USB device request
+ \param[out] none
+ \retval USB device request status
+*/
+static usb_reqsta _usb_std_clearfeature(usb_core_driver *udev, usb_req *req)
+{
+ uint8_t ep = 0U;
+
+ switch(req->bmRequestType & (uint8_t)USB_RECPTYPE_MASK) {
+ case USB_RECPTYPE_DEV:
+ if(((uint8_t)USBD_ADDRESSED == udev->dev.cur_status) || \
+ ((uint8_t)USBD_CONFIGURED == udev->dev.cur_status)) {
+
+ /* clear device remote wakeup feature */
+ if((uint16_t)USB_FEATURE_REMOTE_WAKEUP == req->wValue) {
+ udev->dev.pm.dev_remote_wakeup = 0U;
+
+ return REQ_SUPP;
+ }
+ }
+ break;
+
+ case USB_RECPTYPE_ITF:
+ break;
+
+ case USB_RECPTYPE_EP:
+ /* get endpoint address */
+ ep = BYTE_LOW(req->wIndex);
+
+ if((uint8_t)USBD_CONFIGURED == udev->dev.cur_status) {
+ /* clear endpoint halt feature */
+ if(((uint16_t)USB_FEATURE_EP_HALT == req->wValue) && (!CTL_EP(ep))) {
+ (void)usbd_ep_stall_clear(udev, ep);
+
+ (void)udev->dev.class_core->req_proc(udev, req);
+ }
+
+ return REQ_SUPP;
+ }
+ break;
+
+ default:
+ break;
+ }
+
+ return REQ_NOTSUPP;
+}
+
+/*!
+ \brief handle USB Set_Feature request
+ \param[in] udev: pointer to USB device instance
+ \param[in] req: pointer to USB device request
+ \param[out] none
+ \retval USB device request status
+*/
+static usb_reqsta _usb_std_setfeature(usb_core_driver *udev, usb_req *req)
+{
+ uint8_t ep = 0U;
+
+ switch(req->bmRequestType & (uint8_t)USB_RECPTYPE_MASK) {
+ case USB_RECPTYPE_DEV:
+ if(((uint8_t)USBD_ADDRESSED == udev->dev.cur_status) || \
+ ((uint8_t)USBD_CONFIGURED == udev->dev.cur_status)) {
+ /* set device remote wakeup feature */
+ if((uint16_t)USB_FEATURE_REMOTE_WAKEUP == req->wValue) {
+ udev->dev.pm.dev_remote_wakeup = 1U;
+ }
+
+ return REQ_SUPP;
+ }
+ break;
+
+ case USB_RECPTYPE_ITF:
+ break;
+
+ case USB_RECPTYPE_EP:
+ /* get endpoint address */
+ ep = BYTE_LOW(req->wIndex);
+
+ if((uint8_t)USBD_CONFIGURED == udev->dev.cur_status) {
+ /* set endpoint halt feature */
+ if(((uint16_t)USB_FEATURE_EP_HALT == req->wValue) && (!CTL_EP(ep))) {
+ (void)usbd_ep_stall(udev, ep);
+ }
+
+ return REQ_SUPP;
+ }
+ break;
+
+ default:
+ break;
+ }
+
+ return REQ_NOTSUPP;
+}
+
+/*!
+ \brief handle USB Set_Address request
+ \param[in] udev: pointer to USB device instance
+ \param[in] req: pointer to USB device request
+ \param[out] none
+ \retval USB device request status
+*/
+static usb_reqsta _usb_std_setaddress(usb_core_driver *udev, usb_req *req)
+{
+ if((0U == req->wIndex) && (0U == req->wLength)) {
+ udev->dev.dev_addr = (uint8_t)(req->wValue) & 0x7FU;
+
+ if(udev->dev.cur_status != (uint8_t)USBD_CONFIGURED) {
+ usbd_addr_set(udev, udev->dev.dev_addr);
+
+ if(udev->dev.dev_addr) {
+ udev->dev.cur_status = (uint8_t)USBD_ADDRESSED;
+ } else {
+ udev->dev.cur_status = (uint8_t)USBD_DEFAULT;
+ }
+
+ return REQ_SUPP;
+ }
+ }
+
+ return REQ_NOTSUPP;
+}
+
+/*!
+ \brief handle USB Get_Descriptor request
+ \param[in] udev: pointer to USB device instance
+ \param[in] req: pointer to USB device request
+ \param[out] none
+ \retval USB device request status
+*/
+static usb_reqsta _usb_std_getdescriptor(usb_core_driver *udev, usb_req *req)
+{
+ uint8_t desc_type = 0U;
+ uint8_t desc_index = 0U;
+
+ usb_reqsta status = REQ_NOTSUPP;
+
+ usb_transc *transc = &udev->dev.transc_in[0];
+
+ /* get device standard descriptor */
+ switch(req->bmRequestType & USB_RECPTYPE_MASK) {
+ case USB_RECPTYPE_DEV:
+ desc_type = BYTE_HIGH(req->wValue);
+ desc_index = BYTE_LOW(req->wValue);
+
+ switch(desc_type) {
+ case USB_DESCTYPE_DEV:
+ transc->xfer_buf = std_desc_get[desc_type - 1U](udev, desc_index, (uint16_t *) & (transc->remain_len));
+
+ if(64U == req->wLength) {
+ transc->remain_len = 8U;
+ }
+ break;
+
+ case USB_DESCTYPE_CONFIG:
+ transc->xfer_buf = std_desc_get[desc_type - 1U](udev, desc_index, (uint16_t *) & (transc->remain_len));
+ break;
+
+ case USB_DESCTYPE_STR:
+ if(desc_index < (uint8_t)STR_IDX_MAX) {
+ transc->xfer_buf = std_desc_get[desc_type - 1U](udev, desc_index, (uint16_t *) & (transc->remain_len));
+ }
+ break;
+
+ case USB_DESCTYPE_ITF:
+ case USB_DESCTYPE_EP:
+ case USB_DESCTYPE_DEV_QUALIFIER:
+ case USB_DESCTYPE_OTHER_SPD_CONFIG:
+ case USB_DESCTYPE_ITF_POWER:
+ break;
+
+ case USB_DESCTYPE_BOS:
+ transc->xfer_buf = _usb_bos_desc_get(udev, desc_index, (uint16_t *) & (transc->remain_len));
+ break;
+
+ default:
+ break;
+ }
+ break;
+
+ case USB_RECPTYPE_ITF:
+ /* get device class special descriptor */
+ status = (usb_reqsta)(udev->dev.class_core->req_proc(udev, req));
+ break;
+
+ case USB_RECPTYPE_EP:
+ break;
+
+ default:
+ break;
+ }
+
+ if((0U != transc->remain_len) && (0U != req->wLength)) {
+ if(transc->remain_len < req->wLength) {
+ if((transc->remain_len >= transc->max_len) && (0U == (transc->remain_len % transc->max_len))) {
+ udev->dev.control.ctl_zlp = 1U;
+ }
+ } else {
+ transc->remain_len = req->wLength;
+ }
+
+ status = REQ_SUPP;
+ }
+
+ return status;
+}
+
+/*!
+ \brief handle USB Set_Descriptor request
+ \param[in] udev: pointer to USB device instance
+ \param[in] req: pointer to USB device request
+ \param[out] none
+ \retval USB device request status
+*/
+static usb_reqsta _usb_std_setdescriptor(usb_core_driver *udev, usb_req *req)
+{
+ (void)udev;
+ (void)req;
+
+ /* no handle... */
+ return REQ_SUPP;
+}
+
+/*!
+ \brief handle USB Get_Configuration request
+ \param[in] udev: pointer to USB device instance
+ \param[in] req: pointer to USB device request
+ \param[out] none
+ \retval USB device request status
+*/
+static usb_reqsta _usb_std_getconfiguration(usb_core_driver *udev, usb_req *req)
+{
+ (void)req;
+
+ usb_reqsta req_status = REQ_NOTSUPP;
+ usb_transc *transc = &udev->dev.transc_in[0];
+
+ switch(udev->dev.cur_status) {
+ case USBD_ADDRESSED:
+ if(USB_DEFAULT_CONFIG == udev->dev.config) {
+ req_status = REQ_SUPP;
+ }
+ break;
+
+ case USBD_CONFIGURED:
+ if(udev->dev.config != USB_DEFAULT_CONFIG) {
+ req_status = REQ_SUPP;
+ }
+ break;
+
+ default:
+ break;
+ }
+
+ if(REQ_SUPP == req_status) {
+ transc->xfer_buf = &(udev->dev.config);
+ transc->remain_len = 1U;
+ }
+
+ return req_status;
+}
+
+/*!
+ \brief handle USB Set_Configuration request
+ \param[in] udev: pointer to USB device instance
+ \param[in] req: pointer to USB device request
+ \param[out] none
+ \retval USB device request status
+*/
+static usb_reqsta _usb_std_setconfiguration(usb_core_driver *udev, usb_req *req)
+{
+ static uint8_t config;
+ usb_reqsta status = REQ_NOTSUPP;
+
+ config = (uint8_t)(req->wValue);
+
+ if(config <= USBD_CFG_MAX_NUM) {
+ switch(udev->dev.cur_status) {
+ case USBD_ADDRESSED:
+ if(config) {
+ (void)udev->dev.class_core->init(udev, config);
+
+ udev->dev.config = config;
+ udev->dev.cur_status = (uint8_t)USBD_CONFIGURED;
+ }
+
+ status = REQ_SUPP;
+ break;
+
+ case USBD_CONFIGURED:
+ if(USB_DEFAULT_CONFIG == config) {
+ (void)udev->dev.class_core->deinit(udev, config);
+
+ udev->dev.config = config;
+ udev->dev.cur_status = (uint8_t)USBD_ADDRESSED;
+ } else if(config != udev->dev.config) {
+ /* clear old configuration */
+ (void)udev->dev.class_core->deinit(udev, config);
+
+ /* set new configuration */
+ udev->dev.config = config;
+
+ (void)udev->dev.class_core->init(udev, config);
+ } else {
+ /* no operation */
+ }
+
+ status = REQ_SUPP;
+ break;
+
+ case USBD_DEFAULT:
+ break;
+
+ default:
+ break;
+ }
+ }
+
+ return status;
+}
+
+/*!
+ \brief handle USB Get_Interface request
+ \param[in] udev: pointer to USB device instance
+ \param[in] req: pointer to USB device request
+ \param[out] none
+ \retval USB device request status
+*/
+static usb_reqsta _usb_std_getinterface(usb_core_driver *udev, usb_req *req)
+{
+ switch(udev->dev.cur_status) {
+ case USBD_DEFAULT:
+ break;
+
+ case USBD_ADDRESSED:
+ break;
+
+ case USBD_CONFIGURED:
+ if(BYTE_LOW(req->wIndex) <= USBD_ITF_MAX_NUM) {
+ usb_transc *transc = &udev->dev.transc_in[0];
+
+ transc->xfer_buf = &(udev->dev.class_core->alter_set);
+ transc->remain_len = 1U;
+
+ return REQ_SUPP;
+ }
+ break;
+
+ default:
+ break;
+ }
+
+ return REQ_NOTSUPP;
+}
+
+/*!
+ \brief handle USB Set_Interface request
+ \param[in] udev: pointer to USB device instance
+ \param[in] req: pointer to USB device request
+ \param[out] none
+ \retval USB device request status
+*/
+static usb_reqsta _usb_std_setinterface(usb_core_driver *udev, usb_req *req)
+{
+ switch(udev->dev.cur_status) {
+ case USBD_DEFAULT:
+ break;
+
+ case USBD_ADDRESSED:
+ break;
+
+ case USBD_CONFIGURED:
+ if(BYTE_LOW(req->wIndex) <= USBD_ITF_MAX_NUM) {
+ if(NULL != udev->dev.class_core->set_intf) {
+ (void)udev->dev.class_core->set_intf(udev, req);
+ }
+
+ return REQ_SUPP;
+ }
+ break;
+
+ default:
+ break;
+ }
+
+ return REQ_NOTSUPP;
+}
+
+/*!
+ \brief handle USB SynchFrame request
+ \param[in] udev: pointer to USB device instance
+ \param[in] req: pointer to USB device request
+ \param[out] none
+ \retval USB device request status
+*/
+static usb_reqsta _usb_std_synchframe(usb_core_driver *udev, usb_req *req)
+{
+ (void)udev;
+ (void)req;
+
+ /* no handle */
+ return REQ_SUPP;
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/core/Source/usbd_transc.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/core/Source/usbd_transc.c
new file mode 100644
index 00000000..1a58dfbe
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/device/core/Source/usbd_transc.c
@@ -0,0 +1,265 @@
+/*!
+ \file usbd_transc.c
+ \brief USB transaction core functions
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+ \version 2020-12-07, V3.0.1, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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.
+*/
+
+#include "usbd_enum.h"
+#include "usbd_transc.h"
+
+/*!
+ \brief USB send data in the control transaction
+ \param[in] udev: pointer to USB device instance
+ \param[out] none
+ \retval USB device operation cur_status
+*/
+usbd_status usbd_ctl_send(usb_core_driver *udev)
+{
+ usb_transc *transc = &udev->dev.transc_in[0];
+
+ (void)usbd_ep_send(udev, 0U, transc->xfer_buf, transc->remain_len);
+
+ if(transc->remain_len > transc->max_len) {
+ udev->dev.control.ctl_state = (uint8_t)USB_CTL_DATA_IN;
+ } else {
+ udev->dev.control.ctl_state = (uint8_t)USB_CTL_LAST_DATA_IN;
+ }
+
+ return USBD_OK;
+}
+
+/*!
+ \brief USB receive data in control transaction
+ \param[in] udev: pointer to USB device instance
+ \param[out] none
+ \retval USB device operation cur_status
+*/
+usbd_status usbd_ctl_recev(usb_core_driver *udev)
+{
+ usb_transc *transc = &udev->dev.transc_out[0];
+
+ (void)usbd_ep_recev(udev, 0U, transc->xfer_buf, transc->remain_len);
+
+ if(transc->remain_len > transc->max_len) {
+ udev->dev.control.ctl_state = (uint8_t)USB_CTL_DATA_OUT;
+ } else {
+ udev->dev.control.ctl_state = (uint8_t)USB_CTL_LAST_DATA_OUT;
+ }
+
+ return USBD_OK;
+}
+
+/*!
+ \brief USB send control transaction status
+ \param[in] udev: pointer to USB device instance
+ \param[out] none
+ \retval USB device operation cur_status
+*/
+usbd_status usbd_ctl_status_send(usb_core_driver *udev)
+{
+ udev->dev.control.ctl_state = (uint8_t)USB_CTL_STATUS_IN;
+
+ (void)usbd_ep_send(udev, 0U, NULL, 0U);
+
+ usb_ctlep_startout(udev);
+
+ return USBD_OK;
+}
+
+/*!
+ \brief USB control receive status
+ \param[in] udev: pointer to USB device instance
+ \param[out] none
+ \retval USB device operation cur_status
+*/
+usbd_status usbd_ctl_status_recev(usb_core_driver *udev)
+{
+ udev->dev.control.ctl_state = (uint8_t)USB_CTL_STATUS_OUT;
+
+ (void)usbd_ep_recev(udev, 0U, NULL, 0U);
+
+ usb_ctlep_startout(udev);
+
+ return USBD_OK;
+}
+
+/*!
+ \brief USB setup stage processing
+ \param[in] udev: pointer to USB device instance
+ \param[out] none
+ \retval USB device operation cur_status
+*/
+uint8_t usbd_setup_transc(usb_core_driver *udev)
+{
+ usb_reqsta reqstat = REQ_NOTSUPP;
+
+ usb_req req = udev->dev.control.req;
+
+ switch(req.bmRequestType & USB_REQTYPE_MASK) {
+ /* standard device request */
+ case USB_REQTYPE_STRD:
+ reqstat = usbd_standard_request(udev, &req);
+ break;
+
+ /* device class request */
+ case USB_REQTYPE_CLASS:
+ reqstat = usbd_class_request(udev, &req);
+ break;
+
+ /* vendor defined request */
+ case USB_REQTYPE_VENDOR:
+ reqstat = usbd_vendor_request(udev, &req);
+ break;
+
+ default:
+ break;
+ }
+
+ if(REQ_SUPP == reqstat) {
+ if(0U == req.wLength) {
+ (void)usbd_ctl_status_send(udev);
+ } else {
+ if(req.bmRequestType & 0x80U) {
+ (void)usbd_ctl_send(udev);
+ } else {
+ (void)usbd_ctl_recev(udev);
+ }
+ }
+ } else {
+ usbd_enum_error(udev, &req);
+ }
+
+ return (uint8_t)USBD_OK;
+}
+
+/*!
+ \brief data out stage processing
+ \param[in] udev: pointer to USB device instance
+ \param[in] ep_num: endpoint identifier(0..7)
+ \param[out] none
+ \retval USB device operation cur_status
+*/
+uint8_t usbd_out_transc(usb_core_driver *udev, uint8_t ep_num)
+{
+ if(0U == ep_num) {
+ usb_transc *transc = &udev->dev.transc_out[0];
+
+ switch(udev->dev.control.ctl_state) {
+ case USB_CTL_DATA_OUT:
+ /* update transfer length */
+ transc->remain_len -= transc->max_len;
+
+ if((uint8_t)USB_USE_DMA == udev->bp.transfer_mode) {
+ transc->xfer_buf += transc->max_len;
+ }
+
+ (void)usbd_ctl_recev(udev);
+ break;
+
+ case USB_CTL_LAST_DATA_OUT:
+ if(udev->dev.cur_status == (uint8_t)USBD_CONFIGURED) {
+ if(udev->dev.class_core->ctlx_out != NULL) {
+ (void)udev->dev.class_core->ctlx_out(udev);
+ }
+ }
+
+ transc->remain_len = 0U;
+
+ (void)usbd_ctl_status_send(udev);
+ break;
+
+ default:
+ break;
+ }
+ } else if((udev->dev.class_core->data_out != NULL) && (udev->dev.cur_status == (uint8_t)USBD_CONFIGURED)) {
+ (void)udev->dev.class_core->data_out(udev, ep_num);
+ } else {
+ /* no operation */
+ }
+
+ return (uint8_t)USBD_OK;
+}
+
+/*!
+ \brief data in stage processing
+ \param[in] udev: pointer to USB device instance
+ \param[in] ep_num: endpoint identifier(0..7)
+ \param[out] none
+ \retval USB device operation cur_status
+*/
+uint8_t usbd_in_transc(usb_core_driver *udev, uint8_t ep_num)
+{
+ if(0U == ep_num) {
+ usb_transc *transc = &udev->dev.transc_in[0];
+
+ switch(udev->dev.control.ctl_state) {
+ case USB_CTL_DATA_IN:
+ /* update transfer length */
+ transc->remain_len -= transc->max_len;
+
+ if((uint8_t)USB_USE_DMA == udev->bp.transfer_mode) {
+ transc->xfer_buf += transc->max_len;
+ }
+
+ (void)usbd_ctl_send(udev);
+ break;
+
+ case USB_CTL_LAST_DATA_IN:
+ /* last packet is MPS multiple, so send ZLP packet */
+ if(udev->dev.control.ctl_zlp) {
+ (void)usbd_ep_send(udev, 0U, NULL, 0U);
+
+ udev->dev.control.ctl_zlp = 0U;
+ } else {
+ if(udev->dev.cur_status == (uint8_t)USBD_CONFIGURED) {
+ if(udev->dev.class_core->ctlx_in != NULL) {
+ (void)udev->dev.class_core->ctlx_in(udev);
+ }
+ }
+
+ transc->remain_len = 0U;
+
+ (void)usbd_ctl_status_recev(udev);
+ }
+ break;
+
+ default:
+ break;
+ }
+ } else {
+ if((udev->dev.cur_status == (uint8_t)USBD_CONFIGURED) && (udev->dev.class_core->data_in != NULL)) {
+ (void)udev->dev.class_core->data_in(udev, ep_num);
+ }
+ }
+
+ return (uint8_t)USBD_OK;
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/driver/Include/drv_usb_core.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/driver/Include/drv_usb_core.h
new file mode 100644
index 00000000..ae946645
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/driver/Include/drv_usb_core.h
@@ -0,0 +1,159 @@
+/*!
+ \file drv_usb_core.h
+ \brief USB core low level driver header file
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __DRV_USB_CORE_H
+#define __DRV_USB_CORE_H
+
+#include "drv_usb_regs.h"
+#include "usb_ch9_std.h"
+
+#define USB_FS_EP0_MAX_LEN 64U /*!< maximum packet size of endpoint 0 */
+#define HC_MAX_PACKET_COUNT 140U /*!< maximum packet count */
+
+#define EP_ID(x) ((uint8_t)((x) & 0x7FU)) /*!< endpoint number */
+#define EP_DIR(x) ((uint8_t)((x) >> 7)) /*!< endpoint direction */
+
+enum _usb_mode {
+ DEVICE_MODE = 0U, /*!< device mode */
+ HOST_MODE, /*!< host mode */
+ OTG_MODE /*!< OTG mode */
+};
+
+enum _usb_eptype {
+ USB_EPTYPE_CTRL = 0U, /*!< control endpoint type */
+ USB_EPTYPE_ISOC = 1U, /*!< isochronous endpoint type */
+ USB_EPTYPE_BULK = 2U, /*!< bulk endpoint type */
+ USB_EPTYPE_INTR = 3U, /*!< interrupt endpoint type */
+ USB_EPTYPE_MASK = 3U /*!< endpoint type mask */
+};
+
+typedef enum {
+ USB_OTG_OK = 0U, /*!< USB OTG status OK*/
+ USB_OTG_FAIL /*!< USB OTG status fail*/
+} usb_otg_status;
+
+typedef enum {
+ USB_OK = 0U, /*!< USB status OK*/
+ USB_FAIL /*!< USB status fail*/
+} usb_status;
+
+typedef enum {
+ USB_USE_FIFO, /*!< USB use FIFO transfer mode */
+ USB_USE_DMA /*!< USB use DMA transfer mode */
+} usb_transfer_mode;
+
+typedef struct {
+ uint8_t core_enum; /*!< USB core type */
+ uint8_t core_speed; /*!< USB core speed */
+ uint8_t num_pipe; /*!< USB host channel numbers */
+ uint8_t num_ep; /*!< USB device endpoint numbers */
+ uint8_t transfer_mode; /*!< USB transfer mode */
+ uint8_t phy_itf; /*!< USB core PHY interface */
+ uint8_t sof_enable; /*!< USB SOF output */
+ uint8_t low_power; /*!< USB low power */
+ uint8_t lpm_enable; /*!< USB link power mode(LPM) */
+ uint8_t vbus_sensing_enable; /*!< USB VBUS sensing feature */
+ uint8_t use_dedicated_ep1; /*!< USB dedicated endpoint1 interrupt */
+ uint8_t use_external_vbus; /*!< enable or disable the use of the external VBUS */
+ uint32_t base_reg; /*!< base register address */
+} usb_core_basic;
+
+/* static inline function definitions */
+
+/*!
+ \brief get the global interrupts
+ \param[in] usb_regs: pointer to USB core registers
+ \param[out] none
+ \retval interrupt status
+*/
+__STATIC_INLINE uint32_t usb_coreintr_get(usb_core_regs *usb_regs)
+{
+ return usb_regs->gr->GINTEN & usb_regs->gr->GINTF;
+}
+
+/*!
+ \brief set USB RX FIFO size
+ \param[in] usb_regs: pointer to USB core registers
+ \param[in] size: assigned FIFO size
+ \param[out] none
+ \retval none
+*/
+__STATIC_INLINE void usb_set_rxfifo(usb_core_regs *usb_regs, uint16_t size)
+{
+ usb_regs->gr->GRFLEN = size;
+}
+
+/*!
+ \brief enable the global interrupts
+ \param[in] usb_regs: pointer to USB core registers
+ \param[out] none
+ \retval none
+*/
+__STATIC_INLINE void usb_globalint_enable(usb_core_regs *usb_regs)
+{
+ /* enable USB global interrupt */
+ usb_regs->gr->GAHBCS |= GAHBCS_GINTEN;
+}
+
+/*!
+ \brief disable the global interrupts
+ \param[in] usb_regs: pointer to USB core registers
+ \param[out] none
+ \retval none
+*/
+__STATIC_INLINE void usb_globalint_disable(usb_core_regs *usb_regs)
+{
+ /* disable USB global interrupt */
+ usb_regs->gr->GAHBCS &= ~GAHBCS_GINTEN;
+}
+
+/* function declarations */
+/* configure core capabilities */
+usb_status usb_basic_init(usb_core_basic *usb_basic, usb_core_regs *usb_regs, usb_core_enum usb_core);
+/* initializes the USB controller registers and prepares the core device mode or host mode operation */
+usb_status usb_core_init(usb_core_basic usb_basic, usb_core_regs *usb_regs);
+/* write a packet into the Tx FIFO associated with the endpoint */
+usb_status usb_txfifo_write(usb_core_regs *usb_regs, uint8_t *src_buf, uint8_t fifo_num, uint16_t byte_count);
+/* read a packet from the Rx FIFO associated with the endpoint */
+void *usb_rxfifo_read(usb_core_regs *usb_regs, uint8_t *dest_buf, uint16_t byte_count);
+/* flush a Tx FIFO or all Tx FIFOs */
+usb_status usb_txfifo_flush(usb_core_regs *usb_regs, uint8_t fifo_num);
+/* flush the entire Rx FIFO */
+usb_status usb_rxfifo_flush(usb_core_regs *usb_regs);
+/* set endpoint or channel TX FIFO size */
+void usb_set_txfifo(usb_core_regs *usb_regs, uint8_t fifo, uint16_t size);
+/* set USB current mode */
+void usb_curmode_set(usb_core_regs *usb_regs, uint8_t mode);
+
+#endif /* __DRV_USB_CORE_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/driver/Include/drv_usb_dev.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/driver/Include/drv_usb_dev.h
new file mode 100644
index 00000000..25ab0194
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/driver/Include/drv_usb_dev.h
@@ -0,0 +1,296 @@
+/*!
+ \file drv_usb_dev.h
+ \brief USB device low level driver header file
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+ \version 2020-12-07, V3.0.1, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __DRV_USB_DEV_H
+#define __DRV_USB_DEV_H
+
+#include "usbd_conf.h"
+#include "drv_usb_core.h"
+
+enum usb_ctl_status {
+ USB_CTL_IDLE = 0U, /*!< USB control transfer idle state */
+ USB_CTL_DATA_IN, /*!< USB control transfer data in state */
+ USB_CTL_LAST_DATA_IN, /*!< USB control transfer last data in state */
+ USB_CTL_DATA_OUT, /*!< USB control transfer data out state */
+ USB_CTL_LAST_DATA_OUT, /*!< USB control transfer last data out state */
+ USB_CTL_STATUS_IN, /*!< USB control transfer status in state*/
+ USB_CTL_STATUS_OUT /*!< USB control transfer status out state */
+};
+
+#define EP_IN(x) ((uint8_t)(0x80U | (x))) /*!< device IN endpoint */
+#define EP_OUT(x) ((uint8_t)(x)) /*!< device OUT endpoint */
+
+/* USB descriptor */
+typedef struct _usb_desc {
+ uint8_t *dev_desc; /*!< device descriptor */
+ uint8_t *config_desc; /*!< configure descriptor */
+ uint8_t *bos_desc; /*!< BOS descriptor */
+
+ void *const *strings; /*!< string descriptor */
+} usb_desc;
+
+/* USB power management */
+typedef struct _usb_pm {
+ uint8_t power_mode; /*!< power mode */
+ uint8_t power_low; /*!< power low */
+ uint8_t dev_remote_wakeup; /*!< remote wakeup */
+ uint8_t remote_wakeup_on; /*!< remote wakeup on */
+} usb_pm;
+
+/* USB control information */
+typedef struct _usb_control {
+ usb_req req; /*!< USB standard device request */
+
+ uint8_t ctl_state; /*!< USB control transfer state */
+ uint8_t ctl_zlp; /*!< zero length package */
+} usb_control;
+
+typedef struct {
+ struct {
+ uint8_t num: 4; /*!< the endpoint number.it can be from 0 to 6 */
+ uint8_t pad: 3; /*!< padding between number and direction */
+ uint8_t dir: 1; /*!< the endpoint direction */
+ } ep_addr;
+
+ uint8_t ep_type; /*!< USB endpoint type */
+ uint8_t ep_stall; /*!< USB endpoint stall status */
+
+ uint8_t frame_num; /*!< number of frame */
+ uint16_t max_len; /*!< Maximum packet length */
+
+ /* transaction level variables */
+ uint8_t *xfer_buf; /*!< transmit buffer */
+ uint32_t xfer_len; /*!< transmit buffer length */
+ uint32_t xfer_count; /*!< transmit buffer count */
+
+ uint32_t remain_len; /*!< remain packet length */
+
+ uint32_t dma_addr; /*!< DMA address */
+} usb_transc;
+
+typedef struct _usb_core_driver usb_dev;
+
+typedef struct _usb_class_core {
+ uint8_t command; /*!< device class request command */
+ uint8_t alter_set; /*!< alternative set */
+
+ uint8_t (*init)(usb_dev *udev, uint8_t config_index); /*!< initialize handler */
+ uint8_t (*deinit)(usb_dev *udev, uint8_t config_index); /*!< de-initialize handler */
+
+ uint8_t (*req_proc)(usb_dev *udev, usb_req *req); /*!< device request handler */
+
+ uint8_t (*set_intf)(usb_dev *udev, usb_req *req); /*!< device set interface callback */
+
+ uint8_t (*ctlx_in)(usb_dev *udev); /*!< device contrl in callback */
+ uint8_t (*ctlx_out)(usb_dev *udev); /*!< device contrl out callback */
+
+ uint8_t (*data_in)(usb_dev *udev, uint8_t ep_num); /*!< device data in handler */
+ uint8_t (*data_out)(usb_dev *udev, uint8_t ep_num); /*!< device data out handler */
+
+ uint8_t (*SOF)(usb_dev *udev); /*!< Start of frame handler */
+
+ uint8_t (*incomplete_isoc_in)(usb_dev *udev); /*!< Incomplete synchronization IN transfer handler */
+ uint8_t (*incomplete_isoc_out)(usb_dev *udev); /*!< Incomplete synchronization OUT transfer handler */
+} usb_class_core;
+
+typedef struct _usb_perp_dev {
+ uint8_t config; /*!< configuration */
+ uint8_t dev_addr; /*!< device address */
+
+ __IO uint8_t cur_status; /*!< current status */
+ __IO uint8_t backup_status; /*!< backup status */
+
+ usb_transc transc_in[USBFS_MAX_TX_FIFOS]; /*!< endpoint IN transaction */
+ usb_transc transc_out[USBFS_MAX_TX_FIFOS]; /*!< endpoint OUT transaction */
+
+ usb_pm pm; /*!< power management */
+ usb_control control; /*!< USB control information */
+ usb_desc *desc; /*!< USB descriptors pointer */
+ usb_class_core *class_core; /*!< class driver */
+ void *class_data[USBD_ITF_MAX_NUM]; /*!< class data pointer */
+ void *user_data; /*!< user data pointer */
+ void *pdata; /*!< reserved data pointer */
+} usb_perp_dev;
+
+typedef struct _usb_core_driver {
+ usb_core_basic bp; /*!< USB basic parameters */
+ usb_core_regs regs; /*!< USB registers */
+ usb_perp_dev dev; /*!< USB peripheral device */
+} usb_core_driver;
+
+/* static inline function definitions */
+
+/*!
+ \brief configure the USB device to be disconnected
+ \param[in] udev: pointer to USB device
+ \param[out] none
+ \retval operation status
+*/
+__STATIC_INLINE void usb_dev_disconnect(usb_core_driver *udev)
+{
+ udev->regs.dr->DCTL |= DCTL_SD;
+}
+
+/*!
+ \brief configure the USB device to be connected
+ \param[in] udev: pointer to USB device
+ \param[out] none
+ \retval operation status
+*/
+__STATIC_INLINE void usb_dev_connect(usb_core_driver *udev)
+{
+ udev->regs.dr->DCTL &= ~DCTL_SD;
+}
+
+/*!
+ \brief set the USB device address
+ \param[in] udev: pointer to USB device
+ \param[in] dev_addr: device address for setting
+ \param[out] none
+ \retval operation status
+*/
+__STATIC_INLINE void usb_devaddr_set(usb_core_driver *udev, uint8_t dev_addr)
+{
+ udev->regs.dr->DCFG &= ~DCFG_DAR;
+ udev->regs.dr->DCFG |= (uint32_t)dev_addr << 4U;
+}
+
+/*!
+ \brief read device all OUT endpoint interrupt register
+ \param[in] udev: pointer to USB device
+ \param[out] none
+ \retval interrupt status
+*/
+__STATIC_INLINE uint32_t usb_oepintnum_read(usb_core_driver *udev)
+{
+ uint32_t value = udev->regs.dr->DAEPINT;
+
+ value &= udev->regs.dr->DAEPINTEN;
+
+ return (value & DAEPINT_OEPITB) >> 16U;
+}
+
+/*!
+ \brief read device OUT endpoint interrupt flag register
+ \param[in] udev: pointer to USB device
+ \param[in] ep_num: endpoint number
+ \param[out] none
+ \retval interrupt status
+*/
+__STATIC_INLINE uint32_t usb_oepintr_read(usb_core_driver *udev, uint8_t ep_num)
+{
+ uint32_t value = udev->regs.er_out[ep_num]->DOEPINTF;
+
+ value &= udev->regs.dr->DOEPINTEN;
+
+ return value;
+}
+
+/*!
+ \brief read device all IN endpoint interrupt register
+ \param[in] udev: pointer to USB device
+ \param[out] none
+ \retval interrupt status
+*/
+__STATIC_INLINE uint32_t usb_iepintnum_read(usb_core_driver *udev)
+{
+ uint32_t value = udev->regs.dr->DAEPINT;
+
+ value &= udev->regs.dr->DAEPINTEN;
+
+ return value & DAEPINT_IEPITB;
+}
+
+/*!
+ \brief set remote wakeup signaling
+ \param[in] udev: pointer to USB device
+ \param[out] none
+ \retval none
+*/
+__STATIC_INLINE void usb_rwkup_set(usb_core_driver *udev)
+{
+ if(udev->dev.pm.dev_remote_wakeup) {
+ /* enable remote wakeup signaling */
+ udev->regs.dr->DCTL |= DCTL_RWKUP;
+ }
+}
+
+/*!
+ \brief reset remote wakeup signaling
+ \param[in] udev: pointer to USB device
+ \param[out] none
+ \retval none
+*/
+__STATIC_INLINE void usb_rwkup_reset(usb_core_driver *udev)
+{
+ if(udev->dev.pm.dev_remote_wakeup) {
+ /* disable remote wakeup signaling */
+ udev->regs.dr->DCTL &= ~DCTL_RWKUP;
+ }
+}
+
+/* function declarations */
+/* initialize USB core registers for device mode */
+usb_status usb_devcore_init(usb_core_driver *udev);
+/* enable the USB device mode interrupts */
+usb_status usb_devint_enable(usb_core_driver *udev);
+/* active the USB endpoint 0 transaction */
+usb_status usb_transc0_active(usb_core_driver *udev, usb_transc *transc);
+/* active the USB transaction */
+usb_status usb_transc_active(usb_core_driver *udev, usb_transc *transc);
+/* deactivate the USB transaction */
+usb_status usb_transc_deactivate(usb_core_driver *udev, usb_transc *transc);
+/* configure USB transaction to start IN transfer */
+usb_status usb_transc_inxfer(usb_core_driver *udev, usb_transc *transc);
+/* configure USB transaction to start OUT transfer */
+usb_status usb_transc_outxfer(usb_core_driver *udev, usb_transc *transc);
+/* set the USB transaction STALL status */
+usb_status usb_transc_stall(usb_core_driver *udev, usb_transc *transc);
+/* clear the USB transaction STALL status */
+usb_status usb_transc_clrstall(usb_core_driver *udev, usb_transc *transc);
+/* read device IN endpoint interrupt flag register */
+uint32_t usb_iepintr_read(usb_core_driver *udev, uint8_t ep_num);
+/* configures OUT endpoint 0 to receive SETUP packets */
+void usb_ctlep_startout(usb_core_driver *udev);
+/* active remote wakeup signaling */
+void usb_rwkup_active(usb_core_driver *udev);
+/* active USB core clock */
+void usb_clock_active(usb_core_driver *udev);
+/* USB device suspend */
+void usb_dev_suspend(usb_core_driver *udev);
+/* stop the device and clean up FIFOs */
+void usb_dev_stop(usb_core_driver *udev);
+
+#endif /* __DRV_USB_DEV_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/driver/Include/drv_usb_host.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/driver/Include/drv_usb_host.h
new file mode 100644
index 00000000..0469b120
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/driver/Include/drv_usb_host.h
@@ -0,0 +1,187 @@
+/*!
+ \file drv_usb_host.h
+ \brief USB host mode low level driver header file
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __DRV_USB_HOST_H
+#define __DRV_USB_HOST_H
+
+#include "drv_usb_regs.h"
+#include "usb_ch9_std.h"
+#include "drv_usb_core.h"
+
+typedef enum _usb_pipe_status {
+ PIPE_IDLE = 0U,
+ PIPE_XF,
+ PIPE_HALTED,
+ PIPE_NAK,
+ PIPE_NYET,
+ PIPE_STALL,
+ PIPE_TRACERR,
+ PIPE_BBERR,
+ PIPE_REQOVR,
+ PIPE_DTGERR,
+} usb_pipe_staus;
+
+typedef enum _usb_pipe_mode {
+ PIPE_PERIOD = 0U,
+ PIPE_NON_PERIOD = 1U
+} usb_pipe_mode;
+
+typedef enum _usb_urb_state {
+ URB_IDLE = 0U,
+ URB_DONE,
+ URB_NOTREADY,
+ URB_ERROR,
+ URB_STALL,
+ URB_PING
+} usb_urb_state;
+
+typedef struct _usb_pipe {
+ uint8_t in_used;
+ uint8_t dev_addr;
+ uint32_t dev_speed;
+
+ struct {
+ uint8_t num;
+ uint8_t dir;
+ uint8_t type;
+ uint16_t mps;
+ } ep;
+
+ uint8_t ping;
+ uint32_t DPID;
+
+ uint8_t *xfer_buf;
+ uint32_t xfer_len;
+ uint32_t xfer_count;
+
+ uint8_t data_toggle_in;
+ uint8_t data_toggle_out;
+
+ __IO uint32_t err_count;
+ __IO usb_pipe_staus pp_status;
+ __IO usb_urb_state urb_state;
+} usb_pipe;
+
+
+typedef struct _usb_host_drv {
+ __IO uint32_t connect_status;
+ __IO uint32_t port_enabled;
+ __IO uint32_t backup_xfercount[USBFS_MAX_TX_FIFOS];
+
+ usb_pipe pipe[USBFS_MAX_TX_FIFOS];
+ void *data;
+} usb_host_drv;
+
+typedef struct _usb_core_driver {
+ usb_core_basic bp;
+ usb_core_regs regs;
+ usb_host_drv host;
+} usb_core_driver;
+
+/*!
+ \brief get USB even frame
+ \param[in] pudev: pointer to USB device
+ \param[out] none
+ \retval none
+*/
+__STATIC_INLINE uint8_t usb_frame_even(usb_core_driver *pudev)
+{
+ return (uint8_t)!(pudev->regs.hr->HFINFR & 0x01U);
+}
+
+/*!
+ \brief configure USB clock of PHY
+ \param[in] pudev: pointer to USB device
+ \param[in] clock: PHY clock
+ \param[out] none
+ \retval none
+*/
+__STATIC_INLINE void usb_phyclock_config(usb_core_driver *pudev, uint8_t clock)
+{
+ pudev->regs.hr->HCTL &= ~HCTL_CLKSEL;
+ pudev->regs.hr->HCTL |= clock;
+}
+
+/*!
+ \brief read USB port
+ \param[in] pudev: pointer to USB device
+ \param[out] none
+ \retval port status
+*/
+__STATIC_INLINE uint32_t usb_port_read(usb_core_driver *pudev)
+{
+ return *pudev->regs.HPCS & ~(HPCS_PE | HPCS_PCD | HPCS_PEDC);
+}
+
+/*!
+ \brief get USB current speed
+ \param[in] pudev: pointer to USB device
+ \param[out] none
+ \retval USB current speed
+*/
+__STATIC_INLINE uint32_t usb_curspeed_get(usb_core_driver *pudev)
+{
+ return *pudev->regs.HPCS & HPCS_PS;
+}
+
+/*!
+ \brief get USB current frame
+ \param[in] pudev: pointer to USB device
+ \param[out] none
+ \retval USB current frame
+*/
+__STATIC_INLINE uint32_t usb_curframe_get(usb_core_driver *pudev)
+{
+ return (pudev->regs.hr->HFINFR & 0xFFFFU);
+}
+
+/* function declarations */
+/* initializes USB core for host mode */
+usb_status usb_host_init(usb_core_driver *pudev);
+/* control the VBUS to power */
+void usb_portvbus_switch(usb_core_driver *pudev, uint8_t state);
+/* reset host port */
+uint32_t usb_port_reset(usb_core_driver *pudev);
+/* initialize host pipe */
+usb_status usb_pipe_init(usb_core_driver *pudev, uint8_t pipe_num);
+/* prepare host pipe for transferring packets */
+usb_status usb_pipe_xfer(usb_core_driver *pudev, uint8_t pipe_num);
+/* halt host pipe */
+usb_status usb_pipe_halt(usb_core_driver *pudev, uint8_t pipe_num);
+/* configure host pipe to do ping operation */
+usb_status usb_pipe_ping(usb_core_driver *pudev, uint8_t pipe_num);
+/* stop the USB host and clean up FIFO */
+void usb_host_stop(usb_core_driver *pudev);
+
+#endif /* __DRV_USB_HOST_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/driver/Include/drv_usb_hw.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/driver/Include/drv_usb_hw.h
new file mode 100644
index 00000000..9bf1b59c
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/driver/Include/drv_usb_hw.h
@@ -0,0 +1,69 @@
+/*!
+ \file drv_usb_hw.h
+ \brief usb hardware configuration header file
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __DRV_USB_HW_H
+#define __DRV_USB_HW_H
+
+#include "usb_conf.h"
+
+/* function declarations */
+/* configure USB clock */
+void usb_rcu_config(void);
+/* configure USB interrupt */
+void usb_intr_config(void);
+/* initializes delay unit using Timer2 */
+void usb_timer_init(void);
+/* delay in micro seconds */
+void usb_udelay(const uint32_t usec);
+/* delay in milliseconds */
+void usb_mdelay(const uint32_t msec);
+/* configures system clock after wakeup from STOP mode */
+void system_clk_config_stop(void);
+
+/* configure the CTC peripheral */
+#ifdef USE_IRC48M
+void ctc_config(void);
+#endif /* USE_IRC48M */
+
+#ifdef USE_HOST_MODE
+void systick_config(void);
+
+/* configure USB VBus */
+void usb_vbus_config(void);
+
+/* drive USB VBus */
+void usb_vbus_drive(uint8_t State);
+#endif /* USE_HOST_MODE */
+
+#endif /* __DRV_USB_HW_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/driver/Include/drv_usb_regs.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/driver/Include/drv_usb_regs.h
new file mode 100644
index 00000000..95c759dc
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/driver/Include/drv_usb_regs.h
@@ -0,0 +1,649 @@
+/*!
+ \file drv_usb_regs.h
+ \brief USB cell registers definition and handle macros
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __DRV_USB_REGS_H
+#define __DRV_USB_REGS_H
+
+#include "usb_conf.h"
+
+#define USBHS_REG_BASE 0x40040000L /*!< base address of USBHS registers */
+#define USBFS_REG_BASE 0x50000000L /*!< base address of USBFS registers */
+
+#define USBFS_MAX_TX_FIFOS 15U /*!< FIFO number */
+
+#define USBFS_MAX_PACKET_SIZE 64U /*!< USBFS max packet size */
+#define USBFS_MAX_CHANNEL_COUNT 8U /*!< USBFS host channel count */
+#define USBFS_MAX_EP_COUNT 4U /*!< USBFS device endpoint count */
+#define USBFS_MAX_FIFO_WORDLEN 320U /*!< USBFS max fifo size in words */
+
+#define USBHS_MAX_PACKET_SIZE 512U /*!< USBHS max packet size */
+#define USBHS_MAX_CHANNEL_COUNT 12U /*!< USBHS host channel count */
+#define USBHS_MAX_EP_COUNT 6U /*!< USBHS device endpoint count */
+#define USBHS_MAX_FIFO_WORDLEN 1280U /*!< USBHS max fifo size in words */
+
+#define USB_DATA_FIFO_OFFSET 0x1000U /*!< USB data fifo offset */
+#define USB_DATA_FIFO_SIZE 0x1000U /*!< USB data fifo size */
+
+typedef enum {
+ USB_CORE_ENUM_HS = 0, /*!< USB core type is HS */
+ USB_CORE_ENUM_FS = 1 /*!< USB core type is FS */
+} usb_core_enum;
+
+enum USB_SPEED {
+ USB_SPEED_UNKNOWN = 0, /*!< USB speed unknown */
+ USB_SPEED_LOW, /*!< USB speed low */
+ USB_SPEED_FULL, /*!< USB speed full */
+ USB_SPEED_HIGH, /*!< USB speed high */
+};
+
+enum usb_reg_offset {
+ USB_REG_OFFSET_CORE = 0x0000U, /*!< global OTG control and status register */
+ USB_REG_OFFSET_DEV = 0x0800U, /*!< device mode control and status registers */
+ USB_REG_OFFSET_EP = 0x0020U,
+ USB_REG_OFFSET_EP_IN = 0x0900U, /*!< device IN endpoint 0 control register */
+ USB_REG_OFFSET_EP_OUT = 0x0B00U, /*!< device OUT endpoint 0 control register */
+ USB_REG_OFFSET_HOST = 0x0400U, /*!< host control register */
+ USB_REG_OFFSET_CH = 0x0020U,
+ USB_REG_OFFSET_PORT = 0x0440U, /*!< host port control and status register */
+ USB_REG_OFFSET_CH_INOUT = 0x0500U, /*!< Host channel-x control registers */
+ USB_REG_OFFSET_PWRCLKCTL = 0x0E00U, /*!< power and clock register */
+};
+
+typedef struct {
+ __IO uint32_t GOTGCS; /*!< USB global OTG control and status register 000h */
+ __IO uint32_t GOTGINTF; /*!< USB global OTG interrupt flag register 004h */
+ __IO uint32_t GAHBCS; /*!< USB global AHB control and status register 008h */
+ __IO uint32_t GUSBCS; /*!< USB global USB control and status register 00Ch */
+ __IO uint32_t GRSTCTL; /*!< USB global reset control register 010h */
+ __IO uint32_t GINTF; /*!< USB global interrupt flag register 014h */
+ __IO uint32_t GINTEN; /*!< USB global interrupt enable register 018h */
+ __IO uint32_t GRSTATR; /*!< USB receive status debug read register 01Ch */
+ __IO uint32_t GRSTATP; /*!< USB receive status and pop register 020h */
+ __IO uint32_t GRFLEN; /*!< USB global receive FIFO length register 024h */
+ __IO uint32_t DIEP0TFLEN_HNPTFLEN; /*!< USB device IN endpoint 0/host non-periodic transmit FIFO length register 028h */
+ __IO uint32_t HNPTFQSTAT; /*!< USB host non-periodic FIFO/queue status register 02Ch */
+ uint32_t Reserved30[2]; /*!< Reserved 030h */
+ __IO uint32_t GCCFG; /*!< USB global core configuration register 038h */
+ __IO uint32_t CID; /*!< USB core ID register 03Ch */
+ uint32_t Reserved40[48]; /*!< Reserved 040h-0FFh */
+ __IO uint32_t HPTFLEN; /*!< USB host periodic transmit FIFO length register 100h */
+ __IO uint32_t DIEPTFLEN[15]; /*!< USB device IN endpoint transmit FIFO length register 104h */
+} usb_gr;
+
+typedef struct {
+ __IO uint32_t HCTL; /*!< USB host control register 400h */
+ __IO uint32_t HFT; /*!< USB host frame interval register 404h */
+ __IO uint32_t HFINFR; /*!< USB host frame information remaining register 408h */
+ uint32_t Reserved40C; /*!< Reserved 40Ch */
+ __IO uint32_t HPTFQSTAT; /*!< USB host periodic transmit FIFO/queue status register 410h */
+ __IO uint32_t HACHINT; /*!< USB host all channels interrupt register 414h */
+ __IO uint32_t HACHINTEN; /*!< USB host all channels interrupt enable register 418h */
+} usb_hr;
+
+typedef struct {
+ __IO uint32_t HCHCTL; /*!< USB host channel control register 500h */
+ __IO uint32_t HCHSTCTL; /*!< Reserved 504h */
+ __IO uint32_t HCHINTF; /*!< USB host channel interrupt flag register 508h */
+ __IO uint32_t HCHINTEN; /*!< USB host channel interrupt enable register 50Ch */
+ __IO uint32_t HCHLEN; /*!< USB host channel transfer length register 510h */
+ __IO uint32_t HCHDMAADDR; /*!< USB host channel-x DMA address register 514h*/
+ uint32_t Reserved[2];
+} usb_pr;
+
+typedef struct {
+ __IO uint32_t DCFG; /*!< USB device configuration register 800h */
+ __IO uint32_t DCTL; /*!< USB device control register 804h */
+ __IO uint32_t DSTAT; /*!< USB device status register 808h */
+ uint32_t Reserved0C; /*!< Reserved 80Ch */
+ __IO uint32_t DIEPINTEN; /*!< USB device IN endpoint common interrupt enable register 810h */
+ __IO uint32_t DOEPINTEN; /*!< USB device OUT endpoint common interrupt enable register 814h */
+ __IO uint32_t DAEPINT; /*!< USB device all endpoints interrupt register 818h */
+ __IO uint32_t DAEPINTEN; /*!< USB device all endpoints interrupt enable register 81Ch */
+ uint32_t Reserved20; /*!< Reserved 820h */
+ uint32_t Reserved24; /*!< Reserved 824h */
+ __IO uint32_t DVBUSDT; /*!< USB device VBUS discharge time register 828h */
+ __IO uint32_t DVBUSPT; /*!< USB device VBUS pulsing time register 82Ch */
+ __IO uint32_t DTHRCTL; /*!< dev threshold control 830h */
+ __IO uint32_t DIEPFEINTEN; /*!< USB Device IN endpoint FIFO empty interrupt enable register 834h */
+ __IO uint32_t DEP1INT; /*!< USB device endpoint 1 interrupt register 838h */
+ __IO uint32_t DEP1INTEN; /*!< USB device endpoint 1 interrupt enable register 83Ch */
+ uint32_t Reserved40; /*!< Reserved 840h */
+ __IO uint32_t DIEP1INTEN; /*!< USB device IN endpoint-1 interrupt enable register 844h */
+ uint32_t Reserved48[15]; /*!< Reserved 848-880h */
+ __IO uint32_t DOEP1INTEN; /*!< USB device OUT endpoint-1 interrupt enable register 884h */
+} usb_dr;
+
+typedef struct {
+ __IO uint32_t DIEPCTL; /*!< USB device IN endpoint control register 900h + (EpNum * 20h) + 00h */
+ uint32_t Reserved04; /*!< Reserved 900h + (EpNum * 20h) + 04h */
+ __IO uint32_t DIEPINTF; /*!< USB device IN endpoint interrupt flag register 900h + (EpNum * 20h) + 08h */
+ uint32_t Reserved0C; /*!< Reserved 900h + (EpNum * 20h) + 0Ch */
+ __IO uint32_t DIEPLEN; /*!< USB device IN endpoint transfer length register 900h + (EpNum * 20h) + 10h */
+ __IO uint32_t DIEPDMAADDR; /*!< Device IN endpoint-x DMA address register 900h + (EpNum * 20h) + 14h */
+ __IO uint32_t DIEPTFSTAT; /*!< USB device IN endpoint transmit FIFO status register 900h + (EpNum * 20h) + 18h */
+} usb_erin;
+
+typedef struct {
+ __IO uint32_t DOEPCTL; /*!< USB device IN endpoint control register B00h + (EpNum * 20h) + 00h */
+ uint32_t Reserved04; /*!< Reserved B00h + (EpNum * 20h) + 04h */
+ __IO uint32_t DOEPINTF; /*!< USB device IN endpoint interrupt flag register B00h + (EpNum * 20h) + 08h */
+ uint32_t Reserved0C; /*!< Reserved B00h + (EpNum * 20h) + 0Ch */
+ __IO uint32_t DOEPLEN; /*!< USB device IN endpoint transfer length register B00h + (EpNum * 20h) + 10h */
+ __IO uint32_t DOEPDMAADDR; /*!< Device OUT endpoint-x DMA address register B00h + (EpNum * 20h) + 0Ch */
+} usb_erout;
+
+typedef struct _usb_regs {
+ usb_gr *gr; /*!< USBFS global registers */
+ usb_dr *dr; /*!< Device control and status registers */
+ usb_hr *hr; /*!< Host control and status registers */
+ usb_erin *er_in[6]; /*!< USB device IN endpoint register */
+ usb_erout *er_out[6]; /*!< USB device OUT endpoint register */
+ usb_pr *pr[15]; /*!< USB Host channel-x control register */
+
+ __IO uint32_t *HPCS; /*!< USB host port control and status register */
+ __IO uint32_t *DFIFO[USBFS_MAX_TX_FIFOS];
+ __IO uint32_t *PWRCLKCTL; /*!< USB power and clock control register */
+} usb_core_regs;
+
+/* global OTG control and status register bits definitions */
+#define GOTGCS_BSV BIT(19) /*!< B-Session Valid */
+#define GOTGCS_ASV BIT(18) /*!< A-session valid */
+#define GOTGCS_DI BIT(17) /*!< debounce interval */
+#define GOTGCS_CIDPS BIT(16) /*!< id pin status */
+#define GOTGCS_DHNPEN BIT(11) /*!< device HNP enable */
+#define GOTGCS_HHNPEN BIT(10) /*!< host HNP enable */
+#define GOTGCS_HNPREQ BIT(9) /*!< HNP request */
+#define GOTGCS_HNPS BIT(8) /*!< HNP successes */
+#define GOTGCS_SRPREQ BIT(1) /*!< SRP request */
+#define GOTGCS_SRPS BIT(0) /*!< SRP successes */
+
+/* global OTG interrupt flag register bits definitions */
+#define GOTGINTF_DF BIT(19) /*!< debounce finish */
+#define GOTGINTF_ADTO BIT(18) /*!< A-device timeout */
+#define GOTGINTF_HNPDET BIT(17) /*!< host negotiation request detected */
+#define GOTGINTF_HNPEND BIT(9) /*!< HNP end */
+#define GOTGINTF_SRPEND BIT(8) /*!< SRP end */
+#define GOTGINTF_SESEND BIT(2) /*!< session end */
+
+/* global AHB control and status register bits definitions */
+#define GAHBCS_PTXFTH BIT(8) /*!< periodic Tx FIFO threshold */
+#define GAHBCS_TXFTH BIT(7) /*!< tx FIFO threshold */
+#define GAHBCS_DMAEN BIT(5) /*!< DMA function Enable */
+#define GAHBCS_BURST BITS(1, 4) /*!< the AHB burst type used by DMA */
+#define GAHBCS_GINTEN BIT(0) /*!< global interrupt enable */
+
+/* global USB control and status register bits definitions */
+#define GUSBCS_FDM BIT(30) /*!< force device mode */
+#define GUSBCS_FHM BIT(29) /*!< force host mode */
+#define GUSBCS_ULPIEOI BIT(21) /*!< ULPI external over-current indicator */
+#define GUSBCS_ULPIEVD BIT(20) /*!< ULPI external VBUS driver */
+#define GUSBCS_UTT BITS(10, 13) /*!< USB turnaround time */
+#define GUSBCS_HNPCEN BIT(9) /*!< HNP capability enable */
+#define GUSBCS_SRPCEN BIT(8) /*!< SRP capability enable */
+#define GUSBCS_EMBPHY BIT(6) /*!< embedded PHY selected */
+#define GUSBCS_TOC BITS(0, 2) /*!< timeout calibration */
+
+/* global reset control register bits definitions */
+#define GRSTCTL_DMAIDL BIT(31) /*!< DMA idle state */
+#define GRSTCTL_DMABSY BIT(30) /*!< DMA busy */
+#define GRSTCTL_TXFNUM BITS(6, 10) /*!< tx FIFO number */
+#define GRSTCTL_TXFF BIT(5) /*!< tx FIFO flush */
+#define GRSTCTL_RXFF BIT(4) /*!< rx FIFO flush */
+#define GRSTCTL_HFCRST BIT(2) /*!< host frame counter reset */
+#define GRSTCTL_HCSRST BIT(1) /*!< HCLK soft reset */
+#define GRSTCTL_CSRST BIT(0) /*!< core soft reset */
+
+/* global interrupt flag register bits definitions */
+#define GINTF_WKUPIF BIT(31) /*!< wakeup interrupt flag */
+#define GINTF_SESIF BIT(30) /*!< session interrupt flag */
+#define GINTF_DISCIF BIT(29) /*!< disconnect interrupt flag */
+#define GINTF_IDPSC BIT(28) /*!< id pin status change */
+#define GINTF_PTXFEIF BIT(26) /*!< periodic tx FIFO empty interrupt flag */
+#define GINTF_HCIF BIT(25) /*!< host channels interrupt flag */
+#define GINTF_HPIF BIT(24) /*!< host port interrupt flag */
+#define GINTF_PXNCIF BIT(21) /*!< periodic transfer not complete interrupt flag */
+#define GINTF_ISOONCIF BIT(21) /*!< isochronous OUT transfer not complete interrupt flag */
+#define GINTF_ISOINCIF BIT(20) /*!< isochronous IN transfer not complete interrupt flag */
+#define GINTF_OEPIF BIT(19) /*!< OUT endpoint interrupt flag */
+#define GINTF_IEPIF BIT(18) /*!< IN endpoint interrupt flag */
+#define GINTF_EOPFIF BIT(15) /*!< end of periodic frame interrupt flag */
+#define GINTF_ISOOPDIF BIT(14) /*!< isochronous OUT packet dropped interrupt flag */
+#define GINTF_ENUMFIF BIT(13) /*!< enumeration finished */
+#define GINTF_RST BIT(12) /*!< USB reset */
+#define GINTF_SP BIT(11) /*!< USB suspend */
+#define GINTF_ESP BIT(10) /*!< early suspend */
+#define GINTF_GONAK BIT(7) /*!< global OUT NAK effective */
+#define GINTF_GNPINAK BIT(6) /*!< global IN non-periodic NAK effective */
+#define GINTF_NPTXFEIF BIT(5) /*!< non-periodic tx FIFO empty interrupt flag */
+#define GINTF_RXFNEIF BIT(4) /*!< rx FIFO non-empty interrupt flag */
+#define GINTF_SOF BIT(3) /*!< start of frame */
+#define GINTF_OTGIF BIT(2) /*!< OTG interrupt flag */
+#define GINTF_MFIF BIT(1) /*!< mode fault interrupt flag */
+#define GINTF_COPM BIT(0) /*!< current operation mode */
+
+/* global interrupt enable register bits definitions */
+#define GINTEN_WKUPIE BIT(31) /*!< wakeup interrupt enable */
+#define GINTEN_SESIE BIT(30) /*!< session interrupt enable */
+#define GINTEN_DISCIE BIT(29) /*!< disconnect interrupt enable */
+#define GINTEN_IDPSCIE BIT(28) /*!< id pin status change interrupt enable */
+#define GINTEN_PTXFEIE BIT(26) /*!< periodic tx FIFO empty interrupt enable */
+#define GINTEN_HCIE BIT(25) /*!< host channels interrupt enable */
+#define GINTEN_HPIE BIT(24) /*!< host port interrupt enable */
+#define GINTEN_IPXIE BIT(21) /*!< periodic transfer not complete interrupt enable */
+#define GINTEN_ISOONCIE BIT(21) /*!< isochronous OUT transfer not complete interrupt enable */
+#define GINTEN_ISOINCIE BIT(20) /*!< isochronous IN transfer not complete interrupt enable */
+#define GINTEN_OEPIE BIT(19) /*!< OUT endpoints interrupt enable */
+#define GINTEN_IEPIE BIT(18) /*!< IN endpoints interrupt enable */
+#define GINTEN_EOPFIE BIT(15) /*!< end of periodic frame interrupt enable */
+#define GINTEN_ISOOPDIE BIT(14) /*!< isochronous OUT packet dropped interrupt enable */
+#define GINTEN_ENUMFIE BIT(13) /*!< enumeration finish enable */
+#define GINTEN_RSTIE BIT(12) /*!< USB reset interrupt enable */
+#define GINTEN_SPIE BIT(11) /*!< USB suspend interrupt enable */
+#define GINTEN_ESPIE BIT(10) /*!< early suspend interrupt enable */
+#define GINTEN_GONAKIE BIT(7) /*!< global OUT NAK effective interrupt enable */
+#define GINTEN_GNPINAKIE BIT(6) /*!< global non-periodic IN NAK effective interrupt enable */
+#define GINTEN_NPTXFEIE BIT(5) /*!< non-periodic Tx FIFO empty interrupt enable */
+#define GINTEN_RXFNEIE BIT(4) /*!< receive FIFO non-empty interrupt enable */
+#define GINTEN_SOFIE BIT(3) /*!< start of frame interrupt enable */
+#define GINTEN_OTGIE BIT(2) /*!< OTG interrupt enable */
+#define GINTEN_MFIE BIT(1) /*!< mode fault interrupt enable */
+
+/* global receive status read and pop register bits definitions */
+#define GRSTATRP_RPCKST BITS(17, 20) /*!< received packet status */
+#define GRSTATRP_DPID BITS(15, 16) /*!< data PID */
+#define GRSTATRP_BCOUNT BITS(4, 14) /*!< byte count */
+#define GRSTATRP_CNUM BITS(0, 3) /*!< channel number */
+#define GRSTATRP_EPNUM BITS(0, 3) /*!< endpoint number */
+
+/* global receive FIFO length register bits definitions */
+#define GRFLEN_RXFD BITS(0, 15) /*!< rx FIFO depth */
+
+/* host non-periodic transmit FIFO length register bits definitions */
+#define HNPTFLEN_HNPTXFD BITS(16, 31) /*!< non-periodic Tx FIFO depth */
+#define HNPTFLEN_HNPTXRSAR BITS(0, 15) /*!< non-periodic Tx RAM start address */
+
+/* USB IN endpoint 0 transmit FIFO length register bits definitions */
+#define DIEP0TFLEN_IEP0TXFD BITS(16, 31) /*!< IN Endpoint 0 Tx FIFO depth */
+#define DIEP0TFLEN_IEP0TXRSAR BITS(0, 15) /*!< IN Endpoint 0 TX RAM start address */
+
+/* host non-periodic transmit FIFO/queue status register bits definitions */
+#define HNPTFQSTAT_NPTXRQTOP BITS(24, 30) /*!< top entry of the non-periodic Tx request queue */
+#define HNPTFQSTAT_NPTXRQS BITS(16, 23) /*!< non-periodic Tx request queue space */
+#define HNPTFQSTAT_NPTXFS BITS(0, 15) /*!< non-periodic Tx FIFO space */
+#define HNPTFQSTAT_CNUM BITS(27, 30) /*!< channel number*/
+#define HNPTFQSTAT_EPNUM BITS(27, 30) /*!< endpoint number */
+#define HNPTFQSTAT_TYPE BITS(25, 26) /*!< token type */
+#define HNPTFQSTAT_TMF BIT(24) /*!< terminate flag */
+
+/* global core configuration register bits definitions */
+#define GCCFG_VBUSIG BIT(21) /*!< vbus ignored */
+#define GCCFG_SOFOEN BIT(20) /*!< SOF output enable */
+#define GCCFG_VBUSBCEN BIT(19) /*!< the VBUS B-device comparer enable */
+#define GCCFG_VBUSACEN BIT(18) /*!< the VBUS A-device comparer enable */
+#define GCCFG_PWRON BIT(16) /*!< power on */
+
+/* core ID register bits definitions */
+#define CID_CID BITS(0, 31) /*!< core ID */
+
+/* host periodic transmit FIFO length register bits definitions */
+#define HPTFLEN_HPTXFD BITS(16, 31) /*!< host periodic Tx FIFO depth */
+#define HPTFLEN_HPTXFSAR BITS(0, 15) /*!< host periodic Tx RAM start address */
+
+/* device IN endpoint transmit FIFO length register bits definitions */
+#define DIEPTFLEN_IEPTXFD BITS(16, 31) /*!< IN endpoint Tx FIFO x depth */
+#define DIEPTFLEN_IEPTXRSAR BITS(0, 15) /*!< IN endpoint FIFOx Tx x RAM start address */
+
+/* host control register bits definitions */
+#define HCTL_SPDFSLS BIT(2) /*!< speed limited to FS and LS */
+#define HCTL_CLKSEL BITS(0, 1) /*!< clock select for USB clock */
+
+/* host frame interval register bits definitions */
+#define HFT_FRI BITS(0, 15) /*!< frame interval */
+
+/* host frame information remaining register bits definitions */
+#define HFINFR_FRT BITS(16, 31) /*!< frame remaining time */
+#define HFINFR_FRNUM BITS(0, 15) /*!< frame number */
+
+/* host periodic transmit FIFO/queue status register bits definitions */
+#define HPTFQSTAT_PTXREQT BITS(24, 31) /*!< top entry of the periodic Tx request queue */
+#define HPTFQSTAT_PTXREQS BITS(16, 23) /*!< periodic Tx request queue space */
+#define HPTFQSTAT_PTXFS BITS(0, 15) /*!< periodic Tx FIFO space */
+#define HPTFQSTAT_OEFRM BIT(31) /*!< odd/eveb frame */
+#define HPTFQSTAT_CNUM BITS(27, 30) /*!< channel number */
+#define HPTFQSTAT_EPNUM BITS(27, 30) /*!< endpoint number */
+#define HPTFQSTAT_TYPE BITS(25, 26) /*!< token type */
+#define HPTFQSTAT_TMF BIT(24) /*!< terminate flag */
+
+#define TFQSTAT_TXFS BITS(0, 15)
+#define TFQSTAT_CNUM BITS(27, 30)
+
+/* host all channels interrupt register bits definitions */
+#define HACHINT_HACHINT BITS(0, 11) /*!< host all channel interrupts */
+
+/* host all channels interrupt enable register bits definitions */
+#define HACHINTEN_CINTEN BITS(0, 11) /*!< channel interrupt enable */
+
+/* host port control and status register bits definitions */
+#define HPCS_PS BITS(17, 18) /*!< port speed */
+#define HPCS_PP BIT(12) /*!< port power */
+#define HPCS_PLST BITS(10, 11) /*!< port line status */
+#define HPCS_PRST BIT(8) /*!< port reset */
+#define HPCS_PSP BIT(7) /*!< port suspend */
+#define HPCS_PREM BIT(6) /*!< port resume */
+#define HPCS_PEDC BIT(3) /*!< port enable/disable change */
+#define HPCS_PE BIT(2) /*!< port enable */
+#define HPCS_PCD BIT(1) /*!< port connect detected */
+#define HPCS_PCST BIT(0) /*!< port connect status */
+
+/* host channel-x control register bits definitions */
+#define HCHCTL_CEN BIT(31) /*!< channel enable */
+#define HCHCTL_CDIS BIT(30) /*!< channel disable */
+#define HCHCTL_ODDFRM BIT(29) /*!< odd frame */
+#define HCHCTL_DAR BITS(22, 28) /*!< device address */
+#define HCHCTL_MPC BITS(20, 21) /*!< multiple packet count */
+#define HCHCTL_EPTYPE BITS(18, 19) /*!< endpoint type */
+#define HCHCTL_LSD BIT(17) /*!< low-speed device */
+#define HCHCTL_EPDIR BIT(15) /*!< endpoint direction */
+#define HCHCTL_EPNUM BITS(11, 14) /*!< endpoint number */
+#define HCHCTL_MPL BITS(0, 10) /*!< maximum packet length */
+
+/* host channel-x split transaction register bits definitions */
+#define HCHSTCTL_SPLEN BIT(31) /*!< enable high-speed split transaction */
+#define HCHSTCTL_CSPLT BIT(16) /*!< complete-split enable */
+#define HCHSTCTL_ISOPCE BITS(14, 15) /*!< isochronous OUT payload continuation encoding */
+#define HCHSTCTL_HADDR BITS(7, 13) /*!< HUB address */
+#define HCHSTCTL_PADDR BITS(0, 6) /*!< port address */
+
+/* host channel-x interrupt flag register bits definitions */
+#define HCHINTF_DTER BIT(10) /*!< data toggle error */
+#define HCHINTF_REQOVR BIT(9) /*!< request queue overrun */
+#define HCHINTF_BBER BIT(8) /*!< babble error */
+#define HCHINTF_USBER BIT(7) /*!< USB bus Error */
+#define HCHINTF_NYET BIT(6) /*!< NYET */
+#define HCHINTF_ACK BIT(5) /*!< ACK */
+#define HCHINTF_NAK BIT(4) /*!< NAK */
+#define HCHINTF_STALL BIT(3) /*!< STALL */
+#define HCHINTF_DMAER BIT(2) /*!< DMA error */
+#define HCHINTF_CH BIT(1) /*!< channel halted */
+#define HCHINTF_TF BIT(0) /*!< transfer finished */
+
+/* host channel-x interrupt enable register bits definitions */
+#define HCHINTEN_DTERIE BIT(10) /*!< data toggle error interrupt enable */
+#define HCHINTEN_REQOVRIE BIT(9) /*!< request queue overrun interrupt enable */
+#define HCHINTEN_BBERIE BIT(8) /*!< babble error interrupt enable */
+#define HCHINTEN_USBERIE BIT(7) /*!< USB bus error interrupt enable */
+#define HCHINTEN_NYETIE BIT(6) /*!< NYET interrupt enable */
+#define HCHINTEN_ACKIE BIT(5) /*!< ACK interrupt enable */
+#define HCHINTEN_NAKIE BIT(4) /*!< NAK interrupt enable */
+#define HCHINTEN_STALLIE BIT(3) /*!< STALL interrupt enable */
+#define HCHINTEN_DMAERIE BIT(2) /*!< DMA error interrupt enable */
+#define HCHINTEN_CHIE BIT(1) /*!< channel halted interrupt enable */
+#define HCHINTEN_TFIE BIT(0) /*!< transfer finished interrupt enable */
+
+/* host channel-x transfer length register bits definitions */
+#define HCHLEN_PING BIT(31) /*!< PING token request */
+#define HCHLEN_DPID BITS(29, 30) /*!< data PID */
+#define HCHLEN_PCNT BITS(19, 28) /*!< packet count */
+#define HCHLEN_TLEN BITS(0, 18) /*!< transfer length */
+
+/* host channel-x DMA address register bits definitions */
+#define HCHDMAADDR_DMAADDR BITS(0, 31) /*!< DMA address */
+
+#define PORT_SPEED(x) (((uint32_t)(x) << 17) & HPCS_PS) /*!< Port speed */
+
+#define PORT_SPEED_HIGH PORT_SPEED(0U) /*!< high speed */
+#define PORT_SPEED_FULL PORT_SPEED(1U) /*!< full speed */
+#define PORT_SPEED_LOW PORT_SPEED(2U) /*!< low speed */
+
+#define PIPE_CTL_DAR(x) (((uint32_t)(x) << 22) & HCHCTL_DAR) /*!< device address */
+#define PIPE_CTL_EPTYPE(x) (((uint32_t)(x) << 18) & HCHCTL_EPTYPE) /*!< endpoint type */
+#define PIPE_CTL_EPNUM(x) (((uint32_t)(x) << 11) & HCHCTL_EPNUM) /*!< endpoint number */
+#define PIPE_CTL_EPDIR(x) (((uint32_t)(x) << 15) & HCHCTL_EPDIR) /*!< endpoint direction */
+#define PIPE_CTL_EPMPL(x) (((uint32_t)(x) << 0) & HCHCTL_MPL) /*!< maximum packet length */
+#define PIPE_CTL_LSD(x) (((uint32_t)(x) << 17) & HCHCTL_LSD) /*!< low-Speed device */
+
+#define PIPE_XFER_PCNT(x) (((uint32_t)(x) << 19) & HCHLEN_PCNT) /*!< packet count */
+#define PIPE_XFER_DPID(x) (((uint32_t)(x) << 29) & HCHLEN_DPID) /*!< data PID */
+
+#define PIPE_DPID_DATA0 PIPE_XFER_DPID(0) /*!< DATA0 */
+#define PIPE_DPID_DATA1 PIPE_XFER_DPID(2) /*!< DATA1 */
+#define PIPE_DPID_DATA2 PIPE_XFER_DPID(1) /*!< DATA2 */
+#define PIPE_DPID_SETUP PIPE_XFER_DPID(3) /*!< MDATA (non-control)/SETUP (control) */
+
+extern const uint32_t PIPE_DPID[2];
+
+/* device configuration registers bits definitions */
+#define DCFG_EOPFT BITS(11, 12) /*!< end of periodic frame time */
+#define DCFG_DAR BITS(4, 10) /*!< device address */
+#define DCFG_NZLSOH BIT(2) /*!< non-zero-length status OUT handshake */
+#define DCFG_DS BITS(0, 1) /*!< device speed */
+
+/* device control registers bits definitions */
+#define DCTL_POIF BIT(11) /*!< power-on initialization finished */
+#define DCTL_CGONAK BIT(10) /*!< clear global OUT NAK */
+#define DCTL_SGONAK BIT(9) /*!< set global OUT NAK */
+#define DCTL_CGINAK BIT(8) /*!< clear global IN NAK */
+#define DCTL_SGINAK BIT(7) /*!< set global IN NAK */
+#define DCTL_GONS BIT(3) /*!< global OUT NAK status */
+#define DCTL_GINS BIT(2) /*!< global IN NAK status */
+#define DCTL_SD BIT(1) /*!< soft disconnect */
+#define DCTL_RWKUP BIT(0) /*!< remote wakeup */
+
+/* device status registers bits definitions */
+#define DSTAT_FNRSOF BITS(8, 21) /*!< the frame number of the received SOF. */
+#define DSTAT_ES BITS(1, 2) /*!< enumerated speed */
+#define DSTAT_SPST BIT(0) /*!< suspend status */
+
+/* device IN endpoint common interrupt enable registers bits definitions */
+#define DIEPINTEN_NAKEN BIT(13) /*!< NAK handshake sent by USBHS interrupt enable bit */
+#define DIEPINTEN_TXFEEN BIT(7) /*!< transmit FIFO empty interrupt enable bit */
+#define DIEPINTEN_IEPNEEN BIT(6) /*!< IN endpoint NAK effective interrupt enable bit */
+#define DIEPINTEN_EPTXFUDEN BIT(4) /*!< endpoint Tx FIFO underrun interrupt enable bit */
+#define DIEPINTEN_CITOEN BIT(3) /*!< control In Timeout interrupt enable bit */
+#define DIEPINTEN_EPDISEN BIT(1) /*!< endpoint disabled interrupt enable bit */
+#define DIEPINTEN_TFEN BIT(0) /*!< transfer finished interrupt enable bit */
+
+/* device OUT endpoint common interrupt enable registers bits definitions */
+#define DOEPINTEN_NYETEN BIT(14) /*!< NYET handshake is sent interrupt enable bit */
+#define DOEPINTEN_BTBSTPEN BIT(6) /*!< back-to-back SETUP packets interrupt enable bit */
+#define DOEPINTEN_EPRXFOVREN BIT(4) /*!< endpoint Rx FIFO overrun interrupt enable bit */
+#define DOEPINTEN_STPFEN BIT(3) /*!< SETUP phase finished interrupt enable bit */
+#define DOEPINTEN_EPDISEN BIT(1) /*!< endpoint disabled interrupt enable bit */
+#define DOEPINTEN_TFEN BIT(0) /*!< transfer finished interrupt enable bit */
+
+/* device all endpoints interrupt registers bits definitions */
+#define DAEPINT_OEPITB BITS(16, 21) /*!< device all OUT endpoint interrupt bits */
+#define DAEPINT_IEPITB BITS(0, 5) /*!< device all IN endpoint interrupt bits */
+
+/* device all endpoints interrupt enable registers bits definitions */
+#define DAEPINTEN_OEPIE BITS(16, 21) /*!< OUT endpoint interrupt enable */
+#define DAEPINTEN_IEPIE BITS(0, 3) /*!< IN endpoint interrupt enable */
+
+/* device Vbus discharge time registers bits definitions */
+#define DVBUSDT_DVBUSDT BITS(0, 15) /*!< device VBUS discharge time */
+
+/* device Vbus pulsing time registers bits definitions */
+#define DVBUSPT_DVBUSPT BITS(0, 11) /*!< device VBUS pulsing time */
+
+/* device IN endpoint FIFO empty interrupt enable register bits definitions */
+#define DIEPFEINTEN_IEPTXFEIE BITS(0, 5) /*!< IN endpoint Tx FIFO empty interrupt enable bits */
+
+/* device endpoint 0 control register bits definitions */
+#define DEP0CTL_EPEN BIT(31) /*!< endpoint enable */
+#define DEP0CTL_EPD BIT(30) /*!< endpoint disable */
+#define DEP0CTL_SNAK BIT(27) /*!< set NAK */
+#define DEP0CTL_CNAK BIT(26) /*!< clear NAK */
+#define DIEP0CTL_TXFNUM BITS(22, 25) /*!< tx FIFO number */
+#define DEP0CTL_STALL BIT(21) /*!< STALL handshake */
+#define DOEP0CTL_SNOOP BIT(20) /*!< snoop mode */
+#define DEP0CTL_EPTYPE BITS(18, 19) /*!< endpoint type */
+#define DEP0CTL_NAKS BIT(17) /*!< NAK status */
+#define DEP0CTL_EPACT BIT(15) /*!< endpoint active */
+#define DEP0CTL_MPL BITS(0, 1) /*!< maximum packet length */
+
+/* device endpoint x control register bits definitions */
+#define DEPCTL_EPEN BIT(31) /*!< endpoint enable */
+#define DEPCTL_EPD BIT(30) /*!< endpoint disable */
+#define DEPCTL_SODDFRM BIT(29) /*!< set odd frame */
+#define DEPCTL_SD1PID BIT(29) /*!< set DATA1 PID */
+#define DEPCTL_SEVNFRM BIT(28) /*!< set even frame */
+#define DEPCTL_SD0PID BIT(28) /*!< set DATA0 PID */
+#define DEPCTL_SNAK BIT(27) /*!< set NAK */
+#define DEPCTL_CNAK BIT(26) /*!< clear NAK */
+#define DIEPCTL_TXFNUM BITS(22, 25) /*!< tx FIFO number */
+#define DEPCTL_STALL BIT(21) /*!< STALL handshake */
+#define DOEPCTL_SNOOP BIT(20) /*!< snoop mode */
+#define DEPCTL_EPTYPE BITS(18, 19) /*!< endpoint type */
+#define DEPCTL_NAKS BIT(17) /*!< NAK status */
+#define DEPCTL_EOFRM BIT(16) /*!< even/odd frame */
+#define DEPCTL_DPID BIT(16) /*!< endpoint data PID */
+#define DEPCTL_EPACT BIT(15) /*!< endpoint active */
+#define DEPCTL_MPL BITS(0, 10) /*!< maximum packet length */
+
+/* device IN endpoint-x interrupt flag register bits definitions */
+#define DIEPINTF_NAK BIT(13) /*!< NAK handshake sent by USBHS */
+#define DIEPINTF_TXFE BIT(7) /*!< transmit FIFO empty */
+#define DIEPINTF_IEPNE BIT(6) /*!< IN endpoint NAK effective */
+#define DIEPINTF_EPTXFUD BIT(4) /*!< endpoint Tx FIFO underrun */
+#define DIEPINTF_CITO BIT(3) /*!< control In Timeout interrupt */
+#define DIEPINTF_EPDIS BIT(1) /*!< endpoint disabled */
+#define DIEPINTF_TF BIT(0) /*!< transfer finished */
+
+/* device OUT endpoint-x interrupt flag register bits definitions */
+#define DOEPINTF_NYET BIT(14) /*!< NYET handshake is sent */
+#define DOEPINTF_BTBSTP BIT(6) /*!< back-to-back SETUP packets */
+#define DOEPINTF_EPRXFOVR BIT(4) /*!< endpoint Rx FIFO overrun */
+#define DOEPINTF_STPF BIT(3) /*!< SETUP phase finished */
+#define DOEPINTF_EPDIS BIT(1) /*!< endpoint disabled */
+#define DOEPINTF_TF BIT(0) /*!< transfer finished */
+
+/* device IN endpoint 0 transfer length register bits definitions */
+#define DIEP0LEN_PCNT BITS(19, 20) /*!< packet count */
+#define DIEP0LEN_TLEN BITS(0, 6) /*!< transfer length */
+
+/* device OUT endpoint 0 transfer length register bits definitions */
+#define DOEP0LEN_STPCNT BITS(29, 30) /*!< SETUP packet count */
+#define DOEP0LEN_PCNT BIT(19) /*!< packet count */
+#define DOEP0LEN_TLEN BITS(0, 6) /*!< transfer length */
+
+/* device OUT endpoint-x transfer length register bits definitions */
+#define DOEPLEN_RXDPID BITS(29, 30) /*!< received data PID */
+#define DOEPLEN_STPCNT BITS(29, 30) /*!< SETUP packet count */
+#define DIEPLEN_MCNT BITS(29, 30) /*!< multi count */
+#define DEPLEN_PCNT BITS(19, 28) /*!< packet count */
+#define DEPLEN_TLEN BITS(0, 18) /*!< transfer length */
+
+/* device IN endpoint-x DMA address register bits definitions */
+#define DIEPDMAADDR_DMAADDR BITS(0, 31) /*!< DMA address */
+
+/* device OUT endpoint-x DMA address register bits definitions */
+#define DOEPDMAADDR_DMAADDR BITS(0, 31) /*!< DMA address */
+
+/* device IN endpoint-x transmit FIFO status register bits definitions */
+#define DIEPTFSTAT_IEPTFS BITS(0, 15) /*!< IN endpoint Tx FIFO space remaining */
+
+/* USB power and clock registers bits definition */
+#define PWRCLKCTL_SHCLK BIT(1) /*!< stop HCLK */
+#define PWRCLKCTL_SUCLK BIT(0) /*!< stop the USB clock */
+
+#define RSTAT_GOUT_NAK 1U /* global OUT NAK (triggers an interrupt) */
+#define RSTAT_DATA_UPDT 2U /* OUT data packet received */
+#define RSTAT_XFER_COMP 3U /* OUT transfer completed (triggers an interrupt) */
+#define RSTAT_SETUP_COMP 4U /* SETUP transaction completed (triggers an interrupt) */
+#define RSTAT_SETUP_UPDT 6U /* SETUP data packet received */
+
+#define DSTAT_EM_HS_PHY_30MHZ_60MHZ 0U /* USB enumerate speed use high-speed PHY clock in 30MHz or 60MHz */
+#define DSTAT_EM_FS_PHY_30MHZ_60MHZ 1U /* USB enumerate speed use full-speed PHY clock in 30MHz or 60MHz */
+#define DSTAT_EM_LS_PHY_6MHZ 2U /* USB enumerate speed use low-speed PHY clock in 6MHz */
+#define DSTAT_EM_FS_PHY_48MHZ 3U /* USB enumerate speed use full-speed PHY clock in 48MHz */
+
+#define DPID_DATA0 0U /* device endpoint data PID is DATA0 */
+#define DPID_DATA1 2U /* device endpoint data PID is DATA1 */
+#define DPID_DATA2 1U /* device endpoint data PID is DATA2 */
+#define DPID_MDATA 3U /* device endpoint data PID is MDATA */
+
+#define GAHBCS_DMAINCR(regval) (GAHBCS_BURST & ((regval) << 1)) /*!< AHB burst type used by DMA*/
+
+#define DMA_INCR0 GAHBCS_DMAINCR(0U) /*!< single burst type used by DMA*/
+#define DMA_INCR1 GAHBCS_DMAINCR(1U) /*!< 4-beat incrementing burst type used by DMA*/
+#define DMA_INCR4 GAHBCS_DMAINCR(3U) /*!< 8-beat incrementing burst type used by DMA*/
+#define DMA_INCR8 GAHBCS_DMAINCR(5U) /*!< 16-beat incrementing burst type used by DMA*/
+#define DMA_INCR16 GAHBCS_DMAINCR(7U) /*!< 32-beat incrementing burst type used by DMA*/
+
+#define DCFG_PFRI(regval) (DCFG_EOPFT & ((regval) << 11)) /*!< end of periodic frame time configuration */
+
+#define FRAME_INTERVAL_80 DCFG_PFRI(0U) /*!< 80% of the frame time */
+#define FRAME_INTERVAL_85 DCFG_PFRI(1U) /*!< 85% of the frame time */
+#define FRAME_INTERVAL_90 DCFG_PFRI(2U) /*!< 90% of the frame time */
+#define FRAME_INTERVAL_95 DCFG_PFRI(3U) /*!< 95% of the frame time */
+
+#define DCFG_DEVSPEED(regval) (DCFG_DS & ((regval) << 0)) /*!< device speed configuration */
+
+#define USB_SPEED_EXP_HIGH DCFG_DEVSPEED(0U) /*!< device external PHY high speed */
+#define USB_SPEED_EXP_FULL DCFG_DEVSPEED(1U) /*!< device external PHY full speed */
+#define USB_SPEED_INP_FULL DCFG_DEVSPEED(3U) /*!< device internal PHY full speed */
+
+#define DEP0_MPL(regval) (DEP0CTL_MPL & ((regval) << 0)) /*!< maximum packet length configuration */
+
+#define EP0MPL_64 DEP0_MPL(0U) /*!< maximum packet length 64 bytes */
+#define EP0MPL_32 DEP0_MPL(1U) /*!< maximum packet length 32 bytes */
+#define EP0MPL_16 DEP0_MPL(2U) /*!< maximum packet length 16 bytes */
+#define EP0MPL_8 DEP0_MPL(3U) /*!< maximum packet length 8 bytes */
+
+#define DOEP0_TLEN(regval) (DOEP0LEN_TLEN & ((regval) << 0)) /*!< Transfer length */
+#define DOEP0_PCNT(regval) (DOEP0LEN_PCNT & ((regval) << 19)) /*!< Packet count */
+#define DOEP0_STPCNT(regval) (DOEP0LEN_STPCNT & ((regval) << 29)) /*!< SETUP packet count */
+
+#define USB_ULPI_PHY 1U /*!< ULPI interface external PHY */
+#define USB_EMBEDDED_PHY 2U /*!< Embedded PHY */
+
+#define GRXSTS_PKTSTS_IN 2U
+#define GRXSTS_PKTSTS_IN_XFER_COMP 3U
+#define GRXSTS_PKTSTS_DATA_TOGGLE_ERR 5U
+#define GRXSTS_PKTSTS_CH_HALTED 7U
+
+#define HCTL_30_60MHZ 0U /*!< USB clock 30-60MHZ */
+#define HCTL_48MHZ 1U /*!< USB clock 48MHZ */
+#define HCTL_6MHZ 2U /*!< USB clock 6MHZ */
+
+#define EP0_OUT ((uint8_t)0x00) /*!< endpoint out 0 */
+#define EP0_IN ((uint8_t)0x80) /*!< endpoint in 0 */
+#define EP1_OUT ((uint8_t)0x01) /*!< endpoint out 1 */
+#define EP1_IN ((uint8_t)0x81) /*!< endpoint in 1 */
+#define EP2_OUT ((uint8_t)0x02) /*!< endpoint out 2 */
+#define EP2_IN ((uint8_t)0x82) /*!< endpoint in 2 */
+#define EP3_OUT ((uint8_t)0x03) /*!< endpoint out 3 */
+#define EP3_IN ((uint8_t)0x83) /*!< endpoint in 3 */
+
+#endif /* __DRV_USB_REGS_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/driver/Include/drv_usbd_int.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/driver/Include/drv_usbd_int.h
new file mode 100644
index 00000000..48919a7e
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/driver/Include/drv_usbd_int.h
@@ -0,0 +1,45 @@
+/*!
+ \file drv_usbd_int.h
+ \brief USB device mode interrupt header file
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __DRV_USBD_INT_H
+#define __DRV_USBD_INT_H
+
+#include "drv_usb_core.h"
+#include "drv_usb_dev.h"
+
+/* function declarations */
+/* USB device-mode interrupts global service routine handler */
+void usbd_isr(usb_core_driver *udev);
+
+#endif /* __DRV_USBD_INT_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/driver/Include/drv_usbh_int.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/driver/Include/drv_usbh_int.h
new file mode 100644
index 00000000..e8ce7b52
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/driver/Include/drv_usbh_int.h
@@ -0,0 +1,55 @@
+/*!
+ \file drv_usbh_int.h.h
+ \brief USB host mode interrupt management header file
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __DRV_USBH_INT_H
+#define __DRV_USBH_INT_H
+
+#include "drv_usb_host.h"
+#include "usbh_core.h"
+
+typedef struct _usbh_int_cb {
+ uint8_t (*connect)(usbh_host *puhost);
+ uint8_t (*disconnect)(usbh_host *puhost);
+ uint8_t (*port_enabled)(usbh_host *puhost);
+ uint8_t (*port_disabled)(usbh_host *puhost);
+ uint8_t (*SOF)(usbh_host *puhost);
+} usbh_int_cb;
+
+extern usbh_int_cb *usbh_int_fop;
+
+/* function declarations */
+/* handle global host interrupt */
+uint32_t usbh_isr(usb_core_driver *pudev);
+
+#endif /* __DRV_USBH_INT_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/driver/Source/drv_usb_core.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/driver/Source/drv_usb_core.c
new file mode 100644
index 00000000..7c8accd2
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/driver/Source/drv_usb_core.c
@@ -0,0 +1,343 @@
+/*!
+ \file drv_usb_core.c
+ \brief USB core driver which can operate in host and device mode
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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.
+*/
+
+#include "drv_usb_core.h"
+#include "drv_usb_hw.h"
+
+/* local function prototypes ('static') */
+static void usb_core_reset(usb_core_regs *usb_regs);
+
+/*!
+ \brief configure USB core basic
+ \param[in] usb_basic: pointer to usb capabilities
+ \param[in] usb_regs: USB core registers
+ \param[in] usb_core: USB core
+ \param[out] none
+ \retval operation status
+*/
+usb_status usb_basic_init(usb_core_basic *usb_basic,
+ usb_core_regs *usb_regs,
+ usb_core_enum usb_core)
+{
+ /* configure USB default transfer mode as FIFO mode */
+ usb_basic->transfer_mode = (uint8_t)USB_USE_FIFO;
+
+ /* USB default speed is full-speed */
+ usb_basic->core_speed = (uint8_t)USB_SPEED_FULL;
+
+ usb_basic->core_enum = (uint8_t)usb_core;
+
+ switch(usb_core) {
+ case USB_CORE_ENUM_FS:
+ usb_basic->base_reg = (uint32_t)USBFS_REG_BASE;
+
+ /* set the host channel numbers */
+ usb_basic->num_pipe = USBFS_MAX_CHANNEL_COUNT;
+
+ /* set the device endpoint numbers */
+ usb_basic->num_ep = USBFS_MAX_EP_COUNT;
+
+ /* USBFS core use embedded physical layer */
+ usb_basic->phy_itf = USB_EMBEDDED_PHY;
+ break;
+
+ default:
+ return USB_FAIL;
+ }
+
+ usb_basic->sof_enable = USB_SOF_OUTPUT;
+ usb_basic->low_power = USB_LOW_POWER;
+
+ /* assign main registers address */
+ *usb_regs = (usb_core_regs) {
+ .gr = (usb_gr *)(usb_basic->base_reg + USB_REG_OFFSET_CORE),
+ .hr = (usb_hr *)(usb_basic->base_reg + USB_REG_OFFSET_HOST),
+ .dr = (usb_dr *)(usb_basic->base_reg + USB_REG_OFFSET_DEV),
+
+ .HPCS = (uint32_t *)(usb_basic->base_reg + USB_REG_OFFSET_PORT),
+ .PWRCLKCTL = (uint32_t *)(usb_basic->base_reg + USB_REG_OFFSET_PWRCLKCTL)
+ };
+
+ /* assign device endpoint registers address */
+ for(uint8_t i = 0U; i < usb_basic->num_ep; i++) {
+ usb_regs->er_in[i] = (usb_erin *) \
+ (usb_basic->base_reg + USB_REG_OFFSET_EP_IN + (i * USB_REG_OFFSET_EP));
+
+ usb_regs->er_out[i] = (usb_erout *)\
+ (usb_basic->base_reg + USB_REG_OFFSET_EP_OUT + (i * USB_REG_OFFSET_EP));
+ }
+
+ /* assign host pipe registers address */
+ for(uint8_t i = 0U; i < usb_basic->num_pipe; i++) {
+ usb_regs->pr[i] = (usb_pr *) \
+ (usb_basic->base_reg + USB_REG_OFFSET_CH_INOUT + (i * USB_REG_OFFSET_CH));
+
+ usb_regs->DFIFO[i] = (uint32_t *) \
+ (usb_basic->base_reg + USB_DATA_FIFO_OFFSET + (i * USB_DATA_FIFO_SIZE));
+ }
+
+ return USB_OK;
+}
+
+/*!
+ \brief initializes the USB controller registers and
+ prepares the core device mode or host mode operation
+ \param[in] usb_basic: pointer to USB capabilities
+ \param[in] usb_regs: pointer to USB core registers
+ \param[out] none
+ \retval operation status
+*/
+usb_status usb_core_init(usb_core_basic usb_basic, usb_core_regs *usb_regs)
+{
+ if(USB_ULPI_PHY == usb_basic.phy_itf) {
+ usb_regs->gr->GCCFG &= ~GCCFG_PWRON;
+
+ if(usb_basic.sof_enable) {
+ usb_regs->gr->GCCFG |= GCCFG_SOFOEN;
+ }
+
+ /* init the ULPI interface */
+ usb_regs->gr->GUSBCS &= ~(GUSBCS_EMBPHY | GUSBCS_ULPIEOI);
+
+#ifdef USBHS_EXTERNAL_VBUS_ENABLED
+ /* use external VBUS driver */
+ usb_regs->gr->GUSBCS |= GUSBCS_ULPIEVD;
+#else
+ /* use internal VBUS driver */
+ usb_regs->gr->GUSBCS &= ~GUSBCS_ULPIEVD;
+#endif /* USBHS_EXTERNAL_VBUS_ENABLED */
+
+ /* soft reset the core */
+ usb_core_reset(usb_regs);
+ } else {
+ usb_regs->gr->GUSBCS |= GUSBCS_EMBPHY;
+
+ /* soft reset the core */
+ usb_core_reset(usb_regs);
+
+ /* active the transceiver and enable VBUS sensing */
+ usb_regs->gr->GCCFG |= GCCFG_PWRON | GCCFG_VBUSACEN | GCCFG_VBUSBCEN;
+
+#ifndef VBUS_SENSING_ENABLED
+ usb_regs->gr->GCCFG |= GCCFG_VBUSIG;
+#endif /* VBUS_SENSING_ENABLED */
+
+ /* enable SOF output */
+ if(usb_basic.sof_enable) {
+ usb_regs->gr->GCCFG |= GCCFG_SOFOEN;
+ }
+
+ usb_mdelay(20U);
+ }
+
+ if((uint8_t)USB_USE_DMA == usb_basic.transfer_mode) {
+ usb_regs->gr->GAHBCS &= ~GAHBCS_BURST;
+ usb_regs->gr->GAHBCS |= DMA_INCR8 | GAHBCS_DMAEN;
+ }
+
+#ifdef USE_OTG_MODE
+
+ /* enable USB OTG features */
+ usb_regs->gr->GUSBCS |= GUSBCS_HNPCEN | GUSBCS_SRPCEN;
+
+ /* enable the USB wakeup and suspend interrupts */
+ usb_regs->gr->GINTF = 0xBFFFFFFFU;
+
+ usb_regs->gr->GINTEN = GINTEN_WKUPIE | GINTEN_SPIE | \
+ GINTEN_OTGIE | GINTEN_SESIE | GINTEN_CIDPSCIE;
+
+#endif /* USE_OTG_MODE */
+
+ return USB_OK;
+}
+
+/*!
+ \brief write a packet into the Tx FIFO associated with the endpoint
+ \param[in] usb_regs: pointer to USB core registers
+ \param[in] src_buf: pointer to source buffer
+ \param[in] fifo_num: FIFO number which is in (0..3)
+ \param[in] byte_count: packet byte count
+ \param[out] none
+ \retval operation status
+*/
+usb_status usb_txfifo_write(usb_core_regs *usb_regs,
+ uint8_t *src_buf,
+ uint8_t fifo_num,
+ uint16_t byte_count)
+{
+ uint32_t word_count = (byte_count + 3U) / 4U;
+
+ __IO uint32_t *fifo = usb_regs->DFIFO[fifo_num];
+
+ while(word_count-- > 0U) {
+ *fifo = *((__packed uint32_t *)src_buf);
+
+ src_buf += 4U;
+ }
+
+ return USB_OK;
+}
+
+/*!
+ \brief read a packet from the Rx FIFO associated with the endpoint
+ \param[in] usb_regs: pointer to USB core registers
+ \param[in] dest_buf: pointer to destination buffer
+ \param[in] byte_count: packet byte count
+ \param[out] none
+ \retval void type pointer
+*/
+void *usb_rxfifo_read(usb_core_regs *usb_regs, uint8_t *dest_buf, uint16_t byte_count)
+{
+ uint32_t word_count = (byte_count + 3U) / 4U;
+
+ __IO uint32_t *fifo = usb_regs->DFIFO[0];
+
+ while(word_count-- > 0U) {
+ *(__packed uint32_t *)dest_buf = *fifo;
+
+ dest_buf += 4U;
+ }
+
+ return ((void *)dest_buf);
+}
+
+/*!
+ \brief flush a Tx FIFO or all Tx FIFOs
+ \param[in] usb_regs: pointer to USB core registers
+ \param[in] fifo_num: FIFO number which is in (0..3)
+ \param[out] none
+ \retval operation status
+*/
+usb_status usb_txfifo_flush(usb_core_regs *usb_regs, uint8_t fifo_num)
+{
+ usb_regs->gr->GRSTCTL = ((uint32_t)fifo_num << 6U) | GRSTCTL_TXFF;
+
+ /* wait for Tx FIFO flush bit is set */
+ while(usb_regs->gr->GRSTCTL & GRSTCTL_TXFF) {
+ /* no operation */
+ }
+
+ /* wait for 3 PHY clocks*/
+ usb_udelay(3U);
+
+ return USB_OK;
+}
+
+/*!
+ \brief flush the entire Rx FIFO
+ \param[in] usb_regs: pointer to usb core registers
+ \param[out] none
+ \retval operation status
+*/
+usb_status usb_rxfifo_flush(usb_core_regs *usb_regs)
+{
+ usb_regs->gr->GRSTCTL = GRSTCTL_RXFF;
+
+ /* wait for Rx FIFO flush bit is set */
+ while(usb_regs->gr->GRSTCTL & GRSTCTL_RXFF) {
+ /* no operation */
+ }
+
+ /* wait for 3 PHY clocks */
+ usb_udelay(3U);
+
+ return USB_OK;
+}
+
+/*!
+ \brief set endpoint or channel TX FIFO size
+ \param[in] usb_regs: pointer to USB core registers
+ \param[in] fifo: TX FIFO number
+ \param[in] size: assigned TX FIFO size
+ \param[out] none
+ \retval none
+*/
+void usb_set_txfifo(usb_core_regs *usb_regs, uint8_t fifo, uint16_t size)
+{
+ uint32_t tx_offset;
+
+ tx_offset = usb_regs->gr->GRFLEN;
+
+ if(fifo == 0U) {
+ usb_regs->gr->DIEP0TFLEN_HNPTFLEN = ((uint32_t)size << 16) | tx_offset;
+ } else {
+ tx_offset += (usb_regs->gr->DIEP0TFLEN_HNPTFLEN) >> 16;
+
+ for(uint8_t i = 0U; i < (fifo - 1U); i++) {
+ tx_offset += (usb_regs->gr->DIEPTFLEN[i] >> 16);
+ }
+
+ /* Multiply Tx_Size by 2 to get higher performance */
+ usb_regs->gr->DIEPTFLEN[fifo - 1U] = ((uint32_t)size << 16) | tx_offset;
+ }
+}
+
+/*!
+ \brief set USB current mode
+ \param[in] usb_regs: pointer to USB core registers
+ \param[out] none
+ \retval none
+*/
+void usb_curmode_set(usb_core_regs *usb_regs, uint8_t mode)
+{
+ usb_regs->gr->GUSBCS &= ~(GUSBCS_FDM | GUSBCS_FHM);
+
+ if(DEVICE_MODE == mode) {
+ usb_regs->gr->GUSBCS |= GUSBCS_FDM;
+ } else if(HOST_MODE == mode) {
+ usb_regs->gr->GUSBCS |= GUSBCS_FHM;
+ } else {
+ /* OTG mode and other mode can not be here! */
+ }
+}
+
+/*!
+ \brief configure USB core to soft reset
+ \param[in] usb_regs: pointer to USB core registers
+ \param[out] none
+ \retval none
+*/
+static void usb_core_reset(usb_core_regs *usb_regs)
+{
+ /* enable core soft reset */
+ usb_regs->gr->GRSTCTL |= GRSTCTL_CSRST;
+
+ /* wait for the core to be soft reset */
+ while(usb_regs->gr->GRSTCTL & GRSTCTL_CSRST) {
+ /* no operation */
+ }
+
+ /* wait for additional 3 PHY clocks */
+ usb_udelay(3U);
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/driver/Source/drv_usb_dev.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/driver/Source/drv_usb_dev.c
new file mode 100644
index 00000000..3b00ab01
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/driver/Source/drv_usb_dev.c
@@ -0,0 +1,609 @@
+/*!
+ \file drv_usb_dev.c
+ \brief USB device mode low level driver
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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.
+*/
+
+#include "drv_usb_hw.h"
+#include "drv_usb_core.h"
+#include "drv_usb_dev.h"
+
+/* endpoint 0 max packet length */
+static const uint8_t EP0_MAXLEN[4] = {
+ [DSTAT_EM_HS_PHY_30MHZ_60MHZ] = EP0MPL_64,
+ [DSTAT_EM_FS_PHY_30MHZ_60MHZ] = EP0MPL_64,
+ [DSTAT_EM_FS_PHY_48MHZ] = EP0MPL_64,
+ [DSTAT_EM_LS_PHY_6MHZ] = EP0MPL_8
+};
+
+#ifdef USB_FS_CORE
+
+/* USB endpoint Tx FIFO size */
+static uint16_t USBFS_TX_FIFO_SIZE[USBFS_MAX_EP_COUNT] = {
+ (uint16_t)TX0_FIFO_FS_SIZE,
+ (uint16_t)TX1_FIFO_FS_SIZE,
+ (uint16_t)TX2_FIFO_FS_SIZE,
+ (uint16_t)TX3_FIFO_FS_SIZE
+};
+
+#endif /* USBFS_CORE */
+
+/*!
+ \brief initialize USB core registers for device mode
+ \param[in] udev: pointer to USB device
+ \param[out] none
+ \retval operation status
+*/
+usb_status usb_devcore_init(usb_core_driver *udev)
+{
+ uint8_t i;
+
+ /* restart the PHY clock (maybe don't need to...) */
+ *udev->regs.PWRCLKCTL = 0U;
+
+ /* config periodic frame interval to default value */
+ udev->regs.dr->DCFG &= ~DCFG_EOPFT;
+ udev->regs.dr->DCFG |= FRAME_INTERVAL_80;
+
+ udev->regs.dr->DCFG &= ~DCFG_DS;
+
+#ifdef USB_FS_CORE
+ if(udev->bp.core_enum == (uint8_t)USB_CORE_ENUM_FS) {
+ /* set full-speed PHY */
+ udev->regs.dr->DCFG |= USB_SPEED_INP_FULL;
+
+ /* set Rx FIFO size */
+ usb_set_rxfifo(&udev->regs, RX_FIFO_FS_SIZE);
+
+ /* set endpoint 0 to 3's Tx FIFO length and RAM address */
+ for(i = 0U; i < USBFS_MAX_EP_COUNT; i++) {
+ usb_set_txfifo(&udev->regs, i, USBFS_TX_FIFO_SIZE[i]);
+ }
+ }
+#endif /* USB_FS_CORE */
+
+ /* make sure all FIFOs are flushed */
+
+ /* flush all Tx FIFOs */
+ (void)usb_txfifo_flush(&udev->regs, 0x10U);
+
+ /* flush entire Rx FIFO */
+ (void)usb_rxfifo_flush(&udev->regs);
+
+ /* clear all pending device interrupts */
+ udev->regs.dr->DIEPINTEN = 0U;
+ udev->regs.dr->DOEPINTEN = 0U;
+ udev->regs.dr->DAEPINT = 0xFFFFFFFFU;
+ udev->regs.dr->DAEPINTEN = 0U;
+
+ /* configure all IN/OUT endpoints */
+ for(i = 0U; i < udev->bp.num_ep; i++) {
+ if(udev->regs.er_in[i]->DIEPCTL & DEPCTL_EPEN) {
+ udev->regs.er_in[i]->DIEPCTL |= DEPCTL_EPD | DEPCTL_SNAK;
+ } else {
+ udev->regs.er_in[i]->DIEPCTL = 0U;
+ }
+
+ /* set IN endpoint transfer length to 0 */
+ udev->regs.er_in[i]->DIEPLEN = 0U;
+
+ /* clear all pending IN endpoint interrupts */
+ udev->regs.er_in[i]->DIEPINTF = 0xFFU;
+
+ if(udev->regs.er_out[i]->DOEPCTL & DEPCTL_EPEN) {
+ udev->regs.er_out[i]->DOEPCTL |= DEPCTL_EPD | DEPCTL_SNAK;
+ } else {
+ udev->regs.er_out[i]->DOEPCTL = 0U;
+ }
+
+ /* set OUT endpoint transfer length to 0 */
+ udev->regs.er_out[i]->DOEPLEN = 0U;
+
+ /* clear all pending OUT endpoint interrupts */
+ udev->regs.er_out[i]->DOEPINTF = 0xFFU;
+ }
+
+ udev->regs.dr->DIEPINTEN |= DIEPINTEN_EPTXFUDEN;
+
+ (void)usb_devint_enable(udev);
+
+ return USB_OK;
+}
+
+/*!
+ \brief enable the USB device mode interrupts
+ \param[in] udev: pointer to USB device
+ \param[out] none
+ \retval operation status
+*/
+usb_status usb_devint_enable(usb_core_driver *udev)
+{
+ /* clear any pending USB OTG interrupts */
+ udev->regs.gr->GOTGINTF = 0xFFFFFFFFU;
+
+ /* clear any pending interrupts */
+ udev->regs.gr->GINTF = 0xBFFFFFFFU;
+
+ /* enable the USB wakeup and suspend interrupts */
+ udev->regs.gr->GINTEN = GINTEN_WKUPIE | GINTEN_SPIE;
+
+ /* enable device_mode-related interrupts */
+ if((uint8_t)USB_USE_FIFO == udev->bp.transfer_mode) {
+ udev->regs.gr->GINTEN |= GINTEN_RXFNEIE;
+ }
+
+ udev->regs.gr->GINTEN |= GINTEN_RSTIE | GINTEN_ENUMFIE | GINTEN_IEPIE | \
+ GINTEN_OEPIE | GINTEN_SOFIE | GINTEN_ISOONCIE | GINTEN_ISOINCIE;
+
+#ifdef VBUS_SENSING_ENABLED
+ udev->regs.gr->GINTEN |= GINTEN_SESIE | GINTEN_OTGIE;
+#endif /* VBUS_SENSING_ENABLED */
+
+ return USB_OK;
+}
+
+/*!
+ \brief active the USB endpoint0 transaction
+ \param[in] udev: pointer to USB device
+ \param[in] transc: the USB endpoint0 transaction
+ \param[out] none
+ \retval operation status
+*/
+usb_status usb_transc0_active(usb_core_driver *udev, usb_transc *transc)
+{
+ __IO uint32_t *reg_addr = NULL;
+
+ /* get the endpoint number */
+ uint8_t ep_num = transc->ep_addr.num;
+
+ if(ep_num) {
+ /* not endpoint 0 */
+ return USB_FAIL;
+ }
+
+ if(transc->ep_addr.dir) {
+ reg_addr = &udev->regs.er_in[0]->DIEPCTL;
+ } else {
+ reg_addr = &udev->regs.er_out[0]->DOEPCTL;
+ }
+
+ /* endpoint 0 is activated after USB clock is enabled */
+
+ *reg_addr &= ~(DEPCTL_MPL | DEPCTL_EPTYPE | DIEPCTL_TXFNUM);
+
+ /* set endpoint 0 maximum packet length */
+ *reg_addr |= EP0_MAXLEN[udev->regs.dr->DSTAT & DSTAT_ES];
+
+ /* activate endpoint */
+ *reg_addr |= ((uint32_t)transc->ep_type << 18U) | ((uint32_t)ep_num << 22U) | DEPCTL_SD0PID | DEPCTL_EPACT;
+
+ return USB_OK;
+}
+
+/*!
+ \brief active the USB transaction
+ \param[in] udev: pointer to USB device
+ \param[in] transc: the USB transaction
+ \param[out] none
+ \retval status
+*/
+usb_status usb_transc_active(usb_core_driver *udev, usb_transc *transc)
+{
+ __IO uint32_t *reg_addr = NULL;
+ __IO uint32_t epinten = 0U;
+
+ /* get the endpoint number */
+ uint8_t ep_num = transc->ep_addr.num;
+
+ /* enable endpoint interrupt number */
+ if(transc->ep_addr.dir) {
+ reg_addr = &udev->regs.er_in[ep_num]->DIEPCTL;
+
+ epinten = 1U << ep_num;
+ } else {
+ reg_addr = &udev->regs.er_out[ep_num]->DOEPCTL;
+
+ epinten = 1U << (16U + ep_num);
+ }
+
+ /* if the endpoint is not active, need change the endpoint control register */
+ if(!(*reg_addr & DEPCTL_EPACT)) {
+ *reg_addr &= ~(DEPCTL_MPL | DEPCTL_EPTYPE | DIEPCTL_TXFNUM);
+
+ /* set endpoint maximum packet length */
+ if(0U == ep_num) {
+ *reg_addr |= EP0_MAXLEN[udev->regs.dr->DSTAT & DSTAT_ES];
+ } else {
+ *reg_addr |= transc->max_len;
+ }
+
+ /* activate endpoint */
+ *reg_addr |= ((uint32_t)transc->ep_type << 18U) | ((uint32_t)ep_num << 22U) | DEPCTL_SD0PID | DEPCTL_EPACT;
+ }
+
+
+ /* enable the interrupts for this endpoint */
+ udev->regs.dr->DAEPINTEN |= epinten;
+
+ return USB_OK;
+}
+
+/*!
+ \brief deactivate the USB transaction
+ \param[in] udev: pointer to USB device
+ \param[in] transc: the USB transaction
+ \param[out] none
+ \retval status
+*/
+usb_status usb_transc_deactivate(usb_core_driver *udev, usb_transc *transc)
+{
+ uint32_t epinten = 0U;
+
+ uint8_t ep_num = transc->ep_addr.num;
+
+ /* disable endpoint interrupt number */
+ if(transc->ep_addr.dir) {
+ epinten = 1U << ep_num;
+
+ udev->regs.er_in[ep_num]->DIEPCTL &= ~DEPCTL_EPACT;
+ } else {
+ epinten = 1U << (ep_num + 16U);
+
+ udev->regs.er_out[ep_num]->DOEPCTL &= ~DEPCTL_EPACT;
+ }
+
+
+ /* disable the interrupts for this endpoint */
+ udev->regs.dr->DAEPINTEN &= ~epinten;
+
+ return USB_OK;
+}
+
+/*!
+ \brief configure USB transaction to start IN transfer
+ \param[in] udev: pointer to USB device
+ \param[in] transc: the USB IN transaction
+ \param[out] none
+ \retval operation status
+*/
+usb_status usb_transc_inxfer(usb_core_driver *udev, usb_transc *transc)
+{
+ usb_status status = USB_OK;
+
+ uint8_t ep_num = transc->ep_addr.num;
+
+ __IO uint32_t epctl = udev->regs.er_in[ep_num]->DIEPCTL;
+ __IO uint32_t eplen = udev->regs.er_in[ep_num]->DIEPLEN;
+
+ eplen &= ~(DEPLEN_TLEN | DEPLEN_PCNT);
+
+ /* zero length packet or endpoint 0 */
+ if(0U == transc->xfer_len) {
+ /* set transfer packet count to 1 */
+ eplen |= 1U << 19U;
+ } else {
+ /* set transfer packet count */
+ if(0U == ep_num) {
+ transc->xfer_len = USB_MIN(transc->xfer_len, transc->max_len);
+
+ eplen |= 1U << 19U;
+ } else {
+ eplen |= (((transc->xfer_len - 1U) + transc->max_len) / transc->max_len) << 19U;
+ }
+
+ /* set endpoint transfer length */
+ eplen |= transc->xfer_len;
+
+ if(transc->ep_type == (uint8_t)USB_EPTYPE_ISOC) {
+ eplen |= DIEPLEN_MCNT & (1U << 29U);
+ }
+ }
+
+ udev->regs.er_in[ep_num]->DIEPLEN = eplen;
+
+ if(transc->ep_type == (uint8_t)USB_EPTYPE_ISOC) {
+ if(((udev->regs.dr->DSTAT & DSTAT_FNRSOF) >> 8U) & 0x01U) {
+ epctl |= DEPCTL_SEVNFRM;
+ } else {
+ epctl |= DEPCTL_SODDFRM;
+ }
+ }
+
+ if((uint8_t)USB_USE_DMA == udev->bp.transfer_mode) {
+ udev->regs.er_in[ep_num]->DIEPDMAADDR = transc->dma_addr;
+ }
+
+ /* enable the endpoint and clear the NAK */
+ epctl |= DEPCTL_CNAK | DEPCTL_EPEN;
+
+ udev->regs.er_in[ep_num]->DIEPCTL = epctl;
+
+ if((uint8_t)USB_USE_FIFO == udev->bp.transfer_mode) {
+ if(transc->ep_type != (uint8_t)USB_EPTYPE_ISOC) {
+ /* enable the Tx FIFO empty interrupt for this endpoint */
+ if(transc->xfer_len > 0U) {
+ udev->regs.dr->DIEPFEINTEN |= 1U << ep_num;
+ }
+ } else {
+ (void)usb_txfifo_write(&udev->regs, transc->xfer_buf, ep_num, (uint16_t)transc->xfer_len);
+ }
+ }
+
+ return status;
+}
+
+/*!
+ \brief configure usb transaction to start OUT transfer
+ \param[in] udev: pointer to usb device
+ \param[in] transc: the usb OUT transaction
+ \param[out] none
+ \retval status
+*/
+usb_status usb_transc_outxfer(usb_core_driver *udev, usb_transc *transc)
+{
+ usb_status status = USB_OK;
+
+ uint8_t ep_num = transc->ep_addr.num;
+
+ uint32_t epctl = udev->regs.er_out[ep_num]->DOEPCTL;
+ uint32_t eplen = udev->regs.er_out[ep_num]->DOEPLEN;
+
+ eplen &= ~(DEPLEN_TLEN | DEPLEN_PCNT);
+
+ /* zero length packet or endpoint 0 */
+ if((0U == transc->xfer_len) || (0U == ep_num)) {
+ /* set the transfer length to max packet size */
+ eplen |= transc->max_len;
+
+ /* set the transfer packet count to 1 */
+ eplen |= 1U << 19U;
+ } else {
+ /* configure the transfer size and packet count as follows:
+ * pktcnt = N
+ * xfersize = N * maxpacket
+ */
+ uint32_t packet_count = (transc->xfer_len + transc->max_len - 1U) / transc->max_len;
+
+ eplen |= packet_count << 19U;
+ eplen |= packet_count * transc->max_len;
+ }
+
+ udev->regs.er_out[ep_num]->DOEPLEN = eplen;
+
+ if((uint8_t)USB_USE_DMA == udev->bp.transfer_mode) {
+ udev->regs.er_out[ep_num]->DOEPDMAADDR = transc->dma_addr;
+ }
+
+ if(transc->ep_type == (uint8_t)USB_EPTYPE_ISOC) {
+ if(transc->frame_num) {
+ epctl |= DEPCTL_SD1PID;
+ } else {
+ epctl |= DEPCTL_SD0PID;
+ }
+ }
+
+ /* enable the endpoint and clear the NAK */
+ epctl |= DEPCTL_EPEN | DEPCTL_CNAK;
+
+ udev->regs.er_out[ep_num]->DOEPCTL = epctl;
+
+ return status;
+}
+
+/*!
+ \brief set the USB transaction STALL status
+ \param[in] udev: pointer to USB device
+ \param[in] transc: the USB transaction
+ \param[out] none
+ \retval status
+*/
+usb_status usb_transc_stall(usb_core_driver *udev, usb_transc *transc)
+{
+ __IO uint32_t *reg_addr = NULL;
+
+ uint8_t ep_num = transc->ep_addr.num;
+
+ if(transc->ep_addr.dir) {
+ reg_addr = &(udev->regs.er_in[ep_num]->DIEPCTL);
+
+ /* set the endpoint disable bit */
+ if(*reg_addr & DEPCTL_EPEN) {
+ *reg_addr |= DEPCTL_EPD;
+ }
+ } else {
+ /* set the endpoint stall bit */
+ reg_addr = &(udev->regs.er_out[ep_num]->DOEPCTL);
+ }
+
+ /* set the endpoint stall bit */
+ *reg_addr |= DEPCTL_STALL;
+
+ return USB_OK;
+}
+
+/*!
+ \brief clear the USB transaction STALL status
+ \param[in] udev: pointer to USB device
+ \param[in] transc: the USB transaction
+ \param[out] none
+ \retval operation status
+*/
+usb_status usb_transc_clrstall(usb_core_driver *udev, usb_transc *transc)
+{
+ __IO uint32_t *reg_addr = NULL;
+
+ uint8_t ep_num = transc->ep_addr.num;
+
+ if(transc->ep_addr.dir) {
+ reg_addr = &(udev->regs.er_in[ep_num]->DIEPCTL);
+ } else {
+ reg_addr = &(udev->regs.er_out[ep_num]->DOEPCTL);
+ }
+
+ /* clear the endpoint stall bits */
+ *reg_addr &= ~DEPCTL_STALL;
+
+ /* reset data PID of the periodic endpoints */
+ if((transc->ep_type == (uint8_t)USB_EPTYPE_INTR) || (transc->ep_type == (uint8_t)USB_EPTYPE_BULK)) {
+ *reg_addr |= DEPCTL_SD0PID;
+ }
+
+ return USB_OK;
+}
+
+/*!
+ \brief read device IN endpoint interrupt flag register
+ \param[in] udev: pointer to USB device
+ \param[in] ep_num: endpoint number
+ \param[out] none
+ \retval interrupt value
+*/
+uint32_t usb_iepintr_read(usb_core_driver *udev, uint8_t ep_num)
+{
+ uint32_t value = 0U, fifoemptymask, commonintmask;
+
+ commonintmask = udev->regs.dr->DIEPINTEN;
+ fifoemptymask = udev->regs.dr->DIEPFEINTEN;
+
+ /* check FIFO empty interrupt enable bit */
+ commonintmask |= ((fifoemptymask >> ep_num) & 0x1U) << 7;
+
+ value = udev->regs.er_in[ep_num]->DIEPINTF & commonintmask;
+
+ return value;
+}
+
+/*!
+ \brief configures OUT endpoint 0 to receive SETUP packets
+ \param[in] udev: pointer to USB device
+ \param[out] none
+ \retval none
+*/
+void usb_ctlep_startout(usb_core_driver *udev)
+{
+ /* set OUT endpoint 0 receive length to 24 bytes, 1 packet and 3 setup packets */
+ udev->regs.er_out[0]->DOEPLEN = DOEP0_TLEN(8U * 3U) | DOEP0_PCNT(1U) | DOEP0_STPCNT(3U);
+
+ if((uint8_t)USB_USE_DMA == udev->bp.transfer_mode) {
+ udev->regs.er_out[0]->DOEPDMAADDR = (uint32_t)&udev->dev.control.req;
+
+ /* endpoint enable */
+ udev->regs.er_out[0]->DOEPCTL |= DEPCTL_EPACT | DEPCTL_EPEN;
+ }
+}
+
+/*!
+ \brief active remote wakeup signaling
+ \param[in] udev: pointer to USB device
+ \param[out] none
+ \retval none
+*/
+void usb_rwkup_active(usb_core_driver *udev)
+{
+ if(udev->dev.pm.dev_remote_wakeup) {
+ if(udev->regs.dr->DSTAT & DSTAT_SPST) {
+ if(udev->bp.low_power) {
+ /* ungate USB core clock */
+ *udev->regs.PWRCLKCTL &= ~(PWRCLKCTL_SHCLK | PWRCLKCTL_SUCLK);
+ }
+
+ /* active remote wakeup signaling */
+ udev->regs.dr->DCTL |= DCTL_RWKUP;
+
+ usb_mdelay(5U);
+
+ udev->regs.dr->DCTL &= ~DCTL_RWKUP;
+ }
+ }
+}
+
+/*!
+ \brief active USB core clock
+ \param[in] udev: pointer to USB device
+ \param[out] none
+ \retval none
+*/
+void usb_clock_active(usb_core_driver *udev)
+{
+ if(udev->bp.low_power) {
+ if(udev->regs.dr->DSTAT & DSTAT_SPST) {
+ /* un-gate USB Core clock */
+ *udev->regs.PWRCLKCTL &= ~(PWRCLKCTL_SHCLK | PWRCLKCTL_SUCLK);
+ }
+ }
+}
+
+/*!
+ \brief USB device suspend
+ \param[in] udev: pointer to USB device
+ \param[out] none
+ \retval none
+*/
+void usb_dev_suspend(usb_core_driver *udev)
+{
+ __IO uint32_t devstat = udev->regs.dr->DSTAT;
+
+ if((udev->bp.low_power) && (devstat & DSTAT_SPST)) {
+ /* switch-off the USB clocks */
+ *udev->regs.PWRCLKCTL |= PWRCLKCTL_SHCLK;
+
+ /* enter DEEP_SLEEP mode with LDO in low power mode */
+ pmu_to_deepsleepmode(PMU_LDO_LOWPOWER, PMU_LOWDRIVER_DISABLE, WFI_CMD);
+ }
+}
+
+/*!
+ \brief stop the device and clean up FIFOs
+ \param[in] udev: pointer to USB device
+ \param[out] none
+ \retval none
+*/
+void usb_dev_stop(usb_core_driver *udev)
+{
+ uint32_t i;
+
+ udev->dev.cur_status = 1U;
+
+ /* clear all interrupt flag and enable bits */
+ for(i = 0U; i < udev->bp.num_ep; i++) {
+ udev->regs.er_in[i]->DIEPINTF = 0xFFU;
+ udev->regs.er_out[i]->DOEPINTF = 0xFFU;
+ }
+
+ udev->regs.dr->DIEPINTEN = 0U;
+ udev->regs.dr->DOEPINTEN = 0U;
+ udev->regs.dr->DAEPINTEN = 0U;
+ udev->regs.dr->DAEPINT = 0xFFFFFFFFU;
+
+ /* flush the FIFO */
+ (void)usb_rxfifo_flush(&udev->regs);
+ (void)usb_txfifo_flush(&udev->regs, 0x10U);
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/driver/Source/drv_usb_host.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/driver/Source/drv_usb_host.c
new file mode 100644
index 00000000..130fadc2
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/driver/Source/drv_usb_host.c
@@ -0,0 +1,452 @@
+/*!
+ \file drv_usb_host.c
+ \brief USB host mode low level driver
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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.
+*/
+
+#include "drv_usb_hw.h"
+#include "drv_usb_core.h"
+#include "drv_usb_host.h"
+
+const uint32_t PIPE_DPID[2] = {
+ PIPE_DPID_DATA0,
+ PIPE_DPID_DATA1
+};
+
+/*!
+ \brief initializes USB core for host mode
+ \param[in] pudev: pointer to selected usb host
+ \param[out] none
+ \retval operation status
+*/
+usb_status usb_host_init(usb_core_driver *pudev)
+{
+ uint32_t i = 0U, inten = 0U;
+
+ uint32_t nptxfifolen = 0U;
+ uint32_t ptxfifolen = 0U;
+
+ /* restart the PHY Clock */
+ *pudev->regs.PWRCLKCTL = 0U;
+
+ /* support FS/LS only */
+ pudev->regs.hr->HCTL &= ~HCTL_SPDFSLS;
+
+ /* configure data FIFOs size */
+#ifdef USB_FS_CORE
+ if(USB_CORE_ENUM_FS == pudev->bp.core_enum) {
+ /* set Rx FIFO size */
+ pudev->regs.gr->GRFLEN = USB_RX_FIFO_FS_SIZE;
+
+ /* set non-periodic Tx FIFO size and address */
+ nptxfifolen |= USB_RX_FIFO_FS_SIZE;
+ nptxfifolen |= USB_HTX_NPFIFO_FS_SIZE << 16U;
+ pudev->regs.gr->DIEP0TFLEN_HNPTFLEN = nptxfifolen;
+
+ /* set periodic Tx FIFO size and address */
+ ptxfifolen |= USB_RX_FIFO_FS_SIZE + USB_HTX_NPFIFO_FS_SIZE;
+ ptxfifolen |= USB_HTX_PFIFO_FS_SIZE << 16U;
+ pudev->regs.gr->HPTFLEN = ptxfifolen;
+ }
+#endif /* USB_FS_CORE */
+
+#ifdef USE_OTG_MODE
+
+ /* clear host set hnp enable in the usb_otg control register */
+ pudev->regs.gr->GOTGCS &= ~GOTGCS_HHNPEN;
+
+#endif /* USE_OTG_MODE */
+
+ /* make sure the FIFOs are flushed */
+
+ /* flush all Tx FIFOs in device or host mode */
+ usb_txfifo_flush(&pudev->regs, 0x10U);
+
+ /* flush the entire Rx FIFO */
+ usb_rxfifo_flush(&pudev->regs);
+
+ /* disable all interrupts */
+ pudev->regs.gr->GINTEN = 0U;
+
+ /* clear any pending USB OTG interrupts */
+ pudev->regs.gr->GOTGINTF = 0xFFFFFFFFU;
+
+ /* enable the USB wakeup and suspend interrupts */
+ pudev->regs.gr->GINTF = 0xBFFFFFFFU;
+
+ /* clear all pending host channel interrupts */
+ for(i = 0U; i < pudev->bp.num_pipe; i++) {
+ pudev->regs.pr[i]->HCHINTF = 0xFFFFFFFFU;
+ pudev->regs.pr[i]->HCHINTEN = 0U;
+ }
+
+#ifndef USE_OTG_MODE
+ usb_portvbus_switch(pudev, 1U);
+#endif /* USE_OTG_MODE */
+
+ pudev->regs.gr->GINTEN = GINTEN_WKUPIE | GINTEN_SPIE;
+
+ /* enable host_mode-related interrupts */
+ if(USB_USE_FIFO == pudev->bp.transfer_mode) {
+ inten = GINTEN_RXFNEIE;
+ }
+
+ inten |= GINTEN_SESIE | GINTEN_HPIE | GINTEN_HCIE | GINTEN_ISOINCIE;
+
+ pudev->regs.gr->GINTEN |= inten;
+
+ inten = GINTEN_DISCIE | GINTEN_SOFIE;
+
+ pudev->regs.gr->GINTEN &= ~inten;
+
+ return USB_OK;
+}
+
+/*!
+ \brief control the VBUS to power
+ \param[in] pudev: pointer to selected usb host
+ \param[in] state: VBUS state
+ \param[out] none
+ \retval none
+*/
+void usb_portvbus_switch(usb_core_driver *pudev, uint8_t state)
+{
+ uint32_t port = 0U;
+
+ /* enable or disable the external charge pump */
+ usb_vbus_drive(state);
+
+ /* turn on the host port power. */
+ port = usb_port_read(pudev);
+
+ if(!(port & HPCS_PP) && (1U == state)) {
+ port |= HPCS_PP;
+ }
+
+ if((port & HPCS_PP) && (0U == state)) {
+ port &= ~HPCS_PP;
+ }
+
+ *pudev->regs.HPCS = port;
+
+ usb_mdelay(200U);
+}
+
+/*!
+ \brief reset host port
+ \param[in] pudev: pointer to usb device
+ \param[out] none
+ \retval operation status
+*/
+uint32_t usb_port_reset(usb_core_driver *pudev)
+{
+ __IO uint32_t port = usb_port_read(pudev);
+
+ *pudev->regs.HPCS = port | HPCS_PRST;
+
+ usb_mdelay(20U); /* see note */
+
+ *pudev->regs.HPCS = port & ~HPCS_PRST;
+
+ usb_mdelay(20U);
+
+ return 1U;
+}
+
+/*!
+ \brief initialize host pipe
+ \param[in] pudev: pointer to usb device
+ \param[in] pipe_num: host pipe number which is in (0..7)
+ \param[out] none
+ \retval operation status
+*/
+usb_status usb_pipe_init(usb_core_driver *pudev, uint8_t pipe_num)
+{
+ usb_status status = USB_OK;
+
+ __IO uint32_t pp_ctl = 0U;
+ __IO uint32_t pp_inten = HCHINTEN_TFIE;
+
+ usb_pipe *pp = &pudev->host.pipe[pipe_num];
+
+ /* clear old interrupt conditions for this host channel */
+ pudev->regs.pr[pipe_num]->HCHINTF = 0xFFFFFFFFU;
+
+ if(USB_USE_DMA == pudev->bp.transfer_mode) {
+ pp_inten |= HCHINTEN_DMAERIE;
+ }
+
+ if(pp->ep.dir) {
+ pp_inten |= HCHINTEN_BBERIE;
+ }
+
+ /* enable channel interrupts required for this transfer */
+ switch(pp->ep.type) {
+ case USB_EPTYPE_CTRL:
+ case USB_EPTYPE_BULK:
+ pp_inten |= HCHINTEN_STALLIE | HCHINTEN_USBERIE \
+ | HCHINTEN_DTERIE | HCHINTEN_NAKIE;
+
+ if(!pp->ep.dir) {
+ pp_inten |= HCHINTEN_NYETIE;
+
+ if(pp->ping) {
+ pp_inten |= HCHINTEN_ACKIE;
+ }
+ }
+ break;
+
+ case USB_EPTYPE_INTR:
+ pp_inten |= HCHINTEN_STALLIE | HCHINTEN_USBERIE | HCHINTEN_DTERIE \
+ | HCHINTEN_NAKIE | HCHINTEN_REQOVRIE;
+ break;
+
+ case USB_EPTYPE_ISOC:
+ pp_inten |= HCHINTEN_REQOVRIE | HCHINTEN_ACKIE;
+
+ if(pp->ep.dir) {
+ pp_inten |= HCHINTEN_USBERIE;
+ }
+ break;
+
+ default:
+ break;
+ }
+
+ pudev->regs.pr[pipe_num]->HCHINTEN = pp_inten;
+
+ /* enable the top level host channel interrupt */
+ pudev->regs.hr->HACHINTEN |= 1U << pipe_num;
+
+ /* make sure host channel interrupts are enabled */
+ pudev->regs.gr->GINTEN |= GINTEN_HCIE;
+
+ /* program the host channel control register */
+ pp_ctl |= PIPE_CTL_DAR(pp->dev_addr);
+ pp_ctl |= PIPE_CTL_EPNUM(pp->ep.num);
+ pp_ctl |= PIPE_CTL_EPDIR(pp->ep.dir);
+ pp_ctl |= PIPE_CTL_EPTYPE(pp->ep.type);
+ pp_ctl |= PIPE_CTL_LSD(pp->dev_speed == PORT_SPEED_LOW);
+
+ pp_ctl |= pp->ep.mps;
+ pp_ctl |= ((uint32_t)(pp->ep.type == USB_EPTYPE_INTR) << 29U) & HCHCTL_ODDFRM;
+
+ pudev->regs.pr[pipe_num]->HCHCTL = pp_ctl;
+
+ return status;
+}
+
+/*!
+ \brief prepare host channel for transferring packets
+ \param[in] pudev: pointer to usb device
+ \param[in] pipe_num: host pipe number which is in (0..7)
+ \param[out] none
+ \retval operation status
+*/
+usb_status usb_pipe_xfer(usb_core_driver *pudev, uint8_t pipe_num)
+{
+ usb_status status = USB_OK;
+
+ uint16_t dword_len = 0U;
+ uint16_t packet_count = 0U;
+
+ __IO uint32_t pp_ctl = 0U;
+
+ usb_pipe *pp = &pudev->host.pipe[pipe_num];
+
+ uint16_t max_packet_len = pp->ep.mps;
+
+ /* compute the expected number of packets associated to the transfer */
+ if(pp->xfer_len > 0U) {
+ packet_count = (uint16_t)((pp->xfer_len + max_packet_len - 1U) / max_packet_len);
+
+ if(packet_count > HC_MAX_PACKET_COUNT) {
+ packet_count = HC_MAX_PACKET_COUNT;
+ pp->xfer_len = (uint16_t)(packet_count * max_packet_len);
+ }
+ } else {
+ packet_count = 1U;
+ }
+
+ if(pp->ep.dir) {
+ pp->xfer_len = (uint16_t)(packet_count * max_packet_len);
+ }
+
+ /* initialize the host channel transfer information */
+ pudev->regs.pr[pipe_num]->HCHLEN = pp->xfer_len | pp->DPID | PIPE_XFER_PCNT(packet_count);
+
+ if(USB_USE_DMA == pudev->bp.transfer_mode) {
+ pudev->regs.pr[pipe_num]->HCHDMAADDR = (unsigned int)pp->xfer_buf;
+ }
+
+ pp_ctl = pudev->regs.pr[pipe_num]->HCHCTL;
+
+ if(usb_frame_even(pudev)) {
+ pp_ctl |= HCHCTL_ODDFRM;
+ } else {
+ pp_ctl &= ~HCHCTL_ODDFRM;
+ }
+
+ /* set host channel enabled */
+ pp_ctl |= HCHCTL_CEN;
+ pp_ctl &= ~HCHCTL_CDIS;
+
+ pudev->regs.pr[pipe_num]->HCHCTL = pp_ctl;
+
+ if(USB_USE_FIFO == pudev->bp.transfer_mode) {
+ if((0U == pp->ep.dir) && (pp->xfer_len > 0U)) {
+ switch(pp->ep.type) {
+ /* non-periodic transfer */
+ case USB_EPTYPE_CTRL:
+ case USB_EPTYPE_BULK:
+ dword_len = (uint16_t)((pp->xfer_len + 3U) / 4U);
+
+ /* check if there is enough space in fifo space */
+ if(dword_len > (pudev->regs.gr->HNPTFQSTAT & HNPTFQSTAT_NPTXFS)) {
+ /* need to process data in nptxfempty interrupt */
+ pudev->regs.gr->GINTEN |= GINTEN_NPTXFEIE;
+ }
+ break;
+
+ /* periodic transfer */
+ case USB_EPTYPE_INTR:
+ case USB_EPTYPE_ISOC:
+ dword_len = (uint16_t)((pp->xfer_len + 3U) / 4U);
+
+ /* check if there is enough space in fifo space */
+ if(dword_len > (pudev->regs.hr->HPTFQSTAT & HPTFQSTAT_PTXFS)) {
+ /* need to process data in ptxfempty interrupt */
+ pudev->regs.gr->GINTEN |= GINTEN_PTXFEIE;
+ }
+ break;
+
+ default:
+ break;
+ }
+
+ /* write packet into the tx fifo. */
+ usb_txfifo_write(&pudev->regs, pp->xfer_buf, pipe_num, (uint16_t)pp->xfer_len);
+ }
+ }
+
+ return status;
+}
+
+/*!
+ \brief halt pipe
+ \param[in] pudev: pointer to usb device
+ \param[in] pipe_num: host pipe number which is in (0..7)
+ \param[out] none
+ \retval operation status
+*/
+usb_status usb_pipe_halt(usb_core_driver *pudev, uint8_t pipe_num)
+{
+ __IO uint32_t pp_ctl = pudev->regs.pr[pipe_num]->HCHCTL;
+
+ uint8_t ep_type = (uint8_t)((pp_ctl & HCHCTL_EPTYPE) >> 18U);
+
+ pp_ctl |= HCHCTL_CEN | HCHCTL_CDIS;
+
+ switch(ep_type) {
+ case USB_EPTYPE_CTRL:
+ case USB_EPTYPE_BULK:
+ if(0U == (pudev->regs.gr->HNPTFQSTAT & HNPTFQSTAT_NPTXFS)) {
+ pp_ctl &= ~HCHCTL_CEN;
+ }
+ break;
+
+ case USB_EPTYPE_INTR:
+ case USB_EPTYPE_ISOC:
+ if(0U == (pudev->regs.hr->HPTFQSTAT & HPTFQSTAT_PTXFS)) {
+ pp_ctl &= ~HCHCTL_CEN;
+ }
+ break;
+
+ default:
+ break;
+ }
+
+ pudev->regs.pr[pipe_num]->HCHCTL = pp_ctl;
+
+ return USB_OK;
+}
+
+/*!
+ \brief configure host pipe to do ping operation
+ \param[in] pudev: pointer to usb device
+ \param[in] pipe_num: host pipe number which is in (0..7)
+ \param[out] none
+ \retval operation status
+*/
+usb_status usb_pipe_ping(usb_core_driver *pudev, uint8_t pipe_num)
+{
+ uint32_t pp_ctl = 0U;
+
+ pudev->regs.pr[pipe_num]->HCHLEN = HCHLEN_PING | (HCHLEN_PCNT & (1U << 19U));
+
+ pp_ctl = pudev->regs.pr[pipe_num]->HCHCTL;
+
+ pp_ctl |= HCHCTL_CEN;
+ pp_ctl &= ~HCHCTL_CDIS;
+
+ pudev->regs.pr[pipe_num]->HCHCTL = pp_ctl;
+
+ return USB_OK;
+}
+
+/*!
+ \brief stop the USB host and clean up FIFO
+ \param[in] pudev: pointer to usb device
+ \param[out] none
+ \retval none
+*/
+void usb_host_stop(usb_core_driver *pudev)
+{
+ uint32_t i;
+ __IO uint32_t pp_ctl = 0U;
+
+ pudev->regs.hr->HACHINTEN = 0x0U;
+ pudev->regs.hr->HACHINT = 0xFFFFFFFFU;
+
+ /* flush out any leftover queued requests. */
+ for(i = 0U; i < pudev->bp.num_pipe; i++) {
+ pp_ctl = pudev->regs.pr[i]->HCHCTL;
+
+ pp_ctl &= ~(HCHCTL_CEN | HCHCTL_EPDIR);
+ pp_ctl |= HCHCTL_CDIS;
+
+ pudev->regs.pr[i]->HCHCTL = pp_ctl;
+ }
+
+ /* flush the FIFO */
+ usb_rxfifo_flush(&pudev->regs);
+ usb_txfifo_flush(&pudev->regs, 0x10U);
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/driver/Source/drv_usbd_int.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/driver/Source/drv_usbd_int.c
new file mode 100644
index 00000000..21dbf17a
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/driver/Source/drv_usbd_int.c
@@ -0,0 +1,491 @@
+/*!
+ \file drv_usbd_int.c
+ \brief USB device mode interrupt routines
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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.
+*/
+
+#include "usbd_conf.h"
+#include "drv_usbd_int.h"
+#include "usbd_transc.h"
+
+/* local function prototypes ('static') */
+static uint32_t usbd_int_epout(usb_core_driver *udev);
+static uint32_t usbd_int_epin(usb_core_driver *udev);
+static uint32_t usbd_int_rxfifo(usb_core_driver *udev);
+static uint32_t usbd_int_reset(usb_core_driver *udev);
+static uint32_t usbd_int_enumfinish(usb_core_driver *udev);
+static uint32_t usbd_int_suspend(usb_core_driver *udev);
+static uint32_t usbd_emptytxfifo_write(usb_core_driver *udev, uint32_t ep_num);
+
+static const uint8_t USB_SPEED[4] = {
+ [DSTAT_EM_HS_PHY_30MHZ_60MHZ] = (uint8_t)USB_SPEED_HIGH,
+ [DSTAT_EM_FS_PHY_30MHZ_60MHZ] = (uint8_t)USB_SPEED_FULL,
+ [DSTAT_EM_FS_PHY_48MHZ] = (uint8_t)USB_SPEED_FULL,
+ [DSTAT_EM_LS_PHY_6MHZ] = (uint8_t)USB_SPEED_LOW
+};
+
+/*!
+ \brief USB device-mode interrupts global service routine handler
+ \param[in] udev: pointer to USB device instance
+ \param[out] none
+ \retval none
+*/
+void usbd_isr(usb_core_driver *udev)
+{
+ if(HOST_MODE != (udev->regs.gr->GINTF & GINTF_COPM)) {
+ uint32_t intr = udev->regs.gr->GINTF & udev->regs.gr->GINTEN;
+
+ /* there are no interrupts, avoid spurious interrupt */
+ if(!intr) {
+ return;
+ }
+
+ /* OUT endpoints interrupts */
+ if(intr & GINTF_OEPIF) {
+ (void)usbd_int_epout(udev);
+ }
+
+ /* IN endpoints interrupts */
+ if(intr & GINTF_IEPIF) {
+ (void)usbd_int_epin(udev);
+ }
+
+ /* suspend interrupt */
+ if(intr & GINTF_SP) {
+ (void)usbd_int_suspend(udev);
+ }
+
+ /* wakeup interrupt */
+ if(intr & GINTF_WKUPIF) {
+ /* inform upper layer by the resume event */
+ udev->dev.cur_status = USBD_CONFIGURED;
+
+ /* clear interrupt */
+ udev->regs.gr->GINTF = GINTF_WKUPIF;
+ }
+
+ /* start of frame interrupt */
+ if(intr & GINTF_SOF) {
+ if(udev->dev.class_core->SOF) {
+ (void)udev->dev.class_core->SOF(udev);
+ }
+
+ /* clear interrupt */
+ udev->regs.gr->GINTF = GINTF_SOF;
+ }
+
+ /* receive FIFO not empty interrupt */
+ if(intr & GINTF_RXFNEIF) {
+ (void)usbd_int_rxfifo(udev);
+ }
+
+ /* USB reset interrupt */
+ if(intr & GINTF_RST) {
+ (void)usbd_int_reset(udev);
+ }
+
+ /* enumeration has been done interrupt */
+ if(intr & GINTF_ENUMFIF) {
+ (void)usbd_int_enumfinish(udev);
+ }
+
+ /* incomplete synchronization IN transfer interrupt*/
+ if(intr & GINTF_ISOINCIF) {
+ if(NULL != udev->dev.class_core->incomplete_isoc_in) {
+ (void)udev->dev.class_core->incomplete_isoc_in(udev);
+ }
+
+ /* Clear interrupt */
+ udev->regs.gr->GINTF = GINTF_ISOINCIF;
+ }
+
+ /* incomplete synchronization OUT transfer interrupt*/
+ if(intr & GINTF_ISOONCIF) {
+ if(NULL != udev->dev.class_core->incomplete_isoc_out) {
+ (void)udev->dev.class_core->incomplete_isoc_out(udev);
+ }
+
+ /* clear interrupt */
+ udev->regs.gr->GINTF = GINTF_ISOONCIF;
+ }
+
+#ifdef VBUS_SENSING_ENABLED
+
+ /* Session request interrupt */
+ if(intr & GINTF_SESIF) {
+ udev->regs.gr->GINTF = GINTF_SESIF;
+ }
+
+ /* OTG mode interrupt */
+ if(intr & GINTF_OTGIF) {
+ if(udev->regs.gr->GOTGINTF & GOTGINTF_SESEND) {
+
+ }
+
+ /* Clear OTG interrupt */
+ udev->regs.gr->GINTF = GINTF_OTGIF;
+ }
+#endif /* VBUS_SENSING_ENABLED */
+ }
+}
+
+/*!
+ \brief indicates that an OUT endpoint has a pending interrupt
+ \param[in] udev: pointer to USB device instance
+ \param[out] none
+ \retval operation status
+*/
+static uint32_t usbd_int_epout(usb_core_driver *udev)
+{
+ uint32_t epintnum = 0U;
+ uint8_t ep_num = 0U;
+
+ for(epintnum = usb_oepintnum_read(udev); epintnum; epintnum >>= 1, ep_num++) {
+ if(epintnum & 0x01U) {
+ __IO uint32_t oepintr = usb_oepintr_read(udev, ep_num);
+
+ /* transfer complete interrupt */
+ if(oepintr & DOEPINTF_TF) {
+ /* clear the bit in DOEPINTF for this interrupt */
+ udev->regs.er_out[ep_num]->DOEPINTF = DOEPINTF_TF;
+
+ if((uint8_t)USB_USE_DMA == udev->bp.transfer_mode) {
+ __IO uint32_t eplen = udev->regs.er_out[ep_num]->DOEPLEN;
+
+ udev->dev.transc_out[ep_num].xfer_count = udev->dev.transc_out[ep_num].max_len - \
+ (eplen & DEPLEN_TLEN);
+ }
+
+ /* inform upper layer: data ready */
+ (void)usbd_out_transc(udev, ep_num);
+
+ if((uint8_t)USB_USE_DMA == udev->bp.transfer_mode) {
+ if((0U == ep_num) && ((uint8_t)USB_CTL_STATUS_OUT == udev->dev.control.ctl_state)) {
+ usb_ctlep_startout(udev);
+ }
+ }
+ }
+
+ /* setup phase finished interrupt (control endpoints) */
+ if(oepintr & DOEPINTF_STPF) {
+ /* inform the upper layer that a setup packet is available */
+ (void)usbd_setup_transc(udev);
+
+ udev->regs.er_out[ep_num]->DOEPINTF = DOEPINTF_STPF;
+ }
+ }
+ }
+
+ return 1U;
+}
+
+/*!
+ \brief indicates that an IN endpoint has a pending interrupt
+ \param[in] udev: pointer to USB device instance
+ \param[out] none
+ \retval operation status
+*/
+static uint32_t usbd_int_epin(usb_core_driver *udev)
+{
+ uint32_t epintnum = 0U;
+ uint8_t ep_num = 0U;
+
+ for(epintnum = usb_iepintnum_read(udev); epintnum; epintnum >>= 1, ep_num++) {
+ if(epintnum & 0x1U) {
+ __IO uint32_t iepintr = usb_iepintr_read(udev, ep_num);
+
+ if(iepintr & DIEPINTF_TF) {
+ udev->regs.er_in[ep_num]->DIEPINTF = DIEPINTF_TF;
+
+ /* data transmission is completed */
+ (void)usbd_in_transc(udev, ep_num);
+
+ if((uint8_t)USB_USE_DMA == udev->bp.transfer_mode) {
+ if((0U == ep_num) && ((uint8_t)USB_CTL_STATUS_IN == udev->dev.control.ctl_state)) {
+ usb_ctlep_startout(udev);
+ }
+ }
+ }
+
+ if(iepintr & DIEPINTF_TXFE) {
+ usbd_emptytxfifo_write(udev, (uint32_t)ep_num);
+
+ udev->regs.er_in[ep_num]->DIEPINTF = DIEPINTF_TXFE;
+ }
+ }
+ }
+
+ return 1U;
+}
+
+/*!
+ \brief handle the RX status queue level interrupt
+ \param[in] udev: pointer to USB device instance
+ \param[out] none
+ \retval operation status
+*/
+static uint32_t usbd_int_rxfifo(usb_core_driver *udev)
+{
+ usb_transc *transc = NULL;
+
+ uint8_t data_PID = 0U;
+ uint32_t bcount = 0U;
+
+ __IO uint32_t devrxstat = 0U;
+
+ /* disable the Rx status queue non-empty interrupt */
+ udev->regs.gr->GINTEN &= ~GINTEN_RXFNEIE;
+
+ /* get the status from the top of the FIFO */
+ devrxstat = udev->regs.gr->GRSTATP;
+
+ uint8_t ep_num = (uint8_t)(devrxstat & GRSTATRP_EPNUM);
+
+ transc = &udev->dev.transc_out[ep_num];
+
+ bcount = (devrxstat & GRSTATRP_BCOUNT) >> 4U;
+ data_PID = (uint8_t)((devrxstat & GRSTATRP_DPID) >> 15U);
+
+ switch((devrxstat & GRSTATRP_RPCKST) >> 17U) {
+ case RSTAT_GOUT_NAK:
+ break;
+
+ case RSTAT_DATA_UPDT:
+ if(bcount > 0U) {
+ (void)usb_rxfifo_read(&udev->regs, transc->xfer_buf, (uint16_t)bcount);
+
+ transc->xfer_buf += bcount;
+ transc->xfer_count += bcount;
+ }
+ break;
+
+ case RSTAT_XFER_COMP:
+ /* trigger the OUT endpoint interrupt */
+ break;
+
+ case RSTAT_SETUP_COMP:
+ /* trigger the OUT endpoint interrupt */
+ break;
+
+ case RSTAT_SETUP_UPDT:
+ if((0U == transc->ep_addr.num) && (8U == bcount) && (DPID_DATA0 == data_PID)) {
+ /* copy the setup packet received in FIFO into the setup buffer in RAM */
+ (void)usb_rxfifo_read(&udev->regs, (uint8_t *)&udev->dev.control.req, (uint16_t)bcount);
+
+ transc->xfer_count += bcount;
+ }
+ break;
+
+ default:
+ break;
+ }
+
+ /* enable the Rx status queue level interrupt */
+ udev->regs.gr->GINTEN |= GINTEN_RXFNEIE;
+
+ return 1U;
+}
+
+/*!
+ \brief handle USB reset interrupt
+ \param[in] udev: pointer to USB device instance
+ \param[out] none
+ \retval status
+*/
+static uint32_t usbd_int_reset(usb_core_driver *udev)
+{
+ uint32_t i;
+
+ /* clear the remote wakeup signaling */
+ udev->regs.dr->DCTL &= ~DCTL_RWKUP;
+
+ /* flush the Tx FIFO */
+ (void)usb_txfifo_flush(&udev->regs, 0U);
+
+ for(i = 0U; i < udev->bp.num_ep; i++) {
+ udev->regs.er_in[i]->DIEPINTF = 0xFFU;
+ udev->regs.er_out[i]->DOEPINTF = 0xFFU;
+ }
+
+ /* clear all pending device endpoint interrupts */
+ udev->regs.dr->DAEPINT = 0xFFFFFFFFU;
+
+ /* enable endpoint 0 interrupts */
+ udev->regs.dr->DAEPINTEN = 1U | (1U << 16U);
+
+ /* enable OUT endpoint interrupts */
+ udev->regs.dr->DOEPINTEN = DOEPINTEN_STPFEN | DOEPINTEN_TFEN;
+
+ /* enable IN endpoint interrupts */
+ udev->regs.dr->DIEPINTEN = DIEPINTEN_TFEN;
+
+ /* reset device address */
+ udev->regs.dr->DCFG &= ~DCFG_DAR;
+
+ /* configure endpoint 0 to receive SETUP packets */
+ usb_ctlep_startout(udev);
+
+ /* clear USB reset interrupt */
+ udev->regs.gr->GINTF = GINTF_RST;
+
+ udev->dev.transc_out[0] = (usb_transc) {
+ .ep_type = USB_EPTYPE_CTRL,
+ .max_len = USB_FS_EP0_MAX_LEN
+ };
+
+ (void)usb_transc_active(udev, &udev->dev.transc_out[0]);
+
+ udev->dev.transc_in[0] = (usb_transc) {
+ .ep_addr = {
+ .dir = 1U
+ },
+
+ .ep_type = USB_EPTYPE_CTRL,
+ .max_len = USB_FS_EP0_MAX_LEN
+ };
+
+ (void)usb_transc_active(udev, &udev->dev.transc_in[0]);
+
+ /* upon reset call user call back */
+ udev->dev.cur_status = (uint8_t)USBD_DEFAULT;
+
+ return 1U;
+}
+
+/*!
+ \brief handle USB speed enumeration finish interrupt
+ \param[in] udev: pointer to USB device instance
+ \param[out] none
+ \retval status
+*/
+static uint32_t usbd_int_enumfinish(usb_core_driver *udev)
+{
+ uint8_t enum_speed = (uint8_t)((udev->regs.dr->DSTAT & DSTAT_ES) >> 1U);
+
+ udev->regs.dr->DCTL &= ~DCTL_CGINAK;
+ udev->regs.dr->DCTL |= DCTL_CGINAK;
+
+ udev->regs.gr->GUSBCS &= ~GUSBCS_UTT;
+
+ /* set USB turn-around time based on device speed and PHY interface */
+ if(USB_SPEED[enum_speed] == (uint8_t)USB_SPEED_HIGH) {
+ udev->bp.core_speed = (uint8_t)USB_SPEED_HIGH;
+
+ udev->regs.gr->GUSBCS |= 0x09U << 10U;
+ } else {
+ udev->bp.core_speed = (uint8_t)USB_SPEED_FULL;
+
+ udev->regs.gr->GUSBCS |= 0x05U << 10U;
+ }
+
+ /* clear interrupt */
+ udev->regs.gr->GINTF = GINTF_ENUMFIF;
+
+ return 1U;
+}
+
+/*!
+ \brief USB suspend interrupt handler
+ \param[in] udev: pointer to USB device instance
+ \param[out] none
+ \retval operation status
+*/
+static uint32_t usbd_int_suspend(usb_core_driver *udev)
+{
+ __IO uint8_t low_power = udev->bp.low_power;
+ __IO uint8_t suspend = (uint8_t)(udev->regs.dr->DSTAT & DSTAT_SPST);
+ __IO uint8_t is_configured = (udev->dev.cur_status == (uint8_t)USBD_CONFIGURED) ? 1U : 0U;
+
+ udev->dev.backup_status = udev->dev.cur_status;
+ udev->dev.cur_status = (uint8_t)USBD_SUSPENDED;
+
+ if(low_power && suspend && is_configured) {
+ /* switch-off the OTG clocks */
+ *udev->regs.PWRCLKCTL |= PWRCLKCTL_SUCLK | PWRCLKCTL_SHCLK;
+
+ /* enter DEEP_SLEEP mode with LDO in low power mode */
+ pmu_to_deepsleepmode(PMU_LDO_LOWPOWER, PMU_LOWDRIVER_DISABLE, WFI_CMD);
+ }
+
+ /* clear interrupt */
+ udev->regs.gr->GINTF = GINTF_SP;
+
+ return 1U;
+}
+
+/*!
+ \brief check FIFO for the next packet to be loaded
+ \param[in] udev: pointer to USB device instance
+ \param[in] ep_num: endpoint identifier which is in (0..3)
+ \param[out] none
+ \retval status
+*/
+static uint32_t usbd_emptytxfifo_write(usb_core_driver *udev, uint32_t ep_num)
+{
+ uint32_t len;
+ uint32_t word_count;
+
+ usb_transc *transc = &udev->dev.transc_in[ep_num];
+
+ len = transc->xfer_len - transc->xfer_count;
+
+ /* get the data length to write */
+ if(len > transc->max_len) {
+ len = transc->max_len;
+ }
+
+ word_count = (len + 3U) / 4U;
+
+ while(((udev->regs.er_in[ep_num]->DIEPTFSTAT & DIEPTFSTAT_IEPTFS) >= word_count) && \
+ (transc->xfer_count < transc->xfer_len)) {
+ len = transc->xfer_len - transc->xfer_count;
+
+ if(len > transc->max_len) {
+ len = transc->max_len;
+ }
+
+ /* write FIFO in word(4bytes) */
+ word_count = (len + 3U) / 4U;
+
+ /* write the FIFO */
+ (void)usb_txfifo_write(&udev->regs, transc->xfer_buf, (uint8_t)ep_num, (uint16_t)len);
+
+ transc->xfer_buf += len;
+ transc->xfer_count += len;
+
+ if(transc->xfer_count == transc->xfer_len) {
+ /* disable the device endpoint FIFO empty interrupt */
+ udev->regs.dr->DIEPFEINTEN &= ~(0x01U << ep_num);
+ }
+ }
+
+ return 1U;
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/driver/Source/drv_usbh_int.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/driver/Source/drv_usbh_int.c
new file mode 100644
index 00000000..cf6db76a
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/driver/Source/drv_usbh_int.c
@@ -0,0 +1,624 @@
+/*!
+ \file drv_usbh_int.c
+ \brief USB host mode interrupt handler file
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+ \version 2021-07-26, V3.0.1, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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.
+*/
+
+#include "drv_usb_core.h"
+#include "drv_usb_host.h"
+#include "drv_usbh_int.h"
+#include "usbh_core.h"
+
+#if defined (__CC_ARM) /*!< ARM compiler */
+#pragma O0
+#elif defined (__GNUC__) /*!< GNU compiler */
+#pragma GCC optimize ("O0")
+#elif defined (__TASKING__) /*!< TASKING compiler */
+#pragma optimize=0
+#endif /* __CC_ARM */
+
+/* local function prototypes ('static') */
+static uint32_t usbh_int_port(usb_core_driver *pudev);
+static uint32_t usbh_int_pipe(usb_core_driver *pudev);
+static uint32_t usbh_int_pipe_in(usb_core_driver *pudev, uint32_t pp_num);
+static uint32_t usbh_int_pipe_out(usb_core_driver *pudev, uint32_t pp_num);
+static uint32_t usbh_int_rxfifonoempty(usb_core_driver *pudev);
+static uint32_t usbh_int_txfifoempty(usb_core_driver *pudev, usb_pipe_mode pp_mode);
+
+/*!
+ \brief handle global host interrupt
+ \param[in] pudev: pointer to USB core instance
+ \param[out] none
+ \retval operation status
+*/
+uint32_t usbh_isr(usb_core_driver *pudev)
+{
+ uint32_t retval = 0U;
+
+ __IO uint32_t intr = 0U;
+
+ /* check if host mode */
+ if(HOST_MODE == (pudev->regs.gr->GINTF & GINTF_COPM)) {
+ intr = usb_coreintr_get(&pudev->regs);
+
+ if(!intr) {
+ return 0U;
+ }
+
+ if(intr & GINTF_SOF) {
+ usbh_int_fop->SOF(pudev->host.data);
+
+ /* clear interrupt */
+ pudev->regs.gr->GINTF = GINTF_SOF;
+ }
+
+ if(intr & GINTF_RXFNEIF) {
+ retval |= usbh_int_rxfifonoempty(pudev);
+ }
+
+ if(intr & GINTF_NPTXFEIF) {
+ retval |= usbh_int_txfifoempty(pudev, PIPE_NON_PERIOD);
+ }
+
+ if(intr & GINTF_PTXFEIF) {
+ retval |= usbh_int_txfifoempty(pudev, PIPE_PERIOD);
+ }
+
+ if(intr & GINTF_HCIF) {
+ retval |= usbh_int_pipe(pudev);
+ }
+
+ if(intr & GINTF_HPIF) {
+ retval |= usbh_int_port(pudev);
+ }
+
+ if(intr & GINTF_DISCIF) {
+ usbh_int_fop->disconnect(pudev->host.data);
+
+ /* clear interrupt */
+ pudev->regs.gr->GINTF = GINTF_DISCIF;
+ }
+
+ if(intr & GINTF_ISOONCIF) {
+ pudev->regs.pr[0]->HCHCTL |= HCHCTL_CEN | HCHCTL_CDIS;
+
+ /* clear interrupt */
+ pudev->regs.gr->GINTF = GINTF_ISOONCIF;
+ }
+
+ if(intr & GINTF_SESIF) {
+ usb_portvbus_switch(pudev, 1U);
+
+ pudev->regs.gr->GINTF = GINTF_SESIF;
+ }
+
+ if(intr & GINTF_WKUPIF) {
+ /* clear interrupt */
+ pudev->regs.gr->GINTF = GINTF_WKUPIF;
+ }
+ }
+
+ return retval;
+}
+
+/*!
+ \brief handle USB pipe halt
+ \param[in] pudev: pointer to USB core instance
+ \param[in] pp_num: pp_num: host channel number which is in (0..7)
+ \param[in] pp_int: pipe interrupt
+ \param[in] pp_status: pipe status
+ \param[out] none
+ \retval none
+*/
+static inline void usb_pp_halt(usb_core_driver *pudev,
+ uint8_t pp_num,
+ uint32_t pp_int,
+ usb_pipe_staus pp_status)
+{
+ pudev->regs.pr[pp_num]->HCHINTEN |= HCHINTEN_CHIE;
+
+ usb_pipe_halt(pudev, pp_num);
+
+ pudev->regs.pr[pp_num]->HCHINTF = pp_int;
+
+ pudev->host.pipe[pp_num].pp_status = pp_status;
+}
+
+/*!
+ \brief handle the host port interrupt
+ \param[in] pudev: pointer to USB device instance
+ \param[out] none
+ \retval operation status
+*/
+#if defined (__ICCARM__) /*!< IAR compiler */
+#pragma optimize = none
+#endif /* __ICCARM */
+static uint32_t usbh_int_port(usb_core_driver *pudev)
+{
+ uint32_t retval = 0U;
+
+ /* note: when the USB PHY use USB HS PHY, the flag is needed */
+ uint8_t port_reset = 0U;
+
+ __IO uint32_t port_state = *pudev->regs.HPCS;
+
+ /* clear the interrupt bits in GINTSTS */
+ port_state &= ~(HPCS_PE | HPCS_PCD | HPCS_PEDC);
+
+ /* port connect detected */
+ if(*pudev->regs.HPCS & HPCS_PCD) {
+ port_state |= HPCS_PCD;
+
+ usbh_int_fop->connect(pudev->host.data);
+
+ retval |= 1U;
+ }
+
+ /* port enable changed */
+ if(*pudev->regs.HPCS & HPCS_PEDC) {
+ port_state |= HPCS_PEDC;
+
+ if(*pudev->regs.HPCS & HPCS_PE) {
+ uint32_t port_speed = usb_curspeed_get(pudev);
+ uint32_t clock_type = pudev->regs.hr->HCTL & HCTL_CLKSEL;
+
+ pudev->host.connect_status = 1U;
+
+ if(PORT_SPEED_LOW == port_speed) {
+ pudev->regs.hr->HFT = 6000U;
+
+ if(HCTL_6MHZ != clock_type) {
+ if(USB_EMBEDDED_PHY == pudev->bp.phy_itf) {
+ usb_phyclock_config(pudev, HCTL_6MHZ);
+ }
+
+ port_reset = 1U;
+ }
+ } else if(PORT_SPEED_FULL == port_speed) {
+ pudev->regs.hr->HFT = 48000U;
+
+ if(HCTL_48MHZ != clock_type) {
+ if(USB_EMBEDDED_PHY == pudev->bp.phy_itf) {
+ usb_phyclock_config(pudev, HCTL_48MHZ);
+ }
+
+ port_reset = 1U;
+ }
+ } else {
+ /* for high speed device and others */
+ port_reset = 1U;
+ }
+
+ usbh_int_fop->port_enabled(pudev->host.data);
+
+ pudev->regs.gr->GINTEN |= GINTEN_DISCIE | GINTEN_SOFIE;
+ } else {
+ usbh_int_fop->port_disabled(pudev->host.data);
+ }
+ }
+
+ if(port_reset) {
+ usb_port_reset(pudev);
+ }
+
+ /* clear port interrupts */
+ *pudev->regs.HPCS = port_state;
+
+ return retval;
+}
+
+/*!
+ \brief handle all host channels interrupt
+ \param[in] pudev: pointer to USB device instance
+ \param[out] none
+ \retval operation status
+*/
+static uint32_t usbh_int_pipe(usb_core_driver *pudev)
+{
+ uint32_t pp_num = 0U;
+ uint32_t retval = 0U;
+
+ for(pp_num = 0U; pp_num < pudev->bp.num_pipe; pp_num++) {
+ if((pudev->regs.hr->HACHINT & HACHINT_HACHINT) & (1UL << pp_num)) {
+ if(pudev->regs.pr[pp_num]->HCHCTL & HCHCTL_EPDIR) {
+ retval |= usbh_int_pipe_in(pudev, pp_num);
+ } else {
+ retval |= usbh_int_pipe_out(pudev, pp_num);
+ }
+ }
+ }
+
+ return retval;
+}
+
+/*!
+ \brief handle the IN channel interrupt
+ \param[in] pudev: pointer to USB device instance
+ \param[in] pp_num: host channel number which is in (0..7)
+ \param[out] none
+ \retval operation status
+*/
+#if defined (__ICCARM__) /*!< IAR compiler */
+#pragma optimize = none
+#endif /* __ICCARM */
+static uint32_t usbh_int_pipe_in(usb_core_driver *pudev, uint32_t pp_num)
+{
+ usb_pr *pp_reg = pudev->regs.pr[pp_num];
+
+ usb_pipe *pp = &pudev->host.pipe[pp_num];
+
+ __IO uint32_t intr_pp = pp_reg->HCHINTF & pp_reg->HCHINTEN;
+
+ uint8_t ep_type = (uint8_t)((pp_reg->HCHCTL & HCHCTL_EPTYPE) >> 18U);
+
+ if(intr_pp & HCHINTF_ACK) {
+ pp_reg->HCHINTF = HCHINTF_ACK;
+ } else if(intr_pp & HCHINTF_STALL) {
+ usb_pp_halt(pudev, (uint8_t)pp_num, HCHINTF_STALL, PIPE_STALL);
+ pp_reg->HCHINTF = HCHINTF_NAK;
+
+ /* note: When there is a 'STALL', reset also NAK,
+ else, the pudev->host.pp_status = HC_STALL
+ will be overwritten by 'NAK' in code below */
+ intr_pp &= ~HCHINTF_NAK;
+ } else if(intr_pp & HCHINTF_DTER) {
+ usb_pp_halt(pudev, (uint8_t)pp_num, HCHINTF_DTER, PIPE_DTGERR);
+ pp_reg->HCHINTF = HCHINTF_NAK;
+ } else {
+ /* no operation */
+ }
+
+ if(intr_pp & HCHINTF_REQOVR) {
+ usb_pp_halt(pudev, (uint8_t)pp_num, HCHINTF_REQOVR, PIPE_REQOVR);
+ } else if(intr_pp & HCHINTF_TF) {
+ if((uint8_t)USB_USE_DMA == pudev->bp.transfer_mode) {
+ pudev->host.backup_xfercount[pp_num] = pp->xfer_len - (pp_reg->HCHLEN & HCHLEN_TLEN);
+ }
+
+ pp->pp_status = PIPE_XF;
+ pp->err_count = 0U;
+
+ pp_reg->HCHINTF = HCHINTF_TF;
+
+ switch(ep_type) {
+ case USB_EPTYPE_CTRL:
+ case USB_EPTYPE_BULK:
+ usb_pp_halt(pudev, (uint8_t)pp_num, HCHINTF_NAK, PIPE_XF);
+
+ pp->data_toggle_in ^= 1U;
+ break;
+
+ case USB_EPTYPE_INTR:
+ case USB_EPTYPE_ISOC:
+ pp_reg->HCHCTL |= HCHCTL_ODDFRM;
+ pp->urb_state = URB_DONE;
+ break;
+
+ default:
+ break;
+ }
+ } else if(intr_pp & HCHINTF_CH) {
+ pp_reg->HCHINTEN &= ~HCHINTEN_CHIE;
+
+ switch(pp->pp_status) {
+ case PIPE_XF:
+ pp->urb_state = URB_DONE;
+ break;
+
+ case PIPE_STALL:
+ pp->urb_state = URB_STALL;
+ break;
+
+ case PIPE_TRACERR:
+ case PIPE_DTGERR:
+ pp->err_count = 0U;
+ pp->urb_state = URB_ERROR;
+
+ pp->data_toggle_in ^= 1U;
+ break;
+
+ case PIPE_IDLE:
+ case PIPE_HALTED:
+ case PIPE_NAK:
+ case PIPE_NYET:
+ case PIPE_BBERR:
+ case PIPE_REQOVR:
+ default:
+ if((uint8_t)USB_EPTYPE_INTR == ep_type) {
+ pp->data_toggle_in ^= 1U;
+ }
+ break;
+ }
+
+ pp_reg->HCHINTF = HCHINTF_CH;
+ } else if(intr_pp & HCHINTF_USBER) {
+ pp->err_count++;
+ usb_pp_halt(pudev, (uint8_t)pp_num, HCHINTF_USBER, PIPE_TRACERR);
+ } else if(intr_pp & HCHINTF_NAK) {
+ switch(ep_type) {
+ case USB_EPTYPE_CTRL:
+ case USB_EPTYPE_BULK:
+ /* re-activate the channel */
+ pp_reg->HCHCTL = (pp_reg->HCHCTL | HCHCTL_CEN) & ~HCHCTL_CDIS;
+ break;
+
+ case USB_EPTYPE_INTR:
+ pp_reg->HCHINTEN |= HCHINTEN_CHIE;
+
+ (void)usb_pipe_halt(pudev, (uint8_t)pp_num);
+ break;
+
+ default:
+ break;
+ }
+
+ pp->pp_status = PIPE_NAK;
+
+ pp_reg->HCHINTF = HCHINTF_NAK;
+ } else {
+ /* no operation */
+ }
+
+ return 1U;
+}
+
+/*!
+ \brief handle the OUT channel interrupt
+ \param[in] pudev: pointer to USB device instance
+ \param[in] pp_num: host channel number which is in (0..7)
+ \param[out] none
+ \retval operation status
+*/
+#if defined (__ICCARM__) /*!< IAR compiler */
+#pragma optimize = none
+#endif /* __ICCARM */
+static uint32_t usbh_int_pipe_out(usb_core_driver *pudev, uint32_t pp_num)
+{
+ usb_pr *pp_reg = pudev->regs.pr[pp_num];
+
+ usb_pipe *pp = &pudev->host.pipe[pp_num];
+
+ uint32_t intr_pp = pp_reg->HCHINTF & pp_reg->HCHINTEN;
+
+ if(intr_pp & HCHINTF_ACK) {
+ if(URB_PING == pp->urb_state) {
+ pp->err_count = 0U;
+ usb_pp_halt(pudev, (uint8_t)pp_num, HCHINTF_TF, PIPE_XF);
+ }
+
+ pp_reg->HCHINTF = HCHINTF_ACK;
+ } else if(intr_pp & HCHINTF_STALL) {
+ usb_pp_halt(pudev, (uint8_t)pp_num, HCHINTF_STALL, PIPE_STALL);
+ } else if(intr_pp & HCHINTF_DTER) {
+ usb_pp_halt(pudev, (uint8_t)pp_num, HCHINTF_DTER, PIPE_DTGERR);
+ pp_reg->HCHINTF = HCHINTF_NAK;
+ } else if(intr_pp & HCHINTF_REQOVR) {
+ usb_pp_halt(pudev, (uint8_t)pp_num, HCHINTF_REQOVR, PIPE_REQOVR);
+ } else if(intr_pp & HCHINTF_TF) {
+ pp->err_count = 0U;
+ usb_pp_halt(pudev, (uint8_t)pp_num, HCHINTF_TF, PIPE_XF);
+ } else if(intr_pp & HCHINTF_NAK) {
+ pp->err_count = 0U;
+ usb_pp_halt(pudev, (uint8_t)pp_num, HCHINTF_NAK, PIPE_NAK);
+ } else if(intr_pp & HCHINTF_USBER) {
+ pp->err_count++;
+ usb_pp_halt(pudev, (uint8_t)pp_num, HCHINTF_USBER, PIPE_TRACERR);
+ } else if(intr_pp & HCHINTF_NYET) {
+ pp->err_count = 0U;
+ usb_pp_halt(pudev, (uint8_t)pp_num, HCHINTF_NYET, PIPE_NYET);
+ } else if(intr_pp & HCHINTF_CH) {
+ pudev->regs.pr[pp_num]->HCHINTEN &= ~HCHINTEN_CHIE;
+
+ switch(pp->pp_status) {
+ case PIPE_XF:
+ pp->urb_state = URB_DONE;
+
+ if((uint8_t)USB_EPTYPE_BULK == ((pp_reg->HCHCTL & HCHCTL_EPTYPE) >> 18U)) {
+ pp->data_toggle_out ^= 1U;
+ }
+ break;
+
+ case PIPE_NAK:
+
+ if(URB_PING == pp->urb_state) {
+ (void)usb_pipe_ping(pudev, (uint8_t)pp_num);
+ } else {
+ pp->urb_state = URB_NOTREADY;
+ }
+ break;
+
+ case PIPE_NYET:
+ if(1U == pudev->host.pipe[pp_num].ping) {
+ (void)usb_pipe_ping(pudev, (uint8_t)pp_num);
+ pp->urb_state = URB_PING;
+ } else {
+ pp->urb_state = URB_NOTREADY;
+ }
+ break;
+
+ case PIPE_STALL:
+ pp->urb_state = URB_STALL;
+ break;
+
+ case PIPE_TRACERR:
+ if(3U == pp->err_count) {
+ pp->urb_state = URB_ERROR;
+ pp->err_count = 0U;
+ }
+ break;
+
+ case PIPE_IDLE:
+ case PIPE_HALTED:
+ case PIPE_BBERR:
+ case PIPE_REQOVR:
+ case PIPE_DTGERR:
+ default:
+ break;
+ }
+
+ pp_reg->HCHINTF = HCHINTF_CH;
+ } else {
+ /* no operation */
+ }
+
+ return 1U;
+}
+
+/*!
+ \brief handle the RX FIFO non-empty interrupt
+ \param[in] pudev: pointer to USB device instance
+ \param[out] none
+ \retval operation status
+*/
+#if defined (__ICCARM__) /*!< IAR compiler */
+#pragma optimize = none
+#endif /* __ICCARM */
+static uint32_t usbh_int_rxfifonoempty(usb_core_driver *pudev)
+{
+ uint32_t count = 0U;
+
+ __IO uint8_t pp_num = 0U;
+ __IO uint32_t rx_stat = 0U;
+
+ /* disable the RX status queue level interrupt */
+ pudev->regs.gr->GINTEN &= ~GINTEN_RXFNEIE;
+
+ rx_stat = pudev->regs.gr->GRSTATP;
+ pp_num = (uint8_t)(rx_stat & GRSTATRP_CNUM);
+
+ switch((rx_stat & GRSTATRP_RPCKST) >> 17U) {
+ case GRXSTS_PKTSTS_IN:
+ count = (rx_stat & GRSTATRP_BCOUNT) >> 4U;
+
+ /* read the data into the host buffer. */
+ if((count > 0U) && (NULL != pudev->host.pipe[pp_num].xfer_buf)) {
+ (void)usb_rxfifo_read(&pudev->regs, pudev->host.pipe[pp_num].xfer_buf, (uint16_t)count);
+
+ /* manage multiple transfer packet */
+ pudev->host.pipe[pp_num].xfer_buf += count;
+ pudev->host.pipe[pp_num].xfer_count += count;
+
+ pudev->host.backup_xfercount[pp_num] = pudev->host.pipe[pp_num].xfer_count;
+
+ if(pudev->regs.pr[pp_num]->HCHLEN & HCHLEN_PCNT) {
+ /* re-activate the channel when more packets are expected */
+ __IO uint32_t pp_ctl = pudev->regs.pr[pp_num]->HCHCTL;
+
+ pp_ctl |= HCHCTL_CEN;
+ pp_ctl &= ~HCHCTL_CDIS;
+
+ pudev->regs.pr[pp_num]->HCHCTL = pp_ctl;
+ }
+ }
+ break;
+
+ case GRXSTS_PKTSTS_IN_XFER_COMP:
+ break;
+
+ case GRXSTS_PKTSTS_DATA_TOGGLE_ERR:
+ count = (rx_stat & GRSTATRP_BCOUNT) >> 4U;
+
+ while(count > 0U) {
+ rx_stat = pudev->regs.gr->GRSTATP;
+ count--;
+ }
+ break;
+
+ case GRXSTS_PKTSTS_CH_HALTED:
+ break;
+
+ default:
+ break;
+ }
+
+ /* enable the RX status queue level interrupt */
+ pudev->regs.gr->GINTEN |= GINTEN_RXFNEIE;
+
+ return 1U;
+}
+
+/*!
+ \brief handle the TX FIFO empty interrupt
+ \param[in] pudev: pointer to USB device instance
+ \param[in] pp_mode: pipe mode
+ \param[out] none
+ \retval operation status
+*/
+#if defined (__ICCARM__) /*!< IAR compiler */
+#pragma optimize = none
+#endif /* __ICCARM */
+static uint32_t usbh_int_txfifoempty(usb_core_driver *pudev, usb_pipe_mode pp_mode)
+{
+ uint8_t pp_num = 0U;
+ uint16_t word_count = 0U, len = 0U;
+ __IO uint32_t *txfiforeg = 0U, txfifostate = 0U;
+
+ if(PIPE_NON_PERIOD == pp_mode) {
+ txfiforeg = &pudev->regs.gr->HNPTFQSTAT;
+ } else if(PIPE_PERIOD == pp_mode) {
+ txfiforeg = &pudev->regs.hr->HPTFQSTAT;
+ } else {
+ return 0U;
+ }
+
+ txfifostate = *txfiforeg;
+
+ pp_num = (uint8_t)((txfifostate & TFQSTAT_CNUM) >> 27U);
+
+ word_count = (uint16_t)(pudev->host.pipe[pp_num].xfer_len + 3U) / 4U;
+
+ while(((txfifostate & TFQSTAT_TXFS) >= word_count) && (0U != pudev->host.pipe[pp_num].xfer_len)) {
+ len = (uint16_t)(txfifostate & TFQSTAT_TXFS) * 4U;
+
+ if(len > pudev->host.pipe[pp_num].xfer_len) {
+ /* last packet */
+ len = (uint16_t)pudev->host.pipe[pp_num].xfer_len;
+
+ if(PIPE_NON_PERIOD == pp_mode) {
+ pudev->regs.gr->GINTEN &= ~GINTEN_NPTXFEIE;
+ } else {
+ pudev->regs.gr->GINTEN &= ~GINTEN_PTXFEIE;
+ }
+ }
+
+ word_count = (uint16_t)((pudev->host.pipe[pp_num].xfer_len + 3U) / 4U);
+ usb_txfifo_write(&pudev->regs, pudev->host.pipe[pp_num].xfer_buf, pp_num, len);
+
+ pudev->host.pipe[pp_num].xfer_buf += len;
+ pudev->host.pipe[pp_num].xfer_len -= len;
+ pudev->host.pipe[pp_num].xfer_count += len;
+
+ txfifostate = *txfiforeg;
+ }
+
+ return 1U;
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/hid/Include/usbh_hid_core.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/hid/Include/usbh_hid_core.h
new file mode 100644
index 00000000..58c2df70
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/hid/Include/usbh_hid_core.h
@@ -0,0 +1,205 @@
+/*!
+ \file usbh_hid_core.h
+ \brief header file for the usbh_hid_core.c
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __USBH_HID_CORE_H
+#define __USBH_HID_CORE_H
+
+#include "usb_hid.h"
+#include "usbh_enum.h"
+#include "usbh_transc.h"
+
+#define HID_MIN_POLL 10U
+#define HID_REPORT_SIZE 16U
+#define HID_MAX_USAGE 10U
+#define HID_MAX_NBR_REPORT_FMT 10U
+#define HID_QUEUE_SIZE 10U
+
+#define HID_ITEM_LONG 0xFEU
+
+#define HID_ITEM_TYPE_MAIN 0x00U
+#define HID_ITEM_TYPE_GLOBAL 0x01U
+#define HID_ITEM_TYPE_LOCAL 0x02U
+#define HID_ITEM_TYPE_RESERVED 0x03U
+
+#define HID_MAIN_ITEM_TAG_INPUT 0x08U
+#define HID_MAIN_ITEM_TAG_OUTPUT 0x09U
+#define HID_MAIN_ITEM_TAG_COLLECTION 0x0AU
+#define HID_MAIN_ITEM_TAG_FEATURE 0x0BU
+#define HID_MAIN_ITEM_TAG_ENDCOLLECTION 0x0CU
+
+#define HID_GLOBAL_ITEM_TAG_USAGE_PAGE 0x00U
+#define HID_GLOBAL_ITEM_TAG_LOG_MIN 0x01U
+#define HID_GLOBAL_ITEM_TAG_LOG_MAX 0x02U
+#define HID_GLOBAL_ITEM_TAG_PHY_MIN 0x03U
+#define HID_GLOBAL_ITEM_TAG_PHY_MAX 0x04U
+#define HID_GLOBAL_ITEM_TAG_UNIT_EXPONENT 0x05U
+#define HID_GLOBAL_ITEM_TAG_UNIT 0x06U
+#define HID_GLOBAL_ITEM_TAG_REPORT_SIZE 0x07U
+#define HID_GLOBAL_ITEM_TAG_REPORT_ID 0x08U
+#define HID_GLOBAL_ITEM_TAG_REPORT_COUNT 0x09U
+#define HID_GLOBAL_ITEM_TAG_PUSH 0x0AU
+#define HID_GLOBAL_ITEM_TAG_POP 0x0BU
+
+#define HID_LOCAL_ITEM_TAG_USAGE 0x00U
+#define HID_LOCAL_ITEM_TAG_USAGE_MIN 0x01U
+#define HID_LOCAL_ITEM_TAG_USAGE_MAX 0x02U
+#define HID_LOCAL_ITEM_TAG_DESIGNATOR_INDEX 0x03U
+#define HID_LOCAL_ITEM_TAG_DESIGNATOR_MIN 0x04U
+#define HID_LOCAL_ITEM_TAG_DESIGNATOR_MAX 0x05U
+#define HID_LOCAL_ITEM_TAG_STRING_INDEX 0x07U
+#define HID_LOCAL_ITEM_TAG_STRING_MIN 0x08U
+#define HID_LOCAL_ITEM_TAG_STRING_MAX 0x09U
+#define HID_LOCAL_ITEM_TAG_DELIMITER 0x0AU
+
+#define USB_HID_DESC_SIZE 9U
+
+/* states for HID state machine */
+typedef enum {
+ HID_INIT = 0U,
+ HID_IDLE,
+ HID_SEND_DATA,
+ HID_BUSY,
+ HID_GET_DATA,
+ HID_SYNC,
+ HID_POLL,
+ HID_ERROR,
+} hid_state;
+
+typedef enum {
+ HID_REQ_INIT = 0U,
+ HID_REQ_IDLE,
+ HID_REQ_GET_REPORT_DESC,
+ HID_REQ_GET_HID_DESC,
+ HID_REQ_SET_IDLE,
+ HID_REQ_SET_PROTOCOL,
+ HID_REQ_SET_REPORT,
+} hid_ctlstate;
+
+typedef enum {
+ HID_MOUSE = 0x01U,
+ HID_KEYBOARD = 0x02U,
+ HID_UNKNOWN = 0xFFU,
+} hid_type;
+
+typedef struct _hid_report_data {
+ uint8_t ReportID;
+ uint8_t ReportType;
+ uint16_t UsagePage;
+ uint32_t Usage[HID_MAX_USAGE];
+ uint32_t NbrUsage;
+ uint32_t UsageMin;
+ uint32_t UsageMax;
+ int32_t LogMin;
+ int32_t LogMax;
+ int32_t PhyMin;
+ int32_t PhyMax;
+ int32_t UnitExp;
+ uint32_t Unit;
+ uint32_t ReportSize;
+ uint32_t ReportCnt;
+ uint32_t Flag;
+ uint32_t PhyUsage;
+ uint32_t AppUsage;
+ uint32_t LogUsage;
+} hid_report_data;
+
+typedef struct _hid_report_ID {
+ uint8_t size; /*!< report size return by the device ID */
+ uint8_t reportID; /*!< report ID */
+ uint8_t type; /*!< report type (INPUT/OUTPUT/FEATURE) */
+} hid_report_ID;
+
+typedef struct _hid_collection {
+ uint32_t usage;
+ uint8_t type;
+ struct _hid_collection *next_ptr;
+} hid_collection;
+
+typedef struct _hid_appcollection {
+ uint32_t usage;
+ uint8_t type;
+ uint8_t nbr_report_fmt;
+ hid_report_data report_data[HID_MAX_NBR_REPORT_FMT];
+} hid_appcollection;
+
+typedef struct {
+ uint8_t *buf;
+ uint16_t head;
+ uint16_t tail;
+ uint16_t size;
+ uint8_t lock;
+} data_fifo;
+
+/* structure for HID process */
+typedef struct _hid_process {
+ uint8_t pipe_in;
+ uint8_t pipe_out;
+ uint8_t ep_addr;
+ uint8_t ep_in;
+ uint8_t ep_out;
+ __IO uint8_t data_ready;
+ uint8_t *pdata;
+ uint16_t len;
+ uint16_t poll;
+
+ __IO uint32_t timer;
+
+ data_fifo fifo;
+ usb_desc_hid hid_desc;
+ hid_report_data hid_report;
+
+ hid_state state;
+ hid_ctlstate ctl_state;
+ usbh_status(*init)(usb_core_driver *pudev, usbh_host *puhost);
+ void (*machine)(usb_core_driver *pudev, usbh_host *puhost);
+} usbh_hid_handler;
+
+extern usbh_class usbh_hid;
+
+/* function declarations */
+/* set HID report */
+usbh_status usbh_set_report(usb_core_driver *pudev,
+ usbh_host *puhost,
+ uint8_t report_type,
+ uint8_t report_ID,
+ uint8_t report_len,
+ uint8_t *report_buf);
+/* read data from FIFO */
+uint16_t usbh_hid_fifo_read(data_fifo *fifo, void *buf, uint16_t nbytes);
+/* write data to FIFO */
+uint16_t usbh_hid_fifo_write(data_fifo *fifo, void *buf, uint16_t nbytes);
+/* initialize FIFO */
+void usbh_hid_fifo_init(data_fifo *fifo, uint8_t *buf, uint16_t size);
+
+#endif /* __USBH_HID_CORE_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/hid/Include/usbh_hid_keybd.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/hid/Include/usbh_hid_keybd.h
new file mode 100644
index 00000000..002312ec
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/hid/Include/usbh_hid_keybd.h
@@ -0,0 +1,302 @@
+/*!
+ \file usbh_hid_keybd.h
+ \brief header file for usbh_hid_keybd.c
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __USBH_HID_KEYBD_H
+#define __USBH_HID_KEYBD_H
+
+#include "usb_conf.h"
+#include "usbh_hid_core.h"
+
+//#define AZERTY_KEYBOARD
+#define QWERTY_KEYBOARD
+
+#define KBD_LEFT_CTRL 0x01U
+#define KBD_LEFT_SHIFT 0x02U
+#define KBD_LEFT_ALT 0x04U
+#define KBD_LEFT_GUI 0x08U
+#define KBD_RIGHT_CTRL 0x10U
+#define KBD_RIGHT_SHIFT 0x20U
+#define KBD_RIGHT_ALT 0x40U
+#define KBD_RIGHT_GUI 0x80U
+
+#define KEY_NONE 0x00U
+#define KEY_ERRORROLLOVER 0x01U
+#define KEY_POSTFAIL 0x02U
+#define KEY_ERRORUNDEFINED 0x03U
+#define KEY_A 0x04U
+#define KEY_B 0x05U
+#define KEY_C 0x06U
+#define KEY_D 0x07U
+#define KEY_E 0x08U
+#define KEY_F 0x09U
+#define KEY_G 0x0AU
+#define KEY_H 0x0BU
+#define KEY_I 0x0CU
+#define KEY_J 0x0DU
+#define KEY_K 0x0EU
+#define KEY_L 0x0FU
+#define KEY_M 0x10U
+#define KEY_N 0x11U
+#define KEY_O 0x12U
+#define KEY_P 0x13U
+#define KEY_Q 0x14U
+#define KEY_R 0x15U
+#define KEY_S 0x16U
+#define KEY_T 0x17U
+#define KEY_U 0x18U
+#define KEY_V 0x19U
+#define KEY_W 0x1AU
+#define KEY_X 0x1BU
+#define KEY_Y 0x1CU
+#define KEY_Z 0x1DU
+#define KEY_1_EXCLAMATION_MARK 0x1EU
+#define KEY_2_AT 0x1FU
+#define KEY_3_NUMBER_SIGN 0x20U
+#define KEY_4_DOLLAR 0x21U
+#define KEY_5_PERCENT 0x22U
+#define KEY_6_CARET 0x23U
+#define KEY_7_AMPERSAND 0x24U
+#define KEY_8_ASTERISK 0x25U
+#define KEY_9_OPARENTHESIS 0x26U
+#define KEY_0_CPARENTHESIS 0x27U
+#define KEY_ENTER 0x28U
+#define KEY_ESCAPE 0x29U
+#define KEY_BACKSPACE 0x2AU
+#define KEY_TAB 0x2BU
+#define KEY_SPACEBAR 0x2CU
+#define KEY_MINUS_UNDERSCORE 0x2DU
+#define KEY_EQUAL_PLUS 0x2EU
+#define KEY_OBRACKET_AND_OBRACE 0x2FU
+#define KEY_CBRACKET_AND_CBRACE 0x30U
+#define KEY_BACKSLASH_VERTICAL_BAR 0x31U
+#define KEY_NONUS_NUMBER_SIGN_TILDE 0x32U
+#define KEY_SEMICOLON_COLON 0x33U
+#define KEY_SINGLE_AND_DOUBLE_QUOTE 0x34U
+#define KEY_GRAVE ACCENT AND TILDE 0x35U
+#define KEY_COMMA_AND_LESS 0x36U
+#define KEY_DOT_GREATER 0x37U
+#define KEY_SLASH_QUESTION 0x38U
+#define KEY_CAPS LOCK 0x39U
+#define KEY_F1 0x3AU
+#define KEY_F2 0x3BU
+#define KEY_F3 0x3CU
+#define KEY_F4 0x3DU
+#define KEY_F5 0x3EU
+#define KEY_F6 0x3FU
+#define KEY_F7 0x40U
+#define KEY_F8 0x41U
+#define KEY_F9 0x42U
+#define KEY_F10 0x43U
+#define KEY_F11 0x44U
+#define KEY_F12 0x45U
+#define KEY_PRINTSCREEN 0x46U
+#define KEY_SCROLL LOCK 0x47U
+#define KEY_PAUSE 0x48U
+#define KEY_INSERT 0x49U
+#define KEY_HOME 0x4AU
+#define KEY_PAGEUP 0x4BU
+#define KEY_DELETE 0x4CU
+#define KEY_END1 0x4DU
+#define KEY_PAGEDOWN 0x4EU
+#define KEY_RIGHTARROW 0x4FU
+#define KEY_LEFTARROW 0x50U
+#define KEY_DOWNARROW 0x51U
+#define KEY_UPARROW 0x52U
+#define KEY_KEYPAD_NUM_LOCK_AND_CLEAR 0x53U
+#define KEY_KEYPAD_SLASH 0x54U
+#define KEY_KEYPAD_ASTERIKS 0x55U
+#define KEY_KEYPAD_MINUS 0x56U
+#define KEY_KEYPAD_PLUS 0x57U
+#define KEY_KEYPAD_ENTER 0x58U
+#define KEY_KEYPAD_1_END 0x59U
+#define KEY_KEYPAD_2_DOWN_ARROW 0x5AU
+#define KEY_KEYPAD_3_PAGEDN 0x5BU
+#define KEY_KEYPAD_4_LEFT_ARROW 0x5CU
+#define KEY_KEYPAD_5 0x5DU
+#define KEY_KEYPAD_6_RIGHT_ARROW 0x5EU
+#define KEY_KEYPAD_7_HOME 0x5FU
+#define KEY_KEYPAD_8_UP_ARROW 0x60U
+#define KEY_KEYPAD_9_PAGEUP 0x61U
+#define KEY_KEYPAD_0_INSERT 0x62U
+#define KEY_KEYPAD_DECIMAL_SEPARATOR_DELETE 0x63U
+#define KEY_NONUS_BACK_SLASH_VERTICAL_BAR 0x64U
+#define KEY_APPLICATION 0x65U
+#define KEY_POWER 0x66U
+#define KEY_KEYPAD_EQUAL 0x67U
+#define KEY_F13 0x68U
+#define KEY_F14 0x69U
+#define KEY_F15 0x6AU
+#define KEY_F16 0x6BU
+#define KEY_F17 0x6CU
+#define KEY_F18 0x6DU
+#define KEY_F19 0x6EU
+#define KEY_F20 0x6FU
+#define KEY_F21 0x70U
+#define KEY_F22 0x71U
+#define KEY_F23 0x72U
+#define KEY_F24 0x73U
+#define KEY_EXECUTE 0x74U
+#define KEY_HELP 0x75U
+#define KEY_MENU 0x76U
+#define KEY_SELECT 0x77U
+#define KEY_STOP 0x78U
+#define KEY_AGAIN 0x79U
+#define KEY_UNDO 0x7AU
+#define KEY_CUT 0x7BU
+#define KEY_COPY 0x7CU
+#define KEY_PASTE 0x7DU
+#define KEY_FIND 0x7EU
+#define KEY_MUTE 0x7FU
+#define KEY_VOLUME_UP 0x80U
+#define KEY_VOLUME_DOWN 0x81U
+#define KEY_LOCKING_CAPS_LOCK 0x82U
+#define KEY_LOCKING_NUM_LOCK 0x83U
+#define KEY_LOCKING_SCROLL_LOCK 0x84U
+#define KEY_KEYPAD_COMMA 0x85U
+#define KEY_KEYPAD_EQUAL_SIGN 0x86U
+#define KEY_INTERNATIONAL1 0x87U
+#define KEY_INTERNATIONAL2 0x88U
+#define KEY_INTERNATIONAL3 0x89U
+#define KEY_INTERNATIONAL4 0x8AU
+#define KEY_INTERNATIONAL5 0x8BU
+#define KEY_INTERNATIONAL6 0x8CU
+#define KEY_INTERNATIONAL7 0x8DU
+#define KEY_INTERNATIONAL8 0x8EU
+#define KEY_INTERNATIONAL9 0x8FU
+#define KEY_LANG1 0x90U
+#define KEY_LANG2 0x91U
+#define KEY_LANG3 0x92U
+#define KEY_LANG4 0x93U
+#define KEY_LANG5 0x94U
+#define KEY_LANG6 0x95U
+#define KEY_LANG7 0x96U
+#define KEY_LANG8 0x97U
+#define KEY_LANG9 0x98U
+#define KEY_ALTERNATE_ERASE 0x99U
+#define KEY_SYSREQ 0x9AU
+#define KEY_CANCEL 0x9BU
+#define KEY_CLEAR 0x9CU
+#define KEY_PRIOR 0x9DU
+#define KEY_RETURN 0x9EU
+#define KEY_SEPARATOR 0x9FU
+#define KEY_OUT 0xA0U
+#define KEY_OPER 0xA1U
+#define KEY_CLEAR_AGAIN 0xA2U
+#define KEY_CRSEL 0xA3U
+#define KEY_EXSEL 0xA4U
+#define KEY_KEYPAD_00 0xB0U
+#define KEY_KEYPAD_000 0xB1U
+#define KEY_THOUSANDS_SEPARATOR 0xB2U
+#define KEY_DECIMAL_SEPARATOR 0xB3U
+#define KEY_CURRENCY_UNIT 0xB4U
+#define KEY_CURRENCY_SUB_UNIT 0xB5U
+#define KEY_KEYPAD_OPARENTHESIS 0xB6U
+#define KEY_KEYPAD_CPARENTHESIS 0xB7U
+#define KEY_KEYPAD_OBRACE 0xB8U
+#define KEY_KEYPAD_CBRACE 0xB9U
+#define KEY_KEYPAD_TAB 0xBAU
+#define KEY_KEYPAD_BACKSPACE 0xBBU
+#define KEY_KEYPAD_A 0xBCU
+#define KEY_KEYPAD_B 0xBDU
+#define KEY_KEYPAD_C 0xBEU
+#define KEY_KEYPAD_D 0xBFU
+#define KEY_KEYPAD_E 0xC0U
+#define KEY_KEYPAD_F 0xC1U
+#define KEY_KEYPAD_XOR 0xC2U
+#define KEY_KEYPAD_CARET 0xC3U
+#define KEY_KEYPAD_PERCENT 0xC4U
+#define KEY_KEYPAD_LESS 0xC5U
+#define KEY_KEYPAD_GREATER 0xC6U
+#define KEY_KEYPAD_AMPERSAND 0xC7U
+#define KEY_KEYPAD_LOGICAL_AND 0xC8U
+#define KEY_KEYPAD_VERTICAL_BAR 0xC9U
+#define KEY_KEYPAD_LOGIACL_OR 0xCAU
+#define KEY_KEYPAD_COLON 0xCBU
+#define KEY_KEYPAD_NUMBER_SIGN 0xCCU
+#define KEY_KEYPAD_SPACE 0xCDU
+#define KEY_KEYPAD_AT 0xCEU
+#define KEY_KEYPAD_EXCLAMATION_MARK 0xCFU
+#define KEY_KEYPAD_MEMORY_STORE 0xD0U
+#define KEY_KEYPAD_MEMORY_RECALL 0xD1U
+#define KEY_KEYPAD_MEMORY_CLEAR 0xD2U
+#define KEY_KEYPAD_MEMORY_ADD 0xD3U
+#define KEY_KEYPAD_MEMORY_SUBTRACT 0xD4U
+#define KEY_KEYPAD_MEMORY_MULTIPLY 0xD5U
+#define KEY_KEYPAD_MEMORY_DIVIDE 0xD6U
+#define KEY_KEYPAD_PLUSMINUS 0xD7U
+#define KEY_KEYPAD_CLEAR 0xD8U
+#define KEY_KEYPAD_CLEAR_ENTRY 0xD9U
+#define KEY_KEYPAD_BINARY 0xDAU
+#define KEY_KEYPAD_OCTAL 0xDBU
+#define KEY_KEYPAD_DECIMAL 0xDCU
+#define KEY_KEYPAD_HEXADECIMAL 0xDDU
+#define KEY_LEFTCONTROL 0xE0U
+#define KEY_LEFTSHIFT 0xE1U
+#define KEY_LEFTALT 0xE2U
+#define KEY_LEFT_GUI 0xE3U
+#define KEY_RIGHTCONTROL 0xE4U
+#define KEY_RIGHTSHIFT 0xE5U
+#define KEY_RIGHTALT 0xE6U
+#define KEY_RIGHT_GUI 0xE7U
+
+#define KBR_MAX_NBR_PRESSED 6U
+
+typedef struct {
+ uint8_t state;
+ uint8_t lctrl;
+ uint8_t lshift;
+ uint8_t lalt;
+ uint8_t lgui;
+ uint8_t rctrl;
+ uint8_t rshift;
+ uint8_t ralt;
+ uint8_t rgui;
+ uint8_t keys[6];
+} hid_keybd_info;
+
+/* function declarations */
+/* initialize keyboard */
+void usr_keybrd_init(void);
+/* process keyboard data */
+void usr_keybrd_process_data(uint8_t pbuf);
+/* initialize the keyboard function */
+usbh_status usbh_hid_keybd_init(usb_core_driver *pudev, usbh_host *puhost);
+/* get keyboard information */
+hid_keybd_info *usbh_hid_keybd_info_get(usb_core_driver *pudev, usbh_host *puhost);
+/* get the ascii code of hid */
+uint8_t usbh_hid_ascii_code_get(hid_keybd_info *info);
+/* keyboard machine */
+void usbh_hid_keybrd_machine(usb_core_driver *pudev, usbh_host *puhost);
+
+#endif /* __USBH_HID_KEYBD_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/hid/Include/usbh_hid_mouse.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/hid/Include/usbh_hid_mouse.h
new file mode 100644
index 00000000..bbb16824
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/hid/Include/usbh_hid_mouse.h
@@ -0,0 +1,58 @@
+/*!
+ \file usbh_hid_mouse.h
+ \brief header file for the usbh_hid_mouse.c
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __USBH_HID_MOUSE_H
+#define __USBH_HID_MOUSE_H
+
+#include "usbh_hid_core.h"
+
+typedef struct _hid_mouse_info {
+ uint8_t x;
+ uint8_t y;
+ uint8_t buttons[3];
+} hid_mouse_info;
+
+/* function declarations */
+/* initialize mouse */
+void usr_mouse_init(void);
+/* process mouse data */
+void usr_mouse_process_data(hid_mouse_info *data);
+/* initialize mouse function */
+usbh_status usbh_hid_mouse_init(usb_core_driver *pudev, usbh_host *puhost);
+/* get mouse information */
+hid_mouse_info *usbh_hid_mouse_info_get(usb_core_driver *pudev, usbh_host *puhost);
+/* mouse machine */
+void usbh_hid_mouse_machine(usb_core_driver *pudev, usbh_host *puhost);
+
+#endif /* __USBH_HID_MOUSE_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/hid/Include/usbh_hid_parser.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/hid/Include/usbh_hid_parser.h
new file mode 100644
index 00000000..ba950e4b
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/hid/Include/usbh_hid_parser.h
@@ -0,0 +1,60 @@
+/*!
+ \file usbh_hid_core.h
+ \brief header file for the usbh_hid_core.c
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __USBH_HID_PARSER_H
+#define __USBH_HID_PARSER_H
+
+#include "usbh_hid_core.h"
+#include "usbh_hid_usage.h"
+
+typedef struct {
+ uint8_t *data;
+ uint32_t size;
+ uint8_t shift;
+ uint8_t count;
+ uint8_t sign;
+ uint32_t logical_min; /*min value device can return*/
+ uint32_t logical_max; /*max value device can return*/
+ uint32_t physical_min; /*min vale read can report*/
+ uint32_t physical_max; /*max value read can report*/
+ uint32_t resolution;
+} hid_report_item;
+
+/* function declarations */
+/* read a hid report item */
+uint32_t hid_item_read(hid_report_item *ri, uint8_t ndx);
+/* write a hid report item */
+uint32_t hid_item_write(hid_report_item *ri, uint32_t value, uint8_t ndx);
+
+#endif /* __USBH_HID_PARSER_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/hid/Include/usbh_hid_usage.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/hid/Include/usbh_hid_usage.h
new file mode 100644
index 00000000..f2c3029a
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/hid/Include/usbh_hid_usage.h
@@ -0,0 +1,141 @@
+/*!
+ \file usbh_hid_core.h
+ \brief header file for the usbh_hid_core.c
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __USDH_HID_USAGE_H
+#define __USDH_HID_USAGE_H
+
+/* HID 1.11 usage pages */
+#define HID_USAGE_PAGE_UNDEFINED uint16_t (0x00) /* Undefined */
+
+/* top level pages */
+#define HID_USAGE_PAGE_GEN_DES uint16_t (0x01) /* Generic Desktop Controls*/
+#define HID_USAGE_PAGE_SIM_CTR uint16_t (0x02) /* Simulation Controls */
+#define HID_USAGE_PAGE_VR_CTR uint16_t (0x03) /* VR Controls */
+#define HID_USAGE_PAGE_SPORT_CTR uint16_t (0x04) /* Sport Controls */
+#define HID_USAGE_PAGE_GAME_CTR uint16_t (0x05) /* Game Controls */
+#define HID_USAGE_PAGE_GEN_DEV uint16_t (0x06) /* Generic Device Controls */
+#define HID_USAGE_PAGE_KEYB uint16_t (0x07) /* Keyboard/Keypad */
+#define HID_USAGE_PAGE_LED uint16_t (0x08) /* LEDs */
+#define HID_USAGE_PAGE_BUTTON uint16_t (0x09) /* Button */
+#define HID_USAGE_PAGE_ORDINAL uint16_t (0x0A) /* Ordinal */
+#define HID_USAGE_PAGE_PHONE uint16_t (0x0B) /* Telephony */
+#define HID_USAGE_PAGE_CONSUMER uint16_t (0x0C) /* Consumer */
+#define HID_USAGE_PAGE_DIGITIZER uint16_t (0x0D) /* Digitizer*/
+#define HID_USAGE_PAGE_PID uint16_t (0x0F) /* PID Page (force feedback and related devices) */
+#define HID_USAGE_PAGE_UNICODE uint16_t (0x10) /* Unicode */
+#define HID_USAGE_PAGE_ALNUM_DISP uint16_t (0x14) /* Alphanumeric Display */
+/* end of top level pages */
+
+#define HID_USAGE_PAGE_MEDICAL uint16_t (0x40) /* Medical Instruments */
+
+/* 80-83 Monitor pages USB Device Class Definition for Monitor Devices */
+/* 84-87 Power pages USB Device Class Definition for Power Devices */
+#define HID_USAGE_PAGE_BARCODE uint16_t (0x8C) /* Bar Code Scanner page */
+#define HID_USAGE_PAGE_SCALE uint16_t (0x8D) /* Scale page */
+#define HID_USAGE_PAGE_MSR uint16_t (0x8E) /* Magnetic Stripe Reading (MSR) Devices */
+#define HID_USAGE_PAGE_POS uint16_t (0x8F) /* Reserved Point of Sale pages */
+#define HID_USAGE_PAGE_CAMERA_CTR uint16_t (0x90) /* Camera Control Page */
+#define HID_USAGE_PAGE_ARCADE uint16_t (0x91) /* Arcade Page */
+
+/* usage definitions for the "generic desktop" page */
+#define HID_USAGE_UNDEFINED uint16_t (0x00) /* Undefined */
+#define HID_USAGE_POINTER uint16_t (0x01) /* Pointer (Physical Collection) */
+#define HID_USAGE_MOUSE uint16_t (0x02) /* Mouse (Application Collection) */
+#define HID_USAGE_JOYSTICK uint16_t (0x04) /* Joystick (Application Collection) */
+#define HID_USAGE_GAMEPAD uint16_t (0x05) /* Game Pad (Application Collection) */
+#define HID_USAGE_KBD uint16_t (0x06) /* Keyboard (Application Collection) */
+#define HID_USAGE_KEYPAD uint16_t (0x07) /* Keypad (Application Collection) */
+#define HID_USAGE_MAX_CTR uint16_t (0x08) /* Multi-axis Controller (Application Collection) */
+#define HID_USAGE_X uint16_t (0x30) /* X (Dynamic Value) */
+#define HID_USAGE_Y uint16_t (0x31) /* Y (Dynamic Value) */
+#define HID_USAGE_Z uint16_t (0x32) /* Z (Dynamic Value) */
+#define HID_USAGE_RX uint16_t (0x33) /* Rx (Dynamic Value) */
+#define HID_USAGE_RY uint16_t (0x34) /* Ry (Dynamic Value) */
+#define HID_USAGE_RZ uint16_t (0x35) /* Rz (Dynamic Value) */
+#define HID_USAGE_SLIDER uint16_t (0x36) /* Slider (Dynamic Value) */
+#define HID_USAGE_DIAL uint16_t (0x37) /* Dial (Dynamic Value) */
+#define HID_USAGE_WHEEL uint16_t (0x38) /* Wheel (Dynamic Value) */
+#define HID_USAGE_HATSW uint16_t (0x39) /* Hat switch (Dynamic Value) */
+#define HID_USAGE_COUNTEDBUF uint16_t (0x3A) /* Counted Buffer (Logical Collection) */
+#define HID_USAGE_BYTECOUNT uint16_t (0x3B) /* Byte Count (Dynamic Value) */
+#define HID_USAGE_MOTIONWAKE uint16_t (0x3C) /* Motion Wakeup (One Shot Control) */
+#define HID_USAGE_START uint16_t (0x3D) /* Start (On/Off Control) */
+#define HID_USAGE_SELECT uint16_t (0x3E) /* Select (On/Off Control) */
+#define HID_USAGE_VX uint16_t (0x40) /* Vx (Dynamic Value) */
+#define HID_USAGE_VY uint16_t (0x41) /* Vy (Dynamic Value) */
+#define HID_USAGE_VZ uint16_t (0x42) /* Vz (Dynamic Value) */
+#define HID_USAGE_VBRX uint16_t (0x43) /* Vbrx (Dynamic Value) */
+#define HID_USAGE_VBRY uint16_t (0x44) /* Vbry (Dynamic Value) */
+#define HID_USAGE_VBRZ uint16_t (0x45) /* Vbrz (Dynamic Value) */
+#define HID_USAGE_VNO uint16_t (0x46) /* Vno (Dynamic Value) */
+#define HID_USAGE_FEATNOTIF uint16_t (0x47) /* Feature Notification (Dynamic Value),(Dynamic Flag) */
+#define HID_USAGE_SYSCTL uint16_t (0x80) /* System Control (Application Collection) */
+#define HID_USAGE_PWDOWN uint16_t (0x81) /* System Power Down (One Shot Control) */
+#define HID_USAGE_SLEEP uint16_t (0x82) /* System Sleep (One Shot Control) */
+#define HID_USAGE_WAKEUP uint16_t (0x83) /* System Wake Up (One Shot Control) */
+#define HID_USAGE_CONTEXTM uint16_t (0x84) /* System Context Menu (One Shot Control) */
+#define HID_USAGE_MAINM uint16_t (0x85) /* System Main Menu (One Shot Control) */
+#define HID_USAGE_APPM uint16_t (0x86) /* System App Menu (One Shot Control) */
+#define HID_USAGE_MENUHELP uint16_t (0x87) /* System Menu Help (One Shot Control) */
+#define HID_USAGE_MENUEXIT uint16_t (0x88) /* System Menu Exit (One Shot Control) */
+#define HID_USAGE_MENUSELECT uint16_t (0x89) /* System Menu Select (One Shot Control) */
+#define HID_USAGE_SYSM_RIGHT uint16_t (0x8A) /* System Menu Right (Re-Trigger Control) */
+#define HID_USAGE_SYSM_LEFT uint16_t (0x8B) /* System Menu Left (Re-Trigger Control) */
+#define HID_USAGE_SYSM_UP uint16_t (0x8C) /* System Menu Up (Re-Trigger Control) */
+#define HID_USAGE_SYSM_DOWN uint16_t (0x8D) /* System Menu Down (Re-Trigger Control) */
+#define HID_USAGE_COLDRESET uint16_t (0x8E) /* System Cold Restart (One Shot Control) */
+#define HID_USAGE_WARMRESET uint16_t (0x8F) /* System Warm Restart (One Shot Control) */
+#define HID_USAGE_DUP uint16_t (0x90) /* D-pad Up (On/Off Control) */
+#define HID_USAGE_DDOWN uint16_t (0x91) /* D-pad Down (On/Off Control) */
+#define HID_USAGE_DRIGHT uint16_t (0x92) /* D-pad Right (On/Off Control) */
+#define HID_USAGE_DLEFT uint16_t (0x93) /* D-pad Left (On/Off Control) */
+#define HID_USAGE_SYS_DOCK uint16_t (0xA0) /* System Dock (One Shot Control) */
+#define HID_USAGE_SYS_UNDOCK uint16_t (0xA1) /* System Undock (One Shot Control) */
+#define HID_USAGE_SYS_SETUP uint16_t (0xA2) /* System Setup (One Shot Control) */
+#define HID_USAGE_SYS_BREAK uint16_t (0xA3) /* System Break (One Shot Control) */
+#define HID_USAGE_SYS_DBGBRK uint16_t (0xA4) /* System Debugger Break (One Shot Control) */
+#define HID_USAGE_APP_BRK uint16_t (0xA5) /* Application Break (One Shot Control) */
+#define HID_USAGE_APP_DBGBRK uint16_t (0xA6) /* Application Debugger Break (One Shot Control) */
+#define HID_USAGE_SYS_SPKMUTE uint16_t (0xA7) /* System Speaker Mute (One Shot Control) */
+#define HID_USAGE_SYS_HIBERN uint16_t (0xA8) /* System Hibernate (One Shot Control) */
+#define HID_USAGE_SYS_SIDPINV uint16_t (0xB0) /* System Display Invert (One Shot Control) */
+#define HID_USAGE_SYS_DISPINT uint16_t (0xB1) /* System Display Internal (One Shot Control) */
+#define HID_USAGE_SYS_DISPEXT uint16_t (0xB2) /* System Display External (One Shot Control) */
+#define HID_USAGE_SYS_DISPBOTH uint16_t (0xB3) /* System Display Both (One Shot Control) */
+#define HID_USAGE_SYS_DISPDUAL uint16_t (0xB4) /* System Display Dual (One Shot Control) */
+#define HID_USAGE_SYS_DISPTGLIE uint16_t (0xB5) /* System Display Toggle Int/Ext (One Shot Control) */
+#define HID_USAGE_SYS_DISP_SWAP uint16_t (0xB6) /* System Display Swap Primary/Secondary (One Shot Control) */
+#define HID_USAGE_SYS_DIPS_LCDA uint16_t (0xB7) /* System Display LCD Autoscale (One Shot Control) */
+
+#endif /* __USDH_HID_USAGE_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/hid/Source/usbh_hid_core.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/hid/Source/usbh_hid_core.c
new file mode 100644
index 00000000..0cd3288d
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/hid/Source/usbh_hid_core.c
@@ -0,0 +1,674 @@
+/*!
+ \file usbh_hid_core.c
+ \brief USB host HID class driver
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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.
+*/
+
+#include "usbh_pipe.h"
+#include "usbh_hid_core.h"
+#include "usbh_hid_mouse.h"
+#include "usbh_hid_keybd.h"
+#include
+#include
+
+/* local function prototypes ('static') */
+static void usbh_hiddesc_parse(usb_desc_hid *hid_desc, uint8_t *buf);
+static void usbh_hid_itf_deinit(usbh_host *puhost);
+static usbh_status usbh_hid_itf_init(usbh_host *puhost);
+static usbh_status usbh_hid_class_req(usbh_host *puhost);
+static usbh_status usbh_hid_handle(usbh_host *puhost);
+static usbh_status usbh_hid_reportdesc_get(usbh_host *puhost, uint16_t len);
+static usbh_status usbh_hid_sof(usbh_host *puhost);
+static usbh_status usbh_hid_desc_get(usbh_host *puhost, uint16_t len);
+static usbh_status usbh_set_idle(usbh_host *puhost, uint8_t duration, uint8_t report_ID);
+static usbh_status usbh_set_protocol(usbh_host *puhost, uint8_t protocol);
+
+usbh_class usbh_hid = {
+ USB_HID_CLASS,
+ usbh_hid_itf_init,
+ usbh_hid_itf_deinit,
+ usbh_hid_class_req,
+ usbh_hid_handle,
+ usbh_hid_sof
+};
+
+/*!
+ \brief get report
+ \param[in] puhost: pointer to usb host
+ \param[in] report_type: duration for HID set idle request
+ \param[in] report_ID: targeted report ID for HID set idle request
+ \param[in] report_len: length of data report to be send
+ \param[in] report_buf: report buffer
+ \param[out] none
+ \retval operation status
+*/
+usbh_status usbh_get_report(usbh_host *puhost,
+ uint8_t report_type,
+ uint8_t report_ID,
+ uint8_t report_len,
+ uint8_t *report_buf)
+{
+ usbh_status status = USBH_BUSY;
+
+ if(CTL_IDLE == puhost->control.ctl_state) {
+ puhost->control.setup.req = (usb_req) {
+ .bmRequestType = USB_TRX_IN | USB_RECPTYPE_ITF | USB_REQTYPE_CLASS,
+ .bRequest = GET_REPORT,
+ .wValue = (report_type << 8U) | report_ID,
+ .wIndex = 0U,
+ .wLength = report_len
+ };
+
+ usbh_ctlstate_config(puhost, report_buf, report_len);
+ }
+
+ status = usbh_ctl_handler(puhost);
+
+ return status;
+}
+
+/*!
+ \brief set report
+ \param[in] pudev: pointer to usb core instance
+ \param[in] puhost: pointer to usb host
+ \param[in] report_type: duration for HID set idle request
+ \param[in] report_ID: targeted report ID for HID set idle request
+ \param[in] report_len: length of data report to be send
+ \param[in] report_buf: report buffer
+ \param[out] none
+ \retval operation status
+*/
+usbh_status usbh_set_report(usb_core_driver *pudev,
+ usbh_host *puhost,
+ uint8_t report_type,
+ uint8_t report_ID,
+ uint8_t report_len,
+ uint8_t *report_buf)
+{
+ usbh_status status = USBH_BUSY;
+
+ if(CTL_IDLE == puhost->control.ctl_state) {
+ puhost->control.setup.req = (usb_req) {
+ .bmRequestType = USB_TRX_OUT | USB_RECPTYPE_ITF | USB_REQTYPE_CLASS,
+ .bRequest = SET_REPORT,
+ .wValue = (report_type << 8U) | report_ID,
+ .wIndex = 0U,
+ .wLength = report_len
+ };
+
+ usbh_ctlstate_config(puhost, report_buf, report_len);
+ }
+
+ status = usbh_ctl_handler(puhost);
+
+ return status;
+}
+
+/*!
+ \brief de-initialize the host pipes used for the HID class
+ \param[in] puhost: pointer to usb host
+ \param[out] none
+ \retval operation status
+*/
+void usbh_hid_itf_deinit(usbh_host *puhost)
+{
+ usbh_hid_handler *hid = (usbh_hid_handler *)puhost->active_class->class_data;
+
+ if(0x00U != hid->pipe_in) {
+ usb_pipe_halt(puhost->data, hid->pipe_in);
+
+ usbh_pipe_free(puhost->data, hid->pipe_in);
+
+ hid->pipe_in = 0U; /* reset the pipe as free */
+ }
+
+ if(0x00U != hid->pipe_out) {
+ usb_pipe_halt(puhost->data, hid->pipe_out);
+
+ usbh_pipe_free(puhost->data, hid->pipe_out);
+
+ hid->pipe_out = 0U; /* reset the channel as free */
+ }
+}
+
+/*!
+ \brief return device type
+ \param[in] pudev: pointer to usb core instance
+ \param[in] puhost: pointer to usb host
+ \param[out] none
+ \retval hid_type
+*/
+hid_type usbh_hid_device_type_get(usb_core_driver *pudev, usbh_host *puhost)
+{
+ hid_type type = HID_UNKNOWN;
+ uint8_t interface_protocol;
+
+ if(HOST_CLASS_HANDLER == puhost->cur_state) {
+ interface_protocol = puhost->dev_prop.cfg_desc_set.itf_desc_set[puhost->dev_prop.cur_itf][0].itf_desc.bInterfaceProtocol;
+
+ if(USB_HID_PROTOCOL_KEYBOARD == interface_protocol) {
+ type = HID_KEYBOARD;
+ } else {
+ if(USB_HID_PROTOCOL_MOUSE == interface_protocol) {
+ type = HID_MOUSE;
+ }
+ }
+ }
+
+ return type;
+}
+
+/*!
+ \brief return HID device poll time
+ \param[in] pudev: pointer to usb core instance
+ \param[in] puhost: pointer to usb host
+ \param[out] none
+ \retval poll time (ms)
+*/
+uint8_t usbh_hid_poll_interval_get(usb_core_driver *pudev, usbh_host *puhost)
+{
+ usbh_hid_handler *hid = (usbh_hid_handler *)puhost->active_class->class_data;
+
+ if((HOST_CLASS_ENUM == puhost->cur_state) ||
+ (HOST_USER_INPUT == puhost->cur_state) ||
+ (HOST_CHECK_CLASS == puhost->cur_state) ||
+ (HOST_CLASS_HANDLER == puhost->cur_state)) {
+ return (uint8_t)(hid->poll);
+ } else {
+ return 0U;
+ }
+}
+
+/*!
+ \brief read from FIFO
+ \param[in] fifo: fifo address
+ \param[in] buf: read buffer
+ \param[in] nbytes: number of item to read
+ \param[out] none
+ \retval number of read items
+*/
+uint16_t usbh_hid_fifo_read(data_fifo *fifo, void *buf, uint16_t nbytes)
+{
+ uint16_t i = 0U;
+ uint8_t *p = (uint8_t *) buf;
+
+ if(0U == fifo->lock) {
+ fifo->lock = 1U;
+
+ for(i = 0U; i < nbytes; i++) {
+ if(fifo->tail != fifo->head) {
+ *p++ = fifo->buf[fifo->tail];
+ fifo->tail++;
+
+ if(fifo->tail == fifo->size) {
+ fifo->tail = 0U;
+ }
+ } else {
+ fifo->lock = 0U;
+
+ return i;
+ }
+ }
+ }
+
+ fifo->lock = 0U;
+
+ return nbytes;
+}
+
+/*!
+ \brief write to FIFO
+ \param[in] fifo: fifo address
+ \param[in] buf: read buffer
+ \param[in] nbytes: number of item to read
+ \param[out] none
+ \retval number of write items
+*/
+uint16_t usbh_hid_fifo_write(data_fifo *fifo, void *buf, uint16_t nbytes)
+{
+ uint16_t i = 0U;
+ uint8_t *p = (uint8_t *) buf;
+
+ if(0U == fifo->lock) {
+ fifo->lock = 1U;
+
+ for(i = 0U; i < nbytes; i++) {
+ if((fifo->head + 1U == fifo->tail) ||
+ ((fifo->head + 1U == fifo->size) && (0U == fifo->tail))) {
+ fifo->lock = 0U;
+
+ return i;
+ } else {
+ fifo->buf[fifo->head] = *p++;
+ fifo->head++;
+
+ if(fifo->head == fifo->size) {
+ fifo->head = 0U;
+ }
+ }
+ }
+ }
+
+ fifo->lock = 0U;
+
+ return nbytes;
+}
+
+/*!
+ \brief initialize FIFO
+ \param[in] fifo: fifo address
+ \param[in] buf: read buffer
+ \param[in] size: size of FIFO
+ \param[out] none
+ \retval none
+*/
+void usbh_hid_fifo_init(data_fifo *fifo, uint8_t *buf, uint16_t size)
+{
+ fifo->head = 0U;
+ fifo->tail = 0U;
+ fifo->lock = 0U;
+ fifo->size = size;
+ fifo->buf = buf;
+}
+
+/*!
+ \brief initialize the hid class
+ \param[in] puhost: pointer to usb host
+ \param[out] none
+ \retval operation status
+*/
+static usbh_status usbh_hid_itf_init(usbh_host *puhost)
+{
+ uint8_t num = 0U, ep_num = 0U, interface = 0U;
+ usbh_status status = USBH_BUSY;
+
+ interface = usbh_interface_find(&puhost->dev_prop, USB_HID_CLASS, USB_HID_SUBCLASS_BOOT_ITF, 0xFFU);
+
+ if(0xFFU == interface) {
+ puhost->usr_cb->dev_not_supported();
+
+ status = USBH_FAIL;
+ } else {
+ usbh_interface_select(&puhost->dev_prop, interface);
+
+ static usbh_hid_handler hid_handler;
+
+ memset((void *)&hid_handler, 0, sizeof(usbh_hid_handler));
+
+ hid_handler.state = HID_ERROR;
+
+ uint8_t itf_protocol = puhost->dev_prop.cfg_desc_set.itf_desc_set[puhost->dev_prop.cur_itf][0].itf_desc.bInterfaceProtocol;
+ if(USB_HID_PROTOCOL_KEYBOARD == itf_protocol) {
+ hid_handler.init = usbh_hid_keybd_init;
+ hid_handler.machine = usbh_hid_keybrd_machine;
+ } else if(USB_HID_PROTOCOL_MOUSE == itf_protocol) {
+ hid_handler.init = usbh_hid_mouse_init;
+ hid_handler.machine = usbh_hid_mouse_machine;
+ } else {
+ status = USBH_FAIL;
+ }
+
+ hid_handler.state = HID_INIT;
+ hid_handler.ctl_state = HID_REQ_INIT;
+ hid_handler.ep_addr = puhost->dev_prop.cfg_desc_set.itf_desc_set[puhost->dev_prop.cur_itf][0].ep_desc[0].bEndpointAddress;
+ hid_handler.len = puhost->dev_prop.cfg_desc_set.itf_desc_set[puhost->dev_prop.cur_itf][0].ep_desc[0].wMaxPacketSize;
+ hid_handler.poll = puhost->dev_prop.cfg_desc_set.itf_desc_set[puhost->dev_prop.cur_itf][0].ep_desc[0].bInterval;
+
+ if(hid_handler.poll < HID_MIN_POLL) {
+ hid_handler.poll = HID_MIN_POLL;
+ }
+
+ /* check for available number of endpoints */
+ /* find the number of endpoints in the interface descriptor */
+ /* choose the lower number in order not to overrun the buffer allocated */
+ ep_num = USB_MIN(puhost->dev_prop.cfg_desc_set.itf_desc_set[puhost->dev_prop.cur_itf][0].itf_desc.bNumEndpoints, USBH_MAX_EP_NUM);
+
+ /* decode endpoint IN and OUT address from interface descriptor */
+ for(num = 0U; num < ep_num; num++) {
+ usb_desc_ep *ep_desc = &puhost->dev_prop.cfg_desc_set.itf_desc_set[puhost->dev_prop.cur_itf][0].ep_desc[num];
+
+ uint8_t ep_addr = ep_desc->bEndpointAddress;
+
+ if(ep_addr & 0x80U) {
+ hid_handler.ep_in = ep_addr;
+ hid_handler.pipe_in = usbh_pipe_allocate(puhost->data, ep_addr);
+
+ /* open channel for IN endpoint */
+ usbh_pipe_create(puhost->data,
+ &puhost->dev_prop,
+ hid_handler.pipe_in,
+ USB_EPTYPE_INTR,
+ hid_handler.len);
+
+ usbh_pipe_toggle_set(puhost->data, hid_handler.pipe_in, 0U);
+ } else {
+ hid_handler.ep_out = ep_addr;
+ hid_handler.pipe_out = usbh_pipe_allocate(puhost->data, ep_addr);
+
+ /* open channel for OUT endpoint */
+ usbh_pipe_create(puhost->data,
+ &puhost->dev_prop,
+ hid_handler.pipe_out,
+ USB_EPTYPE_INTR,
+ hid_handler.len);
+
+ usbh_pipe_toggle_set(puhost->data, hid_handler.pipe_out, 0U);
+ }
+ }
+
+ puhost->active_class->class_data = (void *)&hid_handler;
+
+ status = USBH_OK;
+ }
+
+ return status;
+}
+
+/*!
+ \brief handle HID class requests for HID class
+ \param[in] puhost: pointer to usb host
+ \param[out] none
+ \retval operation status
+*/
+static usbh_status usbh_hid_class_req(usbh_host *puhost)
+{
+ usbh_status status = USBH_BUSY;
+ usbh_status class_req_status = USBH_BUSY;
+
+ usbh_hid_handler *hid = (usbh_hid_handler *)puhost->active_class->class_data;
+
+ /* handle HID control state machine */
+ switch(hid->ctl_state) {
+ case HID_REQ_INIT:
+ case HID_REQ_GET_HID_DESC:
+ /* get HID descriptor */
+ if(USBH_OK == usbh_hid_desc_get(puhost, USB_HID_DESC_SIZE)) {
+ usbh_hiddesc_parse(&hid->hid_desc, puhost->dev_prop.data);
+
+ hid->ctl_state = HID_REQ_GET_REPORT_DESC;
+ }
+ break;
+
+ case HID_REQ_GET_REPORT_DESC:
+ /* get report descriptor */
+ if(USBH_OK == usbh_hid_reportdesc_get(puhost, hid->hid_desc.wDescriptorLength)) {
+ hid->ctl_state = HID_REQ_SET_IDLE;
+ }
+ break;
+
+ case HID_REQ_SET_IDLE:
+ class_req_status = usbh_set_idle(puhost, 0U, 0U);
+
+ /* set idle */
+ if(USBH_OK == class_req_status) {
+ hid->ctl_state = HID_REQ_SET_PROTOCOL;
+ } else {
+ if(USBH_NOT_SUPPORTED == class_req_status) {
+ hid->ctl_state = HID_REQ_SET_PROTOCOL;
+ }
+ }
+ break;
+
+ case HID_REQ_SET_PROTOCOL:
+ /* set protocol */
+ if(USBH_OK == usbh_set_protocol(puhost, 0U)) {
+ hid->ctl_state = HID_REQ_IDLE;
+
+ /* all requests performed */
+ status = USBH_OK;
+ }
+ break;
+
+ case HID_REQ_IDLE:
+ default:
+ break;
+ }
+
+ return status;
+}
+
+/*!
+ \brief manage state machine for HID data transfers
+ \param[in] puhost: pointer to usb host
+ \param[out] none
+ \retval operation status
+*/
+static usbh_status usbh_hid_handle(usbh_host *puhost)
+{
+ usbh_status status = USBH_OK;
+ usbh_hid_handler *hid = (usbh_hid_handler *)puhost->active_class->class_data;
+
+ switch(hid->state) {
+ case HID_INIT:
+ hid->init(puhost->data, puhost);
+ hid->state = HID_IDLE;
+ break;
+
+ case HID_IDLE:
+ hid->state = HID_SYNC;
+ status = USBH_OK;
+ break;
+
+ case HID_SYNC:
+ /* sync with start of even frame */
+ if(true == usb_frame_even(puhost->data)) {
+ hid->state = HID_GET_DATA;
+ }
+ break;
+
+ case HID_GET_DATA:
+ usbh_data_recev(puhost->data, hid->pdata, hid->pipe_in, hid->len);
+
+ hid->state = HID_POLL;
+ hid->timer = usb_curframe_get(puhost->data);
+ hid->data_ready = 0U;
+ break;
+
+ case HID_POLL:
+ if(URB_DONE == usbh_urbstate_get(puhost->data, hid->pipe_in)) {
+ if(0U == hid->data_ready) { /* handle data once */
+ usbh_hid_fifo_write(&hid->fifo, hid->pdata, hid->len);
+ hid->data_ready = 1U;
+
+ hid->machine(puhost->data, puhost);
+ }
+ } else {
+ if(URB_STALL == usbh_urbstate_get(puhost->data, hid->pipe_in)) { /* IN endpoint stalled */
+ /* issue clear feature on interrupt in endpoint */
+ if(USBH_OK == (usbh_clrfeature(puhost, hid->ep_addr, hid->pipe_in))) {
+ /* change state to issue next in token */
+ hid->state = HID_GET_DATA;
+ }
+ }
+ }
+ break;
+
+ default:
+ break;
+ }
+ return status;
+}
+
+/*!
+ \brief send get report descriptor command to the device
+ \param[in] puhost: pointer to usb host
+ \param[in] len: HID report descriptor length
+ \param[out] none
+ \retval operation status
+*/
+static usbh_status usbh_hid_reportdesc_get(usbh_host *puhost, uint16_t len)
+{
+ usbh_status status = USBH_BUSY;
+
+ if(CTL_IDLE == puhost->control.ctl_state) {
+ puhost->control.setup.req = (usb_req) {
+ .bmRequestType = USB_TRX_IN | USB_RECPTYPE_ITF | USB_REQTYPE_STRD,
+ .bRequest = USB_GET_DESCRIPTOR,
+ .wValue = USBH_DESC(USB_DESCTYPE_REPORT),
+ .wIndex = 0U,
+ .wLength = len
+ };
+
+ usbh_ctlstate_config(puhost, puhost->dev_prop.data, len);
+ }
+
+ status = usbh_ctl_handler(puhost);
+
+ return status;
+}
+
+/*!
+ \brief managing the SOF process
+ \param[in] puhost: pointer to usb host
+ \param[out] none
+ \retval operation status
+*/
+static usbh_status usbh_hid_sof(usbh_host *puhost)
+{
+ usbh_hid_handler *hid = (usbh_hid_handler *)puhost->active_class->class_data;
+
+ if(HID_POLL == hid->state) {
+ uint32_t frame_count = usb_curframe_get(puhost->data);
+
+ if((frame_count > hid->timer) && ((frame_count - hid->timer) >= hid->poll)) {
+ hid->state = HID_GET_DATA;
+ } else if((frame_count < hid->timer) && ((frame_count + 0x3FFFU - hid->timer) >= hid->poll)) {
+ hid->state = HID_GET_DATA;
+ } else {
+ /* no operation */
+ }
+ }
+
+ return USBH_OK;
+}
+
+/*!
+ \brief send the command of get HID descriptor to the device
+ \param[in] puhost: pointer to usb host
+ \param[in] len: HID descriptor length
+ \param[out] none
+ \retval operation status
+*/
+static usbh_status usbh_hid_desc_get(usbh_host *puhost, uint16_t len)
+{
+ usbh_status status = USBH_BUSY;
+
+ if(CTL_IDLE == puhost->control.ctl_state) {
+ puhost->control.setup.req = (usb_req) {
+ .bmRequestType = USB_TRX_IN | USB_RECPTYPE_ITF | USB_REQTYPE_STRD,
+ .bRequest = USB_GET_DESCRIPTOR,
+ .wValue = USBH_DESC(USB_DESCTYPE_HID),
+ .wIndex = 0U,
+ .wLength = len
+ };
+
+ usbh_ctlstate_config(puhost, puhost->dev_prop.data, len);
+ }
+
+ status = usbh_ctl_handler(puhost);
+
+ return status;
+}
+
+/*!
+ \brief set idle state
+ \param[in] puhost: pointer to usb host
+ \param[in] duration: duration for HID set idle request
+ \param[in] report_ID: targeted report ID for HID set idle request
+ \param[out] none
+ \retval operation status
+*/
+static usbh_status usbh_set_idle(usbh_host *puhost, uint8_t duration, uint8_t report_ID)
+{
+ usbh_status status = USBH_BUSY;
+
+ if(CTL_IDLE == puhost->control.ctl_state) {
+ puhost->control.setup.req = (usb_req) {
+ .bmRequestType = USB_TRX_OUT | USB_RECPTYPE_ITF | USB_REQTYPE_CLASS,
+ .bRequest = SET_IDLE,
+ .wValue = (duration << 8U) | report_ID,
+ .wIndex = 0U,
+ .wLength = 0U
+ };
+
+ usbh_ctlstate_config(puhost, NULL, 0U);
+ }
+
+ status = usbh_ctl_handler(puhost);
+
+ return status;
+}
+
+/*!
+ \brief set protocol state
+ \param[in] puhost: pointer to usb host
+ \param[in] protocol: boot/report protocol
+ \param[out] none
+ \retval operation status
+*/
+static usbh_status usbh_set_protocol(usbh_host *puhost, uint8_t protocol)
+{
+ usbh_status status = USBH_BUSY;
+
+ if(CTL_IDLE == puhost->control.ctl_state) {
+ puhost->control.setup.req = (usb_req) {
+ .bmRequestType = USB_TRX_OUT | USB_RECPTYPE_ITF | USB_REQTYPE_CLASS,
+ .bRequest = SET_PROTOCOL,
+ .wValue = !protocol,
+ .wIndex = 0U,
+ .wLength = 0U
+ };
+
+ usbh_ctlstate_config(puhost, NULL, 0U);
+ }
+
+ status = usbh_ctl_handler(puhost);
+
+ return status;
+}
+
+/*!
+ \brief parse the HID descriptor
+ \param[in] hid_desc: pointer to HID descriptor
+ \param[in] buf: pointer to buffer where the source descriptor is available
+ \param[out] none
+ \retval none
+*/
+static void usbh_hiddesc_parse(usb_desc_hid *hid_desc, uint8_t *buf)
+{
+ hid_desc->header.bLength = *(uint8_t *)(buf + 0U);
+ hid_desc->header.bDescriptorType = *(uint8_t *)(buf + 1U);
+ hid_desc->bcdHID = BYTE_SWAP(buf + 2U);
+ hid_desc->bCountryCode = *(uint8_t *)(buf + 4U);
+ hid_desc->bNumDescriptors = *(uint8_t *)(buf + 5U);
+ hid_desc->bDescriptorType = *(uint8_t *)(buf + 6U);
+ hid_desc->wDescriptorLength = BYTE_SWAP(buf + 7U);
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/hid/Source/usbh_hid_keybd.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/hid/Source/usbh_hid_keybd.c
new file mode 100644
index 00000000..ad8948f1
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/hid/Source/usbh_hid_keybd.c
@@ -0,0 +1,388 @@
+/*!
+ \file usbh_hid_keybd.c
+ \brief USB host HID keyboard driver
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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.
+*/
+
+#include "usbh_hid_keybd.h"
+#include "usbh_hid_parser.h"
+#include
+
+hid_keybd_info keybd_info;
+
+uint32_t keybd_report_data[2];
+
+static const hid_report_item imp_0_lctrl = {
+ (uint8_t *)(void *)keybd_report_data + 0, /* data */
+ 1, /* size */
+ 0, /* shift */
+ 0, /* count (only for array items) */
+ 0, /* signed */
+ 0, /* min value read can return */
+ 1, /* max value read can return */
+ 0, /* min vale device can report */
+ 1, /* max value device can report */
+ 1 /* resolution */
+};
+
+static const hid_report_item imp_0_lshift = {
+ (uint8_t *)(void *)keybd_report_data + 0, /* data */
+ 1, /* size */
+ 1, /* shift */
+ 0, /* count (only for array items) */
+ 0, /* signed */
+ 0, /* min value read can return */
+ 1, /* max value read can return */
+ 0, /* min vale device can report */
+ 1, /* max value device can report */
+ 1 /* resolution */
+};
+
+static const hid_report_item imp_0_lalt = {
+ (uint8_t *)(void *)keybd_report_data + 0, /* data */
+ 1, /* size */
+ 2, /* shift */
+ 0, /* count (only for array items) */
+ 0, /* signed */
+ 0, /* min value read can return */
+ 1, /* max value read can return */
+ 0, /* min vale device can report */
+ 1, /* max value device can report */
+ 1 /* resolution */
+};
+
+static const hid_report_item imp_0_lgui = {
+ (uint8_t *)(void *)keybd_report_data + 0, /* data */
+ 1, /* size */
+ 3, /* shift */
+ 0, /* count (only for array items) */
+ 0, /* signed */
+ 0, /* min value read can return */
+ 1, /* max value read can return */
+ 0, /* min vale device can report */
+ 1, /* max value device can report */
+ 1 /* resolution */
+};
+
+static const hid_report_item imp_0_rctrl = {
+ (uint8_t *)(void *)keybd_report_data + 0, /* data */
+ 1, /* size */
+ 4, /* shift */
+ 0, /* count (only for array items) */
+ 0, /* signed */
+ 0, /* min value read can return */
+ 1, /* max value read can return */
+ 0, /* min vale device can report */
+ 1, /* max value device can report */
+ 1 /* resolution */
+};
+
+static const hid_report_item imp_0_rshift = {
+ (uint8_t *)(void *)keybd_report_data + 0, /* data */
+ 1, /* size */
+ 5, /* shift */
+ 0, /* count (only for array items) */
+ 0, /* signed */
+ 0, /* min value read can return */
+ 1, /* max value read can return */
+ 0, /* min vale device can report */
+ 1, /* max value device can report */
+ 1 /* resolution */
+};
+
+static const hid_report_item imp_0_ralt = {
+ (uint8_t *)(void *)keybd_report_data + 0, /* data */
+ 1, /* size */
+ 6, /* shift */
+ 0, /* count (only for array items) */
+ 0, /* signed */
+ 0, /* min value read can return */
+ 1, /* max value read can return */
+ 0, /* min vale device can report */
+ 1, /* max value device can report */
+ 1 /* resolution */
+};
+
+static const hid_report_item imp_0_rgui = {
+ (uint8_t *)(void *)keybd_report_data + 0, /* data */
+ 1, /* size */
+ 7, /* shift */
+ 0, /* count (only for array items) */
+ 0, /* signed */
+ 0, /* min value read can return */
+ 1, /* max value read can return */
+ 0, /* min vale device can report */
+ 1, /* max value device can report */
+ 1 /* resolution */
+};
+
+static const hid_report_item imp_0_key_array = {
+ (uint8_t *)(void *)keybd_report_data + 2, /* data */
+ 8, /* size */
+ 0, /* shift */
+ 6, /* count (only for array items) */
+ 0, /* signed */
+ 0, /* min value read can return */
+ 101, /* max value read can return */
+ 0, /* min vale device can report */
+ 101, /* max value device can report */
+ 1 /* resolution */
+};
+
+/* local constants */
+static const uint8_t hid_keybrd_codes[] = {
+ 0, 0, 0, 0, 31, 50, 48, 33,
+ 19, 34, 35, 36, 24, 37, 38, 39, /* 0x00 - 0x0F */
+ 52, 51, 25, 26, 17, 20, 32, 21,
+ 23, 49, 18, 47, 22, 46, 2, 3, /* 0x10 - 0x1F */
+ 4, 5, 6, 7, 8, 9, 10, 11,
+ 43, 110, 15, 16, 61, 12, 13, 27, /* 0x20 - 0x2F */
+ 28, 29, 42, 40, 41, 1, 53, 54,
+ 55, 30, 112, 113, 114, 115, 116, 117, /* 0x30 - 0x3F */
+ 118, 119, 120, 121, 122, 123, 124, 125,
+ 126, 75, 80, 85, 76, 81, 86, 89, /* 0x40 - 0x4F */
+ 79, 84, 83, 90, 95, 100, 105, 106,
+ 108, 93, 98, 103, 92, 97, 102, 91, /* 0x50 - 0x5F */
+ 96, 101, 99, 104, 45, 129, 0, 0,
+ 0, 0, 0, 0, 0, 0, 0, 0, /* 0x60 - 0x6F */
+ 0, 0, 0, 0, 0, 0, 0, 0,
+ 0, 0, 0, 0, 0, 0, 0, 0, /* 0x70 - 0x7F */
+ 0, 0, 0, 0, 0, 107, 0, 56,
+ 0, 0, 0, 0, 0, 0, 0, 0, /* 0x80 - 0x8F */
+ 0, 0, 0, 0, 0, 0, 0, 0,
+ 0, 0, 0, 0, 0, 0, 0, 0, /* 0x90 - 0x9F */
+ 0, 0, 0, 0, 0, 0, 0, 0,
+ 0, 0, 0, 0, 0, 0, 0, 0, /* 0xA0 - 0xAF */
+ 0, 0, 0, 0, 0, 0, 0, 0,
+ 0, 0, 0, 0, 0, 0, 0, 0, /* 0xB0 - 0xBF */
+ 0, 0, 0, 0, 0, 0, 0, 0,
+ 0, 0, 0, 0, 0, 0, 0, 0, /* 0xC0 - 0xCF */
+ 0, 0, 0, 0, 0, 0, 0, 0,
+ 0, 0, 0, 0, 0, 0, 0, 0, /* 0xD0 - 0xDF */
+ 58, 44, 60, 127, 64, 57, 62, 128 /* 0xE0 - 0xE7 */
+};
+
+#ifdef QWERTY_KEYBOARD
+
+static const int8_t hid_keybrd_key[] = {
+ '\0', '`', '1', '2', '3', '4', '5', '6',
+ '7', '8', '9', '0', '-', '=', '\0', '\r',
+ '\t', 'q', 'w', 'e', 'r', 't', 'y', 'u',
+ 'i', 'o', 'p', '[', ']', '\\',
+ '\0', 'a', 's', 'd', 'f', 'g', 'h', 'j',
+ 'k', 'l', ';', '\'', '\0', '\n',
+ '\0', '\0', 'z', 'x', 'c', 'v', 'b', 'n',
+ 'm', ',', '.', '/', '\0', '\0',
+ '\0', '\0', '\0', ' ', '\0', '\0', '\0', '\0',
+ '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0',
+ '\0', '\0', '\0', '\0', '\0', '\r', '\0', '\0',
+ '\0', '\0', '\0', '\0', '\0', '\0',
+ '\0', '\0', '7', '4', '1',
+ '\0', '/', '8', '5', '2',
+ '0', '*', '9', '6', '3',
+ '.', '-', '+', '\0', '\n', '\0', '\0', '\0', '\0', '\0', '\0',
+ '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0',
+ '\0', '\0', '\0', '\0'
+};
+
+static const int8_t hid_keybrd_shiftkey[] = {
+ '\0', '~', '!', '@', '#', '$', '%', '^', '&', '*', '(', ')',
+ '_', '+', '\0', '\0', '\0', 'Q', 'W', 'E', 'R', 'T', 'Y', 'U',
+ 'I', 'O', 'P', '{', '}', '|', '\0', 'A', 'S', 'D', 'F', 'G',
+ 'H', 'J', 'K', 'L', ':', '"', '\0', '\n', '\0', '\0', 'Z', 'X',
+ 'C', 'V', 'B', 'N', 'M', '<', '>', '?', '\0', '\0', '\0', '\0',
+ '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0',
+ '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0',
+ '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0',
+ '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0',
+ '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0',
+ '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0'
+};
+
+#else
+
+static const int8_t hid_keybrd_key[] = {
+ '\0', '`', '1', '2', '3', '4', '5', '6', '7', '8', '9', '0',
+ '-', '=', '\0', '\r', '\t', 'a', 'z', 'e', 'r', 't', 'y', 'u',
+ 'i', 'o', 'p', '[', ']', '\\', '\0', 'q', 's', 'd', 'f', 'g',
+ 'h', 'j', 'k', 'l', 'm', '\0', '\0', '\n', '\0', '\0', 'w', 'x',
+ 'c', 'v', 'b', 'n', ',', ';', ':', '!', '\0', '\0', '\0', '\0',
+ '\0', ' ', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0',
+ '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\r', '\0', '\0', '\0',
+ '\0', '\0', '\0', '\0', '\0', '\0', '\0', '7', '4', '1', '\0', '/',
+ '8', '5', '2', '0', '*', '9', '6', '3', '.', '-', '+', '\0',
+ '\n', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0',
+ '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0'
+};
+
+static const int8_t hid_keybrd_shiftkey[] = {
+ '\0', '~', '!', '@', '#', '$', '%', '^', '&', '*', '(', ')', '_',
+ '+', '\0', '\0', '\0', 'A', 'Z', 'E', 'R', 'T', 'Y', 'U', 'I', 'O',
+ 'P', '{', '}', '*', '\0', 'Q', 'S', 'D', 'F', 'G', 'H', 'J', 'K',
+ 'L', 'M', '%', '\0', '\n', '\0', '\0', 'W', 'X', 'C', 'V', 'B', 'N',
+ '?', '.', '/', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0',
+ '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0',
+ '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0',
+ '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0',
+ '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0',
+ '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0'
+};
+
+#endif
+
+/* local function prototypes ('static') */
+static usbh_status usbh_hid_keybrd_decode(usb_core_driver *pudev, usbh_host *puhost);
+
+/*!
+ \brief initialize the keyboard function
+ \param[in] pudev: pointer to usb core instance
+ \param[in] puhost: pointer to usb host
+ \param[out] none
+ \retval operation status
+*/
+usbh_status usbh_hid_keybd_init(usb_core_driver *pudev, usbh_host *puhost)
+{
+ usbh_hid_handler *hid = (usbh_hid_handler *)puhost->active_class->class_data;
+
+ keybd_info.lctrl = keybd_info.lshift = 0U;
+ keybd_info.lalt = keybd_info.lgui = 0U;
+ keybd_info.rctrl = keybd_info.rshift = 0U;
+ keybd_info.ralt = keybd_info.rgui = 0U;
+
+ for(uint32_t x = 0U; x < (sizeof(keybd_report_data) / sizeof(uint32_t)); x++) {
+ keybd_report_data[x] = 0U;
+ }
+
+ if(hid->len > (sizeof(keybd_report_data) / sizeof(uint32_t))) {
+ hid->len = (sizeof(keybd_report_data) / sizeof(uint32_t));
+ }
+
+ hid->pdata = (uint8_t *)(void *)keybd_report_data;
+
+ usbh_hid_fifo_init(&hid->fifo, puhost->dev_prop.data, HID_QUEUE_SIZE * sizeof(keybd_report_data));
+
+ /* call user init*/
+ usr_keybrd_init();
+
+ return USBH_OK;
+}
+
+/*!
+ \brief get keyboard information
+ \param[in] pudev: pointer to USB core instance
+ \param[in] puhost: pointer to USB host handler
+ \param[out] none
+ \retval keyboard information
+*/
+hid_keybd_info *usbh_hid_keybd_info_get(usb_core_driver *pudev, usbh_host *puhost)
+{
+ if(USBH_OK == usbh_hid_keybrd_decode(pudev, puhost)) {
+ return &keybd_info;
+ } else {
+ return NULL;
+ }
+}
+
+/*!
+ \brief get ascii code
+ \param[in] info: keyboard information
+ \param[out] none
+ \retval output
+*/
+uint8_t usbh_hid_ascii_code_get(hid_keybd_info *info)
+{
+ uint8_t output;
+ if((1U == info->lshift) || (info->rshift)) {
+ output = hid_keybrd_shiftkey[hid_keybrd_codes[info->keys[0]]];
+ } else {
+ output = hid_keybrd_key[hid_keybrd_codes[info->keys[0]]];
+ }
+
+ return output;
+}
+
+/*!
+ \brief decode the pressed keys
+ \param[in] pudev: pointer to usb core instance
+ \param[in] puhost: pointer to usb host
+ \param[out] none
+ \retval none
+*/
+void usbh_hid_keybrd_machine(usb_core_driver *pudev, usbh_host *puhost)
+{
+ hid_keybd_info *k_pinfo;
+
+ k_pinfo = usbh_hid_keybd_info_get(pudev, puhost);
+
+ if(k_pinfo != NULL) {
+ char c = usbh_hid_ascii_code_get(k_pinfo);
+
+ if(c != 0U) {
+ usr_keybrd_process_data(c);
+ }
+ }
+}
+
+/*!
+ \brief decode keyboard information
+ \param[in] pudev: pointer to usb core instance
+ \param[in] puhost: pointer to usb host
+ \param[out] none
+ \retval operation status
+*/
+static usbh_status usbh_hid_keybrd_decode(usb_core_driver *pudev, usbh_host *puhost)
+{
+ usbh_hid_handler *hid = (usbh_hid_handler *)puhost->active_class->class_data;
+
+ if(hid->len == 0U) {
+ return USBH_FAIL;
+ }
+
+ /* fill report */
+ if(usbh_hid_fifo_read(&hid->fifo, &keybd_report_data, hid->len) == hid->len) {
+ keybd_info.lctrl = (uint8_t)hid_item_read((hid_report_item *)&imp_0_lctrl, 0U);
+ keybd_info.lshift = (uint8_t)hid_item_read((hid_report_item *)&imp_0_lshift, 0U);
+ keybd_info.lalt = (uint8_t)hid_item_read((hid_report_item *)&imp_0_lalt, 0U);
+ keybd_info.lgui = (uint8_t)hid_item_read((hid_report_item *)&imp_0_lgui, 0U);
+ keybd_info.rctrl = (uint8_t)hid_item_read((hid_report_item *)&imp_0_rctrl, 0U);
+ keybd_info.rshift = (uint8_t)hid_item_read((hid_report_item *)&imp_0_rshift, 0U);
+ keybd_info.ralt = (uint8_t)hid_item_read((hid_report_item *)&imp_0_ralt, 0U);
+ keybd_info.rgui = (uint8_t)hid_item_read((hid_report_item *)&imp_0_rgui, 0U);
+
+ for(uint8_t x = 0U; x < sizeof(keybd_info.keys); x++) {
+ keybd_info.keys[x] = (uint8_t)hid_item_read((hid_report_item *)&imp_0_key_array, x);
+ }
+
+ return USBH_OK;
+ }
+
+ return USBH_FAIL;
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/hid/Source/usbh_hid_mouse.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/hid/Source/usbh_hid_mouse.c
new file mode 100644
index 00000000..2c609ed6
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/hid/Source/usbh_hid_mouse.c
@@ -0,0 +1,211 @@
+/*!
+ \file usbh_hid_mouse.c
+ \brief USB host HID mouse driver
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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.
+*/
+
+#include "usbh_hid_mouse.h"
+#include "usbh_hid_parser.h"
+
+hid_mouse_info mouse_info;
+uint32_t mouse_report_data[1];
+
+/* structures defining how to access items in a hid mouse report */
+/* access button 1 state. */
+static const hid_report_item prop_b1 = {
+ (uint8_t *)(void *)mouse_report_data + 0, /* data */
+ 1, /* size */
+ 0, /* shift */
+ 0, /* count (only for array items) */
+ 0, /* signed? */
+ 0, /* min value read can return */
+ 1, /* max value read can return */
+ 0, /* min value device can report */
+ 1, /* max value device can report */
+ 1 /* resolution */
+};
+
+/* access button 2 state. */
+static const hid_report_item prop_b2 = {
+ (uint8_t *)(void *)mouse_report_data + 0, /* data */
+ 1, /* size */
+ 1, /* shift */
+ 0, /* count (only for array items) */
+ 0, /* signed? */
+ 0, /* min value read can return */
+ 1, /* max value read can return */
+ 0, /* min value device can report */
+ 1, /* max value device can report */
+ 1 /* resolution */
+};
+
+/* access button 3 state. */
+static const hid_report_item prop_b3 = {
+ (uint8_t *)(void *)mouse_report_data + 0, /* data */
+ 1, /* size */
+ 2, /* shift */
+ 0, /* count (only for array items) */
+ 0, /* signed? */
+ 0, /* min value read can return */
+ 1, /* max value read can return */
+ 0, /* min vale device can report */
+ 1, /* max value device can report */
+ 1 /* resolution */
+};
+
+/* access x coordinate change. */
+static const hid_report_item prop_x = {
+ (uint8_t *)(void *)mouse_report_data + 1, /* data */
+ 8, /* size */
+ 0, /* shift */
+ 0, /* count (only for array items) */
+ 1, /* signed? */
+ 0, /* min value read can return */
+ 0xFFFF,/* max value read can return */
+ 0, /* min vale device can report */
+ 0xFFFF,/* max value device can report */
+ 1 /* resolution */
+};
+
+/* access y coordinate change. */
+static const hid_report_item prop_y = {
+ (uint8_t *)(void *)mouse_report_data + 2, /* data */
+ 8, /* size */
+ 0, /* shift */
+ 0, /* count (only for array items) */
+ 1, /* signed? */
+ 0, /* min value read can return */
+ 0xFFFF,/* max value read can return */
+ 0, /* min vale device can report */
+ 0xFFFF,/* max value device can report */
+ 1 /* resolution */
+};
+
+/* local function prototypes ('static') */
+static usbh_status usbh_hid_mouse_decode(usb_core_driver *pudev, usbh_host *puhost);
+
+/*!
+ \brief initialize the mouse function
+ \param[in] pudev: pointer to usb core instance
+ \param[in] puhost: pointer to usb host
+ \param[out] none
+ \retval none
+*/
+usbh_status usbh_hid_mouse_init(usb_core_driver *pudev, usbh_host *puhost)
+{
+ usbh_hid_handler *hid = (usbh_hid_handler *)puhost->active_class->class_data;
+
+ mouse_info.x = 0U;
+ mouse_info.y = 0U;
+ mouse_info.buttons[0] = 0U;
+ mouse_info.buttons[1] = 0U;
+ mouse_info.buttons[2] = 0U;
+
+ mouse_report_data[0] = 0U;
+
+ if(hid->len > sizeof(mouse_report_data)) {
+ hid->len = sizeof(mouse_report_data);
+ }
+
+ hid->pdata = (uint8_t *)(void *)mouse_report_data;
+
+ usbh_hid_fifo_init(&hid->fifo, puhost->dev_prop.data, HID_QUEUE_SIZE * sizeof(mouse_report_data));
+
+ usr_mouse_init();
+
+ return USBH_OK;
+}
+
+/*!
+ \brief get mouse information
+ \param[in] pudev: pointer to usb core instance
+ \param[in] puhost: pointer to usb host
+ \param[out] none
+ \retval mouse information
+*/
+hid_mouse_info *usbh_hid_mouse_info_get(usb_core_driver *pudev, usbh_host *puhost)
+{
+ if(usbh_hid_mouse_decode(pudev, puhost) == USBH_OK) {
+ return &mouse_info;
+ } else {
+ return NULL;
+ }
+}
+
+/*!
+ \brief decode mouse data
+ \param[in] pudev: pointer to usb core instance
+ \param[in] puhost: pointer to usb host
+ \param[out] none
+ \retval none
+*/
+void usbh_hid_mouse_machine(usb_core_driver *pudev, usbh_host *puhost)
+{
+ hid_mouse_info *m_pinfo = NULL;
+
+ m_pinfo = usbh_hid_mouse_info_get(pudev, puhost);
+
+ if(NULL != m_pinfo) {
+ /* handle mouse data position */
+ usr_mouse_process_data(&mouse_info);
+ }
+}
+
+/*!
+ \brief decode mouse information
+ \param[in] pudev: pointer to usb core instance
+ \param[in] puhost: pointer to usb host
+ \param[out] none
+ \retval operation status
+*/
+static usbh_status usbh_hid_mouse_decode(usb_core_driver *pudev, usbh_host *puhost)
+{
+ usbh_hid_handler *hid = (usbh_hid_handler *)puhost->active_class->class_data;
+
+ if(0U == hid->len) {
+ return USBH_FAIL;
+ }
+
+ /* fill report */
+ if(usbh_hid_fifo_read(&hid->fifo, &mouse_report_data, hid->len) == hid->len) {
+ /* decode report */
+ mouse_info.x = (uint8_t)hid_item_read((hid_report_item *)&prop_x, 0U);
+ mouse_info.y = (uint8_t)hid_item_read((hid_report_item *)&prop_y, 0U);
+
+ mouse_info.buttons[0] = (uint8_t)hid_item_read((hid_report_item *)&prop_b1, 0U);
+ mouse_info.buttons[1] = (uint8_t)hid_item_read((hid_report_item *)&prop_b2, 0U);
+ mouse_info.buttons[2] = (uint8_t)hid_item_read((hid_report_item *)&prop_b3, 0U);
+
+ return USBH_OK;
+ }
+
+ return USBH_FAIL;
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/hid/Source/usbh_hid_parser.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/hid/Source/usbh_hid_parser.c
new file mode 100644
index 00000000..8006e207
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/hid/Source/usbh_hid_parser.c
@@ -0,0 +1,148 @@
+/*!
+ \file usbh_hid_parser.c
+ \brief USB host HID parser driver
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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.
+*/
+
+#include "usbh_hid_parser.h"
+
+/*!
+ \brief read a hid report item
+ \param[in] ri: pointer to report item
+ \param[in] ndx: report index
+ \param[out] none
+ \retval operation status (0: fail otherwise: item value)
+*/
+uint32_t hid_item_read(hid_report_item *ri, uint8_t ndx)
+{
+ uint32_t val = 0U;
+ uint32_t bofs = 0U;
+ uint8_t *data = ri->data;
+ uint8_t shift = ri->shift;
+
+ /* get the logical value of the item */
+
+ /* if this is an array, wee may need to offset ri->data.*/
+ if(ri->count > 0U) {
+ /* if app tries to read outside of the array. */
+ if(ri->count <= ndx) {
+ return(0U);
+ }
+
+ /* calculate bit offset */
+ bofs = ndx * ri->size;
+ bofs += shift;
+
+ /* calculate byte offset + shift pair from bit offset. */
+ data += bofs / 8U;
+ shift = (uint8_t)(bofs % 8U);
+ }
+
+ /* read data bytes in little endian order */
+ for(uint32_t x = 0U; x < ((ri->size & 0x7U) ? (ri->size / 8U) + 1U : (ri->size / 8U)); x++) {
+ val = (uint32_t)((uint32_t)(*data) << (x * 8U));
+ }
+
+ val = (val >> shift) & ((1U << ri->size) - 1U);
+
+ if((val < ri->logical_min) || (val > ri->logical_max)) {
+ return(0U);
+ }
+
+ /* convert logical value to physical value */
+ /* see if the number is negative or not. */
+ if((ri->sign) && (val & (1U << (ri->size - 1U)))) {
+ /* yes, so sign extend value to 32 bits. */
+ uint32_t vs = (uint32_t)((0xffffffffU & ~((1U << (ri->size)) - 1U)) | val);
+
+ if(1U == ri->resolution) {
+ return((uint32_t)vs);
+ }
+ return((uint32_t)(vs * ri->resolution));
+ } else {
+ if(1U == ri->resolution) {
+ return(val);
+ }
+
+ return (val * ri->resolution);
+ }
+}
+
+/*!
+ \brief write a hid report item
+ \param[in] ri: pointer to report item
+ \param[in] value: the value to be write
+ \param[in] ndx: report index
+ \param[out] none
+ \retval operation status (1: fail 0: Ok)
+*/
+uint32_t hid_item_write(hid_report_item *ri, uint32_t value, uint8_t ndx)
+{
+ uint32_t mask;
+ uint32_t bofs;
+ uint8_t *data = ri->data;
+ uint8_t shift = ri->shift;
+
+ if((value < ri->physical_min) || (value > ri->physical_max)) {
+ return(1U);
+ }
+
+ /* if this is an array, wee may need to offset ri->data.*/
+ if(ri->count > 0U) {
+ /* if app tries to read outside of the array. */
+ if(ri->count >= ndx) {
+ return(0U);
+ }
+
+ /* calculate bit offset */
+ bofs = ndx * ri->size;
+ bofs += shift;
+
+ /* calculate byte offset + shift pair from bit offset. */
+ data += bofs / 8U;
+ shift = (uint8_t)(bofs % 8U);
+ }
+
+ /* convert physical value to logical value. */
+ if(1U != ri->resolution) {
+ value = value / ri->resolution;
+ }
+
+ /* write logical value to report in little endian order. */
+ mask = (1U << ri->size) - 1U;
+ value = (value & mask) << shift;
+
+ for(uint32_t x = 0U; x < ((ri->size & 0x7U) ? (ri->size / 8U) + 1U : (ri->size / 8U)); x++) {
+ *(ri->data + x) = (uint8_t)((*(ri->data + x) & ~(mask >> (x * 8U))) | ((value >> (x * 8U)) & (mask >> (x * 8U))));
+ }
+
+ return 0U;
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/msc/Include/usbh_msc_bbb.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/msc/Include/usbh_msc_bbb.h
new file mode 100644
index 00000000..cec271a3
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/msc/Include/usbh_msc_bbb.h
@@ -0,0 +1,145 @@
+/*!
+ \file usbh_msc_bbb.h
+ \brief header file for usbh_msc_bbb.c
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __USBH_MSC_BBB_H
+#define __USBH_MSC_BBB_H
+
+#include "usbh_enum.h"
+#include "msc_bbb.h"
+
+typedef union {
+ msc_bbb_cbw field;
+
+ uint8_t CBWArray[31];
+} usbh_cbw_pkt;
+
+typedef union {
+ msc_bbb_csw field;
+
+ uint8_t CSWArray[13];
+} usbh_csw_pkt;
+
+enum usbh_msc_state {
+ USBH_MSC_BOT_INIT_STATE = 0U,
+ USBH_MSC_BOT_RESET,
+ USBH_MSC_GET_MAX_LUN,
+ USBH_MSC_TEST_UNIT_READY,
+ USBH_MSC_READ_CAPACITY10,
+ USBH_MSC_MODE_SENSE6,
+ USBH_MSC_REQUEST_SENSE,
+ USBH_MSC_BOT_USB_TRANSFERS,
+ USBH_MSC_DEFAULT_APPLI_STATE,
+ USBH_MSC_CTRL_ERROR_STATE,
+ USBH_MSC_UNRECOVERED_STATE
+};
+
+typedef enum {
+ BOT_OK = 0U,
+ BOT_FAIL,
+ BOT_PHASE_ERROR,
+ BOT_BUSY
+} bot_status;
+
+typedef enum {
+ BOT_CMD_IDLE = 0U,
+ BOT_CMD_SEND,
+ BOT_CMD_WAIT,
+} bot_cmd_state;
+
+/* csw status definitions */
+typedef enum {
+ BOT_CSW_CMD_PASSED = 0U,
+ BOT_CSW_CMD_FAILED,
+ BOT_CSW_PHASE_ERROR,
+} bot_csw_status;
+
+typedef enum {
+ BOT_SEND_CBW = 1U,
+ BOT_SEND_CBW_WAIT,
+ BOT_DATA_IN,
+ BOT_DATA_IN_WAIT,
+ BOT_DATA_OUT,
+ BOT_DATA_OUT_WAIT,
+ BOT_RECEIVE_CSW,
+ BOT_RECEIVE_CSW_WAIT,
+ BOT_ERROR_IN,
+ BOT_ERROR_OUT,
+ BOT_UNRECOVERED_ERROR
+} bot_state;
+
+typedef struct {
+ uint8_t *pbuf;
+ uint32_t data[16];
+ bot_state state;
+ bot_state prev_state;
+ bot_cmd_state cmd_state;
+ usbh_cbw_pkt cbw;
+ usbh_csw_pkt csw;
+} bot_handle;
+
+#define USBH_MSC_BOT_CBW_TAG 0x20304050U
+
+#define USBH_MSC_CSW_MAX_LENGTH 63U
+
+#define USBH_MSC_SEND_CSW_DISABLE 0U
+#define USBH_MSC_SEND_CSW_ENABLE 1U
+
+#define USBH_MSC_DIR_IN 0U
+#define USBH_MSC_DIR_OUT 1U
+#define USBH_MSC_BOTH_DIR 2U
+
+#define USBH_MSC_PAGE_LENGTH 512U
+
+#define CBW_CB_LENGTH 16U
+#define CBW_LENGTH 10U
+#define CBW_LENGTH_TEST_UNIT_READY 0U
+
+#define MAX_BULK_STALL_COUNT_LIMIT 0x04U /*!< If STALL is seen on Bulk
+ Endpoint continously, this means
+ that device and Host has phase error
+ Hence a Reset is needed */
+
+/* function declarations */
+/* initialize the mass storage parameters */
+void usbh_msc_bot_init(usbh_host *puhost);
+/* manage the different states of BOT transfer and updates the status to upper layer */
+usbh_status usbh_msc_bot_process(usbh_host *puhost, uint8_t lun);
+/* manages the different error handling for stall */
+usbh_status usbh_msc_bot_abort(usbh_host *puhost, uint8_t direction);
+/* reset msc bot request struct */
+usbh_status usbh_msc_bot_reset(usbh_host *puhost);
+/* decode the CSW received by the device and updates the same to upper layer */
+bot_csw_status usbh_msc_csw_decode(usbh_host *puhost);
+
+#endif /* __USBH_MSC_BBB_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/msc/Include/usbh_msc_core.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/msc/Include/usbh_msc_core.h
new file mode 100644
index 00000000..a53646df
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/msc/Include/usbh_msc_core.h
@@ -0,0 +1,119 @@
+/*!
+ \file usbh_core.h
+ \brief header file for the usbh_core.c
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __USBH_MSC_CORE_H
+#define __USBH_MSC_CORE_H
+
+#include "usb_msc.h"
+#include "usbh_msc_scsi.h"
+#include "usbh_msc_bbb.h"
+
+#define MSC_MAX_SUPPORTED_LUN 2U
+
+typedef enum {
+ MSC_INIT = 0U,
+ MSC_IDLE,
+ MSC_TEST_UNIT_READY,
+ MSC_READ_CAPACITY10,
+ MSC_READ_INQUIRY,
+ MSC_REQUEST_SENSE,
+ MSC_READ,
+ MSC_WRITE,
+ MSC_UNRECOVERED_ERROR,
+ MSC_PERIODIC_CHECK,
+} msc_state;
+
+typedef enum {
+ MSC_OK,
+ MSC_NOT_READY,
+ MSC_ERROR,
+} msc_error;
+
+typedef enum {
+ MSC_REQ_IDLE = 0U,
+ MSC_REQ_RESET,
+ MSC_REQ_GET_MAX_LUN,
+ MSC_REQ_ERROR,
+} msc_req_state;
+
+/* Structure for LUN */
+typedef struct {
+ msc_state state;
+ msc_error error;
+ msc_scsi_sense sense;
+ scsi_capacity capacity;
+ scsi_std_inquiry_data inquiry;
+ usbh_status prev_ready_state;
+ uint8_t state_changed;
+} msc_lun;
+
+/* structure for msc process */
+typedef struct _msc_process {
+ uint8_t pipe_in;
+ uint8_t pipe_out;
+ uint8_t ep_in;
+ uint8_t ep_out;
+ uint16_t ep_size_in;
+ uint16_t ep_size_out;
+ uint8_t cur_lun;
+ uint16_t rw_lun;
+ uint32_t max_lun;
+ msc_state state;
+ msc_error error;
+ msc_req_state req_state;
+ msc_req_state prev_req_state;
+ bot_handle bot;
+ msc_lun unit[MSC_MAX_SUPPORTED_LUN];
+ uint32_t timer;
+} usbh_msc_handler;
+
+extern usbh_class usbh_msc;
+
+/* function declarations */
+/* get msc logic unit information */
+usbh_status usbh_msc_lun_info_get(usbh_host *puhost, uint8_t lun, msc_lun *info);
+/* msc read interface */
+usbh_status usbh_msc_read(usbh_host *puhost,
+ uint8_t lun,
+ uint32_t address,
+ uint8_t *pbuf,
+ uint32_t length);
+/* msc write interface */
+usbh_status usbh_msc_write(usbh_host *puhost,
+ uint8_t lun,
+ uint32_t address,
+ uint8_t *pbuf,
+ uint32_t length);
+
+#endif /* __USBH_MSC_CORE_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/msc/Include/usbh_msc_scsi.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/msc/Include/usbh_msc_scsi.h
new file mode 100644
index 00000000..b01dabca
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/msc/Include/usbh_msc_scsi.h
@@ -0,0 +1,97 @@
+/*!
+ \file usbh_msc_scsi.h
+ \brief header file for usbh_msc_scsi.c
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __USBH_MSC_SCSI_H
+#define __USBH_MSC_SCSI_H
+
+#include "msc_scsi.h"
+#include "usbh_enum.h"
+
+/* capacity data */
+typedef struct {
+ uint32_t block_nbr;
+ uint16_t block_size;
+} scsi_capacity;
+
+/* inquiry data */
+typedef struct {
+ uint8_t peripheral_qualifier;
+ uint8_t device_type;
+ uint8_t removable_media;
+ uint8_t vendor_id[9];
+ uint8_t product_id[17];
+ uint8_t revision_id[5];
+} scsi_std_inquiry_data;
+
+typedef struct {
+ uint32_t msc_capacity;
+ uint32_t msc_sense_key;
+ uint16_t msc_page_len;
+ uint8_t msc_write_protect;
+} usbh_msc_parameter;
+
+#define DESC_REQUEST_SENSE 0x00U
+#define ALLOCATION_LENGTH_REQUEST_SENSE 63U
+#define XFER_LEN_MODE_SENSE6 63U
+
+#define MASK_MODE_SENSE_WRITE_PROTECT 0x80U
+#define MODE_SENSE_PAGE_CONTROL_FIELD 0x00U
+#define MODE_SENSE_PAGE_CODE 0x3FU
+#define DISK_WRITE_PROTECTED 0x01U
+
+/* function declarations */
+/* send 'Inquiry' command to the device */
+usbh_status usbh_msc_scsi_inquiry(usbh_host *puhost, uint8_t lun, scsi_std_inquiry_data *inquiry);
+/* send 'Test unit ready' command to the device */
+usbh_status usbh_msc_test_unitready(usbh_host *puhost, uint8_t lun);
+/* send the read capacity command to the device */
+usbh_status usbh_msc_read_capacity10(usbh_host *puhost, uint8_t lun, scsi_capacity *capacity);
+/* send the mode sense6 command to the device */
+usbh_status usbh_msc_mode_sense6(usbh_host *puhost, uint8_t lun);
+/* send the Request Sense command to the device */
+usbh_status usbh_msc_request_sense(usbh_host *puhost, uint8_t lun, msc_scsi_sense *sense_data);
+/* send the write10 command to the device */
+usbh_status usbh_msc_write10(usbh_host *puhost,
+ uint8_t lun,
+ uint8_t *data_buf,
+ uint32_t addr,
+ uint32_t byte_num);
+/* send the read10 command to the device */
+usbh_status usbh_msc_read10(usbh_host *puhost,
+ uint8_t lun,
+ uint8_t *data_buf,
+ uint32_t addr,
+ uint32_t byte_num);
+
+#endif /* __USBH_MSC_SCSI_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/msc/Source/usbh_msc_bbb.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/msc/Source/usbh_msc_bbb.c
new file mode 100644
index 00000000..16337938
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/msc/Source/usbh_msc_bbb.c
@@ -0,0 +1,362 @@
+/*!
+ \file usbh_msc_bbb.c
+ \brief USB MSC BBB protocol related functions
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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.
+*/
+
+#include "usbh_pipe.h"
+#include "usbh_msc_core.h"
+#include "usbh_msc_scsi.h"
+#include "usbh_msc_bbb.h"
+#include "usbh_transc.h"
+#include "drv_usbh_int.h"
+
+/*!
+ \brief initialize the mass storage parameters
+ \param[in] puhost: pointer to usb host handler
+ \param[out] none
+ \retval none
+*/
+void usbh_msc_bot_init(usbh_host *puhost)
+{
+ usbh_msc_handler *msc = (usbh_msc_handler *)puhost->active_class->class_data;
+
+ msc->bot.cbw.field.dCBWSignature = BBB_CBW_SIGNATURE;
+ msc->bot.cbw.field.dCBWTag = USBH_MSC_BOT_CBW_TAG;
+ msc->bot.state = BOT_SEND_CBW;
+ msc->bot.cmd_state = BOT_CMD_SEND;
+}
+
+/*!
+ \brief manage the different states of BOT transfer and updates the status to upper layer
+ \param[in] puhost: pointer to usb host handler
+ \param[in] lun: logic unit number
+ \param[out] none
+ \retval operation status
+*/
+usbh_status usbh_msc_bot_process(usbh_host *puhost, uint8_t lun)
+{
+ bot_csw_status csw_status = BOT_CSW_CMD_FAILED;
+ usbh_status status = USBH_BUSY;
+ usbh_status error = USBH_BUSY;
+ usb_urb_state urb_status = URB_IDLE;
+ usbh_msc_handler *msc = (usbh_msc_handler *)puhost->active_class->class_data;
+
+ switch(msc->bot.state) {
+ case BOT_SEND_CBW:
+ msc->bot.cbw.field.bCBWLUN = lun;
+ msc->bot.state = BOT_SEND_CBW_WAIT;
+ /* send CBW */
+ usbh_data_send(puhost->data,
+ msc->bot.cbw.CBWArray,
+ msc->pipe_out,
+ BBB_CBW_LENGTH);
+ break;
+
+ case BOT_SEND_CBW_WAIT:
+ urb_status = usbh_urbstate_get(puhost->data, msc->pipe_out);
+
+ if(URB_DONE == urb_status) {
+ if(0U != msc->bot.cbw.field.dCBWDataTransferLength) {
+ if(USB_TRX_IN == (msc->bot.cbw.field.bmCBWFlags & USB_TRX_MASK)) {
+ msc->bot.state = BOT_DATA_IN;
+ } else {
+ msc->bot.state = BOT_DATA_OUT;
+ }
+ } else {
+ msc->bot.state = BOT_RECEIVE_CSW;
+ }
+
+ } else if(URB_NOTREADY == urb_status) {
+ msc->bot.state = BOT_SEND_CBW;
+ } else {
+ if(URB_STALL == urb_status) {
+ msc->bot.state = BOT_ERROR_OUT;
+ }
+ }
+ break;
+
+ case BOT_DATA_IN:
+ usbh_data_recev(puhost->data,
+ msc->bot.pbuf,
+ msc->pipe_in,
+ msc->ep_size_in);
+
+ msc->bot.state = BOT_DATA_IN_WAIT;
+ break;
+
+ case BOT_DATA_IN_WAIT:
+ urb_status = usbh_urbstate_get(puhost->data, msc->pipe_in);
+
+ /* BOT DATA IN stage */
+ if(URB_DONE == urb_status) {
+ if(msc->bot.cbw.field.dCBWDataTransferLength > msc->ep_size_in) {
+ msc->bot.pbuf += msc->ep_size_in;
+ msc->bot.cbw.field.dCBWDataTransferLength -= msc->ep_size_in;
+ } else {
+ msc->bot.cbw.field.dCBWDataTransferLength = 0U;
+ }
+
+ if(msc->bot.cbw.field.dCBWDataTransferLength > 0U) {
+ usbh_data_recev(puhost->data,
+ msc->bot.pbuf,
+ msc->pipe_in,
+ msc->ep_size_in);
+ } else {
+ msc->bot.state = BOT_RECEIVE_CSW;
+ }
+ } else if(URB_STALL == urb_status) {
+ /* this is data stage stall condition */
+ msc->bot.state = BOT_ERROR_IN;
+ } else {
+ /* no operation */
+ }
+ break;
+
+ case BOT_DATA_OUT:
+ usbh_data_send(puhost->data,
+ msc->bot.pbuf,
+ msc->pipe_out,
+ msc->ep_size_out);
+
+ msc->bot.state = BOT_DATA_OUT_WAIT;
+ break;
+
+ case BOT_DATA_OUT_WAIT:
+ /* BOT DATA OUT stage */
+ urb_status = usbh_urbstate_get(puhost->data, msc->pipe_out);
+ if(URB_DONE == urb_status) {
+ if(msc->bot.cbw.field.dCBWDataTransferLength > msc->ep_size_out) {
+ msc->bot.pbuf += msc->ep_size_out;
+ msc->bot.cbw.field.dCBWDataTransferLength -= msc->ep_size_out;
+ } else {
+ msc->bot.cbw.field.dCBWDataTransferLength = 0; /* reset this value and keep in same state */
+ }
+
+ if(msc->bot.cbw.field.dCBWDataTransferLength > 0) {
+ usbh_data_send(puhost->data,
+ msc->bot.pbuf,
+ msc->pipe_out,
+ msc->ep_size_out);
+ } else {
+ msc->bot.state = BOT_RECEIVE_CSW;
+ }
+ } else if(URB_NOTREADY == urb_status) {
+ msc->bot.state = BOT_DATA_OUT;
+ } else if(URB_STALL == urb_status) {
+ msc->bot.state = BOT_ERROR_OUT;
+ } else {
+ /* no operation */
+ }
+ break;
+
+ case BOT_RECEIVE_CSW:
+ /* BOT CSW stage */
+ usbh_data_recev(puhost->data,
+ msc->bot.csw.CSWArray,
+ msc->pipe_in,
+ BBB_CSW_LENGTH);
+
+ msc->bot.state = BOT_RECEIVE_CSW_WAIT;
+ break;
+
+ case BOT_RECEIVE_CSW_WAIT:
+ urb_status = usbh_urbstate_get(puhost->data, msc->pipe_in);
+
+ /* decode CSW */
+ if(URB_DONE == urb_status) {
+ msc->bot.state = BOT_SEND_CBW;
+ msc->bot.cmd_state = BOT_CMD_SEND;
+
+ csw_status = usbh_msc_csw_decode(puhost);
+ if(BOT_CSW_CMD_PASSED == csw_status) {
+ status = USBH_OK;
+ } else {
+ status = USBH_FAIL;
+ }
+ } else if(URB_STALL == urb_status) {
+ msc->bot.state = BOT_ERROR_IN;
+ } else {
+ /* no operation */
+ }
+ break;
+
+ case BOT_ERROR_IN:
+ error = usbh_msc_bot_abort(puhost, USBH_MSC_DIR_IN);
+
+ if(USBH_OK == error) {
+ msc->bot.state = BOT_RECEIVE_CSW;
+ } else if(USBH_UNRECOVERED_ERROR == status) {
+ /* this means that there is a stall error limit, do reset recovery */
+ msc->bot.state = BOT_UNRECOVERED_ERROR;
+ } else {
+ /* no operation */
+ }
+ break;
+
+ case BOT_ERROR_OUT:
+ status = usbh_msc_bot_abort(puhost, USBH_MSC_DIR_OUT);
+
+ if(USBH_OK == status) {
+ uint8_t toggle = usbh_pipe_toggle_get(puhost->data, msc->pipe_out);
+ usbh_pipe_toggle_set(puhost->data, msc->pipe_out, 1U - toggle);
+ usbh_pipe_toggle_set(puhost->data, msc->pipe_in, 0U);
+ msc->bot.state = BOT_ERROR_IN;
+ } else {
+ if(USBH_UNRECOVERED_ERROR == status) {
+ msc->bot.state = BOT_UNRECOVERED_ERROR;
+ }
+ }
+ break;
+
+ case BOT_UNRECOVERED_ERROR:
+ status = usbh_msc_bot_reset(puhost);
+ if(USBH_OK == status) {
+ msc->bot.state = BOT_SEND_CBW;
+ }
+ break;
+
+ default:
+ break;
+ }
+
+ return status;
+}
+
+/*!
+ \brief manages the different error handling for stall
+ \param[in] puhost: pointer to usb host handler
+ \param[in] direction: data IN or OUT
+ \param[out] none
+ \retval operation status
+*/
+usbh_status usbh_msc_bot_abort(usbh_host *puhost, uint8_t direction)
+{
+ usbh_status status = USBH_BUSY;
+ usbh_msc_handler *msc = (usbh_msc_handler *)puhost->active_class->class_data;
+
+ switch(direction) {
+ case USBH_MSC_DIR_IN :
+ /* send clrfeture command on bulk IN endpoint */
+ status = usbh_clrfeature(puhost,
+ msc->ep_in,
+ msc->pipe_in);
+ break;
+
+ case USBH_MSC_DIR_OUT :
+ /*send clrfeature command on bulk OUT endpoint */
+ status = usbh_clrfeature(puhost,
+ msc->ep_out,
+ msc->pipe_out);
+ break;
+
+ default:
+ break;
+ }
+
+ return status;
+}
+
+/*!
+ \brief reset msc bot transfer
+ \param[in] puhost: pointer to usb host handler
+ \param[out] none
+ \retval operation status
+*/
+usbh_status usbh_msc_bot_reset(usbh_host *puhost)
+{
+ usbh_status status = USBH_BUSY;
+
+ if(CTL_IDLE == puhost->control.ctl_state) {
+ puhost->control.setup.req = (usb_req) {
+ .bmRequestType = USB_TRX_OUT | USB_REQTYPE_CLASS | USB_RECPTYPE_ITF,
+ .bRequest = BBB_RESET,
+ .wValue = 0U,
+ .wIndex = 0U,
+ .wLength = 0U
+ };
+
+ usbh_ctlstate_config(puhost, NULL, 0U);
+ }
+
+ status = usbh_ctl_handler(puhost);
+
+ return status;
+}
+
+/*!
+ \brief decode the CSW received by the device and updates the same to upper layer
+ \param[in] puhost: pointer to usb host
+ \param[out] none
+ \retval on success USBH_MSC_OK, on failure USBH_MSC_FAIL
+ \notes
+ Refer to USB Mass-Storage Class: BOT (www.usb.org)
+ 6.3.1 Valid CSW Conditions :
+ The host shall consider the CSW valid when:
+ 1. dCSWSignature is equal to 53425355h
+ 2. the CSW is 13 (Dh) bytes in length,
+ 3. dCSWTag matches the dCBWTag from the corresponding CBW.
+*/
+bot_csw_status usbh_msc_csw_decode(usbh_host *puhost)
+{
+ bot_csw_status status = BOT_CSW_CMD_FAILED;
+ usbh_msc_handler *msc = (usbh_msc_handler *)puhost->active_class->class_data;
+
+ /* checking if the transfer length is different than 13 */
+ if(BBB_CSW_LENGTH != usbh_xfercount_get(puhost->data, msc->pipe_in)) {
+ status = BOT_CSW_PHASE_ERROR;
+ } else {
+ /* CSW length is correct */
+
+ /* check validity of the CSW Signature and CSWStatus */
+ if(BBB_CSW_SIGNATURE == msc->bot.csw.field.dCSWSignature) {
+ /* check condition 1. dCSWSignature is equal to 53425355h */
+ if(msc->bot.csw.field.dCSWTag == msc->bot.cbw.field.dCBWTag) {
+ /* check condition 3. dCSWTag matches the dCBWTag from the corresponding CBW */
+ if(0U == msc->bot.csw.field.bCSWStatus) {
+ status = BOT_CSW_CMD_PASSED;
+ } else if(1U == msc->bot.csw.field.bCSWStatus) {
+ status = BOT_CSW_CMD_FAILED;
+ } else if(2U == msc->bot.csw.field.bCSWStatus) {
+ status = BOT_CSW_PHASE_ERROR;
+ } else {
+ /* no operation */
+ }
+ }
+ } else {
+ /* If the CSW signature is not valid, we will return the phase error to
+ upper layers for reset recovery */
+ status = BOT_CSW_PHASE_ERROR;
+ }
+ }
+
+ return status;
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/msc/Source/usbh_msc_core.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/msc/Source/usbh_msc_core.c
new file mode 100644
index 00000000..f2917792
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/msc/Source/usbh_msc_core.c
@@ -0,0 +1,560 @@
+/*!
+ \file usbh_core.c
+ \brief USB MSC(mass storage device) class driver
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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.
+*/
+
+#include "usbh_msc_core.h"
+#include "usbh_msc_scsi.h"
+#include "usbh_msc_bbb.h"
+#include "usbh_pipe.h"
+#include "usbh_transc.h"
+#include
+#include
+
+/* local function prototypes ('static') */
+static void usbh_msc_itf_deinit(usbh_host *puhost);
+static usbh_status usbh_msc_itf_init(usbh_host *puhost);
+static usbh_status usbh_msc_req(usbh_host *puhost);
+static usbh_status usbh_msc_handle(usbh_host *puhost);
+static usbh_status usbh_msc_maxlun_get(usbh_host *puhost, uint8_t *maxlun);
+static usbh_status usbh_msc_rdwr_process(usbh_host *puhost, uint8_t lun);
+
+usbh_class usbh_msc = {
+ USB_CLASS_MSC,
+ usbh_msc_itf_init,
+ usbh_msc_itf_deinit,
+ usbh_msc_req,
+ usbh_msc_handle,
+};
+
+/*!
+ \brief interface initialization for MSC class
+ \param[in] puhost: pointer to usb host
+ \param[out] none
+ \retval operation status
+*/
+static usbh_status usbh_msc_itf_init(usbh_host *puhost)
+{
+ usbh_status status = USBH_OK;
+
+ uint8_t interface = usbh_interface_find(&puhost->dev_prop, MSC_CLASS, USB_MSC_SUBCLASS_SCSI, MSC_PROTOCOL);
+
+ if(0xFFU == interface) {
+ puhost->usr_cb->dev_not_supported();
+
+ status = USBH_FAIL;
+ } else {
+ static usbh_msc_handler msc_handler;
+
+ memset((void *)&msc_handler, 0, sizeof(usbh_msc_handler));
+
+ puhost->active_class->class_data = (void *)&msc_handler;
+
+ usbh_interface_select(&puhost->dev_prop, interface);
+
+ usb_desc_ep *ep_desc = &puhost->dev_prop.cfg_desc_set.itf_desc_set[interface][0].ep_desc[0];
+
+ if(ep_desc->bEndpointAddress & 0x80) {
+ msc_handler.ep_in = ep_desc->bEndpointAddress;
+ msc_handler.ep_size_in = ep_desc->wMaxPacketSize;
+ } else {
+ msc_handler.ep_out = ep_desc->bEndpointAddress;
+ msc_handler.ep_size_out = ep_desc->wMaxPacketSize;
+ }
+
+ ep_desc = &puhost->dev_prop.cfg_desc_set.itf_desc_set[interface][0].ep_desc[1];
+
+ if(ep_desc->bEndpointAddress & 0x80) {
+ msc_handler.ep_in = ep_desc->bEndpointAddress;
+ msc_handler.ep_size_in = ep_desc->wMaxPacketSize;
+ } else {
+ msc_handler.ep_out = ep_desc->bEndpointAddress;
+ msc_handler.ep_size_out = ep_desc->wMaxPacketSize;
+ }
+
+ msc_handler.state = MSC_INIT;
+ msc_handler.error = MSC_OK;
+ msc_handler.req_state = MSC_REQ_IDLE;
+ msc_handler.pipe_out = usbh_pipe_allocate(puhost->data, msc_handler.ep_out);
+ msc_handler.pipe_in = usbh_pipe_allocate(puhost->data, msc_handler.ep_in);
+
+ usbh_msc_bot_init(puhost);
+
+ /* open the new channels */
+ usbh_pipe_create(puhost->data,
+ &puhost->dev_prop,
+ msc_handler.pipe_out,
+ USB_EPTYPE_BULK,
+ msc_handler.ep_size_out);
+
+ usbh_pipe_create(puhost->data,
+ &puhost->dev_prop,
+ msc_handler.pipe_in,
+ USB_EPTYPE_BULK,
+ msc_handler.ep_size_in);
+
+ usbh_pipe_toggle_set(puhost->data, msc_handler.pipe_out, 0U);
+ usbh_pipe_toggle_set(puhost->data, msc_handler.pipe_in, 0U);
+ }
+
+ return status;
+}
+
+/*!
+ \brief de-initialize interface by freeing host channels allocated to interface
+ \param[in] puhost: pointer to usb host
+ \param[out] none
+ \retval operation status
+*/
+void usbh_msc_itf_deinit(usbh_host *puhost)
+{
+ usbh_msc_handler *msc = (usbh_msc_handler *)puhost->active_class->class_data;
+
+ if(msc->pipe_out) {
+ usb_pipe_halt(puhost->data, msc->pipe_out);
+ usbh_pipe_free(puhost->data, msc->pipe_out);
+
+ msc->pipe_out = 0U;
+ }
+
+ if(msc->pipe_in) {
+ usb_pipe_halt(puhost->data, msc->pipe_in);
+ usbh_pipe_free(puhost->data, msc->pipe_in);
+
+ msc->pipe_in = 0U;
+ }
+}
+
+/*!
+ \brief initialize the MSC state machine
+ \param[in] puhost: pointer to usb host
+ \param[out] none
+ \retval operation status
+*/
+static usbh_status usbh_msc_req(usbh_host *puhost)
+{
+ usbh_status status = USBH_BUSY;
+ usbh_msc_handler *msc = (usbh_msc_handler *)puhost->active_class->class_data;
+
+ switch(msc->req_state) {
+ case MSC_REQ_IDLE:
+ case MSC_REQ_GET_MAX_LUN:
+ /* issue Get_MaxLun request */
+ status = usbh_msc_maxlun_get(puhost, (uint8_t *)&msc->max_lun);
+
+ if(USBH_OK == status) {
+ msc->max_lun = ((uint8_t)msc->max_lun > MSC_MAX_SUPPORTED_LUN) ? MSC_MAX_SUPPORTED_LUN : (uint8_t)msc->max_lun + 1U;
+
+ for(uint8_t i = 0U; i < msc->max_lun; i++) {
+ msc->unit[i].prev_ready_state = USBH_FAIL;
+ msc->unit[i].state_changed = 0U;
+ }
+ } else {
+ if(USBH_NOT_SUPPORTED == status) {
+ msc->max_lun = 0U;
+ status = USBH_OK;
+ }
+ }
+ break;
+
+ case MSC_REQ_ERROR:
+ /* issue clear feature request */
+ if(USBH_OK == usbh_clrfeature(puhost, 0x00U, puhost->control.pipe_out_num)) {
+ msc->req_state = msc->prev_req_state;
+ }
+ break;
+
+ default:
+ break;
+ }
+
+ return status;
+}
+
+/*!
+ \brief MSC state machine handler
+ \param[in] puhost: pointer to usb host
+ \param[out] none
+ \retval operation status
+*/
+static usbh_status usbh_msc_handle(usbh_host *puhost)
+{
+ usbh_status status = USBH_BUSY;
+ uint8_t scsi_status = USBH_BUSY;
+ uint8_t ready_status = USBH_BUSY;
+ usbh_msc_handler *msc = (usbh_msc_handler *)puhost->active_class->class_data;
+
+
+ switch(msc->state) {
+ case MSC_INIT:
+ if(msc->cur_lun < msc->max_lun) {
+ msc->unit[msc->cur_lun].error = MSC_NOT_READY;
+
+ switch(msc->unit[msc->cur_lun].state) {
+ case MSC_INIT:
+ msc->unit[msc->cur_lun].state = MSC_READ_INQUIRY;
+ msc->timer = puhost->control.timer;
+ break;
+
+ case MSC_READ_INQUIRY:
+ scsi_status = usbh_msc_scsi_inquiry(puhost, msc->cur_lun, &msc->unit[msc->cur_lun].inquiry);
+
+ if(USBH_OK == scsi_status) {
+ msc->unit[msc->cur_lun].state = MSC_TEST_UNIT_READY;
+ } else if(scsi_status == USBH_FAIL) {
+ msc->unit[msc->cur_lun].state = MSC_REQUEST_SENSE;
+ } else {
+ if(scsi_status == USBH_UNRECOVERED_ERROR) {
+ msc->unit[msc->cur_lun].state = MSC_IDLE;
+ msc->unit[msc->cur_lun].error = MSC_ERROR;
+ }
+ }
+ break;
+
+ case MSC_TEST_UNIT_READY:
+ /* issue SCSI command TestUnitReady */
+ ready_status = usbh_msc_test_unitready(puhost, msc->cur_lun);
+
+ if(USBH_OK == ready_status) {
+ if(USBH_OK != msc->unit[msc->cur_lun].prev_ready_state) {
+ msc->unit[msc->cur_lun].state_changed = 1U;
+ } else {
+ msc->unit[msc->cur_lun].state_changed = 0U;
+ }
+
+ msc->unit[msc->cur_lun].state = MSC_READ_CAPACITY10;
+ msc->unit[msc->cur_lun].error = MSC_OK;
+ msc->unit[msc->cur_lun].prev_ready_state = USBH_OK;
+ } else if(USBH_FAIL == ready_status) {
+ if(USBH_FAIL != msc->unit[msc->cur_lun].prev_ready_state) {
+ msc->unit[msc->cur_lun].state_changed = 1U;
+ } else {
+ msc->unit[msc->cur_lun].state_changed = 0U;
+ }
+
+ msc->unit[msc->cur_lun].state = MSC_REQUEST_SENSE;
+ msc->unit[msc->cur_lun].error = MSC_NOT_READY;
+ msc->unit[msc->cur_lun].prev_ready_state = USBH_FAIL;
+ } else {
+ if(USBH_UNRECOVERED_ERROR == ready_status) {
+ msc->unit[msc->cur_lun].state = MSC_IDLE;
+ msc->unit[msc->cur_lun].error = MSC_ERROR;
+ }
+ }
+ break;
+
+ case MSC_READ_CAPACITY10:
+ /* issue READ_CAPACITY10 SCSI command */
+ scsi_status = usbh_msc_read_capacity10(puhost, msc->cur_lun, &msc->unit[msc->cur_lun].capacity);
+
+ if(USBH_OK == scsi_status) {
+ if(1U == msc->unit[msc->cur_lun].state_changed) {
+ }
+ msc->unit[msc->cur_lun].state = MSC_IDLE;
+ msc->unit[msc->cur_lun].error = MSC_OK;
+ msc->cur_lun ++;
+ } else if(USBH_FAIL == scsi_status) {
+ msc->unit[msc->cur_lun].state = MSC_REQUEST_SENSE;
+ } else {
+ if(USBH_UNRECOVERED_ERROR == scsi_status) {
+ msc->unit[msc->cur_lun].state = MSC_IDLE;
+ msc->unit[msc->cur_lun].error = MSC_ERROR;
+ }
+ }
+ break;
+
+ case MSC_REQUEST_SENSE:
+ /* issue RequestSense SCSI command for recovering error code */
+ scsi_status = usbh_msc_request_sense(puhost, msc->cur_lun, &msc->unit[msc->cur_lun].sense);
+ if(USBH_OK == scsi_status) {
+ if((msc->unit[msc->cur_lun].sense.SenseKey == UNIT_ATTENTION) || (msc->unit[msc->cur_lun].sense.SenseKey == NOT_READY)) {
+ if(((puhost->control.timer > msc->timer) && ((puhost->control.timer - msc->timer) < 10000U)) \
+ || ((puhost->control.timer < msc->timer) && ((puhost->control.timer + 0x3FFFU - msc->timer) < 10000U))) {
+ msc->unit[msc->cur_lun].state = MSC_TEST_UNIT_READY;
+ break;
+ }
+ }
+
+ msc->unit[msc->cur_lun].state = MSC_IDLE;
+ msc->cur_lun++;
+ } else if(USBH_FAIL == scsi_status) {
+ msc->unit[msc->cur_lun].state = MSC_UNRECOVERED_ERROR;
+ } else {
+ if(MSC_UNRECOVERED_ERROR == scsi_status) {
+ msc->unit[msc->cur_lun].state = MSC_IDLE;
+ msc->unit[msc->cur_lun].error = MSC_ERROR;
+ }
+ }
+ break;
+
+ case MSC_UNRECOVERED_ERROR:
+ msc->cur_lun ++;
+ break;
+
+ default:
+ break;
+ }
+ } else {
+ msc->cur_lun = 0U;
+ msc->state = MSC_IDLE;
+ }
+ break;
+
+ case MSC_IDLE:
+ puhost->usr_cb->dev_user_app();
+ status = USBH_OK;
+ break;
+
+ default:
+ break;
+ }
+
+ return status;
+}
+
+/*!
+ \brief get max lun of the mass storage device
+ \param[in] puhost: pointer to USB host
+ \param[in] maxlun: pointer to max lun
+ \param[out] none
+ \retval operation status
+*/
+static usbh_status usbh_msc_maxlun_get(usbh_host *puhost, uint8_t *maxlun)
+{
+ usbh_status status = USBH_BUSY;
+
+ if(puhost->control.ctl_state == CTL_IDLE) {
+ puhost->control.setup.req = (usb_req) {
+ .bmRequestType = USB_TRX_IN | USB_REQTYPE_CLASS | USB_RECPTYPE_ITF,
+ .bRequest = BBB_GET_MAX_LUN,
+ .wValue = 0U,
+ .wIndex = 0U,
+ .wLength = 1U
+ };
+
+ usbh_ctlstate_config(puhost, maxlun, 1U);
+ }
+
+ status = usbh_ctl_handler(puhost);
+
+ return status;
+}
+
+/*!
+ \brief get max lun of the mass storage device
+ \param[in] puhost: pointer to USB host
+ \param[in] lun: logic unit number
+ \param[out] none
+ \retval operation status
+*/
+static usbh_status usbh_msc_rdwr_process(usbh_host *puhost, uint8_t lun)
+{
+ usbh_status error = USBH_BUSY;
+ usbh_status scsi_status = USBH_BUSY;
+ usbh_msc_handler *msc = (usbh_msc_handler *)puhost->active_class->class_data;
+
+ /* switch msc req state machine */
+ switch(msc->unit[lun].state) {
+ case MSC_READ:
+ scsi_status = usbh_msc_read10(puhost, lun, NULL, 0U, 0U);
+
+ if(USBH_OK == scsi_status) {
+ msc->unit[lun].state = MSC_IDLE;
+ error = USBH_OK;
+ } else if(USBH_FAIL == scsi_status) {
+ msc->unit[lun].state = MSC_REQUEST_SENSE;
+ } else {
+ if(USBH_UNRECOVERED_ERROR == scsi_status) {
+ msc->unit[lun].state = MSC_UNRECOVERED_ERROR;
+ error = USBH_FAIL;
+ }
+ }
+ break;
+
+ case MSC_WRITE:
+ scsi_status = usbh_msc_write10(puhost, lun, NULL, 0U, 0U);
+
+ if(USBH_OK == scsi_status) {
+ msc->unit[lun].state = MSC_IDLE;
+ error = USBH_OK;
+ } else if(USBH_FAIL == scsi_status) {
+ msc->unit[lun].state = MSC_REQUEST_SENSE;
+ } else {
+ if(USBH_UNRECOVERED_ERROR == scsi_status) {
+ msc->unit[lun].state = MSC_UNRECOVERED_ERROR;
+ error = USBH_FAIL;
+ }
+ }
+ break;
+
+ case MSC_REQUEST_SENSE:
+ scsi_status = usbh_msc_request_sense(puhost, lun, &msc->unit[lun].sense);
+
+ if(USBH_OK == scsi_status) {
+ msc->unit[lun].state = MSC_IDLE;
+ msc->unit[lun].error = MSC_ERROR;
+
+ error = USBH_FAIL;
+ }
+
+ if(USBH_FAIL == scsi_status) {
+ } else {
+ if(USBH_UNRECOVERED_ERROR == scsi_status) {
+ msc->unit[lun].state = MSC_UNRECOVERED_ERROR;
+ error = USBH_FAIL;
+ }
+ }
+ break;
+
+ default:
+ break;
+ }
+
+ return error;
+}
+
+/*!
+ \brief get lun information
+ \param[in] puhost: pointer to USB host
+ \param[in] lun: logic unit number
+ \param[in] info: pointer to lun information
+ \param[out] none
+ \retval operation status
+*/
+usbh_status usbh_msc_lun_info_get(usbh_host *puhost, uint8_t lun, msc_lun *info)
+{
+ usbh_msc_handler *msc = (usbh_msc_handler *)puhost->active_class->class_data;
+
+ if(HOST_CLASS_HANDLER == puhost->cur_state) {
+ memcpy(info, &msc->unit[lun], sizeof(msc_lun));
+
+ return USBH_OK;
+ } else {
+ return USBH_FAIL;
+ }
+}
+
+/*!
+ \brief handle msc read operation
+ \param[in] puhost: pointer to USB host
+ \param[in] lun: logic unit number
+ \param[in] address: data address
+ \param[in] pbuf: pointer to data buffer
+ \param[in] length: buffer length
+ \param[out] none
+ \retval operation status
+*/
+usbh_status usbh_msc_read(usbh_host *puhost,
+ uint8_t lun,
+ uint32_t address,
+ uint8_t *pbuf,
+ uint32_t length)
+{
+ uint32_t timeout = 0U;
+ usbh_msc_handler *msc = (usbh_msc_handler *)puhost->active_class->class_data;
+ usb_core_driver *pudev = (usb_core_driver *)puhost->data;
+
+ if((0U == pudev->host.connect_status) ||
+ (HOST_CLASS_HANDLER != puhost->cur_state) ||
+ (MSC_IDLE != msc->unit[lun].state)) {
+ return USBH_FAIL;
+ }
+
+ msc->state = MSC_READ;
+ msc->unit[lun].state = MSC_READ;
+ msc->rw_lun = lun;
+
+ usbh_msc_read10(puhost, lun, pbuf, address, length);
+
+ timeout = puhost->control.timer;
+
+ while(USBH_BUSY == usbh_msc_rdwr_process(puhost, lun)) {
+ if(((puhost->control.timer > timeout) && ((puhost->control.timer - timeout) > (1000U * length))) \
+ || ((puhost->control.timer < timeout) && ((puhost->control.timer + 0x3FFFU - timeout) > (1000U * length))) \
+ || (0U == pudev->host.connect_status)) {
+ msc->state = MSC_IDLE;
+ return USBH_FAIL;
+ }
+ }
+
+ msc->state = MSC_IDLE;
+
+ return USBH_OK;
+}
+
+/*!
+ \brief handle msc write operation
+ \param[in] puhost: pointer to USB host
+ \param[in] lun: logic unit number
+ \param[in] address: data address
+ \param[in] pbuf: pointer to data buffer
+ \param[in] length: buffer length
+ \param[out] none
+ \retval operation status
+*/
+usbh_status usbh_msc_write(usbh_host *puhost,
+ uint8_t lun,
+ uint32_t address,
+ uint8_t *pbuf,
+ uint32_t length)
+{
+ uint32_t timeout = 0U;
+ usb_core_driver *pudev = (usb_core_driver *)puhost->data;
+ usbh_msc_handler *msc = (usbh_msc_handler *)puhost->active_class->class_data;
+
+ if((0U == pudev->host.connect_status) ||
+ (HOST_CLASS_HANDLER != puhost->cur_state) ||
+ (MSC_IDLE != msc->unit[lun].state)) {
+ return USBH_FAIL;
+ }
+
+ msc->state = MSC_WRITE;
+ msc->unit[lun].state = MSC_WRITE;
+ msc->rw_lun = lun;
+
+ usbh_msc_write10(puhost, lun, pbuf, address, length);
+
+ timeout = puhost->control.timer;
+
+ while(USBH_BUSY == usbh_msc_rdwr_process(puhost, lun)) {
+ if(((puhost->control.timer > timeout) && ((puhost->control.timer - timeout) > (1000U * length))) \
+ || ((puhost->control.timer < timeout) && ((puhost->control.timer + 0x3FFFU - timeout) > (1000U * length))) \
+ || (0U == pudev->host.connect_status)) {
+ msc->state = MSC_IDLE;
+ return USBH_FAIL;
+ }
+ }
+
+ msc->state = MSC_IDLE;
+
+ return USBH_OK;
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/msc/Source/usbh_msc_fatfs.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/msc/Source/usbh_msc_fatfs.c
new file mode 100644
index 00000000..b3dd94f2
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/msc/Source/usbh_msc_fatfs.c
@@ -0,0 +1,234 @@
+/*!
+ \file usbh_msc_fatfs.c
+ \brief USB MSC host FATFS related functions
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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.
+*/
+
+#include "usb_conf.h"
+#include "diskio.h"
+#include "usbh_msc_core.h"
+
+static volatile DSTATUS state = STA_NOINIT; /* disk status */
+
+extern usbh_host usb_host;
+
+/*!
+ \brief initialize the disk drive
+ \param[in] drv: physical drive number (0)
+ \param[out] none
+ \retval operation status
+*/
+DSTATUS disk_initialize(BYTE drv)
+{
+ usb_core_driver *pudev = (usb_core_driver *)usb_host.data;
+
+ if(pudev->host.connect_status) {
+ state &= ~STA_NOINIT;
+ }
+
+ return state;
+}
+
+/*!
+ \brief get disk status
+ \param[in] drv: physical drive number (0)
+ \param[out] none
+ \retval operation status
+*/
+DSTATUS disk_status(BYTE drv)
+{
+ if(drv) {
+ return STA_NOINIT; /* supports only single drive */
+ }
+
+ return state;
+}
+
+/*!
+ \brief read sectors
+ \param[in] drv: physical drive number (0)
+ \param[in] buff: pointer to the data buffer to store read data
+ \param[in] sector: start sector number (LBA)
+ \param[in] count: sector count (1..255)
+ \param[out] none
+ \retval operation status
+*/
+DRESULT disk_read(BYTE drv, BYTE *buff, DWORD sector, UINT count)
+{
+ BYTE status = USBH_OK;
+ usb_core_driver *pudev = (usb_core_driver *)usb_host.data;
+
+ if(drv || (!count)) {
+ return RES_PARERR;
+ }
+
+ if(state & STA_NOINIT) {
+ return RES_NOTRDY;
+ }
+
+ if(pudev->host.connect_status) {
+ do {
+ status = usbh_msc_read(&usb_host, drv, sector, buff, count);
+
+ if(!pudev->host.connect_status) {
+ return RES_ERROR;
+ }
+ } while(status == USBH_BUSY);
+ }
+
+ if(status == USBH_OK) {
+ return RES_OK;
+ }
+
+ return RES_ERROR;
+}
+
+#if _READONLY == 0U
+
+/*!
+ \brief write sectors
+ \param[in] drv: physical drive number (0)
+ \param[in] buff: pointer to the data buffer to store read data
+ \param[in] sector: start sector number (LBA)
+ \param[in] count: sector count (1..255)
+ \param[out] none
+ \retval operation status
+*/
+DRESULT disk_write(BYTE drv, const BYTE *buff, DWORD sector, UINT count)
+{
+ BYTE status = USBH_OK;
+ usb_core_driver *pudev = (usb_core_driver *)usb_host.data;
+
+ if((!count) || drv) {
+ return RES_PARERR;
+ }
+
+ if(state & STA_NOINIT) {
+ return RES_NOTRDY;
+ }
+
+ if(state & STA_PROTECT) {
+ return RES_WRPRT;
+ }
+
+ if(pudev->host.connect_status) {
+ do {
+ status = usbh_msc_write(&usb_host, drv, sector, (BYTE *)buff, count);
+
+ if(!pudev->host.connect_status) {
+ return RES_ERROR;
+ }
+ } while(status == USBH_BUSY);
+ }
+
+ if(status == USBH_OK) {
+ return RES_OK;
+ }
+
+ return RES_ERROR;
+}
+
+#endif /* _READONLY == 0 */
+
+/*!
+ \brief I/O control function
+ \param[in] drv: physical drive number (0)
+ \param[in] ctrl: control code
+ \param[in] buff: pointer to the data buffer to store read data
+ \param[out] none
+ \retval operation status
+*/
+DRESULT disk_ioctl(BYTE drv, BYTE ctrl, void *buff)
+{
+ DRESULT res = RES_OK;
+ msc_lun info;
+
+ if(drv) {
+ return RES_PARERR;
+ }
+
+ res = RES_ERROR;
+
+ if(state & STA_NOINIT) {
+ return RES_NOTRDY;
+ }
+
+ switch(ctrl) {
+ /* make sure that no pending write process */
+ case CTRL_SYNC:
+ res = RES_OK;
+ break;
+
+ /* get number of sectors on the disk (dword) */
+ case GET_SECTOR_COUNT:
+ if(USBH_OK == usbh_msc_lun_info_get(&usb_host, drv, &info)) {
+ *(DWORD *)buff = (DWORD)info.capacity.block_nbr;
+ res = RES_OK;
+ }
+ break;
+
+ /* get r/w sector size (word) */
+ case GET_SECTOR_SIZE:
+ if(USBH_OK == usbh_msc_lun_info_get(&usb_host, drv, &info)) {
+ *(WORD *)buff = (DWORD)info.capacity.block_size;
+ res = RES_OK;
+ }
+ break;
+
+ /* get erase block size in unit of sector (dword) */
+ case GET_BLOCK_SIZE:
+ *(DWORD *)buff = 512;
+ break;
+
+ default:
+ res = RES_PARERR;
+ break;
+ }
+
+ return res;
+}
+
+/*!
+ \brief get fat time
+ \param[in] none
+ \param[out] none
+ \retval time value
+*/
+DWORD get_fattime(void)
+{
+
+ return ((DWORD)(2019U - 1980U) << 25U) /* Year 2019 */
+ | ((DWORD)1U << 21U) /* Month 1 */
+ | ((DWORD)1U << 16U) /* Mday 1 */
+ | ((DWORD)0U << 11U) /* Hour 0 */
+ | ((DWORD)0U << 5U) /* Min 0 */
+ | ((DWORD)0U >> 1U); /* Sec 0 */
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/msc/Source/usbh_msc_scsi.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/msc/Source/usbh_msc_scsi.c
new file mode 100644
index 00000000..dfb4d45a
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/class/msc/Source/usbh_msc_scsi.c
@@ -0,0 +1,397 @@
+/*!
+ \file usbh_msc_scsi.c
+ \brief USB MSC SCSI commands implemention
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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.
+*/
+
+#include "usbh_msc_core.h"
+#include "usbh_msc_scsi.h"
+#include "usbh_msc_bbb.h"
+#include
+
+/*!
+ \brief send 'Inquiry' command to the device
+ \param[in] puhost: pointer to usb host handler
+ \param[in] lun: logic unit number
+ \param[in] inquiry: pointer to the inquiry structure
+ \param[out] none
+ \retval operation status
+*/
+usbh_status usbh_msc_scsi_inquiry(usbh_host *puhost, uint8_t lun, scsi_std_inquiry_data *inquiry)
+{
+ usbh_status error = USBH_FAIL;
+ usbh_msc_handler *msc = (usbh_msc_handler *)puhost->active_class->class_data;
+
+ switch(msc->bot.cmd_state) {
+ case BOT_CMD_SEND:
+ /* prepare the cbw and relevant field*/
+ msc->bot.cbw.field.dCBWDataTransferLength = STANDARD_INQUIRY_DATA_LEN;
+ msc->bot.cbw.field.bmCBWFlags = USB_TRX_IN;
+ msc->bot.cbw.field.bCBWCBLength = CBW_LENGTH;
+
+ memset(msc->bot.cbw.field.CBWCB, 0U, CBW_LENGTH);
+
+ msc->bot.cbw.field.CBWCB[0] = SCSI_INQUIRY;
+ msc->bot.cbw.field.CBWCB[1] = (lun << 5U);
+ msc->bot.cbw.field.CBWCB[4] = 0x24U;
+
+ msc->bot.state = BOT_SEND_CBW;
+ msc->bot.cmd_state = BOT_CMD_WAIT;
+ msc->bot.pbuf = (uint8_t *)(void *)msc->bot.data;
+ error = USBH_BUSY;
+ break;
+
+ case BOT_CMD_WAIT:
+ error = usbh_msc_bot_process(puhost, lun);
+
+ if(USBH_OK == error) {
+ memset(inquiry, 0U, sizeof(scsi_std_inquiry_data));
+
+ /* assign inquiry data */
+ inquiry->device_type = msc->bot.pbuf[0] & 0x1FU;
+ inquiry->peripheral_qualifier = msc->bot.pbuf[0] >> 5U;
+
+ if(0x80U == ((uint32_t)msc->bot.pbuf[1] & 0x80U)) {
+ inquiry->removable_media = 1U;
+ } else {
+ inquiry->removable_media = 0U;
+ }
+
+ memcpy(inquiry->vendor_id, &msc->bot.pbuf[8], 8U);
+ memcpy(inquiry->product_id, &msc->bot.pbuf[16], 16U);
+ memcpy(inquiry->revision_id, &msc->bot.pbuf[32], 4U);
+ }
+ break;
+
+ default:
+ break;
+ }
+
+ return error;
+}
+
+/*!
+ \brief send 'Test unit ready' command to the device
+ \param[in] puhost: pointer to USB host handler
+ \param[in] lun: logic unit number
+ \param[out] none
+ \retval operation status
+*/
+usbh_status usbh_msc_test_unitready(usbh_host *puhost, uint8_t lun)
+{
+ usbh_status status = USBH_FAIL;
+ usbh_msc_handler *msc = (usbh_msc_handler *)puhost->active_class->class_data;
+
+
+ switch(msc->bot.cmd_state) {
+ case BOT_CMD_SEND:
+ /* prepare the CBW and relevant field */
+ msc->bot.cbw.field.dCBWDataTransferLength = CBW_LENGTH_TEST_UNIT_READY;
+ msc->bot.cbw.field.bmCBWFlags = USB_TRX_OUT;
+ msc->bot.cbw.field.bCBWCBLength = CBW_LENGTH;
+
+ memset(msc->bot.cbw.field.CBWCB, 0U, CBW_CB_LENGTH);
+
+ msc->bot.cbw.field.CBWCB[0] = SCSI_TEST_UNIT_READY;
+ msc->bot.state = BOT_SEND_CBW;
+ msc->bot.cmd_state = BOT_CMD_WAIT;
+
+ status = USBH_BUSY;
+ break;
+
+ case BOT_CMD_WAIT:
+ status = usbh_msc_bot_process(puhost, lun);
+ break;
+
+ default:
+ break;
+ }
+
+ return status;
+}
+
+/*!
+ \brief send the read capacity command to the device
+ \param[in] puhost: pointer to usb host handler
+ \param[in] lun: logic unit number
+ \param[in] capacity: pointer to scsi capacity
+ \param[out] none
+ \retval operation status
+*/
+usbh_status usbh_msc_read_capacity10(usbh_host *puhost, uint8_t lun, scsi_capacity *capacity)
+{
+ usbh_status status = USBH_FAIL;
+ usbh_msc_handler *msc = (usbh_msc_handler *)puhost->active_class->class_data;
+
+ switch(msc->bot.cmd_state) {
+ case BOT_CMD_SEND:
+ /* prepare the CBW and relevant field */
+ msc->bot.cbw.field.dCBWDataTransferLength = READ_CAPACITY10_DATA_LEN;
+ msc->bot.cbw.field.bmCBWFlags = USB_TRX_IN;
+ msc->bot.cbw.field.bCBWCBLength = CBW_LENGTH;
+
+ memset(msc->bot.cbw.field.CBWCB, 0U, CBW_CB_LENGTH);
+
+ msc->bot.cbw.field.CBWCB[0] = SCSI_READ_CAPACITY10;
+ msc->bot.state = BOT_SEND_CBW;
+ msc->bot.cmd_state = BOT_CMD_WAIT;
+ msc->bot.pbuf = (uint8_t *)(void *)msc->bot.data;
+
+ status = USBH_BUSY;
+ break;
+
+ case BOT_CMD_WAIT:
+ status = usbh_msc_bot_process(puhost, lun);
+
+ if(USBH_OK == status) {
+ capacity->block_nbr = msc->bot.pbuf[3] | \
+ ((uint32_t)msc->bot.pbuf[2] << 8U) | \
+ ((uint32_t)msc->bot.pbuf[1] << 16U) | \
+ ((uint32_t)msc->bot.pbuf[0] << 24U);
+
+ capacity->block_size = (uint16_t)(msc->bot.pbuf[7] | ((uint32_t)msc->bot.pbuf[6] << 8U));
+ }
+ break;
+
+ default:
+ break;
+ }
+
+ return status;
+}
+
+/*!
+ \brief send the mode sense6 command to the device
+ \param[in] puhost: pointer to usb host handler
+ \param[in] lun: logic unit number
+ \param[out] none
+ \retval operation status
+*/
+usbh_status usbh_msc_mode_sense6(usbh_host *puhost, uint8_t lun)
+{
+ usbh_status status = USBH_FAIL;
+ usbh_msc_handler *msc = (usbh_msc_handler *)puhost->active_class->class_data;
+
+ switch(msc->bot.cmd_state) {
+ case BOT_CMD_SEND:
+ /* prepare the CBW and relevant field */
+ msc->bot.cbw.field.dCBWDataTransferLength = XFER_LEN_MODE_SENSE6;
+ msc->bot.cbw.field.bmCBWFlags = USB_TRX_IN;
+ msc->bot.cbw.field.bCBWCBLength = CBW_LENGTH;
+
+ memset(msc->bot.cbw.field.CBWCB, 0U, CBW_CB_LENGTH);
+
+ msc->bot.cbw.field.CBWCB[0] = SCSI_MODE_SENSE6;
+ msc->bot.cbw.field.CBWCB[2] = MODE_SENSE_PAGE_CONTROL_FIELD | MODE_SENSE_PAGE_CODE;
+ msc->bot.cbw.field.CBWCB[4] = XFER_LEN_MODE_SENSE6;
+ msc->bot.state = BOT_SEND_CBW;
+ msc->bot.cmd_state = BOT_CMD_WAIT;
+ msc->bot.pbuf = (uint8_t *)(void *)msc->bot.data;
+
+ status = USBH_BUSY;
+ break;
+
+ case BOT_CMD_WAIT:
+ status = usbh_msc_bot_process(puhost, lun);
+
+ if(USBH_OK == status) {
+ if(msc->bot.data[2] & MASK_MODE_SENSE_WRITE_PROTECT) {
+
+ } else {
+
+ }
+ }
+ break;
+
+ default:
+ break;
+ }
+
+ return status;
+}
+
+/*!
+ \brief send the Request Sense command to the device
+ \param[in] puhost: pointer to usb host handler
+ \param[in] lun: logic unit number
+ \param[in] sense_data: pointer to sense data
+ \param[out] none
+ \retval operation status
+*/
+usbh_status usbh_msc_request_sense(usbh_host *puhost, uint8_t lun, msc_scsi_sense *sense_data)
+{
+ usbh_status status = USBH_FAIL;
+ usbh_msc_handler *msc = (usbh_msc_handler *)puhost->active_class->class_data;
+
+ switch(msc->bot.cmd_state) {
+ case BOT_CMD_SEND:
+ /* prepare the cbw and relevant field */
+ msc->bot.cbw.field.dCBWDataTransferLength = ALLOCATION_LENGTH_REQUEST_SENSE;
+ msc->bot.cbw.field.bmCBWFlags = USB_TRX_IN;
+ msc->bot.cbw.field.bCBWCBLength = CBW_LENGTH;
+
+ memset(msc->bot.cbw.field.CBWCB, 0U, CBW_CB_LENGTH);
+
+ msc->bot.cbw.field.CBWCB[0] = SCSI_REQUEST_SENSE;
+ msc->bot.cbw.field.CBWCB[1] = (lun << 5U);
+ msc->bot.cbw.field.CBWCB[4] = ALLOCATION_LENGTH_REQUEST_SENSE;
+
+ msc->bot.state = BOT_SEND_CBW;
+ msc->bot.cmd_state = BOT_CMD_WAIT;
+ msc->bot.pbuf = (uint8_t *)(void *)msc->bot.data;
+
+ status = USBH_BUSY;
+ break;
+
+ case BOT_CMD_WAIT:
+ status = usbh_msc_bot_process(puhost, lun);
+
+ if(status == USBH_OK) {
+ /* get sense data */
+ sense_data->SenseKey = msc->bot.pbuf[2] & 0x0FU;
+ sense_data->ASC = msc->bot.pbuf[12];
+ sense_data->ASCQ = msc->bot.pbuf[13];
+ }
+ break;
+
+ default:
+ break;
+ }
+
+ return status;
+}
+
+/*!
+ \brief send the write10 command to the device
+ \param[in] puhost: pointer to usb host handler
+ \param[in] lun: logic unit number
+ \param[in] data_buf: data buffer contains the data to write
+ \param[in] addr: address to which the data will be written
+ \param[in] sector_num: number of sector to be written
+ \param[out] none
+ \retval operation status
+*/
+usbh_status usbh_msc_write10(usbh_host *puhost, uint8_t lun, uint8_t *data_buf, uint32_t addr, uint32_t sector_num)
+{
+ usbh_status status = USBH_FAIL;
+ usbh_msc_handler *msc = (usbh_msc_handler *)puhost->active_class->class_data;
+
+ switch(msc->bot.cmd_state) {
+ case BOT_CMD_SEND:
+ msc->bot.cbw.field.dCBWDataTransferLength = sector_num * msc->unit[lun].capacity.block_size;
+ msc->bot.cbw.field.bmCBWFlags = USB_TRX_OUT;
+ msc->bot.cbw.field.bCBWCBLength = CBW_LENGTH;
+
+ memset(msc->bot.cbw.field.CBWCB, 0U, CBW_CB_LENGTH);
+
+ msc->bot.cbw.field.CBWCB[0] = SCSI_WRITE10;
+
+ /* logical block address */
+ msc->bot.cbw.field.CBWCB[2] = (((uint8_t *)&addr)[3]);
+ msc->bot.cbw.field.CBWCB[3] = (((uint8_t *)&addr)[2]);
+ msc->bot.cbw.field.CBWCB[4] = (((uint8_t *)&addr)[1]);
+ msc->bot.cbw.field.CBWCB[5] = (((uint8_t *)&addr)[0]);
+
+ /* transfer length */
+ msc->bot.cbw.field.CBWCB[7] = (((uint8_t *)§or_num)[1]);
+ msc->bot.cbw.field.CBWCB[8] = (((uint8_t *)§or_num)[0]);
+
+ msc->bot.state = BOT_SEND_CBW;
+ msc->bot.cmd_state = BOT_CMD_WAIT;
+ msc->bot.pbuf = data_buf;
+
+ status = USBH_BUSY;
+ break;
+
+ case BOT_CMD_WAIT:
+ status = usbh_msc_bot_process(puhost, lun);
+ break;
+
+ default:
+ break;
+ }
+
+ return status;
+}
+
+/*!
+ \brief send the read10 command to the device
+ \param[in] puhost: pointer to usb host handler
+ \param[in] lun: logic unit number
+ \param[in] data_buf: data buffer contains the data to write
+ \param[in] addr: address to which the data will be read
+ \param[in] sector_num: number of sector to be read
+ \param[out] none
+ \retval operation status
+*/
+usbh_status usbh_msc_read10(usbh_host *puhost, uint8_t lun, uint8_t *data_buf, uint32_t addr, uint32_t sector_num)
+{
+ usbh_status status = USBH_FAIL;
+ usbh_msc_handler *msc = (usbh_msc_handler *)puhost->active_class->class_data;
+
+ switch(msc->bot.cmd_state) {
+ case BOT_CMD_SEND:
+ /* prepare the CBW and relevant field */
+ msc->bot.cbw.field.dCBWDataTransferLength = sector_num * msc->unit[lun].capacity.block_size;
+ msc->bot.cbw.field.bmCBWFlags = USB_TRX_IN;
+ msc->bot.cbw.field.bCBWCBLength = CBW_LENGTH;
+
+ memset(msc->bot.cbw.field.CBWCB, 0U, CBW_CB_LENGTH);
+
+ msc->bot.cbw.field.CBWCB[0] = SCSI_READ10;
+
+ /* logical block address */
+ msc->bot.cbw.field.CBWCB[2] = (((uint8_t *)&addr)[3]);
+ msc->bot.cbw.field.CBWCB[3] = (((uint8_t *)&addr)[2]);
+ msc->bot.cbw.field.CBWCB[4] = (((uint8_t *)&addr)[1]);
+ msc->bot.cbw.field.CBWCB[5] = (((uint8_t *)&addr)[0]);
+
+ /* transfer length */
+ msc->bot.cbw.field.CBWCB[7] = (((uint8_t *)§or_num)[1]);
+ msc->bot.cbw.field.CBWCB[8] = (((uint8_t *)§or_num)[0]);
+
+ msc->bot.state = BOT_SEND_CBW;
+ msc->bot.cmd_state = BOT_CMD_WAIT;
+ msc->bot.pbuf = data_buf;
+
+ status = USBH_BUSY;
+ break;
+
+ case BOT_CMD_WAIT:
+ status = usbh_msc_bot_process(puhost, lun);
+ break;
+
+ default:
+ break;
+ }
+
+ return status;
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/core/Include/usbh_core.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/core/Include/usbh_core.h
new file mode 100644
index 00000000..7dc5a022
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/core/Include/usbh_core.h
@@ -0,0 +1,267 @@
+/*!
+ \file usbh_core.h
+ \brief USB host core state machine header file
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __USBH_CORE_H
+#define __USBH_CORE_H
+
+#include "usbh_conf.h"
+#include "drv_usb_host.h"
+
+#define MSC_CLASS 0x08U
+#define HID_CLASS 0x03U
+#define MSC_PROTOCOL 0x50U
+#define CBI_PROTOCOL 0x01U
+
+#define USBH_MAX_ERROR_COUNT 3U
+
+#define USBH_DEV_ADDR_DEFAULT 0U
+#define USBH_DEV_ADDR 1U
+
+typedef enum {
+ USBH_OK = 0U,
+ USBH_BUSY,
+ USBH_FAIL,
+ USBH_NOT_SUPPORTED,
+ USBH_UNRECOVERED_ERROR,
+ USBH_SPEED_UNKNOWN_ERROR,
+ USBH_APPLY_DEINIT
+} usbh_status;
+
+/* USB host global operation state */
+typedef enum {
+ HOST_DEFAULT = 0U,
+ HOST_DETECT_DEV_SPEED,
+ HOST_DEV_ATTACHED,
+ HOST_DEV_DETACHED,
+ HOST_ENUM,
+ HOST_SET_WAKEUP_FEATURE,
+ HOST_CHECK_CLASS,
+ HOST_CLASS_ENUM,
+ HOST_CLASS_HANDLER,
+ HOST_USER_INPUT,
+ HOST_SUSPENDED,
+ HOST_WAKEUP,
+ HOST_ERROR
+} usb_host_state;
+
+/* USB host enumeration state */
+typedef enum {
+ ENUM_DEFAULT = 0U,
+ ENUM_GET_DEV_DESC,
+ ENUM_SET_ADDR,
+ ENUM_GET_CFG_DESC,
+ ENUM_GET_CFG_DESC_SET,
+ ENUM_GET_STR_DESC,
+#ifdef USB_MTP
+ ENUM_GET_MTP_STR,
+#endif
+ ENUM_SET_CONFIGURATION,
+ ENUM_DEV_CONFIGURED
+} usbh_enum_state;
+
+/* USB host control transfer state */
+typedef enum {
+ CTL_IDLE = 0U,
+ CTL_SETUP,
+ CTL_SETUP_WAIT,
+ CTL_DATA_IN,
+ CTL_DATA_IN_WAIT,
+ CTL_DATA_OUT,
+ CTL_DATA_OUT_WAIT,
+ CTL_STATUS_IN,
+ CTL_STATUS_IN_WAIT,
+ CTL_STATUS_OUT,
+ CTL_STATUS_OUT_WAIT,
+ CTL_ERROR,
+ CTL_FINISH
+} usbh_ctl_state;
+
+/* user action state */
+typedef enum {
+ USBH_USER_NO_RESP = 0U,
+ USBH_USER_RESP_OK = 1U,
+} usbh_user_status;
+
+typedef enum {
+ USBH_PORT_EVENT = 1U,
+ USBH_URB_EVENT,
+ USBH_CONTROL_EVENT,
+ USBH_CLASS_EVENT,
+ USBH_STATE_CHANGED_EVENT,
+} usbh_os_event;
+
+/* control transfer information */
+typedef struct _usbh_control {
+ uint8_t pipe_in_num;
+ uint8_t pipe_out_num;
+ uint8_t max_len;
+ uint8_t error_count;
+
+ uint8_t *buf;
+ uint16_t ctl_len;
+ uint16_t timer;
+
+ usb_setup setup;
+ usbh_ctl_state ctl_state;
+} usbh_control;
+
+/* USB interface descriptor set */
+typedef struct _usb_desc_itf_set {
+ usb_desc_itf itf_desc;
+ usb_desc_ep ep_desc[USBH_MAX_EP_NUM];
+} usb_desc_itf_set;
+
+/* USB configure descriptor set */
+typedef struct _usb_desc_cfg_set {
+ usb_desc_config cfg_desc;
+ usb_desc_itf_set itf_desc_set[USBH_MAX_INTERFACES_NUM][USBH_MAX_ALT_SETTING];
+} usb_desc_cfg_set;
+
+/* USB device property */
+typedef struct {
+ uint8_t data[USBH_DATA_BUF_MAX_LEN]; /* if DMA is used, the data array must be located in the first position */
+ uint8_t cur_itf;
+ uint8_t addr;
+
+ uint32_t speed;
+
+ usb_desc_dev dev_desc;
+ usb_desc_cfg_set cfg_desc_set;
+
+#if (USBH_KEEP_CFG_DESCRIPTOR == 1U)
+ uint8_t cfgdesc_rawdata[USBH_CFGSET_MAX_LEN];
+#endif /* (USBH_KEEP_CFG_DESCRIPTOR == 1U) */
+} usb_dev_prop;
+
+struct _usbh_host;
+
+/* device class callbacks */
+typedef struct {
+ uint8_t class_code; /*!< USB class type */
+
+ usbh_status(*class_init)(struct _usbh_host *phost);
+ void (*class_deinit)(struct _usbh_host *phost);
+ usbh_status(*class_requests)(struct _usbh_host *phost);
+ usbh_status(*class_machine)(struct _usbh_host *phost);
+ usbh_status(*class_sof)(struct _usbh_host *puhost);
+
+ void *class_data;
+} usbh_class;
+
+/* user callbacks */
+typedef struct {
+ void (*dev_init)(void);
+ void (*dev_deinit)(void);
+ void (*dev_attach)(void);
+ void (*dev_reset)(void);
+ void (*dev_detach)(void);
+ void (*dev_over_currented)(void);
+ void (*dev_speed_detected)(uint32_t dev_speed);
+ void (*dev_devdesc_assigned)(void *dev_desc);
+ void (*dev_address_set)(void);
+
+ void (*dev_cfgdesc_assigned)(usb_desc_config *cfg_desc,
+ usb_desc_itf *itf_desc,
+ usb_desc_ep *ep_desc);
+
+ void (*dev_mfc_str)(void *mfc_str);
+ void (*dev_prod_str)(void *prod_str);
+ void (*dev_seral_str)(void *serial_str);
+ void (*dev_enumerated)(void);
+ usbh_user_status(*dev_user_input)(void);
+ int (*dev_user_app)(void);
+ void (*dev_not_supported)(void);
+ void (*dev_error)(void);
+} usbh_user_cb;
+
+/* host information */
+typedef struct _usbh_host {
+ usb_host_state cur_state; /*!< host state machine value */
+ usb_host_state backup_state; /*!< backup of previous state machine value */
+ usbh_enum_state enum_state; /*!< enumeration state machine */
+ usbh_control control; /*!< USB host control state machine */
+ usb_dev_prop dev_prop; /*!< USB device property */
+
+ usbh_class *uclass[USBH_MAX_SUPPORTED_CLASS]; /*!< USB host supported class */
+ usbh_class *active_class; /*!< USB active class */
+ usbh_user_cb *usr_cb; /*!< USB user callback */
+
+ uint8_t class_num; /*!< USB class number */
+
+ void *data; /*!< used for... */
+
+#if USB_LOW_POWER
+ uint8_t suspend_flag; /*!< host suspend flag */
+ uint8_t dev_supp_remote_wkup; /*!< record device remote wakeup function */
+ uint8_t wakeup_mode; /*!< record wakeup mode */
+#endif /* USB_LOW_POWER*/
+} usbh_host;
+
+/*!
+ \brief get USB URB state
+ \param[in] pudev: pointer to USB core instance
+ \param[in] pp_num: pipe number
+ \param[out] none
+ \retval none
+*/
+static inline usb_urb_state usbh_urbstate_get(usb_core_driver *pudev, uint8_t pp_num)
+{
+ return pudev->host.pipe[pp_num].urb_state;
+}
+
+/*!
+ \brief get USB transfer data count
+ \param[in] pudev: pointer to USB core instance
+ \param[in] pp_num: pipe number
+ \param[out] none
+ \retval none
+*/
+static inline uint32_t usbh_xfercount_get(usb_core_driver *pudev, uint8_t pp_num)
+{
+ return pudev->host.backup_xfercount[pp_num];
+}
+
+/* function declarations */
+/* USB host stack initializations */
+void usbh_init(usbh_host *puhost, usbh_user_cb *user_cb);
+/* USB host register device class */
+usbh_status usbh_class_register(usbh_host *puhost, usbh_class *puclass);
+/* de-initialize USB host */
+usbh_status usbh_deinit(usbh_host *puhost);
+/* USB host core main state machine process */
+void usbh_core_task(usbh_host *puhost);
+/* handle the error on USB host side */
+void usbh_error_handler(usbh_host *puhost, usbh_status err_type);
+
+#endif /* __USBH_CORE_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/core/Include/usbh_enum.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/core/Include/usbh_enum.h
new file mode 100644
index 00000000..95a850c4
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/core/Include/usbh_enum.h
@@ -0,0 +1,71 @@
+/*!
+ \file usbh_enum.h
+ \brief USB host mode USB enumeration header file
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __USBH_ENUM_H
+#define __USBH_ENUM_H
+
+#include "usb_conf.h"
+#include "usbh_core.h"
+
+/* function declarations */
+/* configure USB control status parameters */
+void usbh_ctlstate_config(usbh_host *puhost, uint8_t *buf, uint16_t len);
+/* get device descriptor from the USB device */
+usbh_status usbh_devdesc_get(usbh_host *puhost, uint8_t len);
+/* get configuration descriptor from the USB device */
+usbh_status usbh_cfgdesc_get(usbh_host *puhost, uint16_t len);
+/* get string descriptor from the USB device */
+usbh_status usbh_strdesc_get(usbh_host *puhost, uint8_t str_index, uint8_t *buf, uint16_t len);
+/* set the address to the connected device */
+usbh_status usbh_setaddress(usbh_host *puhost, uint8_t dev_addr);
+/* set the configuration value to the connected device */
+usbh_status usbh_setcfg(usbh_host *puhost, uint16_t config);
+/* set the interface value to the connected device */
+usbh_status usbh_setinterface(usbh_host *puhost, uint8_t itf_num, uint8_t alter_setting);
+/* set or enable a specific device feature */
+usbh_status usbh_setdevfeature(usbh_host *puhost, uint8_t feature_selector, uint16_t windex);
+/* clear or disable a specific device feature */
+usbh_status usbh_clrdevfeature(usbh_host *puhost, uint8_t feature_selector, uint16_t windex);
+/* clear or disable a specific feature */
+usbh_status usbh_clrfeature(usbh_host *puhost, uint8_t ep_addr, uint8_t pp_num);
+/* get the next descriptor header */
+usb_desc_header *usbh_nextdesc_get(uint8_t *pbuf, uint16_t *ptr);
+/* select an interface */
+usbh_status usbh_interface_select(usb_dev_prop *udev, uint8_t interface);
+/* find the interface index for a specific class */
+uint8_t usbh_interface_find(usb_dev_prop *udev, uint8_t main_class, uint8_t sub_class, uint8_t protocol);
+/* find the interface index for a specific class interface and alternate setting number */
+uint8_t usbh_interfaceindex_find(usb_dev_prop *udev, uint8_t interface_number, uint8_t alt_settings);
+
+#endif /* __USBH_ENUM_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/core/Include/usbh_pipe.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/core/Include/usbh_pipe.h
new file mode 100644
index 00000000..0803db24
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/core/Include/usbh_pipe.h
@@ -0,0 +1,100 @@
+/*!
+ \file usbh_pipe.h
+ \brief USB host mode pipe header file
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __USBH_PIPE_H
+#define __USBH_PIPE_H
+
+#include "usbh_core.h"
+
+#define HC_MAX 8U
+
+#define HC_OK 0x0000U
+#define HC_USED 0x8000U
+#define HC_ERROR 0xFFFFU
+#define HC_USED_MASK 0x7FFFU
+
+/*!
+ \brief set toggle for a pipe
+ \param[in] pudev: pointer to USB core instance
+ \param[in] pp_num: pipe number
+ \param[in] toggle: toggle (0/1)
+ \param[out] none
+ \retval operation status
+*/
+__STATIC_INLINE void usbh_pipe_toggle_set(usb_core_driver *pudev, uint8_t pp_num, uint8_t toggle)
+{
+ if(pudev->host.pipe[pp_num].ep.dir) {
+ pudev->host.pipe[pp_num].data_toggle_in = toggle;
+ } else {
+ pudev->host.pipe[pp_num].data_toggle_out = toggle;
+ }
+}
+
+/*!
+ \brief get toggle flag of pipe
+ \param[in] pudev: pointer to USB core instance
+ \param[in] pp_num: pipe number
+ \param[out] none
+ \retval operation status
+*/
+__STATIC_INLINE uint8_t usbh_pipe_toggle_get(usb_core_driver *pudev, uint8_t pp_num)
+{
+ if(pudev->host.pipe[pp_num].ep.dir) {
+ return pudev->host.pipe[pp_num].data_toggle_in;
+ } else {
+ return pudev->host.pipe[pp_num].data_toggle_out;
+ }
+}
+
+/* function declarations */
+/* create a pipe */
+uint8_t usbh_pipe_create(usb_core_driver *pudev,
+ usb_dev_prop *udev,
+ uint8_t pp_num,
+ uint8_t ep_type,
+ uint16_t ep_mpl);
+/* modify a pipe */
+uint8_t usbh_pipe_update(usb_core_driver *pudev,
+ uint8_t pp_num,
+ uint8_t dev_addr,
+ uint32_t dev_speed,
+ uint16_t ep_mpl);
+/* allocate a new pipe */
+uint8_t usbh_pipe_allocate(usb_core_driver *pudev, uint8_t ep_addr);
+/* free a pipe */
+uint8_t usbh_pipe_free(usb_core_driver *pudev, uint8_t pp_num);
+/* delete all USB host pipe */
+uint8_t usbh_pipe_delete(usb_core_driver *pudev);
+
+#endif /* __USBH_PIPE_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/core/Include/usbh_transc.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/core/Include/usbh_transc.h
new file mode 100644
index 00000000..6fe09dd3
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/core/Include/usbh_transc.h
@@ -0,0 +1,51 @@
+/*!
+ \file usbh_transc.h
+ \brief USB host mode transactions header file
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __USBH_TRANSC_H
+#define __USBH_TRANSC_H
+
+#include "usb_conf.h"
+#include "usbh_core.h"
+
+/* function declarations */
+/* send the setup packet to the USB device */
+usbh_status usbh_ctlsetup_send(usb_core_driver *pudev, uint8_t *buf, uint8_t pp_num);
+/* send a data packet to the USB device */
+usbh_status usbh_data_send(usb_core_driver *pudev, uint8_t *buf, uint8_t pp_num, uint16_t len);
+/* receive a data packet from the USB device */
+usbh_status usbh_data_recev(usb_core_driver *pudev, uint8_t *buf, uint8_t pp_num, uint16_t len);
+/* USB control transfer handler */
+usbh_status usbh_ctl_handler(usbh_host *puhost);
+
+#endif /* __USBH_TRANSC_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/core/Source/usbh_core.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/core/Source/usbh_core.c
new file mode 100644
index 00000000..c01464d6
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/core/Source/usbh_core.c
@@ -0,0 +1,684 @@
+/*!
+ \file usbh_core.c
+ \brief USB host core state machine driver
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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.
+*/
+
+#include "drv_usb_hw.h"
+#include "usbh_pipe.h"
+#include "usbh_enum.h"
+#include "usbh_core.h"
+#include "drv_usbh_int.h"
+#include
+
+usb_core_driver usbh_core;
+
+/* local function prototypes ('static') */
+static uint8_t usbh_sof(usbh_host *puhost);
+static uint8_t usbh_connect(usbh_host *puhost);
+static uint8_t usbh_disconnect(usbh_host *puhost);
+static uint8_t usbh_port_enabled(usbh_host *puhost);
+static uint8_t usbh_port_disabled(usbh_host *puhost);
+static usbh_status usbh_enum_task(usbh_host *puhost);
+
+#if USB_LOW_POWER
+static void usb_hwp_suspend(usb_core_driver *udev);
+static void usb_hwp_resume(usb_core_driver *udev);
+#endif /* USB_LOW_POWER */
+
+usbh_int_cb usbh_int_op = {
+ usbh_connect,
+ usbh_disconnect,
+ usbh_port_enabled,
+ usbh_port_disabled,
+ usbh_sof
+};
+
+usbh_int_cb *usbh_int_fop = &usbh_int_op;
+
+/*!
+ \brief USB host stack initializations
+ \param[in] puhost: pointer to USB host
+ \param[in] user_cb: pointer to user callback
+ \param[out] none
+ \retval none
+*/
+void usbh_init(usbh_host *puhost, usbh_user_cb *user_cb)
+{
+ /* host de-initializations */
+ usbh_deinit(puhost);
+
+ puhost->usr_cb = user_cb;
+
+ usbh_core.host.connect_status = 0U;
+
+ for(uint8_t i = 0U; i < USBFS_MAX_TX_FIFOS; i++) {
+ usbh_core.host.pipe[i].err_count = 0U;
+ usbh_core.host.pipe[i].pp_status = PIPE_IDLE;
+ usbh_core.host.backup_xfercount[i] = 0U;
+ }
+
+ usbh_core.host.pipe[0].ep.mps = 8U;
+
+#ifdef USE_USB_FS
+ usb_basic_init(&usbh_core.bp, &usbh_core.regs, USB_CORE_ENUM_FS);
+#endif /* USE_USB_FS */
+
+#ifndef DUAL_ROLE_MODE_ENABLED
+ usb_globalint_disable(&usbh_core.regs);
+
+ usb_core_init(usbh_core.bp, &usbh_core.regs);
+
+#ifndef USE_OTG_MODE
+ usb_curmode_set(&usbh_core.regs, HOST_MODE);
+#endif /* USE_OTG_MODE */
+
+ usb_host_init(&usbh_core);
+
+ usb_globalint_enable(&usbh_core.regs);
+#endif /* DUAL_ROLE_MODE_ENABLED */
+
+ /* link driver to the stack */
+ usbh_core.host.data = (void *)puhost;
+ puhost->data = (void *)&usbh_core;
+
+ /* upon init call usr call back */
+ puhost->usr_cb->dev_init();
+}
+
+/*!
+ \brief USB host register device class
+ \param[in] puhost: pointer to usb host instance
+ \param[in] puclass: pointer to USB device class
+ \param[out] none
+ \retval operation status
+*/
+usbh_status usbh_class_register(usbh_host *puhost, usbh_class *puclass)
+{
+ usbh_status status = USBH_OK;
+
+ if(NULL != puclass) {
+ if(puhost->class_num < USBH_MAX_SUPPORTED_CLASS) {
+ puhost->uclass[puhost->class_num++] = puclass;
+ } else {
+ status = USBH_FAIL;
+ }
+ } else {
+ status = USBH_FAIL;
+ }
+
+ return status;
+}
+
+/*!
+ \brief de-initialize USB host
+ \param[in] puhost: pointer to USB host
+ \param[out] none
+ \retval operation status
+*/
+usbh_status usbh_deinit(usbh_host *puhost)
+{
+ /* software init */
+ puhost->cur_state = HOST_DEFAULT;
+ puhost->backup_state = HOST_DEFAULT;
+ puhost->enum_state = ENUM_DEFAULT;
+
+ puhost->control.ctl_state = CTL_IDLE;
+ puhost->control.max_len = USB_FS_EP0_MAX_LEN;
+
+ puhost->dev_prop.addr = USBH_DEV_ADDR_DEFAULT;
+ puhost->dev_prop.speed = PORT_SPEED_FULL;
+ puhost->dev_prop.cur_itf = 0xFFU;
+
+ usbh_pipe_free(&usbh_core, puhost->control.pipe_in_num);
+ usbh_pipe_free(&usbh_core, puhost->control.pipe_out_num);
+
+ return USBH_OK;
+}
+
+/*!
+ \brief USB host core main state machine process
+ \param[in] puhost: pointer to USB host
+ \param[out] none
+ \retval none
+*/
+void usbh_core_task(usbh_host *puhost)
+{
+ volatile usbh_status status = USBH_FAIL;
+
+ /* check for host port events */
+ if(((0U == usbh_core.host.connect_status) || (0U == usbh_core.host.port_enabled)) && (HOST_DEFAULT != puhost->cur_state)) {
+ if(puhost->cur_state != HOST_DEV_DETACHED) {
+ puhost->cur_state = HOST_DEV_DETACHED;
+ }
+ }
+
+ switch(puhost->cur_state) {
+ case HOST_DEFAULT:
+ if(usbh_core.host.connect_status) {
+ puhost->cur_state = HOST_DETECT_DEV_SPEED;
+
+ usb_mdelay(100U);
+
+ usb_port_reset(&usbh_core);
+
+ puhost->usr_cb->dev_reset();
+ }
+ break;
+
+ case HOST_DETECT_DEV_SPEED:
+ if(usbh_core.host.port_enabled) {
+ puhost->cur_state = HOST_DEV_ATTACHED;
+
+ puhost->dev_prop.speed = usb_curspeed_get(&usbh_core);
+
+ puhost->usr_cb->dev_speed_detected(puhost->dev_prop.speed);
+
+ usb_mdelay(50U);
+ }
+ break;
+
+ case HOST_DEV_ATTACHED:
+ puhost->usr_cb->dev_attach();
+ puhost->control.pipe_out_num = usbh_pipe_allocate(&usbh_core, 0x00U);
+ puhost->control.pipe_in_num = usbh_pipe_allocate(&usbh_core, 0x80U);
+
+ /* open IN control pipe */
+ usbh_pipe_create(&usbh_core,
+ &puhost->dev_prop,
+ puhost->control.pipe_in_num,
+ USB_EPTYPE_CTRL,
+ (uint16_t)puhost->control.max_len);
+
+ /* open OUT control pipe */
+ usbh_pipe_create(&usbh_core,
+ &puhost->dev_prop,
+ puhost->control.pipe_out_num,
+ USB_EPTYPE_CTRL,
+ (uint16_t)puhost->control.max_len);
+
+ puhost->cur_state = HOST_ENUM;
+ break;
+
+ case HOST_ENUM:
+ /* check for enumeration status */
+ if(USBH_OK == usbh_enum_task(puhost)) {
+ /* the function shall return USBH_OK when full enumeration is complete */
+
+ /* user callback for end of device basic enumeration */
+ puhost->usr_cb->dev_enumerated();
+
+#if USB_LOW_POWER
+ puhost->cur_state = HOST_SUSPENDED;
+
+ /* judge device remote wakup function */
+ if((puhost->dev_prop.cfg_desc_set.cfg_desc.bmAttributes) & (1U << 5)) {
+ puhost->dev_supp_remote_wkup = 1;
+ } else {
+ puhost->dev_supp_remote_wkup = 0;
+ }
+#else
+ puhost->cur_state = HOST_SET_WAKEUP_FEATURE;
+#endif /* USB_LOW_POWER */
+ }
+ break;
+
+ case HOST_SET_WAKEUP_FEATURE:
+ if((puhost->dev_prop.cfg_desc_set.cfg_desc.bmAttributes) & (1U << 5)) {
+ if(usbh_setdevfeature(puhost, FEATURE_SELECTOR_REMOTEWAKEUP, 0U) == USBH_OK) {
+ puhost->cur_state = HOST_CHECK_CLASS;
+ }
+ } else {
+ puhost->cur_state = HOST_CHECK_CLASS;
+ }
+ break;
+
+ case HOST_CHECK_CLASS:
+ if(puhost->class_num == 0U) {
+ puhost->cur_state = HOST_ERROR;
+ } else {
+ puhost->active_class = NULL;
+
+ uint8_t itf_class = puhost->dev_prop.cfg_desc_set.itf_desc_set[0][0].itf_desc.bInterfaceClass;
+
+ for(uint8_t index = 0U; index < puhost->class_num; index++) {
+ if((puhost->uclass[index]->class_code == itf_class) || (0xFFU == itf_class)) {
+ puhost->active_class = puhost->uclass[index];
+ }
+ }
+
+ if(puhost->active_class != NULL) {
+ puhost->cur_state = HOST_USER_INPUT;
+ } else {
+ puhost->cur_state = HOST_ERROR;
+ }
+ }
+ break;
+
+ case HOST_USER_INPUT:
+ /* the function should return user response true to move to class state */
+ if(USBH_USER_RESP_OK == puhost->usr_cb->dev_user_input()) {
+ if((USBH_OK == puhost->active_class->class_init(puhost))) {
+ puhost->cur_state = HOST_CLASS_ENUM;
+ }
+ }
+ break;
+
+#if USB_LOW_POWER
+ case HOST_SUSPENDED:
+ if(puhost->dev_supp_remote_wkup) {
+ /* send set feature command*/
+ if(USBH_OK == usbh_setdevfeature(puhost, FEATURE_SELECTOR_REMOTEWAKEUP, 0U)) {
+
+ usb_hwp_suspend(&usbh_core);
+
+ usb_mdelay(20U);
+ puhost->suspend_flag = 1;
+ puhost->usr_cb->dev_user_input();
+
+ /* MCU enter deep-sleep*/
+ pmu_to_deepsleepmode(PMU_LDO_LOWPOWER, PMU_LOWDRIVER_DISABLE, WFI_CMD);
+ puhost->cur_state = HOST_WAKEUP;
+ }
+ } else {
+ /* host suspend */
+ usb_hwp_suspend(&usbh_core);
+
+ usb_mdelay(20U);
+ puhost->suspend_flag = 1U;
+ puhost->usr_cb->dev_user_input();
+
+ /* MCU enter deep-sleep */
+ pmu_to_deepsleepmode(PMU_LDO_LOWPOWER, PMU_LOWDRIVER_DISABLE, WFI_CMD);
+ puhost->cur_state = HOST_WAKEUP;
+ }
+ break;
+
+ case HOST_WAKEUP:
+ /* judge suspend status */
+ if(0 == puhost->suspend_flag) {
+ usb_hwp_resume(&usbh_core);
+ usb_mdelay(500U);
+
+ if(puhost->dev_supp_remote_wkup) {
+ if(USBH_OK == usbh_clrdevfeature(puhost, FEATURE_SELECTOR_DEV, 0U)) {
+ /* user callback for initialization */
+ puhost->usr_cb->dev_init();
+ puhost->cur_state = HOST_CHECK_CLASS;
+ }
+ } else {
+ puhost->cur_state = HOST_CHECK_CLASS;
+ }
+ }
+ break;
+#endif /* USB_LOW_POWER */
+
+ case HOST_CLASS_ENUM:
+ /* process class standard contol requests state machine */
+ status = puhost->active_class->class_requests(puhost);
+
+ if(USBH_OK == status) {
+ puhost->cur_state = HOST_CLASS_HANDLER;
+ } else {
+ usbh_error_handler(puhost, status);
+ }
+ break;
+
+ case HOST_CLASS_HANDLER:
+ /* process class state machine */
+ status = puhost->active_class->class_machine(puhost);
+
+ usbh_error_handler(puhost, status);
+ break;
+
+ case HOST_ERROR:
+ /* re-initilaize host for new enumeration */
+ usbh_deinit(puhost);
+ puhost->usr_cb->dev_deinit();
+ puhost->active_class->class_deinit(puhost);
+ break;
+
+ case HOST_DEV_DETACHED:
+ /* manage user disconnect operations*/
+ puhost->usr_cb->dev_detach();
+
+ /* re-initilaize host for new enumeration */
+ usbh_deinit(puhost);
+ puhost->usr_cb->dev_deinit();
+ puhost->active_class->class_deinit(puhost);
+ usbh_pipe_delete(&usbh_core);
+ puhost->cur_state = HOST_DEFAULT;
+ break;
+
+ default:
+ break;
+ }
+}
+
+/*!
+ \brief handle the error on USB host side
+ \param[in] puhost: pointer to USB host
+ \param[in] err_type: type of error or busy/OK state
+ \param[out] none
+ \retval none
+*/
+void usbh_error_handler(usbh_host *puhost, usbh_status err_type)
+{
+ /* error unrecovered or not supported device speed */
+ if((USBH_SPEED_UNKNOWN_ERROR == err_type) || (USBH_UNRECOVERED_ERROR == err_type)) {
+ puhost->usr_cb->dev_error();
+
+ puhost->cur_state = HOST_ERROR;
+ } else if(USBH_APPLY_DEINIT == err_type) {
+ puhost->cur_state = HOST_ERROR;
+
+ /* user callback for initalization */
+ puhost->usr_cb->dev_init();
+ } else {
+ /* no operation */
+ }
+}
+
+/*!
+ \brief USB SOF callback function from the interrupt
+ \param[in] puhost: pointer to usb host
+ \param[out] none
+ \retval operation status
+*/
+static uint8_t usbh_sof(usbh_host *puhost)
+{
+ /* this callback could be used to implement a scheduler process */
+ puhost->control.timer = (uint16_t)usb_curframe_get(&usbh_core);
+
+ if(puhost->active_class != NULL) {
+ if(puhost->active_class->class_sof != NULL) {
+ puhost->active_class->class_sof(puhost);
+ }
+ }
+
+ return 0U;
+}
+
+/*!
+ \brief USB connect callback function from the interrupt
+ \param[in] puhost: pointer to usb host
+ \param[out] none
+ \retval operation status
+*/
+static uint8_t usbh_connect(usbh_host *puhost)
+{
+ usbh_core.host.connect_status = 1U;
+
+ return 0U;
+}
+
+/*!
+ \brief USB disconnect callback function from the interrupt
+ \param[in] puhost: pointer to usb host
+ \param[out] none
+ \retval operation status
+*/
+static uint8_t usbh_disconnect(usbh_host *puhost)
+{
+ usbh_core.host.connect_status = 0U;
+
+ return 0U;
+}
+
+/*!
+ \brief USB port enable callback function from the interrupt
+ \param[in] puhost: pointer to usb host
+ \param[out] none
+ \retval operation status
+*/
+static uint8_t usbh_port_enabled(usbh_host *puhost)
+{
+ usbh_core.host.port_enabled = 1U;
+
+ return 0U;
+}
+
+/*!
+ \brief USB port disabled callback function from the interrupt
+ \param[in] puhost: pointer to usb host
+ \param[out] none
+ \retval operation status
+*/
+static uint8_t usbh_port_disabled(usbh_host *puhost)
+{
+ usbh_core.host.port_enabled = 0U;
+
+ return 0U;
+}
+
+/*!
+ \brief handle the USB enumeration task
+ \param[in] puhost: pointer to host
+ \param[out] none
+ \retval none
+*/
+static usbh_status usbh_enum_task(usbh_host *puhost)
+{
+ uint8_t str_buf[512];
+
+ usbh_status status = USBH_BUSY;
+
+ static uint8_t index_mfc_str = 0U, index_prod_str = 0U, index_serial_str = 0U;
+
+ switch(puhost->enum_state) {
+ case ENUM_DEFAULT:
+ /* get device descriptor for only 1st 8 bytes : to get ep0 maxpacketsize */
+ if(USBH_OK == usbh_devdesc_get(puhost, 8U)) {
+ puhost->control.max_len = puhost->dev_prop.dev_desc.bMaxPacketSize0;
+
+ /* modify control channels configuration for maximum packet size */
+ usbh_pipe_update(&usbh_core,
+ puhost->control.pipe_out_num,
+ 0U, 0U,
+ (uint16_t)puhost->control.max_len);
+
+ usbh_pipe_update(&usbh_core,
+ puhost->control.pipe_in_num,
+ 0U, 0U,
+ (uint16_t)puhost->control.max_len);
+
+ puhost->enum_state = ENUM_GET_DEV_DESC;
+ }
+ break;
+
+ case ENUM_GET_DEV_DESC:
+ /* get full device descriptor */
+ if(USBH_OK == usbh_devdesc_get(puhost, USB_DEV_DESC_LEN)) {
+ puhost->usr_cb->dev_devdesc_assigned(&puhost->dev_prop.dev_desc);
+
+ index_mfc_str = puhost->dev_prop.dev_desc.iManufacturer;
+ index_prod_str = puhost->dev_prop.dev_desc.iProduct;
+ index_serial_str = puhost->dev_prop.dev_desc.iSerialNumber;
+
+ puhost->enum_state = ENUM_SET_ADDR;
+ }
+ break;
+
+ case ENUM_SET_ADDR:
+ /* set address */
+ if(USBH_OK == usbh_setaddress(puhost, USBH_DEV_ADDR)) {
+ usb_mdelay(2U);
+
+ puhost->dev_prop.addr = USBH_DEV_ADDR;
+
+ /* user callback for device address assigned */
+ puhost->usr_cb->dev_address_set();
+
+ /* modify control channels to update device address */
+ usbh_pipe_update(&usbh_core,
+ puhost->control.pipe_in_num,
+ puhost->dev_prop.addr,
+ 0U, 0U);
+
+ usbh_pipe_update(&usbh_core,
+ puhost->control.pipe_out_num,
+ puhost->dev_prop.addr,
+ 0U, 0U);
+
+ puhost->enum_state = ENUM_GET_CFG_DESC;
+ }
+ break;
+
+ case ENUM_GET_CFG_DESC:
+ /* get standard configuration descriptor */
+ if(USBH_OK == usbh_cfgdesc_get(puhost, USB_CFG_DESC_LEN)) {
+ puhost->enum_state = ENUM_GET_CFG_DESC_SET;
+ }
+ break;
+
+ case ENUM_GET_CFG_DESC_SET:
+ /* get full config descriptor (config, interface, endpoints) */
+ if(USBH_OK == usbh_cfgdesc_get(puhost, puhost->dev_prop.cfg_desc_set.cfg_desc.wTotalLength)) {
+ /* user callback for configuration descriptors available */
+ puhost->usr_cb->dev_cfgdesc_assigned(&puhost->dev_prop.cfg_desc_set.cfg_desc,
+ &puhost->dev_prop.cfg_desc_set.itf_desc_set[0][0].itf_desc,
+ &puhost->dev_prop.cfg_desc_set.itf_desc_set[0][0].ep_desc[0]);
+
+ puhost->enum_state = ENUM_GET_STR_DESC;
+ }
+ break;
+
+ case ENUM_GET_STR_DESC:
+ if(index_mfc_str) {
+ if(USBH_OK == usbh_strdesc_get(puhost,
+ puhost->dev_prop.dev_desc.iManufacturer,
+ str_buf,
+ 0xFFU)) {
+ /* user callback for manufacturing string */
+ puhost->usr_cb->dev_mfc_str(str_buf);
+
+ index_mfc_str = 0U;
+ }
+ } else {
+ if(index_prod_str) {
+ /* check that product string is available */
+ if(USBH_OK == usbh_strdesc_get(puhost,
+ puhost->dev_prop.dev_desc.iProduct,
+ str_buf,
+ 0xFFU)) {
+ puhost->usr_cb->dev_prod_str(str_buf);
+
+ index_prod_str = 0U;
+ }
+ } else {
+ if(index_serial_str) {
+ if(USBH_OK == usbh_strdesc_get(puhost,
+ puhost->dev_prop.dev_desc.iSerialNumber,
+ str_buf,
+ 0xFFU)) {
+ puhost->usr_cb->dev_seral_str(str_buf);
+ puhost->enum_state = ENUM_SET_CONFIGURATION;
+ index_serial_str = 0U;
+ }
+ } else {
+ puhost->enum_state = ENUM_SET_CONFIGURATION;
+ }
+ }
+ }
+ break;
+
+ case ENUM_SET_CONFIGURATION:
+ if(USBH_OK == usbh_setcfg(puhost, (uint16_t)puhost->dev_prop.cfg_desc_set.cfg_desc.bConfigurationValue)) {
+ puhost->enum_state = ENUM_DEV_CONFIGURED;
+ }
+ break;
+
+ case ENUM_DEV_CONFIGURED:
+ status = USBH_OK;
+ break;
+
+ default:
+ break;
+ }
+
+ return status;
+}
+
+
+#if USB_LOW_POWER
+
+/*!
+ \brief handles the USB resume from suspend mode
+ \param[in] pudev: pointer to selected USB device
+ \param[out] none
+ \retval none
+*/
+static void usb_hwp_resume(usb_core_driver *pudev)
+{
+ __IO uint32_t hprt = 0U;
+
+ /* switch-on the clocks */
+ *pudev->regs.PWRCLKCTL &= ~PWRCLKCTL_SUCLK;
+
+ *pudev->regs.PWRCLKCTL &= ~PWRCLKCTL_SHCLK;
+
+ hprt = usb_port_read(pudev);
+
+ hprt &= ~HPCS_PSP;
+ hprt |= HPCS_PREM;
+
+ *pudev->regs.HPCS = hprt;
+
+ usb_mdelay(20U);
+
+ hprt &= ~HPCS_PREM;
+
+ *pudev->regs.HPCS = hprt;
+}
+
+/*!
+ \brief handles the USB enter to suspend mode
+ \param[in] pudev: pointer to selected USB device
+ \param[out] none
+ \retval none
+*/
+static void usb_hwp_suspend(usb_core_driver *pudev)
+{
+ __IO uint32_t hprt = 0U;
+
+ hprt = usb_port_read(pudev);
+
+ hprt |= HPCS_PSP;
+
+ *pudev->regs.HPCS = hprt;
+
+ /* switch-off the clocks */
+ *pudev->regs.PWRCLKCTL |= PWRCLKCTL_SUCLK;
+
+ *pudev->regs.PWRCLKCTL |= PWRCLKCTL_SHCLK;
+}
+
+#endif /* USB_LOW_POWER */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/core/Source/usbh_enum.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/core/Source/usbh_enum.c
new file mode 100644
index 00000000..1d186fb6
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/core/Source/usbh_enum.c
@@ -0,0 +1,693 @@
+/*!
+ \file usbh_enum.c
+ \brief USB host mode enumberation driver
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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.
+*/
+
+#include "usbh_pipe.h"
+#include "usbh_transc.h"
+#include "usbh_enum.h"
+
+/* local function prototypes ('static') */
+static void usbh_devdesc_parse(usb_desc_dev *dev_desc, uint8_t *buf, uint16_t len);
+static void usbh_cfgdesc_parse(usb_desc_config *cfg_desc, uint8_t *buf);
+static void usbh_cfgset_parse(usb_dev_prop *udev, uint8_t *buf);
+static void usbh_itfdesc_parse(usb_desc_itf *itf_desc, uint8_t *buf);
+static void usbh_epdesc_parse(usb_desc_ep *ep_desc, uint8_t *buf);
+static void usbh_strdesc_parse(uint8_t *psrc, uint8_t *pdest, uint16_t len);
+
+/*!
+ \brief configure USB control status parameters
+ \param[in] puhost: pointer to usb host
+ \param[in] buf: control transfer data buffer pointer
+ \param[in] len: length of the data buffer
+ \param[out] none
+ \retval none
+*/
+void usbh_ctlstate_config(usbh_host *puhost, uint8_t *buf, uint16_t len)
+{
+ /* prepare the transactions */
+ puhost->control.buf = buf;
+ puhost->control.ctl_len = len;
+
+ puhost->control.ctl_state = CTL_SETUP;
+}
+
+/*!
+ \brief get device descriptor from the USB device
+ \param[in] puhost: pointer to usb host
+ \param[in] len: length of the descriptor
+ \param[out] none
+ \retval operation status
+*/
+usbh_status usbh_devdesc_get(usbh_host *puhost, uint8_t len)
+{
+ usbh_status status = USBH_BUSY;
+
+ usbh_control *usb_ctl = &puhost->control;
+
+ if(CTL_IDLE == usb_ctl->ctl_state) {
+ usb_ctl->setup.req = (usb_req) {
+ .bmRequestType = USB_TRX_IN | USB_RECPTYPE_DEV | USB_REQTYPE_STRD,
+ .bRequest = USB_GET_DESCRIPTOR,
+ .wValue = USBH_DESC(USB_DESCTYPE_DEV),
+ .wIndex = 0U,
+ .wLength = len
+ };
+
+ usbh_ctlstate_config(puhost, puhost->dev_prop.data, (uint16_t)len);
+ }
+
+ status = usbh_ctl_handler(puhost);
+
+ if(USBH_OK == status) {
+ /* commands successfully sent and response received */
+ usbh_devdesc_parse(&puhost->dev_prop.dev_desc, puhost->dev_prop.data, (uint16_t)len);
+ }
+
+ return status;
+}
+
+/*!
+ \brief get configuration descriptor from the USB device
+ \param[in] puhost: pointer to usb host
+ \param[in] len: length of the descriptor
+ \param[out] none
+ \retval operation status
+*/
+usbh_status usbh_cfgdesc_get(usbh_host *puhost, uint16_t len)
+{
+ uint8_t *pdata = NULL;
+
+ usbh_status status = USBH_BUSY;
+
+ usbh_control *usb_ctl = &puhost->control;
+
+#if (USBH_KEEP_CFG_DESCRIPTOR == 1U)
+ pdata = puhost->dev_prop.cfgdesc_rawdata;
+#else
+ pdata = puhost->dev_prop.data;
+#endif
+
+ if(CTL_IDLE == usb_ctl->ctl_state) {
+ usb_ctl->setup.req = (usb_req) {
+ .bmRequestType = USB_TRX_IN | USB_RECPTYPE_DEV | USB_REQTYPE_STRD,
+ .bRequest = USB_GET_DESCRIPTOR,
+ .wValue = USBH_DESC(USB_DESCTYPE_CONFIG),
+ .wIndex = 0U,
+ .wLength = len
+ };
+
+ usbh_ctlstate_config(puhost, pdata, len);
+ }
+
+ status = usbh_ctl_handler(puhost);
+
+ if(USBH_OK == status) {
+ if(len <= USB_CFG_DESC_LEN) {
+ usbh_cfgdesc_parse(&puhost->dev_prop.cfg_desc_set.cfg_desc, pdata);
+ } else {
+ usbh_cfgset_parse(&puhost->dev_prop, pdata);
+ }
+ }
+
+ return status;
+}
+
+/*!
+ \brief get string descriptor from the USB device
+ \param[in] puhost: pointer to usb host
+ \param[in] str_index: index for the string descriptor
+ \param[in] buf: buffer pointer to the string descriptor
+ \param[in] len: length of the descriptor
+ \param[out] none
+ \retval operation status
+*/
+usbh_status usbh_strdesc_get(usbh_host *puhost,
+ uint8_t str_index,
+ uint8_t *buf,
+ uint16_t len)
+{
+ usbh_status status = USBH_BUSY;
+
+ usbh_control *usb_ctl = &puhost->control;
+
+ if(CTL_IDLE == usb_ctl->ctl_state) {
+ usb_ctl->setup.req = (usb_req) {
+ .bmRequestType = USB_TRX_IN | USB_RECPTYPE_DEV | USB_REQTYPE_STRD,
+ .bRequest = USB_GET_DESCRIPTOR,
+ .wValue = USBH_DESC(USB_DESCTYPE_STR) | str_index,
+ .wIndex = 0x0409U,
+ .wLength = len
+ };
+
+ usbh_ctlstate_config(puhost, puhost->dev_prop.data, len);
+ }
+
+ status = usbh_ctl_handler(puhost);
+
+ if(USBH_OK == status) {
+ /* commands successfully sent and response received */
+ usbh_strdesc_parse(puhost->dev_prop.data, buf, len);
+ }
+
+ return status;
+}
+
+/*!
+ \brief set the address to the connected device
+ \param[in] puhost: pointer to usb host
+ \param[in] dev_addr: device address to assign
+ \param[out] none
+ \retval operation status
+*/
+usbh_status usbh_setaddress(usbh_host *puhost, uint8_t dev_addr)
+{
+ usbh_status status = USBH_BUSY;
+
+ usbh_control *usb_ctl = &puhost->control;
+
+ if(CTL_IDLE == usb_ctl->ctl_state) {
+ usb_ctl->setup.req = (usb_req) {
+ .bmRequestType = USB_TRX_OUT | USB_RECPTYPE_DEV | USB_REQTYPE_STRD,
+ .bRequest = USB_SET_ADDRESS,
+ .wValue = (uint16_t)dev_addr,
+ .wIndex = 0U,
+ .wLength = 0U
+ };
+
+ usbh_ctlstate_config(puhost, NULL, 0U);
+ }
+
+ status = usbh_ctl_handler(puhost);
+
+ return status;
+}
+
+/*!
+ \brief set the configuration value to the connected device
+ \param[in] puhost: pointer to usb host
+ \param[in] config_index: configuration value
+ \param[out] none
+ \retval operation status
+*/
+usbh_status usbh_setcfg(usbh_host *puhost, uint16_t config_index)
+{
+ usbh_status status = USBH_BUSY;
+
+ usbh_control *usb_ctl = &puhost->control;
+
+ if(CTL_IDLE == usb_ctl->ctl_state) {
+ usb_ctl->setup.req = (usb_req) {
+ .bmRequestType = USB_TRX_OUT | USB_RECPTYPE_DEV | USB_REQTYPE_STRD,
+ .bRequest = USB_SET_CONFIGURATION,
+ .wValue = config_index,
+ .wIndex = 0U,
+ .wLength = 0U
+ };
+
+ usbh_ctlstate_config(puhost, NULL, 0U);
+ }
+
+ status = usbh_ctl_handler(puhost);
+
+ return status;
+}
+
+/*!
+ \brief set the interface value to the connected device
+ \param[in] puhost: pointer to usb host
+ \param[in] itf_num: interface number
+ \param[in] set: alternated setting value
+ \param[out] none
+ \retval operation status
+*/
+usbh_status usbh_setinterface(usbh_host *puhost, uint8_t itf_num, uint8_t set)
+{
+ usbh_status status = USBH_BUSY;
+
+ usbh_control *usb_ctl = &puhost->control;
+
+ if(CTL_IDLE == usb_ctl->ctl_state) {
+ usb_ctl->setup.req = (usb_req) {
+ .bmRequestType = USB_TRX_OUT | USB_RECPTYPE_ITF | USB_REQTYPE_STRD,
+ .bRequest = USB_SET_INTERFACE,
+ .wValue = set,
+ .wIndex = itf_num,
+ .wLength = 0U
+ };
+
+ usbh_ctlstate_config(puhost, NULL, 0U);
+ }
+
+ status = usbh_ctl_handler(puhost);
+
+ return status;
+}
+
+/*!
+ \brief set the interface value to the connected device
+ \param[in] puhost: pointer to usb host
+ \param[in] feature_selector: feature selector
+ \param[in] windex: index value
+ \param[out] none
+ \retval operation status
+*/
+usbh_status usbh_setdevfeature(usbh_host *puhost, uint8_t feature_selector, uint16_t windex)
+{
+ usbh_status status = USBH_BUSY;
+
+ usbh_control *usb_ctl = &puhost->control;
+
+ if(CTL_IDLE == usb_ctl->ctl_state) {
+ usb_ctl->setup.req = (usb_req) {
+ .bmRequestType = USB_TRX_OUT | USB_RECPTYPE_DEV | USB_REQTYPE_STRD,
+ .bRequest = USB_SET_FEATURE,
+ .wValue = feature_selector,
+ .wIndex = windex,
+ .wLength = 0U
+ };
+
+ usbh_ctlstate_config(puhost, NULL, 0U);
+ }
+
+ status = usbh_ctl_handler(puhost);
+
+ return status;
+}
+
+/*!
+ \brief clear the interface value to the connected device
+ \param[in] puhost: pointer to usb host
+ \param[in] feature_selector: feature selector
+ \param[in] windex: index value
+ \param[out] none
+ \retval operation status
+*/
+usbh_status usbh_clrdevfeature(usbh_host *puhost, uint8_t feature_selector, uint16_t windex)
+{
+ usbh_status status = USBH_BUSY;
+
+ usbh_control *usb_ctl = &puhost->control;
+
+ if(CTL_IDLE == usb_ctl->ctl_state) {
+ usb_ctl->setup.req = (usb_req) {
+ .bmRequestType = USB_TRX_OUT | USB_RECPTYPE_DEV | USB_REQTYPE_STRD,
+ .bRequest = USB_CLEAR_FEATURE,
+ .wValue = feature_selector,
+ .wIndex = windex,
+ .wLength = 0U
+ };
+
+ usbh_ctlstate_config(puhost, NULL, 0U);
+ }
+
+ status = usbh_ctl_handler(puhost);
+
+ return status;
+}
+
+/*!
+ \brief clear or disable a specific feature
+ \param[in] puhost: pointer to usb host
+ \param[in] ep_addr: endpoint address
+ \param[in] pp_num: pipe number
+ \param[out] none
+ \retval operation status
+*/
+usbh_status usbh_clrfeature(usbh_host *puhost, uint8_t ep_addr, uint8_t pp_num)
+{
+ usbh_status status = USBH_BUSY;
+ usbh_control *usb_ctl = &puhost->control;
+ usb_core_driver *pudev = (usb_core_driver *)puhost->data;
+
+ if(CTL_IDLE == usb_ctl->ctl_state) {
+ usb_ctl->setup.req = (usb_req) {
+ .bmRequestType = USB_TRX_OUT | USB_RECPTYPE_EP | USB_REQTYPE_STRD,
+ .bRequest = USB_CLEAR_FEATURE,
+ .wValue = FEATURE_SELECTOR_EP,
+ .wIndex = ep_addr,
+ .wLength = 0U
+ };
+
+ if(EP_ID(ep_addr) == pudev->host.pipe[pp_num].ep.num) {
+ usbh_pipe_toggle_set(pudev, pp_num, 0U);
+ } else {
+ return USBH_FAIL;
+ }
+
+ usbh_ctlstate_config(puhost, NULL, 0U);
+ }
+
+ status = usbh_ctl_handler(puhost);
+
+ return status;
+}
+
+/*!
+ \brief get the next descriptor header
+ \param[in] pbuf: pointer to buffer where the configuration descriptor set is available
+ \param[in] ptr: data pointer inside the configuration descriptor set
+ \param[out] none
+ \retval return descriptor header
+*/
+usb_desc_header *usbh_nextdesc_get(uint8_t *pbuf, uint16_t *ptr)
+{
+ usb_desc_header *pnext;
+
+ *ptr += ((usb_desc_header *)pbuf)->bLength;
+
+ pnext = (usb_desc_header *)((uint8_t *)pbuf + ((usb_desc_header *)pbuf)->bLength);
+
+ return (pnext);
+}
+
+/*!
+ \brief get the next descriptor header
+ \param[in] udev: pointer to device property
+ \param[in] interface: interface number
+ \param[out] none
+ \retval operation status
+*/
+usbh_status usbh_interface_select(usb_dev_prop *udev, uint8_t interface)
+{
+ usbh_status status = USBH_OK;
+
+ if(interface < udev->cfg_desc_set.cfg_desc.bNumInterfaces) {
+ udev->cur_itf = interface;
+ } else {
+ status = USBH_FAIL;
+ }
+
+ return status;
+}
+
+/*!
+ \brief find the interface index for a specific class
+ \param[in] udev: pointer to device property
+ \param[in] main_class: class code
+ \param[in] sub_class: subclass code
+ \param[in] protocol: Protocol code
+ \param[out] none
+ \retval interface index in the configuration structure
+ \note interface index 0xFF means interface index not found
+*/
+uint8_t usbh_interface_find(usb_dev_prop *udev, uint8_t main_class, uint8_t sub_class, uint8_t protocol)
+{
+ usb_desc_itf *pif;
+
+ uint8_t if_ix = 0U;
+
+ pif = (usb_desc_itf *)0;
+
+ while(if_ix < udev->cfg_desc_set.cfg_desc.bNumInterfaces) {
+ pif = &udev->cfg_desc_set.itf_desc_set[if_ix][0].itf_desc;
+
+ if(((pif->bInterfaceClass == main_class) || (main_class == 0xFFU)) &&
+ ((pif->bInterfaceSubClass == sub_class) || (sub_class == 0xFFU)) &&
+ ((pif->bInterfaceProtocol == protocol) || (protocol == 0xFFU))) {
+ return if_ix;
+ }
+
+ if_ix++;
+ }
+
+ return 0xFFU;
+}
+
+/*!
+ \brief find the interface index for a specific class interface and alternate setting number
+ \param[in] udev: pointer to device property
+ \param[in] interface_number: interface number
+ \param[in] alt_settings: alternate setting number
+ \param[out] none
+ \retval interface index in the configuration structure
+ \note interface index 0xFF means interface index not found
+*/
+uint8_t usbh_interfaceindex_find(usb_dev_prop *udev, uint8_t interface_number, uint8_t alt_settings)
+{
+ usb_desc_itf *pif;
+
+ uint8_t if_ix = 0U;
+
+ pif = (usb_desc_itf *)0;
+
+ while(if_ix < USBH_MAX_INTERFACES_NUM) {
+ pif = &udev->cfg_desc_set.itf_desc_set[if_ix][alt_settings].itf_desc;
+
+ if((pif->bInterfaceNumber == interface_number) && (pif->bAlternateSetting == alt_settings)) {
+ return if_ix;
+ }
+
+ if_ix++;
+ }
+
+ return 0xFFU;
+}
+
+/*!
+ \brief parse the device descriptor
+ \param[in] dev_desc: pointer to usb device descriptor buffer
+ \param[in] buf: pointer to the source descriptor buffer
+ \param[in] len: length of the descriptor
+ \param[out] none
+ \retval none
+*/
+static void usbh_devdesc_parse(usb_desc_dev *dev_desc, uint8_t *buf, uint16_t len)
+{
+ *dev_desc = (usb_desc_dev) {
+ .header = {
+ .bLength = *(uint8_t *)(buf + 0U),
+ .bDescriptorType = *(uint8_t *)(buf + 1U)
+ },
+
+ .bcdUSB = BYTE_SWAP(buf + 2U),
+ .bDeviceClass = *(uint8_t *)(buf + 4U),
+ .bDeviceSubClass = *(uint8_t *)(buf + 5U),
+ .bDeviceProtocol = *(uint8_t *)(buf + 6U),
+ .bMaxPacketSize0 = *(uint8_t *)(buf + 7U)
+ };
+
+ if(len > 8U) {
+ /* for 1st time after device connection, host may issue only 8 bytes for device descriptor length */
+ dev_desc->idVendor = BYTE_SWAP(buf + 8U);
+ dev_desc->idProduct = BYTE_SWAP(buf + 10U);
+ dev_desc->bcdDevice = BYTE_SWAP(buf + 12U);
+ dev_desc->iManufacturer = *(uint8_t *)(buf + 14U);
+ dev_desc->iProduct = *(uint8_t *)(buf + 15U);
+ dev_desc->iSerialNumber = *(uint8_t *)(buf + 16U);
+ dev_desc->bNumberConfigurations = *(uint8_t *)(buf + 17U);
+ }
+}
+
+/*!
+ \brief parse the configuration descriptor
+ \param[in] cfg_desc: pointer to usb configuration descriptor buffer
+ \param[in] buf: pointer to the source descriptor buffer
+ \param[out] none
+ \retval none
+*/
+static void usbh_cfgdesc_parse(usb_desc_config *cfg_desc, uint8_t *buf)
+{
+ /* parse configuration descriptor */
+ *cfg_desc = (usb_desc_config) {
+ .header = {
+ .bLength = *(uint8_t *)(buf + 0U),
+ .bDescriptorType = *(uint8_t *)(buf + 1U),
+ },
+
+ .wTotalLength = BYTE_SWAP(buf + 2U),
+ .bNumInterfaces = *(uint8_t *)(buf + 4U),
+ .bConfigurationValue = *(uint8_t *)(buf + 5U),
+ .iConfiguration = *(uint8_t *)(buf + 6U),
+ .bmAttributes = *(uint8_t *)(buf + 7U),
+ .bMaxPower = *(uint8_t *)(buf + 8U)
+ };
+}
+
+/*!
+ \brief parse the configuration descriptor set
+ \param[in] udev: pointer to device property
+ \param[in] buf: pointer to the source descriptor buffer
+ \param[out] none
+ \retval none
+*/
+static void usbh_cfgset_parse(usb_dev_prop *udev, uint8_t *buf)
+{
+ usb_desc_ep *ep = NULL;
+ usb_desc_itf_set *itf = NULL;
+ usb_desc_itf itf_value;
+ usb_desc_config *cfg = NULL;
+
+ usb_desc_header *pdesc = (usb_desc_header *)buf;
+
+ uint8_t itf_index = 0U, ep_index = 0U, alt_setting = 0U;
+ uint8_t pre_itf_index = 0U;
+ uint16_t ptr;
+
+ /* parse configuration descriptor */
+ usbh_cfgdesc_parse(&udev->cfg_desc_set.cfg_desc, buf);
+ cfg = &udev->cfg_desc_set.cfg_desc;
+ ptr = USB_CFG_DESC_LEN;
+
+ if(cfg->bNumInterfaces > USBH_MAX_INTERFACES_NUM) {
+ return;
+ }
+
+ while(ptr < cfg->wTotalLength) {
+ pdesc = usbh_nextdesc_get((uint8_t *)pdesc, &ptr);
+
+ if(pdesc->bDescriptorType == USB_DESCTYPE_ITF) {
+ itf_index = *(((uint8_t *)pdesc) + 2U);
+
+ if(pre_itf_index != itf_index) {
+ alt_setting = 0U;
+ }
+
+ itf = &udev->cfg_desc_set.itf_desc_set[itf_index][alt_setting];
+
+ alt_setting++;
+
+ if((*((uint8_t *)pdesc + 3U)) < 3U) {
+ usbh_itfdesc_parse(&itf_value, (uint8_t *)pdesc);
+
+ /* parse endpoint descriptors relative to the current interface */
+ if(itf_value.bNumEndpoints > USBH_MAX_EP_NUM) {
+ return;
+ }
+
+ usbh_itfdesc_parse(&itf->itf_desc, (uint8_t *)&itf_value);
+
+ /* store the previous interface index */
+ pre_itf_index = itf_index;
+
+ if(0U == itf_value.bNumEndpoints) {
+ continue;
+ }
+
+ for(ep_index = 0U; ep_index < itf_value.bNumEndpoints;) {
+ pdesc = usbh_nextdesc_get((void *)pdesc, &ptr);
+
+ if(pdesc->bDescriptorType == USB_DESCTYPE_EP) {
+ ep = &itf->ep_desc[ep_index];
+
+ usbh_epdesc_parse(ep, (uint8_t *)pdesc);
+
+ ep_index++;
+ }
+ }
+ }
+ }
+ }
+}
+
+/*!
+ \brief parse the interface descriptor
+ \param[in] itf_desc: pointer to usb interface descriptor buffer
+ \param[in] buf: pointer to the source descriptor buffer
+ \param[out] none
+ \retval none
+*/
+static void usbh_itfdesc_parse(usb_desc_itf *itf_desc, uint8_t *buf)
+{
+ *itf_desc = (usb_desc_itf) {
+ .header = {
+ .bLength = *(uint8_t *)(buf + 0U),
+ .bDescriptorType = *(uint8_t *)(buf + 1U),
+ },
+
+ .bInterfaceNumber = *(uint8_t *)(buf + 2U),
+ .bAlternateSetting = *(uint8_t *)(buf + 3U),
+ .bNumEndpoints = *(uint8_t *)(buf + 4U),
+ .bInterfaceClass = *(uint8_t *)(buf + 5U),
+ .bInterfaceSubClass = *(uint8_t *)(buf + 6U),
+ .bInterfaceProtocol = *(uint8_t *)(buf + 7U),
+ .iInterface = *(uint8_t *)(buf + 8U)
+ };
+}
+
+/*!
+ \brief parse the endpoint descriptor
+ \param[in] ep_desc: pointer to usb endpoint descriptor buffer
+ \param[in] buf: pointer to the source descriptor buffer
+ \param[out] none
+ \retval none
+*/
+static void usbh_epdesc_parse(usb_desc_ep *ep_desc, uint8_t *buf)
+{
+ *ep_desc = (usb_desc_ep) {
+ .header = {
+ .bLength = *(uint8_t *)(buf + 0U),
+ .bDescriptorType = *(uint8_t *)(buf + 1U)
+ },
+
+ .bEndpointAddress = *(uint8_t *)(buf + 2U),
+ .bmAttributes = *(uint8_t *)(buf + 3U),
+ .wMaxPacketSize = BYTE_SWAP(buf + 4U),
+ .bInterval = *(uint8_t *)(buf + 6U)
+ };
+}
+
+/*!
+ \brief parse the string descriptor
+ \param[in] psrc: source pointer containing the descriptor data
+ \param[in] pdest: destination address pointer
+ \param[in] len: length of the descriptor
+ \param[out] none
+ \retval none
+*/
+static void usbh_strdesc_parse(uint8_t *psrc, uint8_t *pdest, uint16_t len)
+{
+ uint16_t str_len = 0U, index = 0U;
+
+ /* the unicode string descriptor is not NULL-terminated. The string length is
+ * computed by substracting two from the value of the first byte of the descriptor.
+ */
+
+ /* check which is lower size, the size of string or the length of bytes read from the device */
+ if(USB_DESCTYPE_STR == psrc[1]) {
+ /* make sure the descriptor is string type */
+
+ /* psrc[0] contains Size of Descriptor, subtract 2 to get the length of string */
+ str_len = USB_MIN((uint16_t)psrc[0] - 2U, len);
+
+ psrc += 2U; /* adjust the offset ignoring the string len and descriptor type */
+
+ for(index = 0U; index < str_len; index += 2U) {
+ /* copy only the string and ignore the unicode id, hence add the src */
+ *pdest = psrc[index];
+
+ pdest++;
+ }
+
+ *pdest = 0U; /* mark end of string */
+ }
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/core/Source/usbh_pipe.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/core/Source/usbh_pipe.c
new file mode 100644
index 00000000..fab73ea2
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/core/Source/usbh_pipe.c
@@ -0,0 +1,176 @@
+/*!
+ \file usbh_pipe.c
+ \brief USB host mode pipe operation driver
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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.
+*/
+
+#include "usbh_pipe.h"
+
+/* local function prototypes ('static') */
+static uint16_t usbh_freepipe_get(usb_core_driver *pudev);
+
+/*!
+ \brief create a pipe
+ \param[in] pudev: pointer to usb core instance
+ \param[in] udev: USB device
+ \param[in] pp_num: pipe number
+ \param[in] ep_type: endpoint type
+ \param[in] ep_mpl: endpoint max packet length
+ \param[out] none
+ \retval operation status
+*/
+uint8_t usbh_pipe_create(usb_core_driver *pudev,
+ usb_dev_prop *udev,
+ uint8_t pp_num,
+ uint8_t ep_type,
+ uint16_t ep_mpl)
+{
+ usb_pipe *pp = &pudev->host.pipe[pp_num];
+
+ pp->dev_addr = udev->addr;
+ pp->dev_speed = udev->speed;
+ pp->ep.type = ep_type;
+ pp->ep.mps = ep_mpl;
+ pp->ping = (uint8_t)(udev->speed == PORT_SPEED_HIGH);
+
+ usb_pipe_init(pudev, pp_num);
+
+ return HC_OK;
+}
+
+/*!
+ \brief modify a pipe
+ \param[in] pudev: pointer to usb core instance
+ \param[in] pp_num: pipe number
+ \param[in] dev_addr: device address
+ \param[in] dev_speed: device speed
+ \param[in] ep_mpl: endpoint max packet length
+ \param[out] none
+ \retval operation status
+*/
+uint8_t usbh_pipe_update(usb_core_driver *pudev,
+ uint8_t pp_num,
+ uint8_t dev_addr,
+ uint32_t dev_speed,
+ uint16_t ep_mpl)
+{
+ usb_pipe *pp = &pudev->host.pipe[pp_num];
+
+ if((pp->dev_addr != dev_addr) && (dev_addr)) {
+ pp->dev_addr = dev_addr;
+ }
+
+ if((pp->dev_speed != dev_speed) && (dev_speed)) {
+ pp->dev_speed = dev_speed;
+ }
+
+ if((pp->ep.mps != ep_mpl) && (ep_mpl)) {
+ pp->ep.mps = ep_mpl;
+ }
+
+ usb_pipe_init(pudev, pp_num);
+
+ return HC_OK;
+}
+
+/*!
+ \brief allocate a new pipe
+ \param[in] pudev: pointer to usb core instance
+ \param[in] ep_addr: endpoint address
+ \param[out] none
+ \retval operation status
+*/
+uint8_t usbh_pipe_allocate(usb_core_driver *pudev, uint8_t ep_addr)
+{
+ uint16_t pp_num = usbh_freepipe_get(pudev);
+
+ if(HC_ERROR != pp_num) {
+ pudev->host.pipe[pp_num].in_used = 1U;
+ pudev->host.pipe[pp_num].ep.dir = EP_DIR(ep_addr);
+ pudev->host.pipe[pp_num].ep.num = EP_ID(ep_addr);
+ }
+
+ return (uint8_t)pp_num;
+}
+
+/*!
+ \brief free a pipe
+ \param[in] pudev: pointer to usb core instance
+ \param[in] pp_num: pipe number
+ \param[out] none
+ \retval operation status
+*/
+uint8_t usbh_pipe_free(usb_core_driver *pudev, uint8_t pp_num)
+{
+ if(pp_num < HC_MAX) {
+ pudev->host.pipe[pp_num].in_used = 0U;
+ }
+
+ return USBH_OK;
+}
+
+/*!
+ \brief delete all USB host pipe
+ \param[in] pudev: pointer to usb core instance
+ \param[out] none
+ \retval operation status
+*/
+uint8_t usbh_pipe_delete(usb_core_driver *pudev)
+{
+ uint8_t pp_num = 0U;
+
+ for(pp_num = 2U; pp_num < HC_MAX; pp_num++) {
+ pudev->host.pipe[pp_num] = (usb_pipe) {
+ 0
+ };
+ }
+
+ return USBH_OK;
+}
+
+/*!
+ \brief get a free pipe number for allocation
+ \param[in] pudev: pointer to usb core instance
+ \param[out] none
+ \retval operation status
+*/
+static uint16_t usbh_freepipe_get(usb_core_driver *pudev)
+{
+ uint8_t pp_num = 0U;
+
+ for(pp_num = 0U; pp_num < HC_MAX; pp_num++) {
+ if(0U == pudev->host.pipe[pp_num].in_used) {
+ return (uint16_t)pp_num;
+ }
+ }
+
+ return HC_ERROR;
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/core/Source/usbh_transc.c b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/core/Source/usbh_transc.c
new file mode 100644
index 00000000..d9c5b256
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/host/core/Source/usbh_transc.c
@@ -0,0 +1,372 @@
+/*!
+ \file usbh_transc.c
+ \brief USB host mode transactions driver
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+ \version 2021-09-27, V3.0.1, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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.
+*/
+
+#include "drv_usb_hw.h"
+#include "usbh_pipe.h"
+#include "usbh_transc.h"
+
+/* local function prototypes ('static') */
+static usb_urb_state usbh_urb_wait(usbh_host *puhost, uint8_t pp_num, uint32_t wait_time);
+static void usbh_setup_transc(usbh_host *puhost);
+static void usbh_data_in_transc(usbh_host *puhost);
+static void usbh_data_out_transc(usbh_host *puhost);
+static void usbh_status_in_transc(usbh_host *puhost);
+static void usbh_status_out_transc(usbh_host *puhost);
+static uint32_t usbh_request_submit(usb_core_driver *pudev, uint8_t pp_num);
+
+/*!
+ \brief send the setup packet to the USB device
+ \param[in] pudev: pointer to usb core instance
+ \param[in] buf: data buffer which will be sent to USB device
+ \param[in] pp_num: pipe number
+ \param[out] none
+ \retval operation status
+*/
+usbh_status usbh_ctlsetup_send(usb_core_driver *pudev, uint8_t *buf, uint8_t pp_num)
+{
+ usb_pipe *pp = &pudev->host.pipe[pp_num];
+
+ pp->DPID = PIPE_DPID_SETUP;
+ pp->xfer_buf = buf;
+ pp->xfer_len = USB_SETUP_PACKET_LEN;
+
+ return (usbh_status)usbh_request_submit(pudev, pp_num);
+}
+
+/*!
+ \brief send a data packet to the USB device
+ \param[in] pudev: pointer to usb core instance
+ \param[in] buf: data buffer which will be sent to USB device
+ \param[in] pp_num: pipe number
+ \param[in] len: length of the data to be sent
+ \param[out] none
+ \retval operation status
+*/
+usbh_status usbh_data_send(usb_core_driver *pudev, uint8_t *buf, uint8_t pp_num, uint16_t len)
+{
+ usb_pipe *pp = &pudev->host.pipe[pp_num];
+
+ pp->xfer_buf = buf;
+ pp->xfer_len = len;
+
+ switch(pp->ep.type) {
+ case USB_EPTYPE_CTRL:
+ if(0U == len) {
+ pp->data_toggle_out = 1U;
+ }
+
+ pp->DPID = PIPE_DPID[pp->data_toggle_out];
+ break;
+
+ case USB_EPTYPE_INTR:
+ pp->DPID = PIPE_DPID[pp->data_toggle_out];
+
+ pp->data_toggle_out ^= 1U;
+ break;
+
+ case USB_EPTYPE_BULK:
+ pp->DPID = PIPE_DPID[pp->data_toggle_out];
+ break;
+
+ case USB_EPTYPE_ISOC:
+ pp->DPID = PIPE_DPID[0];
+ break;
+
+ default:
+ break;
+ }
+
+ usbh_request_submit(pudev, pp_num);
+
+ return USBH_OK;
+}
+
+/*!
+ \brief receive a data packet from the USB device
+ \param[in] pudev: pointer to usb core instance
+ \param[in] buf: data buffer which will be received from USB device
+ \param[in] pp_num: pipe number
+ \param[in] len: length of the data to be received
+ \param[out] none
+ \retval operation status
+*/
+usbh_status usbh_data_recev(usb_core_driver *pudev, uint8_t *buf, uint8_t pp_num, uint16_t len)
+{
+ usb_pipe *pp = &pudev->host.pipe[pp_num];
+
+ pp->xfer_buf = buf;
+ pp->xfer_len = len;
+
+ switch(pp->ep.type) {
+ case USB_EPTYPE_CTRL:
+ pp->DPID = PIPE_DPID[1];
+ break;
+
+ case USB_EPTYPE_INTR:
+ pp->DPID = PIPE_DPID[pp->data_toggle_in];
+
+ /* Toggle DATA PID */
+ pp->data_toggle_in ^= 1U;
+ break;
+
+ case USB_EPTYPE_BULK:
+ pp->DPID = PIPE_DPID[pp->data_toggle_in];
+ break;
+
+ case USB_EPTYPE_ISOC:
+ pp->DPID = PIPE_DPID[0];
+ break;
+
+ default:
+ break;
+ }
+
+ usbh_request_submit(pudev, pp_num);
+
+ return USBH_OK;
+}
+
+/*!
+ \brief USB control transfer handler
+ \param[in] puhost: pointer to USB host
+ \param[out] none
+ \retval operation status
+*/
+usbh_status usbh_ctl_handler(usbh_host *puhost)
+{
+ usbh_status status = USBH_BUSY;
+
+ switch(puhost->control.ctl_state) {
+ case CTL_SETUP:
+ usbh_setup_transc(puhost);
+ break;
+
+ case CTL_DATA_IN:
+ usbh_data_in_transc(puhost);
+ break;
+
+ case CTL_DATA_OUT:
+ usbh_data_out_transc(puhost);
+ break;
+
+ case CTL_STATUS_IN:
+ usbh_status_in_transc(puhost);
+ break;
+
+ case CTL_STATUS_OUT:
+ usbh_status_out_transc(puhost);
+ break;
+
+ case CTL_FINISH:
+ puhost->control.ctl_state = CTL_IDLE;
+
+ status = USBH_OK;
+ break;
+
+ case CTL_ERROR:
+ if(++puhost->control.error_count <= USBH_MAX_ERROR_COUNT) {
+ /* do the transmission again, starting from SETUP packet */
+ puhost->control.ctl_state = CTL_SETUP;
+ } else {
+ status = USBH_FAIL;
+ }
+ break;
+
+ default:
+ break;
+ }
+
+ return status;
+}
+
+/*!
+ \brief wait for USB URB(USB request block) state
+ \param[in] puhost: pointer to USB host
+ \param[in] pp_num: pipe number
+ \param[in] wait_time: wait time
+ \param[out] none
+ \retval USB URB state
+*/
+static usb_urb_state usbh_urb_wait(usbh_host *puhost, uint8_t pp_num, uint32_t wait_time)
+{
+ uint32_t timeout = 0U;
+ usb_urb_state urb_status = URB_IDLE;
+ timeout = puhost->control.timer;
+
+ while(URB_DONE != (urb_status = usbh_urbstate_get(puhost->data, pp_num))) {
+ if(URB_NOTREADY == urb_status) {
+ break;
+ } else if(URB_STALL == urb_status) {
+ puhost->control.ctl_state = CTL_SETUP;
+ break;
+ } else if(URB_ERROR == urb_status) {
+ puhost->control.ctl_state = CTL_ERROR;
+ break;
+ } else if((wait_time > 0U) && (((usb_curframe_get(puhost->data) > timeout) && ((usb_curframe_get(puhost->data) - timeout) > wait_time)) \
+ || ((usb_curframe_get(puhost->data) < timeout) && ((usb_curframe_get(puhost->data) + 0x3FFFU - timeout) > wait_time)))) {
+ /* timeout for in transfer */
+ puhost->control.ctl_state = CTL_ERROR;
+ break;
+ } else {
+ /* no operation, just wait */
+ }
+ }
+
+ return urb_status;
+}
+
+/*!
+ \brief USB setup transaction
+ \param[in] puhost: pointer to USB host
+ \param[out] none
+ \retval none
+*/
+static void usbh_setup_transc(usbh_host *puhost)
+{
+ /* send a SETUP packet */
+ usbh_ctlsetup_send(puhost->data,
+ puhost->control.setup.data,
+ puhost->control.pipe_out_num);
+
+ if(URB_DONE == usbh_urb_wait(puhost, puhost->control.pipe_out_num, 0U)) {
+ uint8_t dir = (puhost->control.setup.req.bmRequestType & USB_TRX_MASK);
+
+ if(puhost->control.setup.req.wLength) {
+ if(USB_TRX_IN == dir) {
+ puhost->control.ctl_state = CTL_DATA_IN;
+ } else {
+ puhost->control.ctl_state = CTL_DATA_OUT;
+ }
+ } else {
+ if(USB_TRX_IN == dir) {
+ puhost->control.ctl_state = CTL_STATUS_OUT;
+ } else {
+ puhost->control.ctl_state = CTL_STATUS_IN;
+ }
+ }
+
+ /* set the delay timer to enable timeout for data stage completion */
+ puhost->control.timer = (uint16_t)usb_curframe_get(puhost->data);
+ }
+}
+
+/*!
+ \brief USB data IN transaction
+ \param[in] puhost: pointer to USB host
+ \param[out] none
+ \retval none
+*/
+static void usbh_data_in_transc(usbh_host *puhost)
+{
+ usbh_data_recev(puhost->data,
+ puhost->control.buf,
+ puhost->control.pipe_in_num,
+ puhost->control.ctl_len);
+
+ if(URB_DONE == usbh_urb_wait(puhost, puhost->control.pipe_in_num, DATA_STAGE_TIMEOUT)) {
+ puhost->control.ctl_state = CTL_STATUS_OUT;
+
+ }
+}
+
+/*!
+ \brief USB data OUT transaction
+ \param[in] puhost: pointer to USB host
+ \param[out] none
+ \retval none
+*/
+static void usbh_data_out_transc(usbh_host *puhost)
+{
+ usbh_pipe_toggle_set(puhost->data, puhost->control.pipe_out_num, 1U);
+
+ usbh_data_send(puhost->data,
+ puhost->control.buf,
+ puhost->control.pipe_out_num,
+ puhost->control.ctl_len);
+
+ if(URB_DONE == usbh_urb_wait(puhost, puhost->control.pipe_out_num, DATA_STAGE_TIMEOUT)) {
+ puhost->control.ctl_state = CTL_STATUS_IN;
+
+ }
+}
+
+/*!
+ \brief USB status IN transaction
+ \param[in] puhost: pointer to USB host
+ \param[out] none
+ \retval none
+*/
+static void usbh_status_in_transc(usbh_host *puhost)
+{
+ uint8_t pp_num = puhost->control.pipe_in_num;
+
+ usbh_data_recev(puhost->data, NULL, pp_num, 0U);
+
+ if(URB_DONE == usbh_urb_wait(puhost, pp_num, NODATA_STAGE_TIMEOUT)) {
+ puhost->control.ctl_state = CTL_FINISH;
+ }
+}
+
+/*!
+ \brief USB status OUT transaction
+ \param[in] puhost: pointer to USB host
+ \param[out] none
+ \retval none
+*/
+static void usbh_status_out_transc(usbh_host *puhost)
+{
+ uint8_t pp_num = puhost->control.pipe_out_num;
+
+ usbh_data_send(puhost->data, NULL, pp_num, 0U);
+
+ if(URB_DONE == usbh_urb_wait(puhost, pp_num, NODATA_STAGE_TIMEOUT)) {
+ puhost->control.ctl_state = CTL_FINISH;
+ }
+}
+
+/*!
+ \brief prepare a pipe and start a transfer
+ \param[in] pudev: pointer to usb core instance
+ \param[in] pp_num: pipe number
+ \param[out] none
+ \retval operation status
+*/
+static uint32_t usbh_request_submit(usb_core_driver *pudev, uint8_t pp_num)
+{
+ pudev->host.pipe[pp_num].urb_state = URB_IDLE;
+ pudev->host.pipe[pp_num].xfer_count = 0U;
+
+ return (uint32_t)usb_pipe_xfer(pudev, pp_num);
+}
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/ustd/class/cdc/usb_cdc.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/ustd/class/cdc/usb_cdc.h
new file mode 100644
index 00000000..a8563149
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/ustd/class/cdc/usb_cdc.h
@@ -0,0 +1,180 @@
+/*!
+ \file usb_cdc.h
+ \brief the header file of communication device class standard
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __USB_CDC_H
+#define __USB_CDC_H
+
+#include "usb_ch9_std.h"
+
+/* communications device class code */
+#define USB_CLASS_CDC 0x02U
+
+/* communications interface class control protocol codes */
+#define USB_CDC_PROTOCOL_NONE 0x00U
+#define USB_CDC_PROTOCOL_AT 0x01U
+#define USB_CDC_PROTOCOL_VENDOR 0xFFU
+
+/* data interface class code */
+#define USB_CLASS_DATA 0x0AU
+
+#define USB_DESCTYPE_CDC_ACM 0x21U
+#define USB_DESCTYPE_CS_INTERFACE 0x24U
+
+#define USB_CDC_ACM_CONFIG_DESC_SIZE 0x43U
+
+/* class-specific notification codes for pstn subclasses */
+#define USB_CDC_NOTIFY_SERIAL_STATE 0x20U
+
+/* class-specific request codes */
+#define SEND_ENCAPSULATED_COMMAND 0x00U
+#define GET_ENCAPSULATED_RESPONSE 0x01U
+#define SET_COMM_FEATURE 0x02U
+#define GET_COMM_FEATURE 0x03U
+#define CLEAR_COMM_FEATURE 0x04U
+
+#define SET_AUX_LINE_STATE 0x10U
+#define SET_HOOK_STATE 0x11U
+#define PULSE_SETUP 0x12U
+#define SEND_PULSE 0x13U
+#define SET_PULSE_TIME 0x14U
+#define RING_AUX_JACK 0x15U
+
+#define SET_LINE_CODING 0x20U
+#define GET_LINE_CODING 0x21U
+#define SET_CONTROL_LINE_STATE 0x22U
+#define SEND_BREAK 0x23U
+#define NO_CMD 0xFFU
+
+#define SET_RINGER_PARMS 0x30U
+#define GET_RINGER_PARMS 0x31U
+#define SET_OPERATION_PARMS 0x32U
+#define GET_OPERATION_PARMS 0x33U
+#define SET_LINE_PARMS 0x34U
+#define GET_LINE_PARMS 0x35U
+#define DIAL_DIGITS 0x36U
+#define SET_UNIT_PARAMETER 0x37U
+#define GET_UNIT_PARAMETER 0x38U
+#define CLEAR_UNIT_PARAMETER 0x39U
+#define GET_PROFILE 0x3AU
+
+#define SET_ETHERNET_MULTICAST_FILTERS 0x40U
+#define SET_ETHERNET_POWER_MANAGEMENT_PATTERN FILTER 0x41U
+#define GET_ETHERNET_POWER_MANAGEMENT_PATTERN FILTER 0x42U
+#define SET_ETHERNET_PACKET_FILTER 0x43U
+#define GET_ETHERNET_STATISTIC 0x44U
+
+#define SET_ATM_DATA_FORMAT 0x50U
+#define GET_ATM_DEVICE_STATISTICS 0x51U
+#define SET_ATM_DEFAULT_VC 0x52U
+#define GET_ATM_VC_STATISTICS 0x53U
+
+/* wValue for set control line state */
+#define CDC_ACTIVATE_CARRIER_SIGNAL_RTS 0x0002U
+#define CDC_DEACTIVATE_CARRIER_SIGNAL_RTS 0x0000U
+#define CDC_ACTIVATE_SIGNAL_DTR 0x0001U
+#define CDC_DEACTIVATE_SIGNAL_DTR 0x0000U
+
+/* CDC subclass code */
+enum usb_cdc_subclass {
+ USB_CDC_SUBCLASS_RESERVED = 0U, /*!< reserved */
+ USB_CDC_SUBCLASS_DLCM, /*!< direct line control mode */
+ USB_CDC_SUBCLASS_ACM, /*!< abstract control mode */
+ USB_CDC_SUBCLASS_TCM, /*!< telephone control mode */
+ USB_CDC_SUBCLASS_MCM, /*!< multichannel control model */
+ USB_CDC_SUBCLASS_CCM, /*!< CAPI control model */
+ USB_CDC_SUBCLASS_ENCM, /*!< ethernet networking control model */
+ USB_CDC_SUBCLASS_ANCM /*!< ATM networking control model */
+};
+
+#pragma pack(1)
+
+/* cdc acm line coding structure */
+typedef struct {
+ uint32_t dwDTERate; /*!< data terminal rate */
+ uint8_t bCharFormat; /*!< stop bits */
+ uint8_t bParityType; /*!< parity */
+ uint8_t bDataBits; /*!< data bits */
+} acm_line;
+
+/* notification structure */
+typedef struct {
+ uint8_t bmRequestType; /*!< type of request */
+ uint8_t bNotification; /*!< communication interface class notifications */
+ uint16_t wValue; /*!< value of notification */
+ uint16_t wIndex; /*!< index of interface */
+ uint16_t wLength; /*!< length of notification data */
+} acm_notification;
+
+typedef struct {
+ usb_desc_header header; /*!< descriptor header, including type and size. */
+ uint8_t bDescriptorSubtype; /*!< bDescriptorSubtype: header function descriptor */
+ uint16_t bcdCDC; /*!< bcdCDC: low byte of spec release number (CDC1.10) */
+} usb_desc_header_func;
+
+typedef struct {
+ usb_desc_header header; /*!< descriptor header, including type and size. */
+ uint8_t bDescriptorSubtype; /*!< bDescriptorSubtype: call management function descriptor */
+ uint8_t bmCapabilities; /*!< bmCapabilities: D0 is reset, D1 is ignored */
+ uint8_t bDataInterface; /*!< bDataInterface: 1 interface used for call management */
+} usb_desc_call_managment_func;
+
+typedef struct {
+ usb_desc_header header; /*!< descriptor header, including type and size. */
+ uint8_t bDescriptorSubtype; /*!< bDescriptorSubtype: abstract control management descriptor */
+ uint8_t bmCapabilities; /*!< bmCapabilities: D1 */
+} usb_desc_acm_func;
+
+typedef struct {
+ usb_desc_header header; /*!< descriptor header, including type and size. */
+ uint8_t bDescriptorSubtype; /*!< bDescriptorSubtype: union function descriptor */
+ uint8_t bMasterInterface; /*!< bMasterInterface: communication class interface */
+ uint8_t bSlaveInterface0; /*!< bSlaveInterface0: data class interface */
+} usb_desc_union_func;
+
+#pragma pack()
+
+typedef struct {
+ usb_desc_config config;
+ usb_desc_itf cmd_itf;
+ usb_desc_header_func cdc_header;
+ usb_desc_call_managment_func cdc_call_managment;
+ usb_desc_acm_func cdc_acm;
+ usb_desc_union_func cdc_union;
+ usb_desc_ep cdc_cmd_endpoint;
+ usb_desc_itf cdc_data_interface;
+ usb_desc_ep cdc_out_endpoint;
+ usb_desc_ep cdc_in_endpoint;
+} usb_cdc_desc_config_set;
+
+#endif /* __USB_CDC_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/ustd/class/hid/usb_hid.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/ustd/class/hid/usb_hid.h
new file mode 100644
index 00000000..88c9fde8
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/ustd/class/hid/usb_hid.h
@@ -0,0 +1,81 @@
+/*!
+ \file usb_hid.h
+ \brief definitions for the USB HID class
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __USB_HID_H
+#define __USB_HID_H
+
+#include "usb_ch9_std.h"
+
+#define USB_HID_CLASS 0x03U
+
+#define USB_DESCTYPE_HID 0x21U
+#define USB_DESCTYPE_REPORT 0x22U
+
+/* HID subclass code */
+#define USB_HID_SUBCLASS_BOOT_ITF 0x01U
+
+/* HID protocol codes */
+#define USB_HID_PROTOCOL_KEYBOARD 0x01U
+#define USB_HID_PROTOCOL_MOUSE 0x02U
+
+#define GET_REPORT 0x01U
+#define GET_IDLE 0x02U
+#define GET_PROTOCOL 0x03U
+#define SET_REPORT 0x09U
+#define SET_IDLE 0x0AU
+#define SET_PROTOCOL 0x0BU
+
+#pragma pack(1)
+
+typedef struct {
+ usb_desc_header header; /*!< regular descriptor header containing the descriptor's type and length */
+
+ uint16_t bcdHID; /*!< BCD encoded version that the HID descriptor and device complies to */
+ uint8_t bCountryCode; /*!< country code of the localized device, or zero if universal */
+ uint8_t bNumDescriptors; /*!< total number of HID report descriptors for the interface */
+ uint8_t bDescriptorType; /*!< type of HID report */
+ uint16_t wDescriptorLength; /*!< length of the associated HID report descriptor, in bytes */
+} usb_desc_hid;
+
+#pragma pack()
+
+typedef struct {
+ usb_desc_config config;
+ usb_desc_itf hid_itf;
+ usb_desc_hid hid_vendor;
+ usb_desc_ep hid_epin;
+ usb_desc_ep hid_epout;
+} usb_hid_desc_config_set;
+
+#endif /* __USB_HID_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/ustd/class/msc/msc_bbb.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/ustd/class/msc/msc_bbb.h
new file mode 100644
index 00000000..bb02ea42
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/ustd/class/msc/msc_bbb.h
@@ -0,0 +1,69 @@
+/*!
+ \file msc_bbb.h
+ \brief definitions for the USB MSC BBB(bulk/bulk/bulk) protocol
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __MSC_BBB_H
+#define __MSC_BBB_H
+
+#include "usb_ch9_std.h"
+
+#define BBB_CBW_SIGNATURE 0x43425355U
+#define BBB_CSW_SIGNATURE 0x53425355U
+#define BBB_CBW_LENGTH 31U
+#define BBB_CSW_LENGTH 13U
+
+typedef struct {
+ uint32_t dCBWSignature;
+ uint32_t dCBWTag;
+ uint32_t dCBWDataTransferLength;
+ uint8_t bmCBWFlags;
+ uint8_t bCBWLUN;
+ uint8_t bCBWCBLength;
+ uint8_t CBWCB[16];
+} msc_bbb_cbw;
+
+typedef struct {
+ uint32_t dCSWSignature;
+ uint32_t dCSWTag;
+ uint32_t dCSWDataResidue;
+ uint8_t bCSWStatus;
+} msc_bbb_csw;
+
+/* CSW command status */
+enum msc_csw_status {
+ CSW_CMD_PASSED = 0,
+ CSW_CMD_FAILED,
+ CSW_PHASE_ERROR
+};
+
+#endif /* __MSC_BBB_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/ustd/class/msc/msc_scsi.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/ustd/class/msc/msc_scsi.h
new file mode 100644
index 00000000..76837316
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/ustd/class/msc/msc_scsi.h
@@ -0,0 +1,117 @@
+/*!
+ \file msc_scsi.h
+ \brief definitions for the USB MSC SCSI commands
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __MSC_SCSI_H
+#define __MSC_SCSI_H
+
+#include "usb_ch9_std.h"
+
+/* SCSI commands */
+#define SCSI_FORMAT_UNIT 0x04U
+#define SCSI_INQUIRY 0x12U
+#define SCSI_MODE_SELECT6 0x15U
+#define SCSI_MODE_SELECT10 0x55U
+#define SCSI_MODE_SENSE6 0x1AU
+#define SCSI_READ_TOC_DATA 0x43U
+#define SCSI_MODE_SENSE10 0x5AU
+#define SCSI_ALLOW_MEDIUM_REMOVAL 0x1EU
+#define SCSI_READ6 0x08U
+#define SCSI_READ10 0x28U
+#define SCSI_READ12 0xA8U
+#define SCSI_READ16 0x88U
+
+#define SCSI_READ_CAPACITY10 0x25U
+#define SCSI_READ_CAPACITY16 0x9EU
+
+#define SCSI_REQUEST_SENSE 0x03U
+#define SCSI_START_STOP_UNIT 0x1BU
+#define SCSI_TEST_UNIT_READY 0x00U
+#define SCSI_WRITE6 0x0AU
+#define SCSI_WRITE10 0x2AU
+#define SCSI_WRITE12 0xAAU
+#define SCSI_WRITE16 0x8AU
+
+#define SCSI_VERIFY10 0x2FU
+#define SCSI_VERIFY12 0xAFU
+#define SCSI_VERIFY16 0x8FU
+
+#define SCSI_SEND_DIAGNOSTIC 0x1DU
+#define SCSI_READ_FORMAT_CAPACITIES 0x23U
+
+#define INVALID_CDB 0x20U
+#define INVALID_FIELED_IN_COMMAND 0x24U
+#define PARAMETER_LIST_LENGTH_ERROR 0x1AU
+#define INVALID_FIELD_IN_PARAMETER_LIST 0x26U
+#define ADDRESS_OUT_OF_RANGE 0x21U
+#define MEDIUM_NOT_PRESENT 0x3AU
+#define MEDIUM_HAVE_CHANGED 0x28U
+#define WRITE_PROTECTED 0x27U
+#define UNRECOVERED_READ_ERROR 0x11U
+#define WRITE_FAULT 0x03U
+
+#define READ_FORMAT_CAPACITY_DATA_LEN 0x0CU
+#define READ_CAPACITY10_DATA_LEN 0x08U
+#define MODE_SENSE10_DATA_LEN 0x08U
+#define MODE_SENSE6_DATA_LEN 0x04U
+#define READ_TOC_CMD_LEN 0x14U
+#define REQUEST_SENSE_DATA_LEN 0x12U
+#define STANDARD_INQUIRY_DATA_LEN 0x24U
+#define BLKVFY 0x04U
+
+enum sense_state {
+ NO_SENSE = 0U,
+ RECOVERED_ERROR,
+ NOT_READY,
+ MEDIUM_ERROR,
+ HARDWARE_ERROR,
+ ILLEGAL_REQUEST,
+ UNIT_ATTENTION,
+ DATA_PROTECT,
+ BLANK_CHECK,
+ VENDOR_SPECIFIC,
+ COPY_ABORTED,
+ ABORTED_COMMAND,
+ RESERVED,
+ VOLUME_OVERFLOW,
+ MISCOMPARE
+};
+
+typedef struct {
+ uint8_t SenseKey;
+ uint32_t Information;
+ uint8_t ASC;
+ uint8_t ASCQ;
+} msc_scsi_sense;
+
+#endif /* __MSC_SCSI_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/ustd/class/msc/usb_msc.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/ustd/class/msc/usb_msc.h
new file mode 100644
index 00000000..0629156c
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/ustd/class/msc/usb_msc.h
@@ -0,0 +1,68 @@
+/*!
+ \file usb_msc.h
+ \brief definitions for the USB MSC class
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __USB_MSC_H
+#define __USB_MSC_H
+
+#include "usb_ch9_std.h"
+
+/* mass storage device class code */
+#define USB_CLASS_MSC 0x08U
+
+/* mass storage subclass code */
+#define USB_MSC_SUBCLASS_RBC 0x01U
+#define USB_MSC_SUBCLASS_ATAPI 0x02U
+#define USB_MSC_SUBCLASS_UFI 0x04U
+#define USB_MSC_SUBCLASS_SCSI 0x06U
+#define USB_MSC_SUBCLASS_LOCKABLE 0x07U
+#define USB_MSC_SUBCLASS_IEEE1667 0x08U
+
+/* mass storage interface class control protocol codes */
+#define USB_MSC_PROTOCOL_CBI 0x00U
+#define USB_MSC_PROTOCOL_CBI_ALT 0x01U
+#define USB_MSC_PROTOCOL_BBB 0x50U
+
+/* mass storage request codes */
+#define USB_MSC_REQ_CODES_ADSC 0x00U
+#define USB_MSC_REQ_CODES_GET 0xFCU
+#define USB_MSC_REQ_CODES_PUT 0xFDU
+#define USB_MSC_REQ_CODES_GML 0xFEU
+#define USB_MSC_REQ_CODES_BOMSR 0xFFU
+
+#define BBB_GET_MAX_LUN 0xFEU
+#define BBB_RESET 0xFFU
+
+#define SCSI_CMD_LENGTH 16U
+
+#endif /* __USB_MSC_H */
diff --git a/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/ustd/common/usb_ch9_std.h b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/ustd/common/usb_ch9_std.h
new file mode 100644
index 00000000..c6bc7bbe
--- /dev/null
+++ b/platform/vendor_bsp/gd/GD32F3x0_Firmware_Library/GD32F3x0_usbfs_library/ustd/common/usb_ch9_std.h
@@ -0,0 +1,248 @@
+/*!
+ \file usb_ch9_std.h
+ \brief USB 2.0 standard defines
+
+ \version 2020-08-13, V3.0.0, firmware for GD32F3x0
+*/
+
+/*
+ Copyright (c) 2020, 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 __USB_CH9_STD_H
+#define __USB_CH9_STD_H
+
+#include "usb_conf.h"
+
+#define USB_DEV_QUALIFIER_DESC_LEN 0x0AU /*!< USB device qualifier descriptor length */
+#define USB_DEV_DESC_LEN 0x12U /*!< USB device descriptor length */
+#define USB_CFG_DESC_LEN 0x09U /*!< USB configuration descriptor length */
+#define USB_ITF_DESC_LEN 0x09U /*!< USB interface descriptor length */
+#define USB_EP_DESC_LEN 0x07U /*!< USB endpoint descriptor length */
+#define USB_IAD_DESC_LEN 0x08U /*!< USB IAD descriptor length */
+#define USB_OTG_DESC_LEN 0x03U /*!< USB device OTG descriptor length */
+
+#define USB_SETUP_PACKET_LEN 0x08U /*!< USB setup packet length */
+
+/* bit 7 of bmRequestType: data phase transfer direction */
+#define USB_TRX_MASK 0x80U /*!< USB transfer direction mask */
+#define USB_TRX_OUT 0x00U /*!< USB transfer OUT direction */
+#define USB_TRX_IN 0x80U /*!< USB transfer IN direction */
+
+/* bit 6..5 of bmRequestType: request type */
+#define USB_REQTYPE_STRD 0x00U /*!< USB standard request */
+#define USB_REQTYPE_CLASS 0x20U /*!< USB class request */
+#define USB_REQTYPE_VENDOR 0x40U /*!< USB vendor request */
+#define USB_REQTYPE_MASK 0x60U /*!< USB request mask */
+
+#define USBD_BUS_POWERED 0x00U /*!< USB bus power supply */
+#define USBD_SELF_POWERED 0x01U /*!< USB self power supply */
+
+#define USB_STATUS_REMOTE_WAKEUP 2U /*!< USB is in remote wakeup status */
+#define USB_STATUS_SELF_POWERED 1U /*!< USB is in self powered status */
+
+/* bit 4..0 of bmRequestType: recipient type */
+enum _usb_recp_type {
+ USB_RECPTYPE_DEV = 0x0U, /*!< USB device request type */
+ USB_RECPTYPE_ITF = 0x1U, /*!< USB interface request type */
+ USB_RECPTYPE_EP = 0x2U, /*!< USB endpoint request type */
+ USB_RECPTYPE_MASK = 0x3U /*!< USB request type mask */
+};
+
+/* bRequest value */
+enum _usb_request {
+ USB_GET_STATUS = 0x0U, /*!< USB get status request */
+ USB_CLEAR_FEATURE = 0x1U, /*!< USB clear feature request */
+ USB_RESERVED2 = 0x2U,
+ USB_SET_FEATURE = 0x3U, /*!< USB set feature request */
+ USB_RESERVED4 = 0x4U,
+ USB_SET_ADDRESS = 0x5U, /*!< USB set address request */
+ USB_GET_DESCRIPTOR = 0x6U, /*!< USB get descriptor request */
+ USB_SET_DESCRIPTOR = 0x7U, /*!< USB set descriptor request */
+ USB_GET_CONFIGURATION = 0x8U, /*!< USB get configuration request */
+ USB_SET_CONFIGURATION = 0x9U, /*!< USB set configuration request */
+ USB_GET_INTERFACE = 0xAU, /*!< USB get interface request */
+ USB_SET_INTERFACE = 0xBU, /*!< USB set interface request */
+ USB_SYNCH_FRAME = 0xCU /*!< USB synchronize frame request */
+};
+
+/* descriptor types of USB specifications */
+enum _usb_desctype {
+ USB_DESCTYPE_DEV = 0x1U, /*!< USB device descriptor type */
+ USB_DESCTYPE_CONFIG = 0x2U, /*!< USB configuration descriptor type */
+ USB_DESCTYPE_STR = 0x3U, /*!< USB string descriptor type */
+ USB_DESCTYPE_ITF = 0x4U, /*!< USB interface descriptor type */
+ USB_DESCTYPE_EP = 0x5U, /*!< USB endpoint descriptor type */
+ USB_DESCTYPE_DEV_QUALIFIER = 0x6U, /*!< USB device qualifier descriptor type */
+ USB_DESCTYPE_OTHER_SPD_CONFIG = 0x7U, /*!< USB other speed configuration descriptor type */
+ USB_DESCTYPE_ITF_POWER = 0x8U, /*!< USB interface power descriptor type */
+ USB_DESCTYPE_IAD = 0xBU, /*!< USB interface association descriptor type */
+ USB_DESCTYPE_BOS = 0xFU /*!< USB BOS descriptor type */
+};
+
+/* USB Endpoint Descriptor bmAttributes bit definitions */
+/* bits 1..0 : transfer type */
+enum _usbx_type {
+ USB_EP_ATTR_CTL = 0x0U, /*!< USB control transfer type */
+ USB_EP_ATTR_ISO = 0x1U, /*!< USB Isochronous transfer type */
+ USB_EP_ATTR_BULK = 0x2U, /*!< USB Bulk transfer type */
+ USB_EP_ATTR_INT = 0x3U /*!< USB Interrupt transfer type */
+};
+
+/* bits 3..2 : Sync type (only if ISOCHRONOUS) */
+#define USB_EP_ATTR_NOSYNC 0x00U /*!< No Synchronization */
+#define USB_EP_ATTR_ASYNC 0x04U /*!< Asynchronous */
+#define USB_EP_ATTR_ADAPTIVE 0x08U /*!< Adaptive */
+#define USB_EP_ATTR_SYNC 0x0CU /*!< Synchronous */
+#define USB_EP_ATTR_SYNCTYPE 0x0CU /*!< Synchronous type */
+
+/* bits 5..4 : usage type (only if ISOCHRONOUS) */
+#define USB_EP_ATTR_DATA 0x00U /*!< Data endpoint */
+#define USB_EP_ATTR_FEEDBACK 0x10U /*!< Feedback endpoint */
+#define USB_EP_ATTR_IMPLICIT_FEEDBACK_DATA 0x20U /*!< Implicit feedback Data endpoint */
+#define USB_EP_ATTR_USAGETYPE 0x30U /*!< Usage type */
+
+/* endpoint max packet size bits12..11 */
+#define USB_EP_MPS_ADD_0 (0x00 << 11) /*!< None(1 transaction per microframe */
+#define USB_EP_MPS_ADD_1 (0x01 << 11) /*!< 1 additional(2 transaction per microframe */
+#define USB_EP_MPS_ADD_2 (0x02 << 11) /*!< 2 additional(3 transaction per microframe */
+
+#define FEATURE_SELECTOR_EP 0x00U /*!< USB endpoint feature selector */
+#define FEATURE_SELECTOR_DEV 0x01U /*!< USB device feature selector */
+#define FEATURE_SELECTOR_REMOTEWAKEUP 0x01U /*!< USB feature selector remote wakeup */
+
+#define BYTE_SWAP(addr) (((uint16_t)(*((uint8_t *)(addr)))) + \
+ (uint16_t)(((uint16_t)(*(((uint8_t *)(addr)) + 1U))) << 8U))
+
+#define BYTE_LOW(x) ((uint8_t)((x) & 0x00FFU))
+#define BYTE_HIGH(x) ((uint8_t)(((x) & 0xFF00U) >> 8U))
+
+#define USB_MIN(a, b) (((a) < (b)) ? (a) : (b))
+
+#define USB_DEFAULT_CONFIG 0U
+
+/* USB classes */
+#define USB_CLASS_HID 0x03U /*!< USB HID class */
+#define USB_CLASS_MSC 0x08U /*!< USB MSC class */
+
+/* use the following values when USB host need to get descriptor */
+#define USBH_DESC(x) (((x)<< 8U) & 0xFF00U)
+
+/* as per USB specs 9.2.6.4 :standard request with data request timeout: 5sec
+ standard request with no data stage timeout : 50ms */
+#define DATA_STAGE_TIMEOUT 5000U /*!< USB data stage timeout*/
+#define NODATA_STAGE_TIMEOUT 50U /*!< USB no data stage timeout*/
+
+#pragma pack(1)
+
+/* USB standard device request structure */
+typedef struct _usb_req {
+ uint8_t bmRequestType; /*!< type of request */
+ uint8_t bRequest; /*!< request of setup packet */
+ uint16_t wValue; /*!< value of setup packet */
+ uint16_t wIndex; /*!< index of setup packet */
+ uint16_t wLength; /*!< length of setup packet */
+} usb_req;
+
+/* USB setup packet define */
+typedef union _usb_setup {
+ uint8_t data[8];
+
+ usb_req req;
+} usb_setup;
+
+/* USB descriptor defines */
+
+typedef struct _usb_desc_header {
+ uint8_t bLength; /*!< size of the descriptor */
+ uint8_t bDescriptorType; /*!< type of the descriptor */
+} usb_desc_header;
+
+typedef struct _usb_desc_dev {
+ usb_desc_header header; /*!< descriptor header, including type and size */
+
+ uint16_t bcdUSB; /*!< BCD of the supported USB specification */
+ uint8_t bDeviceClass; /*!< USB device class */
+ uint8_t bDeviceSubClass; /*!< USB device subclass */
+ uint8_t bDeviceProtocol; /*!< USB device protocol */
+ uint8_t bMaxPacketSize0; /*!< size of the control (address 0) endpoint's bank in bytes */
+ uint16_t idVendor; /*!< vendor ID for the USB product */
+ uint16_t idProduct; /*!< unique product ID for the USB product */
+ uint16_t bcdDevice; /*!< product release (version) number */
+ uint8_t iManufacturer; /*!< string index for the manufacturer's name */
+ uint8_t iProduct; /*!< string index for the product name/details */
+ uint8_t iSerialNumber; /*!< string index for the product's globally unique hexadecimal serial number */
+ uint8_t bNumberConfigurations; /*!< total number of configurations supported by the device */
+} usb_desc_dev;
+
+typedef struct _usb_desc_config {
+ usb_desc_header header; /*!< descriptor header, including type and size */
+
+ uint16_t wTotalLength; /*!< size of the configuration descriptor header,and all sub descriptors inside the configuration */
+ uint8_t bNumInterfaces; /*!< total number of interfaces in the configuration */
+ uint8_t bConfigurationValue; /*!< configuration index of the current configuration */
+ uint8_t iConfiguration; /*!< index of a string descriptor describing the configuration */
+ uint8_t bmAttributes; /*!< configuration attributes */
+ uint8_t bMaxPower; /*!< maximum power consumption of the device while in the current configuration */
+} usb_desc_config;
+
+typedef struct _usb_desc_itf {
+ usb_desc_header header; /*!< descriptor header, including type and size */
+
+ uint8_t bInterfaceNumber; /*!< index of the interface in the current configuration */
+ uint8_t bAlternateSetting; /*!< alternate setting for the interface number */
+ uint8_t bNumEndpoints; /*!< total number of endpoints in the interface */
+ uint8_t bInterfaceClass; /*!< interface class ID */
+ uint8_t bInterfaceSubClass; /*!< interface subclass ID */
+ uint8_t bInterfaceProtocol; /*!< interface protocol ID */
+ uint8_t iInterface; /*!< index of the string descriptor describing the interface */
+} usb_desc_itf;
+
+typedef struct _usb_desc_ep {
+ usb_desc_header header; /*!< descriptor header, including type and size. */
+
+ uint8_t bEndpointAddress; /*!< logical address of the endpoint */
+ uint8_t bmAttributes; /*!< endpoint attributes */
+ uint16_t wMaxPacketSize; /*!< size of the endpoint bank, in bytes */
+ uint8_t bInterval; /*!< polling interval in milliseconds for the endpoint if it is an INTERRUPT or ISOCHRONOUS type */
+} usb_desc_ep;
+
+typedef struct _usb_desc_LANGID {
+ usb_desc_header header; /*!< descriptor header, including type and size. */
+ uint16_t wLANGID; /*!< LANGID code */
+} usb_desc_LANGID;
+
+typedef struct _usb_desc_str {
+ usb_desc_header header; /*!< descriptor header, including type and size. */
+ uint16_t unicode_string[64]; /*!< unicode string data */
+} usb_desc_str;
+
+#pragma pack()
+
+/* compute string descriptor length */
+#define USB_STRING_LEN(unicode_chars) (sizeof(usb_desc_header) + ((unicode_chars) << 1U))
+
+#endif /* __USB_CH9_STD_H */