feat(driver): Use standard typedef

This commit is contained in:
Wu Jian Gang
2018-05-19 23:25:57 +08:00
parent 3b28e58a3e
commit 78bdcf043e
9 changed files with 107 additions and 105 deletions

View File

@ -19,10 +19,10 @@
void gpio_config(GPIO_ConfigTypeDef* pGPIOConfig) void gpio_config(GPIO_ConfigTypeDef* pGPIOConfig)
{ {
uint16 gpio_pin_mask = pGPIOConfig->GPIO_Pin; uint16_t gpio_pin_mask = pGPIOConfig->GPIO_Pin;
uint32 io_reg; uint32_t io_reg;
uint8 io_num = 0; uint8_t io_num = 0;
uint32 pin_reg; uint32_t pin_reg;
if (pGPIOConfig->GPIO_Mode == GPIO_Mode_Input) { if (pGPIOConfig->GPIO_Mode == GPIO_Mode_Input) {
GPIO_AS_INPUT(gpio_pin_mask); GPIO_AS_INPUT(gpio_pin_mask);
@ -84,7 +84,7 @@ void gpio_config(GPIO_ConfigTypeDef* pGPIOConfig)
* writes is significant, calling code should divide a single call * writes is significant, calling code should divide a single call
* into multiple calls. * into multiple calls.
*/ */
void gpio_output_conf(uint32 set_mask, uint32 clear_mask, uint32 enable_mask, uint32 disable_mask) void gpio_output_conf(uint32_t set_mask, uint32_t clear_mask, uint32_t enable_mask, uint32_t disable_mask)
{ {
GPIO_REG_WRITE(GPIO_OUT_W1TS_ADDRESS, set_mask); GPIO_REG_WRITE(GPIO_OUT_W1TS_ADDRESS, set_mask);
GPIO_REG_WRITE(GPIO_OUT_W1TC_ADDRESS, clear_mask); GPIO_REG_WRITE(GPIO_OUT_W1TC_ADDRESS, clear_mask);
@ -95,7 +95,7 @@ void gpio_output_conf(uint32 set_mask, uint32 clear_mask, uint32 enable_mask, ui
/* /*
* Sample the value of GPIO input pins and returns a bitmask. * Sample the value of GPIO input pins and returns a bitmask.
*/ */
uint32 gpio_input_get(void) uint32_t gpio_input_get(void)
{ {
return GPIO_REG_READ(GPIO_IN_ADDRESS); return GPIO_REG_READ(GPIO_IN_ADDRESS);
} }
@ -119,9 +119,9 @@ void gpio_intr_handler_register(void* fn, void* arg)
/* /*
only highlevel and lowlevel intr can use for wakeup only highlevel and lowlevel intr can use for wakeup
*/ */
void gpio_pin_wakeup_enable(uint32 i, GPIO_INT_TYPE intr_state) void gpio_pin_wakeup_enable(uint32_t i, GPIO_INT_TYPE intr_state)
{ {
uint32 pin_reg; uint32_t pin_reg;
if ((intr_state == GPIO_PIN_INTR_LOLEVEL) || (intr_state == GPIO_PIN_INTR_HILEVEL)) { if ((intr_state == GPIO_PIN_INTR_LOLEVEL) || (intr_state == GPIO_PIN_INTR_HILEVEL)) {
portENTER_CRITICAL(); portENTER_CRITICAL();
@ -138,8 +138,8 @@ void gpio_pin_wakeup_enable(uint32 i, GPIO_INT_TYPE intr_state)
void gpio_pin_wakeup_disable(void) void gpio_pin_wakeup_disable(void)
{ {
uint8 i; uint8_t i;
uint32 pin_reg; uint32_t pin_reg;
for (i = 0; i < GPIO_PIN_COUNT; i++) { for (i = 0; i < GPIO_PIN_COUNT; i++) {
pin_reg = GPIO_REG_READ(GPIO_PIN_ADDR(i)); pin_reg = GPIO_REG_READ(GPIO_PIN_ADDR(i));
@ -153,9 +153,9 @@ void gpio_pin_wakeup_disable(void)
} }
} }
void gpio_pin_intr_state_set(uint32 i, GPIO_INT_TYPE intr_state) void gpio_pin_intr_state_set(uint32_t i, GPIO_INT_TYPE intr_state)
{ {
uint32 pin_reg; uint32_t pin_reg;
portENTER_CRITICAL(); portENTER_CRITICAL();
@ -170,34 +170,34 @@ void gpio_pin_intr_state_set(uint32 i, GPIO_INT_TYPE intr_state)
void gpio16_output_conf(void) void gpio16_output_conf(void)
{ {
WRITE_PERI_REG(PAD_XPD_DCDC_CONF, WRITE_PERI_REG(PAD_XPD_DCDC_CONF,
(READ_PERI_REG(PAD_XPD_DCDC_CONF) & 0xffffffbc) | (uint32)0x1); // mux configuration for XPD_DCDC to output rtc_gpio0 (READ_PERI_REG(PAD_XPD_DCDC_CONF) & 0xffffffbc) | (uint32_t)0x1); // mux configuration for XPD_DCDC to output rtc_gpio0
WRITE_PERI_REG(RTC_GPIO_CONF, WRITE_PERI_REG(RTC_GPIO_CONF,
(READ_PERI_REG(RTC_GPIO_CONF) & (uint32)0xfffffffe) | (uint32)0x0); //mux configuration for out enable (READ_PERI_REG(RTC_GPIO_CONF) & (uint32_t)0xfffffffe) | (uint32_t)0x0); //mux configuration for out enable
WRITE_PERI_REG(RTC_GPIO_ENABLE, WRITE_PERI_REG(RTC_GPIO_ENABLE,
(READ_PERI_REG(RTC_GPIO_ENABLE) & (uint32)0xfffffffe) | (uint32)0x1); //out enable (READ_PERI_REG(RTC_GPIO_ENABLE) & (uint32_t)0xfffffffe) | (uint32_t)0x1); //out enable
} }
void gpio16_output_set(uint8 value) void gpio16_output_set(uint8_t value)
{ {
WRITE_PERI_REG(RTC_GPIO_OUT, WRITE_PERI_REG(RTC_GPIO_OUT,
(READ_PERI_REG(RTC_GPIO_OUT) & (uint32)0xfffffffe) | (uint32)(value & 1)); (READ_PERI_REG(RTC_GPIO_OUT) & (uint32_t)0xfffffffe) | (uint32_t)(value & 1));
} }
void gpio16_input_conf(void) void gpio16_input_conf(void)
{ {
WRITE_PERI_REG(PAD_XPD_DCDC_CONF, WRITE_PERI_REG(PAD_XPD_DCDC_CONF,
(READ_PERI_REG(PAD_XPD_DCDC_CONF) & 0xffffffbc) | (uint32)0x1); // mux configuration for XPD_DCDC and rtc_gpio0 connection (READ_PERI_REG(PAD_XPD_DCDC_CONF) & 0xffffffbc) | (uint32_t)0x1); // mux configuration for XPD_DCDC and rtc_gpio0 connection
WRITE_PERI_REG(RTC_GPIO_CONF, WRITE_PERI_REG(RTC_GPIO_CONF,
(READ_PERI_REG(RTC_GPIO_CONF) & (uint32)0xfffffffe) | (uint32)0x0); //mux configuration for out enable (READ_PERI_REG(RTC_GPIO_CONF) & (uint32_t)0xfffffffe) | (uint32_t)0x0); //mux configuration for out enable
WRITE_PERI_REG(RTC_GPIO_ENABLE, WRITE_PERI_REG(RTC_GPIO_ENABLE,
READ_PERI_REG(RTC_GPIO_ENABLE) & (uint32)0xfffffffe); //out disable READ_PERI_REG(RTC_GPIO_ENABLE) & (uint32_t)0xfffffffe); //out disable
} }
uint8 gpio16_input_get(void) uint8_t gpio16_input_get(void)
{ {
return (uint8)(READ_PERI_REG(RTC_GPIO_IN_DATA) & 1); return (uint8_t)(READ_PERI_REG(RTC_GPIO_IN_DATA) & 1);
} }

View File

@ -59,7 +59,7 @@ void hw_timer_disarm(void)
RTC_REG_WRITE(FRC1_CTRL_ADDRESS, 0); RTC_REG_WRITE(FRC1_CTRL_ADDRESS, 0);
} }
void hw_timer_arm(uint32 val, bool req) void hw_timer_arm(uint32_t val, bool req)
{ {
frc1_auto_load = req; frc1_auto_load = req;
@ -102,18 +102,18 @@ void hw_timer_init(void)
#if 0 #if 0
#include "hw_timer.h" #include "hw_timer.h"
#define REG_WRITE(_r,_v) (*(volatile uint32 *)(_r)) = (_v) #define REG_WRITE(_r,_v) (*(volatile uint32_t *)(_r)) = (_v)
#define REG_READ(_r) (*(volatile uint32 *)(_r)) #define REG_READ(_r) (*(volatile uint32_t *)(_r))
#define WDEV_NOW() REG_READ(0x3ff20c00) #define WDEV_NOW() REG_READ(0x3ff20c00)
uint32 tick_now2 = 0; uint32_t tick_now2 = 0;
void hw_test_timer_cb(void) void hw_test_timer_cb(void)
{ {
static uint16 j = 0; static uint16 j = 0;
j++; j++;
if ((WDEV_NOW() - tick_now2) >= 1000000) { if ((WDEV_NOW() - tick_now2) >= 1000000) {
static uint32 idx = 1; static uint32_t idx = 1;
tick_now2 = WDEV_NOW(); tick_now2 = WDEV_NOW();
os_printf("b%u:%d\n", idx++, j); os_printf("b%u:%d\n", idx++, j);
j = 0; j = 0;

View File

@ -20,18 +20,18 @@
#include "i2c_master.h" #include "i2c_master.h"
static uint8 m_nLastSDA; static uint8_t m_nLastSDA;
static uint8 m_nLastSCL; static uint8_t m_nLastSCL;
/****************************************************************************** /******************************************************************************
* FunctionName : i2c_master_setDC * FunctionName : i2c_master_setDC
* Description : Internal used function - * Description : Internal used function -
* set i2c SDA and SCL bit value for half clk cycle * set i2c SDA and SCL bit value for half clk cycle
* Parameters : uint8 SDA * Parameters : uint8_t SDA
* uint8 SCL * uint8_t SCL
* Returns : NONE * Returns : NONE
*******************************************************************************/ *******************************************************************************/
static void i2c_master_setDC(uint8 SDA, uint8 SCL) static void i2c_master_setDC(uint8_t SDA, uint8_t SCL)
{ {
SDA &= 0x01; SDA &= 0x01;
SCL &= 0x01; SCL &= 0x01;
@ -57,11 +57,11 @@ static void i2c_master_setDC(uint8 SDA, uint8 SCL)
* Description : Internal used function - * Description : Internal used function -
* get i2c SDA bit value * get i2c SDA bit value
* Parameters : NONE * Parameters : NONE
* Returns : uint8 - SDA bit value * Returns : uint8_t - SDA bit value
*******************************************************************************/ *******************************************************************************/
static uint8 i2c_master_getDC(void) static uint8_t i2c_master_getDC(void)
{ {
uint8 sda_out; uint8_t sda_out;
ETS_INTR_LOCK(); ETS_INTR_LOCK();
sda_out = GPIO_INPUT_GET(GPIO_ID_PIN(I2C_MASTER_SDA_GPIO)); sda_out = GPIO_INPUT_GET(GPIO_ID_PIN(I2C_MASTER_SDA_GPIO));
ETS_INTR_UNLOCK(); ETS_INTR_UNLOCK();
@ -76,7 +76,7 @@ static uint8 i2c_master_getDC(void)
*******************************************************************************/ *******************************************************************************/
void i2c_master_init(void) void i2c_master_init(void)
{ {
uint8 i; uint8_t i;
i2c_master_setDC(1, 0); i2c_master_setDC(1, 0);
i2c_master_wait(5); i2c_master_wait(5);
@ -165,10 +165,10 @@ void i2c_master_stop(void)
/****************************************************************************** /******************************************************************************
* FunctionName : i2c_master_setAck * FunctionName : i2c_master_setAck
* Description : set ack to i2c bus as level value * Description : set ack to i2c bus as level value
* Parameters : uint8 level - 0 or 1 * Parameters : uint8_t level - 0 or 1
* Returns : NONE * Returns : NONE
*******************************************************************************/ *******************************************************************************/
void i2c_master_setAck(uint8 level) void i2c_master_setAck(uint8_t level)
{ {
i2c_master_setDC(m_nLastSDA, 0); i2c_master_setDC(m_nLastSDA, 0);
i2c_master_wait(5); i2c_master_wait(5);
@ -186,11 +186,11 @@ void i2c_master_setAck(uint8 level)
* FunctionName : i2c_master_getAck * FunctionName : i2c_master_getAck
* Description : confirm if peer send ack * Description : confirm if peer send ack
* Parameters : NONE * Parameters : NONE
* Returns : uint8 - ack value, 0 or 1 * Returns : uint8_t - ack value, 0 or 1
*******************************************************************************/ *******************************************************************************/
uint8 i2c_master_getAck(void) uint8_t i2c_master_getAck(void)
{ {
uint8 retVal; uint8_t retVal;
i2c_master_setDC(m_nLastSDA, 0); i2c_master_setDC(m_nLastSDA, 0);
i2c_master_wait(5); i2c_master_wait(5);
i2c_master_setDC(1, 0); i2c_master_setDC(1, 0);
@ -247,12 +247,12 @@ void i2c_master_send_nack(void)
* FunctionName : i2c_master_readByte * FunctionName : i2c_master_readByte
* Description : read Byte from i2c bus * Description : read Byte from i2c bus
* Parameters : NONE * Parameters : NONE
* Returns : uint8 - readed value * Returns : uint8_t - readed value
*******************************************************************************/ *******************************************************************************/
uint8 i2c_master_readByte(void) uint8_t i2c_master_readByte(void)
{ {
uint8 retVal = 0; uint8_t retVal = 0;
uint8 k, i; uint8_t k, i;
i2c_master_wait(5); i2c_master_wait(5);
i2c_master_setDC(m_nLastSDA, 0); i2c_master_setDC(m_nLastSDA, 0);
@ -285,13 +285,13 @@ uint8 i2c_master_readByte(void)
/****************************************************************************** /******************************************************************************
* FunctionName : i2c_master_writeByte * FunctionName : i2c_master_writeByte
* Description : write wrdata value(one byte) into i2c * Description : write wrdata value(one byte) into i2c
* Parameters : uint8 wrdata - write value * Parameters : uint8_t wrdata - write value
* Returns : NONE * Returns : NONE
*******************************************************************************/ *******************************************************************************/
void i2c_master_writeByte(uint8 wrdata) void i2c_master_writeByte(uint8_t wrdata)
{ {
uint8 dat; uint8_t dat;
sint8 i; int8_t i;
i2c_master_wait(5); i2c_master_wait(5);

View File

@ -457,7 +457,7 @@ void SPIMasterSendStatus(SpiNum spiNum, uint8_t data)
SET_PERI_REG_BITS(SPI_USER1(spiNum), SPI_USR_MOSI_BITLEN, SET_PERI_REG_BITS(SPI_USER1(spiNum), SPI_USR_MOSI_BITLEN,
((sizeof(data) << 3) - 1), SPI_USR_MOSI_BITLEN_S); ((sizeof(data) << 3) - 1), SPI_USR_MOSI_BITLEN_S);
WRITE_PERI_REG(SPI_W0(spiNum), (uint32)(data)); WRITE_PERI_REG(SPI_W0(spiNum), (uint32_t)(data));
// Start SPI // Start SPI
SET_PERI_REG_MASK(SPI_CMD(spiNum), SPI_USR); SET_PERI_REG_MASK(SPI_CMD(spiNum), SPI_USR);
@ -496,7 +496,7 @@ int SPIMasterRecvStatus(SpiNum spiNum)
(void)(READ_PERI_REG(SPI_W0(spiNum)) & 0xff); (void)(READ_PERI_REG(SPI_W0(spiNum)) & 0xff);
SHOWREG(); SHOWREG();
return (uint8)(READ_PERI_REG(SPI_W0(spiNum)) & 0xff); return (uint8_t)(READ_PERI_REG(SPI_W0(spiNum)) & 0xff);
} }
/** /**

View File

@ -27,17 +27,17 @@ enum {
}; };
typedef struct _os_event_ { typedef struct _os_event_ {
uint32 event; uint32_t event;
uint32 param; uint32_t param;
} os_event_t; } os_event_t;
xTaskHandle xUartTaskHandle; xTaskHandle xUartTaskHandle;
xQueueHandle xQueueUart; xQueueHandle xQueueUart;
static STATUS uart_tx_one_char(uint8 uart, uint8 TxChar) static STATUS uart_tx_one_char(uint8_t uart, uint8_t TxChar)
{ {
while (true) { while (true) {
uint32 fifo_cnt = READ_PERI_REG(UART_STATUS(uart)) & (UART_TXFIFO_CNT << UART_TXFIFO_CNT_S); uint32_t fifo_cnt = READ_PERI_REG(UART_STATUS(uart)) & (UART_TXFIFO_CNT << UART_TXFIFO_CNT_S);
if ((fifo_cnt >> UART_TXFIFO_CNT_S & UART_TXFIFO_CNT) < 126) { if ((fifo_cnt >> UART_TXFIFO_CNT_S & UART_TXFIFO_CNT) < 126) {
break; break;
@ -79,8 +79,8 @@ static void uart_rx_intr_handler_ssc(void *arg)
os_event_t e; os_event_t e;
portBASE_TYPE xHigherPriorityTaskWoken; portBASE_TYPE xHigherPriorityTaskWoken;
uint8 RcvChar; uint8_t RcvChar;
uint8 uart_no = 0; uint8_t uart_no = 0;
if (UART_RXFIFO_FULL_INT_ST != (READ_PERI_REG(UART_INT_ST(uart_no)) & UART_RXFIFO_FULL_INT_ST)) { if (UART_RXFIFO_FULL_INT_ST != (READ_PERI_REG(UART_INT_ST(uart_no)) & UART_RXFIFO_FULL_INT_ST)) {
return; return;
@ -97,7 +97,7 @@ static void uart_rx_intr_handler_ssc(void *arg)
portEND_SWITCHING_ISR(xHigherPriorityTaskWoken); portEND_SWITCHING_ISR(xHigherPriorityTaskWoken);
} }
static void uart_config(uint8 uart_no, UartDevice *uart) static void uart_config(uint8_t uart_no, UartDevice *uart)
{ {
if (uart_no == UART1) { if (uart_no == UART1) {
PIN_FUNC_SELECT(PERIPHS_IO_MUX_GPIO2_U, FUNC_U1TXD_BK); PIN_FUNC_SELECT(PERIPHS_IO_MUX_GPIO2_U, FUNC_U1TXD_BK);
@ -180,7 +180,7 @@ void uart_init(void)
xQueueUart = xQueueCreate(32, sizeof(os_event_t)); xQueueUart = xQueueCreate(32, sizeof(os_event_t));
xTaskCreate(uart_task, (uint8 const*)"uTask", 512, NULL, tskIDLE_PRIORITY + 2, &xUartTaskHandle); xTaskCreate(uart_task, (uint8_t const*)"uTask", 512, NULL, tskIDLE_PRIORITY + 2, &xUartTaskHandle);
} }
#endif #endif
@ -212,13 +212,13 @@ void UART_SetParity(UART_Port uart_no, UART_ParityMode Parity_mode)
} }
} }
void UART_SetBaudrate(UART_Port uart_no, uint32 baud_rate) void UART_SetBaudrate(UART_Port uart_no, uint32_t baud_rate)
{ {
uart_div_modify(uart_no, UART_CLK_FREQ / baud_rate); uart_div_modify(uart_no, UART_CLK_FREQ / baud_rate);
} }
//only when USART_HardwareFlowControl_RTS is set , will the rx_thresh value be set. //only when USART_HardwareFlowControl_RTS is set , will the rx_thresh value be set.
void UART_SetFlowCtrl(UART_Port uart_no, UART_HwFlowCtrl flow_ctrl, uint8 rx_thresh) void UART_SetFlowCtrl(UART_Port uart_no, UART_HwFlowCtrl flow_ctrl, uint8_t rx_thresh)
{ {
if (flow_ctrl & USART_HardwareFlowControl_RTS) { if (flow_ctrl & USART_HardwareFlowControl_RTS) {
PIN_FUNC_SELECT(PERIPHS_IO_MUX_MTDO_U, FUNC_U0RTS); PIN_FUNC_SELECT(PERIPHS_IO_MUX_MTDO_U, FUNC_U0RTS);
@ -247,12 +247,12 @@ void UART_ResetFifo(UART_Port uart_no)
CLEAR_PERI_REG_MASK(UART_CONF0(uart_no), UART_RXFIFO_RST | UART_TXFIFO_RST); CLEAR_PERI_REG_MASK(UART_CONF0(uart_no), UART_RXFIFO_RST | UART_TXFIFO_RST);
} }
void UART_ClearIntrStatus(UART_Port uart_no, uint32 clr_mask) void UART_ClearIntrStatus(UART_Port uart_no, uint32_t clr_mask)
{ {
WRITE_PERI_REG(UART_INT_CLR(uart_no), clr_mask); WRITE_PERI_REG(UART_INT_CLR(uart_no), clr_mask);
} }
void UART_SetIntrEna(UART_Port uart_no, uint32 ena_mask) void UART_SetIntrEna(UART_Port uart_no, uint32_t ena_mask)
{ {
SET_PERI_REG_MASK(UART_INT_ENA(uart_no), ena_mask); SET_PERI_REG_MASK(UART_INT_ENA(uart_no), ena_mask);
} }
@ -297,7 +297,7 @@ void UART_ParamConfig(UART_Port uart_no, UART_ConfigTypeDef* pUARTConfig)
void UART_IntrConfig(UART_Port uart_no, UART_IntrConfTypeDef* pUARTIntrConf) void UART_IntrConfig(UART_Port uart_no, UART_IntrConfTypeDef* pUARTIntrConf)
{ {
uint32 reg_val = 0; uint32_t reg_val = 0;
UART_ClearIntrStatus(uart_no, UART_INTR_MASK); UART_ClearIntrStatus(uart_no, UART_INTR_MASK);
reg_val = READ_PERI_REG(UART_CONF1(uart_no)) & ((UART_RX_FLOW_THRHD << UART_RX_FLOW_THRHD_S) | UART_RX_FLOW_EN) ; reg_val = READ_PERI_REG(UART_CONF1(uart_no)) & ((UART_RX_FLOW_THRHD << UART_RX_FLOW_THRHD_S) | UART_RX_FLOW_EN) ;
@ -320,11 +320,11 @@ static void uart0_rx_intr_handler(void* para)
/* uart0 and uart1 intr combine togther, when interrupt occur, see reg 0x3ff20020, bit2, bit0 represents /* uart0 and uart1 intr combine togther, when interrupt occur, see reg 0x3ff20020, bit2, bit0 represents
* uart1 and uart0 respectively * uart1 and uart0 respectively
*/ */
uint8 uart_no = UART0;//UartDev.buff_uart_no; uint8_t uart_no = UART0;//UartDev.buff_uart_no;
uint8 fifo_len = 0; uint8_t fifo_len = 0;
uint8 buf_idx = 0; uint8_t buf_idx = 0;
uint32 uart_intr_status = READ_PERI_REG(UART_INT_ST(uart_no)) ; uint32_t uart_intr_status = READ_PERI_REG(UART_INT_ST(uart_no)) ;
while (uart_intr_status != 0x0) { while (uart_intr_status != 0x0) {
if (UART_FRM_ERR_INT_ST == (uart_intr_status & UART_FRM_ERR_INT_ST)) { if (UART_FRM_ERR_INT_ST == (uart_intr_status & UART_FRM_ERR_INT_ST)) {

View File

@ -19,6 +19,8 @@
extern "C" { extern "C" {
#endif #endif
#include <stdint.h>
#include "esp8266/gpio_register.h" #include "esp8266/gpio_register.h"
#define ETS_GPIO_INTR_ENABLE() _xt_isr_unmask(1 << ETS_GPIO_INUM) #define ETS_GPIO_INTR_ENABLE() _xt_isr_unmask(1 << ETS_GPIO_INUM)
@ -106,7 +108,7 @@ typedef enum {
} GPIO_Pullup_IF; } GPIO_Pullup_IF;
typedef struct { typedef struct {
uint16 GPIO_Pin; /**< GPIO pin */ uint16_t GPIO_Pin; /**< GPIO pin */
GPIOMode_TypeDef GPIO_Mode; /**< GPIO mode */ GPIOMode_TypeDef GPIO_Mode; /**< GPIO mode */
GPIO_Pullup_IF GPIO_Pullup; /**< GPIO pullup */ GPIO_Pullup_IF GPIO_Pullup; /**< GPIO pullup */
GPIO_INT_TYPE GPIO_IntrType; /**< GPIO interrupt type */ GPIO_INT_TYPE GPIO_IntrType; /**< GPIO interrupt type */
@ -199,11 +201,11 @@ void gpio16_output_conf(void);
/** /**
* @brief Set GPIO16 output level. * @brief Set GPIO16 output level.
* *
* @param uint8 value : GPIO16 output level. * @param uint8_t value : GPIO16 output level.
* *
* @return null * @return null
*/ */
void gpio16_output_set(uint8 value); void gpio16_output_set(uint8_t value);
/** /**
* @brief Enable GPIO pin intput. * @brief Enable GPIO pin intput.
@ -221,23 +223,23 @@ void gpio16_input_conf(void);
* *
* @return the level of GPIO16 input. * @return the level of GPIO16 input.
*/ */
uint8 gpio16_input_get(void); uint8_t gpio16_input_get(void);
/** /**
* @brief Configure Gpio pins out or input. * @brief Configure Gpio pins out or input.
* *
* @param uint32 set_mask : Set the output for the high bit, the * @param uint32_t set_mask : Set the output for the high bit, the
* corresponding bit is 1, the output of high, * corresponding bit is 1, the output of high,
* the corresponding bit is 0, do not change the state. * the corresponding bit is 0, do not change the state.
* @param uint32 set_mask : Set the output for the high bit, the * @param uint32_t set_mask : Set the output for the high bit, the
* corresponding bit is 1, the output of low, * corresponding bit is 1, the output of low,
* the corresponding bit is 0, do not change the state. * the corresponding bit is 0, do not change the state.
* @param uint32 enable_mask : Enable Output * @param uint32_t enable_mask : Enable Output
* @param uint32 disable_mask : Enable Input * @param uint32_t disable_mask : Enable Input
* *
* @return null * @return null
*/ */
void gpio_output_conf(uint32 set_mask, uint32 clear_mask, uint32 enable_mask, uint32 disable_mask); void gpio_output_conf(uint32_t set_mask, uint32_t clear_mask, uint32_t enable_mask, uint32_t disable_mask);
/** /**
* @brief Register an application-specific interrupt handler for GPIO pin interrupts. * @brief Register an application-specific interrupt handler for GPIO pin interrupts.
@ -252,12 +254,12 @@ void gpio_intr_handler_register(void* fn, void* arg);
/** /**
* @brief Configure GPIO wake up to light sleep,Only level way is effective. * @brief Configure GPIO wake up to light sleep,Only level way is effective.
* *
* @param uint32 i : Gpio sequence number * @param uint32_t i : Gpio sequence number
* @param GPIO_INT_TYPE intr_state : the level of wake up to light sleep * @param GPIO_INT_TYPE intr_state : the level of wake up to light sleep
* *
* @return null * @return null
*/ */
void gpio_pin_wakeup_enable(uint32 i, GPIO_INT_TYPE intr_state); void gpio_pin_wakeup_enable(uint32_t i, GPIO_INT_TYPE intr_state);
/** /**
* @brief Disable GPIO wake up to light sleep. * @brief Disable GPIO wake up to light sleep.
@ -271,12 +273,12 @@ void gpio_pin_wakeup_disable();
/** /**
* @brief Config interrupt types of GPIO pin. * @brief Config interrupt types of GPIO pin.
* *
* @param uint32 i : The GPIO sequence number. * @param uint32_t i : The GPIO sequence number.
* @param GPIO_INT_TYPE intr_state : GPIO interrupt types. * @param GPIO_INT_TYPE intr_state : GPIO interrupt types.
* *
* @return null * @return null
*/ */
void gpio_pin_intr_state_set(uint32 i, GPIO_INT_TYPE intr_state); void gpio_pin_intr_state_set(uint32_t i, GPIO_INT_TYPE intr_state);
/** /**
* @brief Sample the value of GPIO input pins and returns a bitmask. * @brief Sample the value of GPIO input pins and returns a bitmask.
@ -285,7 +287,7 @@ void gpio_pin_intr_state_set(uint32 i, GPIO_INT_TYPE intr_state);
* *
* @return bitmask of GPIO pins input * @return bitmask of GPIO pins input
*/ */
uint32 gpio_input_get(void); uint32_t gpio_input_get(void);
/** /**
* @} * @}

View File

@ -43,15 +43,15 @@ void hw_timer_init(void);
/** /**
* @brief Set a trigger timer delay to enable this timer. * @brief Set a trigger timer delay to enable this timer.
* *
* @param uint32 val : Timing * @param uint32_t val : Timing
* - In autoload mode, range : 50 ~ 0x7fffff * - In autoload mode, range : 50 ~ 0x7fffff
* - In non-autoload mode, range : 10 ~ 0x7fffff * - In non-autoload mode, range : 10 ~ 0x7fffff
* *
* @param uint8 req : 0, not autoload; 1, autoload mode. * @param uint8_t req : 0, not autoload; 1, autoload mode.
* *
* @return null * @return null
*/ */
void hw_timer_arm(uint32 val, bool req); void hw_timer_arm(uint32_t val, bool req);
/** /**
* @brief disable this timer. * @brief disable this timer.
@ -67,7 +67,7 @@ void hw_timer_disarm(void);
* *
* For enabled timer, timer callback has to be set. * For enabled timer, timer callback has to be set.
* *
* @param uint32 val : Timing * @param uint32_t val : Timing
* - In autoload mode, range : 50 ~ 0x7fffff * - In autoload mode, range : 50 ~ 0x7fffff
* - In non-autoload mode, range : 10 ~ 0x7fffff * - In non-autoload mode, range : 10 ~ 0x7fffff
* *

View File

@ -117,7 +117,7 @@ void i2c_master_start(void);
* *
* @return null * @return null
*/ */
void i2c_master_setAck(uint8 level); void i2c_master_setAck(uint8_t level);
/** /**
* @brief confirm if peer send ack. * @brief confirm if peer send ack.
@ -126,7 +126,7 @@ void i2c_master_setAck(uint8 level);
* *
* @return null * @return null
*/ */
uint8 i2c_master_getAck(void); uint8_t i2c_master_getAck(void);
/** /**
* @brief read Byte from i2c bus. * @brief read Byte from i2c bus.
@ -135,16 +135,16 @@ uint8 i2c_master_getAck(void);
* *
* @return the byte which read from i2c bus. * @return the byte which read from i2c bus.
*/ */
uint8 i2c_master_readByte(void); uint8_t i2c_master_readByte(void);
/** /**
* @brief write wrdata value(one byte) into i2c. * @brief write wrdata value(one byte) into i2c.
* *
* @param uint8 wrdata:write value * @param uint8_t wrdata:write value
* *
* @return null * @return null
*/ */
void i2c_master_writeByte(uint8 wrdata); void i2c_master_writeByte(uint8_t wrdata);
/** /**
* @brief i2c_master_checkAck. * @brief i2c_master_checkAck.

View File

@ -93,15 +93,15 @@ typedef struct {
UART_ParityMode parity; // chip size in byte UART_ParityMode parity; // chip size in byte
UART_StopBits stop_bits; UART_StopBits stop_bits;
UART_HwFlowCtrl flow_ctrl; UART_HwFlowCtrl flow_ctrl;
uint8 UART_RxFlowThresh ; uint8_t UART_RxFlowThresh ;
uint32 UART_InverseMask; uint32_t UART_InverseMask;
} UART_ConfigTypeDef; } UART_ConfigTypeDef;
typedef struct { typedef struct {
uint32 UART_IntrEnMask; uint32_t UART_IntrEnMask;
uint8 UART_RX_TimeOutIntrThresh; uint8_t UART_RX_TimeOutIntrThresh;
uint8 UART_TX_FifoEmptyIntrThresh; uint8_t UART_TX_FifoEmptyIntrThresh;
uint8 UART_RX_FifoFullIntrThresh; uint8_t UART_RX_FifoFullIntrThresh;
} UART_IntrConfTypeDef; } UART_IntrConfTypeDef;
//======================================= //=======================================
@ -144,21 +144,21 @@ void UART_ResetFifo(UART_Port uart_no);
* @brief Clear uart interrupt flags. * @brief Clear uart interrupt flags.
* *
* @param UART_Port uart_no : UART0 or UART1 * @param UART_Port uart_no : UART0 or UART1
* @param uint32 clr_mask : To clear the interrupt bits * @param uint32_t clr_mask : To clear the interrupt bits
* *
* @return null * @return null
*/ */
void UART_ClearIntrStatus(UART_Port uart_no, uint32 clr_mask); void UART_ClearIntrStatus(UART_Port uart_no, uint32_t clr_mask);
/** /**
* @brief Enable uart interrupts . * @brief Enable uart interrupts .
* *
* @param UART_Port uart_no : UART0 or UART1 * @param UART_Port uart_no : UART0 or UART1
* @param uint32 ena_mask : To enable the interrupt bits * @param uint32_t ena_mask : To enable the interrupt bits
* *
* @return null * @return null
*/ */
void UART_SetIntrEna(UART_Port uart_no, uint32 ena_mask); void UART_SetIntrEna(UART_Port uart_no, uint32_t ena_mask);
/** /**
* @brief Register an application-specific interrupt handler for Uarts interrupts. * @brief Register an application-specific interrupt handler for Uarts interrupts.
@ -233,22 +233,22 @@ void UART_SetParity(UART_Port uart_no, UART_ParityMode Parity_mode) ;
* @brief Configure the Baud rate. * @brief Configure the Baud rate.
* *
* @param UART_Port uart_no : UART0 or UART1 * @param UART_Port uart_no : UART0 or UART1
* @param uint32 baud_rate : the Baud rate * @param uint32_t baud_rate : the Baud rate
* *
* @return null * @return null
*/ */
void UART_SetBaudrate(UART_Port uart_no, uint32 baud_rate); void UART_SetBaudrate(UART_Port uart_no, uint32_t baud_rate);
/** /**
* @brief Configure Hardware flow control. * @brief Configure Hardware flow control.
* *
* @param UART_Port uart_no : UART0 or UART1 * @param UART_Port uart_no : UART0 or UART1
* @param UART_HwFlowCtrl flow_ctrl : Hardware flow control mode * @param UART_HwFlowCtrl flow_ctrl : Hardware flow control mode
* @param uint8 rx_thresh : threshold of Hardware flow control * @param uint8_t rx_thresh : threshold of Hardware flow control
* *
* @return null * @return null
*/ */
void UART_SetFlowCtrl(UART_Port uart_no, UART_HwFlowCtrl flow_ctrl, uint8 rx_thresh); void UART_SetFlowCtrl(UART_Port uart_no, UART_HwFlowCtrl flow_ctrl, uint8_t rx_thresh);
/** /**
* @brief Configure trigging signal of uarts. * @brief Configure trigging signal of uarts.