Browse Source

[bsp][bluetrum] convert uintxx_t to rt_uintxx_t

greedyhao 3 years ago
parent
commit
9fc0c75506

+ 30 - 28
bsp/bluetrum/ab32vg1-ab-prougen/README.md

@@ -10,6 +10,36 @@
 
 通过阅读快速上手章节开发者可以快速地上手该 BSP,将 RT-Thread 运行在开发板上。在进阶使用指南章节,将会介绍更多高级功能,帮助开发者利用 RT-Thread 驱动更多板载资源。
 
+## 注意事项
+
+芯片有部分不开源的代码是以静态库提供的,静态库在软件包中,默认已勾选,直接运行 `pkgs --update` 即可
+
+波特率默认为 1.5M,需要使用 [Downloader](https://github.com/BLUETRUM/Downloader) 下载 `.dcf` 到芯片,需要编译后自动下载,需要在 `Downloader` 中的下载的下拉窗中选择 `自动`;目前暂时屏蔽 uart1 打印
+
+使用 `romfs` 时,需要自己生成 `romfs.c` 进行替换,操作参考[使用 RomFS](https://www.rt-thread.org/document/site/tutorial/qemu-network/filesystems/filesystems/#romfs)
+
+编译报错的时候,如果出现重复定义的报错,可能需要在 `cconfig.h` 中手动添加以下配置
+
+``` c
+#define HAVE_SIGEVENT 1
+#define HAVE_SIGINFO 1
+#define HAVE_SIGVAL 1
+```
+
+所有在中断中使用的函数或数据需要放在 RAM 中,否则会导致系统运行报错。具体做法可以参考下面
+
+``` c
+RT_SECTION(".irq.example.str")
+static const char example_info[] = "example 0x%x";
+
+RT_SECTION(".irq.example")
+void example_isr(void)
+{
+    rt_kprintf(example_info, 11);
+    ...
+}
+```
+
 ## 开发板介绍
 
 ab32vg1-prougen 是 中科蓝讯(Bluetrum) 推出的一款基于 RISC-V 内核的开发板,最高主频为 120Mhz,该开发板芯片为 AB32VG1。
@@ -102,34 +132,6 @@ msh >
 
 4. 输入`scons` 命令重新编译工程。
 
-## 注意事项
-
-波特率默认为 1.5M,需要使用 [Downloader](https://github.com/BLUETRUM/Downloader) 下载 `.dcf` 到芯片,需要编译后自动下载,需要在 `Downloader` 中的下载的下拉窗中选择 `自动`;目前暂时屏蔽 uart1 打印
-
-使用 `romfs` 时,需要自己生成 `romfs.c` 进行替换,操作参考[使用 RomFS](https://www.rt-thread.org/document/site/tutorial/qemu-network/filesystems/filesystems/#romfs)
-
-编译报错的时候,如果出现重复定义的报错,可能需要在 `cconfig.h` 中手动添加以下配置
-
-``` c
-#define HAVE_SIGEVENT 1
-#define HAVE_SIGINFO 1
-#define HAVE_SIGVAL 1
-```
-
-所有在中断中使用的函数或数据需要放在 RAM 中,否则会导致系统运行报错。具体做法可以参考下面
-
-``` c
-RT_SECTION(".irq.example.str")
-static const char example_info[] = "example 0x%x";
-
-RT_SECTION(".irq.example")
-void example_isr(void)
-{
-    rt_kprintf(example_info, 11);
-    ...
-}
-```
-
 ## 维护人信息
 
 - [greedyhao](https://github.com/greedyhao)

+ 6 - 0
bsp/bluetrum/ab32vg1-ab-prougen/link.lds

@@ -46,6 +46,12 @@ SECTIONS
         KEEP (*(.init_array*))
         PROVIDE(__ctors_end__ = .);
 
+        /* section information for at server */
+        . = ALIGN(4);
+        __rtatcmdtab_start = .;
+        KEEP(*(RtAtCmdTab))
+        __rtatcmdtab_end = .;
+
         . = ALIGN(4);
         *save-restore.o (.text* .rodata*)
         *libcpu*cpu*context_gcc.o (.text* .rodata*)

+ 0 - 2
bsp/bluetrum/ab32vg1-ab-prougen/rtconfig.py

@@ -38,9 +38,7 @@ if PLATFORM == 'gcc':
     OBJDUMP = PREFIX + 'objdump'
     OBJCPY  = PREFIX + 'objcopy'
 
-    # DEVICE  = ' -mcmodel=medany -march=rv32imc -mabi=ilp32 -fsingle-precision-constant'
     DEVICE  = ' -mcmodel=medany -march=rv32imc -mabi=ilp32 -msave-restore'
-    # CFLAGS  = DEVICE + ' -fno-common -ffunction-sections -fdata-sections -fstrict-volatile-bitfields'
     CFLAGS = DEVICE + ' -D_USE_LONG_TIME_T'
     AFLAGS  = ' -c' + DEVICE + ' -x assembler-with-cpp'
     LFLAGS  = DEVICE + ' -nostartfiles -Wl,--gc-sections,-Map=rtthread.map,-cref,-u,_start -T link.lds'

+ 1 - 1
bsp/bluetrum/libraries/hal_drivers/drv_common.h

@@ -15,7 +15,7 @@
 #include <rthw.h>
 #include <rtdevice.h>
 
-#define GET_PIN(PORTx,PIN) (uint8_t)__AB32_GET_PIN_##PORTx(PIN)
+#define GET_PIN(PORTx,PIN) (rt_uint8_t)__AB32_GET_PIN_##PORTx(PIN)
 
 void uart0_irq_post(void);
 void uart1_irq_post(void);

+ 14 - 14
bsp/bluetrum/libraries/hal_drivers/drv_gpio.c

@@ -18,9 +18,9 @@
 
 struct port_info
 {
-    uint8_t start_pin;
-    uint8_t delta_pin;
-    uint8_t total_pin;
+    rt_uint8_t start_pin;
+    rt_uint8_t delta_pin;
+    rt_uint8_t total_pin;
 };
 
 /* It needs to be adjusted to the hardware. */
@@ -40,9 +40,9 @@ static const hal_sfr_t port_sfr[] =
     GPIOF_BASE,
 };
 
-static uint8_t _pin_port(uint32_t pin)
+static rt_uint8_t _pin_port(rt_uint32_t pin)
 {
-    uint8_t port = 0;
+    rt_uint8_t port = 0;
     for (port = 0; port < 3; port++) {
         if (pin < (port_table[port].total_pin + port_table[port].delta_pin)) {
             break;
@@ -51,12 +51,12 @@ static uint8_t _pin_port(uint32_t pin)
     return port;
 }
 
-#define PIN_NUM(port, no)       ((uint8_t)(port_table[port].total_pin + no - port_table[port].start_pin))
+#define PIN_NUM(port, no)       ((rt_uint8_t)(port_table[port].total_pin + no - port_table[port].start_pin))
 #define PIN_PORT(pin)           _pin_port(pin)
 #define PORT_SFR(port)          (port_sfr[(port)])
-#define PIN_NO(pin)             (uint8_t)((pin) & 0xFu)
+#define PIN_NO(pin)             (rt_uint8_t)((pin) & 0xFu)
 
-// #define PIN_ABPIN(pin)  (uint8_t)(port_table[PIN_PORT(pin)].total_pin + PIN_NO(pin))
+// #define PIN_ABPIN(pin)  (rt_uint8_t)(port_table[PIN_PORT(pin)].total_pin + PIN_NO(pin))
 
 static rt_base_t ab32_pin_get(const char *name)
 {
@@ -103,22 +103,22 @@ static rt_base_t ab32_pin_get(const char *name)
 
 static void ab32_pin_write(rt_device_t dev, rt_base_t pin, rt_base_t value)
 {
-    uint8_t port = PIN_PORT(pin);
-    uint8_t gpio_pin  = pin - port_table[port].total_pin;
-    hal_gpio_write(PORT_SFR(port), gpio_pin, (uint8_t)value);
+    rt_uint8_t port = PIN_PORT(pin);
+    rt_uint8_t gpio_pin  = pin - port_table[port].total_pin;
+    hal_gpio_write(PORT_SFR(port), gpio_pin, (rt_uint8_t)value);
 }
 
 static int ab32_pin_read(rt_device_t dev, rt_base_t pin)
 {
-    uint8_t port = PIN_PORT(pin);
-    uint8_t gpio_pin  = pin - port_table[port].total_pin;
+    rt_uint8_t port = PIN_PORT(pin);
+    rt_uint8_t gpio_pin  = pin - port_table[port].total_pin;
     return hal_gpio_read(PORT_SFR(port), gpio_pin);
 }
 
 static void ab32_pin_mode(rt_device_t dev, rt_base_t pin, rt_base_t mode)
 {
     struct gpio_init gpio_init;
-    uint8_t port = PIN_PORT(pin);
+    rt_uint8_t port = PIN_PORT(pin);
 
     gpio_init.pin = BIT(pin - port_table[port].total_pin);
     gpio_init.de  = GPIO_DIGITAL;

+ 1 - 1
bsp/bluetrum/libraries/hal_drivers/drv_hwtimer.c

@@ -101,7 +101,7 @@ static void _rt_device_hwtimer_isr(rt_hwtimer_t *timer)
 
 static void timer_init(struct rt_hwtimer_device *timer, rt_uint32_t state)
 {
-    uint32_t prescaler_value = 0;
+    rt_uint32_t prescaler_value = 0;
     hal_sfr_t tim = RT_NULL;
     struct ab32_hwtimer *tim_device = RT_NULL;
 

+ 7 - 7
bsp/bluetrum/libraries/hal_drivers/drv_irrx.c

@@ -41,10 +41,10 @@
 #define NO_KEY      (0u)
 
 struct ab32_irrx_data{
-    uint16_t cnt;                            //ir data bit counter
-    uint16_t rpt_cnt;                        //ir repeat counter
-    uint16_t addr;                           //address,  inverted address   Extended NEC: 16bits address
-    uint16_t cmd;                            //command,  inverted command
+    rt_uint16_t cnt;                            //ir data bit counter
+    rt_uint16_t rpt_cnt;                        //ir repeat counter
+    rt_uint16_t addr;                           //address,  inverted address   Extended NEC: 16bits address
+    rt_uint16_t cmd;                            //command,  inverted command
 };
 typedef struct ab32_irrx_data *ab32_irrx_data_t;
 
@@ -58,7 +58,7 @@ static struct ab32_irrx_data _irrx = {0};
  * @param cmd  inverted command
  */
 RT_SECTION(".irq.irrx")
-uint8_t ab32_get_irkey(uint16_t *addr, uint16_t *cmd)
+rt_uint8_t ab32_get_irkey(rt_uint16_t *addr, rt_uint16_t *cmd)
 {
     if (_irrx.cnt != 32) {
         return NO_KEY;
@@ -90,8 +90,8 @@ static void irrx_isr(int vector, void *param)
     //IR RX data finish interrupt
     if (IRRXCON & BIT(16)) {
         IRRXCPND = BIT(16);
-        _irrx.addr = (uint16_t)IRRXDAT;
-        _irrx.cmd = (uint16_t)(IRRXDAT >> 16);
+        _irrx.addr = (rt_uint16_t)IRRXDAT;
+        _irrx.cmd = (rt_uint16_t)(IRRXDAT >> 16);
         _irrx.cnt = 32;
     }
 

+ 23 - 23
bsp/bluetrum/libraries/hal_drivers/drv_rtc.c

@@ -24,59 +24,59 @@ static struct rt_device rtc;
 
 /************** HAL Start *******************/
 #define IRTC_ENTER_CRITICAL()       uint32_t cpu_ie = PICCON & BIT(0); PICCONCLR = BIT(0);
-#define IRTC_EXIT_CRITICAL()       PICCON |= cpu_ie
+#define IRTC_EXIT_CRITICAL()        PICCON |= cpu_ie
 
-uint8_t get_weekday(struct tm *const _tm)
+rt_uint8_t get_weekday(struct tm *const _tm)
 {
-    uint8_t weekday;
+    rt_uint8_t weekday;
     time_t secs = timegm(_tm);
 
     weekday = (secs / 86400 + 4) % 7;
     return weekday;
 }
 
-void irtc_write(uint32_t cmd)
+void irtc_write(rt_uint32_t cmd)
 {
     RTCDAT = cmd;
     while (RTCCON & RTC_CON_TRANS_DONE);
 }
 
-uint8_t irtc_read(void)
+rt_uint8_t irtc_read(void)
 {
     RTCDAT = 0x00;
     while (RTCCON & RTC_CON_TRANS_DONE);
-    return (uint8_t)RTCDAT;
+    return (rt_uint8_t)RTCDAT;
 }
 
-void irtc_time_write(uint32_t cmd, uint32_t dat)
+void irtc_time_write(rt_uint32_t cmd, rt_uint32_t dat)
 {
     IRTC_ENTER_CRITICAL();
     RTCCON |= RTC_CON_CHIP_SELECT;
     irtc_write(cmd | RTC_WR);
-    irtc_write((uint8_t)(dat >> 24));
-    irtc_write((uint8_t)(dat >> 16));
-    irtc_write((uint8_t)(dat >>  8));
-    irtc_write((uint8_t)(dat >>  0));
+    irtc_write((rt_uint8_t)(dat >> 24));
+    irtc_write((rt_uint8_t)(dat >> 16));
+    irtc_write((rt_uint8_t)(dat >>  8));
+    irtc_write((rt_uint8_t)(dat >>  0));
     RTCCON &= ~RTC_CON_CHIP_SELECT;
     IRTC_EXIT_CRITICAL();
 }
 
-uint32_t irtc_time_read(uint32_t cmd)
+rt_uint32_t irtc_time_read(rt_uint32_t cmd)
 {
-    uint32_t rd_val;
+    rt_uint32_t rd_val;
     IRTC_ENTER_CRITICAL();
     RTCCON |= RTC_CON_CHIP_SELECT;
     irtc_write(cmd | RTC_RD);
-    *((uint8_t *)&rd_val + 3) = irtc_read();
-    *((uint8_t *)&rd_val + 2) = irtc_read();
-    *((uint8_t *)&rd_val + 1) = irtc_read();
-    *((uint8_t *)&rd_val + 0) = irtc_read();
+    *((rt_uint8_t *)&rd_val + 3) = irtc_read();
+    *((rt_uint8_t *)&rd_val + 2) = irtc_read();
+    *((rt_uint8_t *)&rd_val + 1) = irtc_read();
+    *((rt_uint8_t *)&rd_val + 0) = irtc_read();
     RTCCON &= ~RTC_CON_CHIP_SELECT;
     IRTC_EXIT_CRITICAL();
     return rd_val;
 }
 
-void irtc_sfr_write(uint32_t cmd, uint8_t dat)
+void irtc_sfr_write(rt_uint32_t cmd, rt_uint8_t dat)
 {
     IRTC_ENTER_CRITICAL();
     RTCCON |= RTC_CON_CHIP_SELECT;
@@ -86,9 +86,9 @@ void irtc_sfr_write(uint32_t cmd, uint8_t dat)
     IRTC_EXIT_CRITICAL();
 }
 
-uint8_t irtc_sfr_read(uint32_t cmd)
+rt_uint8_t irtc_sfr_read(rt_uint32_t cmd)
 {
-    uint8_t rd_val;
+    rt_uint8_t rd_val;
     IRTC_ENTER_CRITICAL();
     RTCCON |= RTC_CON_CHIP_SELECT;
     irtc_write(cmd | RTC_RD);
@@ -99,8 +99,8 @@ uint8_t irtc_sfr_read(uint32_t cmd)
 
 static void _init_rtc_clock(void)
 {
-    uint8_t rtccon0;
-    uint8_t rtccon2;
+    rt_uint8_t rtccon0;
+    rt_uint8_t rtccon2;
 
     rtccon0 = irtc_sfr_read(RTCCON0_CMD);
     rtccon2 = irtc_sfr_read(RTCCON2_CMD);
@@ -121,7 +121,7 @@ void hal_rtc_init(void)
 {
     time_t sec = 0;
     struct tm tm_new = {0};
-    uint8_t temp;
+    rt_uint8_t temp;
 
     _init_rtc_clock();
     temp = irtc_sfr_read(RTCCON0_CMD);

+ 3 - 3
bsp/bluetrum/libraries/hal_drivers/drv_sdio.c

@@ -50,9 +50,9 @@ struct rthw_sdio
 ALIGN(SDIO_ALIGN_LEN)
 static rt_uint8_t cache_buf[SDIO_BUFF_SIZE];
 
-static uint8_t sd_baud = 119;
+static rt_uint8_t sd_baud = 119;
 
-uint8_t sysclk_update_baud(uint8_t baud);
+rt_uint8_t sysclk_update_baud(rt_uint8_t baud);
 
 static rt_uint32_t ab32_sdio_clk_get(hal_sfr_t hw_sdio)
 {
@@ -633,7 +633,7 @@ int rt_hw_sdio_init(void)
 {
     struct ab32_sdio_des sdio_des = {0};
     struct sd_handle hsd = {0};
-    uint8_t param = 0;
+    rt_uint8_t param = 0;
     hsd.instance = SDMMC0_BASE;
 
     hal_rcu_periph_clk_enable(RCU_SD0);

+ 5 - 5
bsp/bluetrum/libraries/hal_drivers/drv_usart.c

@@ -64,7 +64,7 @@ static struct ab32_uart_config uart_config[] =
 static struct ab32_uart uart_obj[sizeof(uart_config) / sizeof(uart_config[0])] = {0};
 
 #ifdef HUART_ENABLE
-static uint8_t huart_dma[512];
+static rt_uint8_t huart_dma[512];
 #endif
 
 static rt_err_t ab32_configure(struct rt_serial_device *serial, struct serial_configure *cfg)
@@ -179,13 +179,13 @@ static int ab32_getc(struct rt_serial_device *serial)
     uart = rt_container_of(serial, struct ab32_uart, serial);
 
     ch = -1;
-    switch ((uint32_t)(uart->handle.instance)) {
-        case (uint32_t)UART0_BASE:
+    switch ((rt_uint32_t)(uart->handle.instance)) {
+        case (rt_uint32_t)UART0_BASE:
             if (uart->rx_idx != uart->rx_idx_prev) {
                 ch = (int)(uart->rx_buf[uart->rx_idx_prev++ % 10]);
             }
             break;
-        case (uint32_t)UART1_BASE:
+        case (rt_uint32_t)UART1_BASE:
 #ifdef HUART_ENABLE
             if ((uart->uart_dma_flag) && (huart_get_rxcnt())) {
                 ch = huart_getchar();
@@ -197,7 +197,7 @@ static int ab32_getc(struct rt_serial_device *serial)
                 }
             }
             break;
-        case (uint32_t)UART2_BASE:
+        case (rt_uint32_t)UART2_BASE:
             if (uart->rx_idx != uart->rx_idx_prev) {
                 ch = (int)(uart->rx_buf[uart->rx_idx_prev++ % 10]);
             }