未验证 提交 5a61304a 编写于 作者: T Tuber 提交者: GitHub

add ch579m bsp (#5600)

* add ch579m bsp

Author:    Tuber <tuber@xyza.cn>
Date:      Wed Feb 16 07:20:23 2022 +0000

* fix uart reg value error and format code

* change file encode to utf-8
上级 89bf823f
此差异已折叠。
mainmenu "RT-Thread Configuration"
config BSP_DIR
string
option env="BSP_ROOT"
default "."
config RTT_DIR
string
option env="RTT_ROOT"
default "../../../.."
config PKGS_DIR
string
option env="PKGS_ROOT"
default "packages"
source "$RTT_DIR/Kconfig"
source "$PKGS_DIR/Kconfig"
source "board/Kconfig"
# for module compiling
import os
Import('RTT_ROOT')
from building import *
cwd = GetCurrentDir()
objs = []
list = os.listdir(cwd)
for d in list:
path = os.path.join(cwd, d)
if os.path.isfile(os.path.join(path, 'SConscript')):
objs = objs + SConscript(os.path.join(d, 'SConscript'))
Return('objs')
import os
import sys
import rtconfig
if os.getenv('RTT_ROOT'):
RTT_ROOT = os.getenv('RTT_ROOT')
else:
RTT_ROOT = os.path.normpath(os.getcwd() + '/../../../..')
sys.path = sys.path + [os.path.join(RTT_ROOT, 'tools')]
try:
from building import *
except:
print('Cannot found RT-Thread root directory, please check RTT_ROOT')
print(RTT_ROOT)
exit(-1)
TARGET = 'rtthread.' + rtconfig.TARGET_EXT
DefaultEnvironment(tools=[])
env = Environment(tools = ['mingw'],
AS = rtconfig.AS, ASFLAGS = rtconfig.AFLAGS,
CC = rtconfig.CC, CCFLAGS = rtconfig.CFLAGS,
AR = rtconfig.AR, ARFLAGS = '-rc',
LINK = rtconfig.LINK, LINKFLAGS = rtconfig.LFLAGS)
env.PrependENVPath('PATH', rtconfig.EXEC_PATH)
if rtconfig.PLATFORM == 'iar':
env.Replace(CCCOM = ['$CC $CCFLAGS $CPPFLAGS $_CPPDEFFLAGS $_CPPINCFLAGS -o $TARGET $SOURCES'])
env.Replace(ARFLAGS = [''])
env.Replace(LINKCOM = env["LINKCOM"] + ' --map project.map')
Export('RTT_ROOT')
Export('rtconfig')
# prepare building environment
objs = PrepareBuilding(env, RTT_ROOT, has_libcpu=False)
# make a building
DoBuilding(TARGET, objs)
# RT-Thread building script for component
Import('RTT_ROOT')
Import('rtconfig')
from building import *
cwd = GetCurrentDir()
# add the general drivers.
src = Split("""
main.c
""")
CPPPATH = [cwd, str(Dir('#'))]
group = DefineGroup('Applications', src, depend = [''], CPPPATH = CPPPATH)
Return('group')
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2018-11-06 SummerGift change to new framework
*/
#include <rtthread.h>
#include <rtdevice.h>
#include <board.h>
int main(void)
{
return RT_EOK;
}
menu "Hardware Drivers Config"
config SOC_CH579M
bool
select RT_USING_USER_MAIN
select RT_USING_COMPONENTS_INIT
default y
menu "On-chip Peripheral Drivers"
menuconfig BSP_USING_UART
bool "Enable UART"
default y
select RT_USING_SERIAL
if BSP_USING_UART
config BSP_USING_UART0
bool "Enable UART0"
default n
config BSP_USING_UART1
bool "Enable UART1"
default y
config BSP_USING_UART2
bool "Enable UART2"
default n
config BSP_USING_UART3
bool "Enable UART3"
default n
endif
config BSP_USING_USBH
bool "Enable USBH"
default n
select RT_USING_USB_HOST
config BSP_USING_ETH
bool "Enable ETH"
default n
select RT_USING_LWIP
endmenu
endmenu
Import('RTT_ROOT')
Import('rtconfig')
from building import *
cwd = GetCurrentDir()
src = Glob('*.c')
CPPPATH = [cwd]
group = DefineGroup('Drivers', src, depend = [''], CPPPATH = CPPPATH)
Return('group')
\ No newline at end of file
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2022-02-16 Tuber first version
*/
#include <rtthread.h>
#include <rtdevice.h>
#include <rthw.h>
#include "board.h"
#ifdef RT_USING_SERIAL
#include "drv_uart.h"
#endif
#ifdef RT_USING_FINSH
#include <finsh.h>
static void reboot(uint8_t argc, char **argv)
{
rt_hw_cpu_reset();
}
MSH_CMD_EXPORT(reboot, Reboot System)
#endif /* RT_USING_FINSH */
void SysTick_Handler(void)
{
/* enter interrupt */
rt_interrupt_enter();
rt_tick_increase();
/* leave interrupt */
rt_interrupt_leave();
}
void rt_hw_board_init()
{
// 打开PLL
PWR_UnitModCfg(ENABLE, UNIT_SYS_PLL);
// 设置外部40M做主频
SetSysClock(CLK_SOURCE_PLL_40MHz);
SysTick_Config(GetSysClock() / RT_TICK_PER_SECOND);
//开启中断
NVIC_SetPriority(SysTick_IRQn, 0);
NVIC_EnableIRQ(SysTick_IRQn);
#if defined(RT_USING_HEAP)
rt_system_heap_init((void *)HEAP_BEGIN, (void *)HEAP_END);
#endif
#ifdef RT_USING_SERIAL
rt_hw_uart_init();
#endif
#ifdef RT_USING_CONSOLE
rt_console_set_device(RT_CONSOLE_DEVICE_NAME);
#endif
#ifdef RT_USING_COMPONENTS_INIT
rt_components_board_init();
#endif
}
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2022-02-16 Tuber first version
*/
#ifndef __BOARD_H__
#define __BOARD_H__
#include "CH57x_common.h"
#define CH579M_FLASH_START_ADRESS ((uint32_t)0x00000000)
#define FLASH_PAGE_SIZE (64)
#define CH579M_FLASH_SIZE (512 * 1024)
#define CH579M_FLASH_END_ADDRESS ((uint32_t)(CH579M_FLASH_START_ADRESS + CH579M_FLASH_SIZE))
#define CH579M_SRAM_SIZE 32
#define CH579M_SRAM_END (0x20000000 + CH579M_SRAM_SIZE * 1024)
#if defined(__CC_ARM) || defined(__CLANG_ARM)
extern int Image$$RW_IRAM1$$ZI$$Limit;
#define HEAP_BEGIN ((void *)&Image$$RW_IRAM1$$ZI$$Limit)
#elif __ICCARM__
#pragma section="CSTACK"
#define HEAP_BEGIN (__segment_end("CSTACK"))
#else
extern int __bss_end;
#define HEAP_BEGIN ((void *)&__bss_end)
#endif
#define HEAP_END CH579M_SRAM_END
#endif /* __BOARD_H__ */
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2022-02-16 Tuber first version
*/
#include <rtthread.h>
#include <rtdevice.h>
#include "board.h"
#include <netif/ethernetif.h>
#include "drv_eth.h"
#ifdef BSP_USING_ETH
static struct eth_device eth_device;
//DMA接收内存区,必须4字节对齐
__align(4) UINT8 eth_dma_tx_buf[ETH_BUF_SIZE];
__align(4) UINT8 eth_dma_rx_buf[ETH_BUF_SIZE];
UINT16 eth_rx_len = 0; //接收状态和长度
UINT8 eth_rx_buf[ETH_BUF_SIZE]; //中间缓冲区
UINT8 eth_mac_addr[] = { 0xAA, 0xBB, 0xCC, 0xDD, 0xEE, 0xFF };
static rt_err_t eth_init(rt_device_t dev)
{
return RT_EOK;
}
static rt_err_t eth_open(rt_device_t dev, rt_uint16_t oflag)
{
return RT_EOK;
}
static rt_err_t eth_close(rt_device_t dev)
{
return RT_EOK;
}
static rt_size_t eth_read(rt_device_t dev, rt_off_t pos, void *buffer, rt_size_t size)
{
rt_set_errno(-RT_ENOSYS);
return 0;
}
static rt_size_t eth_write(rt_device_t dev, rt_off_t pos, const void *buffer, rt_size_t size)
{
rt_set_errno(-RT_ENOSYS);
return 0;
}
static rt_err_t eth_control(rt_device_t dev, int cmd, void *args)
{
switch (cmd)
{
case NIOCTL_GADDR:
/* get mac address */
if (args) rt_memcpy(args, eth_mac_addr, 6);
else return -RT_ERROR;
break;
default :
break;
}
return RT_EOK;
}
rt_err_t eth_tx(rt_device_t dev, struct pbuf *p)
{
//判断eth是否处于发送状态
if ((R8_ETH_ECON1 & RB_ETH_ECON1_TXRTS) != 0x00)
{
return ERR_INPROGRESS;
}
//确定缓冲区是否足够
if (p->tot_len > sizeof(eth_dma_tx_buf))
{
return ERR_MEM;
}
//拷贝数据到dma缓冲区
rt_memcpy(eth_dma_tx_buf, p->payload, p->tot_len);
//设置数据长度
R16_ETH_ETXLN = p->tot_len;
//开始发送
R8_ETH_ECON1 |= RB_ETH_ECON1_TXRTS;
return ERR_OK;
}
struct pbuf *eth_rx(rt_device_t dev)
{
struct pbuf *p = NULL;
//检查是否有数据
if (eth_rx_len == 0)
{
return NULL;
}
p = pbuf_alloc(PBUF_RAW, eth_rx_len, PBUF_POOL);
if (p == NULL)
{
rt_kprintf("eth_rx: pbuf_alloc failed\n");
eth_rx_len = 0;
return NULL;
}
//拷贝数据到pbuf
rt_memcpy((uint8_t *)((uint8_t *)p->payload), (uint8_t *)((uint8_t *)eth_rx_buf), eth_rx_len);
//恢复状态
eth_rx_len = 0;
return p;
}
int read_eth_link_status()
{
R8_ETH_MIREGADR = 0x01;//状态寄存器
R8_ETH_MISTAT |= 0x00; //读MII寄存器
//获取link状态
if ((R16_ETH_MIRD & 0x04) != 0)
{
return 1; //已插入
}
return 0;
}
void ETH_IRQHandler(void) /* 以太网中断 */
{
rt_interrupt_enter();
//接收到数据包
if ((R8_ETH_EIR & RB_ETH_EIR_RXIF) != 0)
{
//判断缓存区是否有数据
if (eth_rx_len == 0)
{
rt_memcpy(eth_rx_buf, eth_dma_rx_buf, R16_ETH_ERXLN);
eth_rx_len = R16_ETH_ERXLN;
//通知拿数据
eth_device_ready(&eth_device);
}
R8_ETH_EIR |= RB_ETH_EIR_RXIF; //清除中断
}
//接收错误
if ((R8_ETH_EIR & RB_ETH_EIE_RXERIE) != 0)
{
R8_ETH_EIR |= RB_ETH_EIE_RXERIE; //清除中断
}
//发送完成
if ((R8_ETH_EIR & RB_ETH_EIR_TXIF) != 0)
{
R8_ETH_EIR |= RB_ETH_EIR_TXIF; //清除中断
}
//发送错误
if ((R8_ETH_EIR & RB_ETH_EIE_TXERIE) != 0)
{
R8_ETH_EIR |= RB_ETH_EIE_TXERIE; //清除中断
}
//Link 变化标志
if ((R8_ETH_EIR & RB_ETH_EIR_LINKIF) != 0)
{
//获取连接状态
if (read_eth_link_status())
{
eth_device_linkchange(&eth_device, RT_TRUE);
rt_kprintf("eth1: link is up\n");
}
else
{
eth_device_linkchange(&eth_device, RT_FALSE);
rt_kprintf("eth1: link is down\n");
}
R8_ETH_EIR |= RB_ETH_EIR_LINKIF; //清除中断
}
rt_interrupt_leave();
}
int rt_hw_eth_init(void)
{
//使能ETH引脚
R16_PIN_ANALOG_IE |= RB_PIN_ETH_IE;
//进入安全访问模式
R8_SAFE_ACCESS_SIG = 0x57;
R8_SAFE_ACCESS_SIG = 0xA8;
//打开以太网时钟
R8_SLP_CLK_OFF1 &= (~RB_SLP_CLK_ETH);
//打开以太网电源
R8_SLP_POWER_CTRL &= (~RB_SLP_ETH_PWR_DN);
//退出安全访问模式
R8_SAFE_ACCESS_SIG = 0x00;
//开启以太网中断
R8_ETH_EIE |= RB_ETH_EIE_INTIE;
//启用以太网接收中断
R8_ETH_EIE |= RB_ETH_EIE_RXIE;
//R8_ETH_EIE |= RB_ETH_EIE_RXERIE;
//启用以太网发送中断
R8_ETH_EIE |= RB_ETH_EIR_TXIF;
R8_ETH_EIE |= RB_ETH_EIR_TXERIF;
//启用Link变化中断
R8_ETH_EIE |= RB_ETH_EIE_LINKIE;
//启用内置的50欧姆阻抗匹配电阻
R8_ETH_EIE |= RB_ETH_EIE_R_EN50;
//配置接收过滤模式
R8_ETH_ERXFCON = RB_ETH_ERXFCON_ANDOR | RB_ETH_ERXFCON_CRCEN;
//设置发送dma
R16_ETH_ETXST = (uint32_t)eth_dma_tx_buf;
//设置接收dma
R16_ETH_ERXST = (uint32_t)eth_dma_rx_buf;
//设置最大接收长度
R16_ETH_MAMXFL = sizeof(eth_dma_rx_buf);
//使能MAC层接收
R8_ETH_MACON1 |= RB_ETH_MACON1_MARXEN;
//开启硬件CRC
R8_ETH_MACON2 |= RB_ETH_MACON2_TXCRCEN;
//所有短包填充0至60字节,再4字节 CRC
R8_ETH_MACON2 |= 0x20;
//使能接收
R8_ETH_ECON1 |= RB_ETH_ECON1_RXEN;
//开启中断
NVIC_EnableIRQ(ETH_IRQn);
//设置回调函数
eth_device.parent.init = eth_init;
eth_device.parent.open = eth_open;
eth_device.parent.close = eth_close;
eth_device.parent.read = eth_read;
eth_device.parent.write = eth_write;
eth_device.parent.control = eth_control;
eth_device.parent.user_data = RT_NULL;
eth_device.eth_rx = eth_rx;
eth_device.eth_tx = eth_tx;
return eth_device_init(&(eth_device), "e0");
}
INIT_DEVICE_EXPORT(rt_hw_eth_init);
#endif /* BSP_USING_ETH */
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2022-02-16 Tuber first version
*/
#ifndef __DRV_ETH_H__
#define __DRV_ETH_H__
#include <rtthread.h>
#define ETH_BUF_SIZE 1536
int rt_hw_eth_init(void);
#endif
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2022-02-16 Tuber first version
*/
#include <rtthread.h>
#include <rtdevice.h>
#include "board.h"
#include "drv_uart.h"
#ifdef BSP_USING_UART
struct uart_device
{
struct rt_serial_device serial;
char *name;
};
#ifdef BSP_USING_UART0
static struct uart_device uart_device0 =
{
.name = "uart0",
};
#endif
#ifdef BSP_USING_UART1
static struct uart_device uart_device1 =
{
.name = "uart1",
};
#endif
#ifdef BSP_USING_UART2
static struct uart_device uart_device2 =
{
.name = "uart2",
};
#endif
#ifdef BSP_USING_UART3
static struct uart_device uart_device3 =
{
.name = "uart3",
};
#endif
static rt_err_t uart_configure(struct rt_serial_device *serial, struct serial_configure *cfg)
{
UINT32 x;
UINT8V R8_UARTx_FCR = 0, R8_UARTx_LCR = 0, R8_UARTx_IER = 0, R8_UARTx_DIV = 0;
UINT16V R16_UARTx_DL = 0;
struct uart_device *uart_device = serial->parent.user_data;
//设置波特率
x = 10 * GetSysClock() / 8 / cfg->baud_rate;
x = (x + 5) / 10;
R16_UARTx_DL = (UINT16)x;
//设置数据长度
switch (cfg->data_bits)
{
case DATA_BITS_5:
//R8_UARTx_LCR |= 0x00;
break;
case DATA_BITS_6:
R8_UARTx_LCR |= 0x01;
break;
case DATA_BITS_7:
R8_UARTx_LCR |= 0x02;
break;
case DATA_BITS_8:
default:
R8_UARTx_LCR |= 0x03;
break;
}
//设置停止位
switch (cfg->stop_bits)
{
case STOP_BITS_2:
R8_UARTx_LCR |= 0x04;
break;
case STOP_BITS_1:
default:
//R8_UARTx_LCR |= 0x00;
break;
}
//设置校验位
switch (cfg->parity)
{
case PARITY_ODD:
R8_UART1_LCR |= R8_LCR_PAR_EN;
//R8_UART1_LCR |= 0x00;
break;
case PARITY_EVEN:
R8_UART1_LCR |= R8_LCR_PAR_EN;
R8_UART1_LCR |= 0x10;
break;
case PARITY_NONE:
default:
//R8_UART1_LCR &= (~R8_UART1_LCR);
break;
}
#ifdef BSP_USING_UART0
if (uart_device == &uart_device0)
{
GPIOB_SetBits(GPIO_Pin_7);
GPIOB_ModeCfg(GPIO_Pin_4, GPIO_ModeIN_PU); // RXD-配置上拉输入
GPIOB_ModeCfg(GPIO_Pin_7, GPIO_ModeOut_PP_5mA); // TXD-配置推挽输出,注意先让IO口输出高电平
R16_UART0_DL = R16_UARTx_DL;
R8_UART0_FCR = (2 << 6) | RB_FCR_TX_FIFO_CLR | RB_FCR_RX_FIFO_CLR | RB_FCR_FIFO_EN; // FIFO打开,触发点4字节
R8_UART0_LCR = R8_UARTx_LCR;
R8_UART0_IER = RB_IER_TXD_EN;
R8_UART0_DIV = 1;
}
#endif
#ifdef BSP_USING_UART1
if (uart_device == &uart_device1)
{
GPIOA_SetBits(GPIO_Pin_9);
GPIOA_ModeCfg(GPIO_Pin_8, GPIO_ModeIN_PU); // RXD-配置上拉输入
GPIOA_ModeCfg(GPIO_Pin_9, GPIO_ModeOut_PP_5mA); // TXD-配置推挽输出,注意先让IO口输出高电平
R16_UART1_DL = R16_UARTx_DL;
R8_UART1_FCR = (2 << 6) | RB_FCR_TX_FIFO_CLR | RB_FCR_RX_FIFO_CLR | RB_FCR_FIFO_EN; // FIFO打开,触发点4字节
R8_UART1_LCR = R8_UARTx_LCR;
R8_UART1_IER = RB_IER_TXD_EN;
R8_UART1_DIV = 1;
}
#endif
#ifdef BSP_USING_UART2
if (uart_device == &uart_device2)
{
GPIOA_SetBits(GPIO_Pin_7);
GPIOA_ModeCfg(GPIO_Pin_6, GPIO_ModeIN_PU); // RXD-配置上拉输入
GPIOA_ModeCfg(GPIO_Pin_7, GPIO_ModeOut_PP_5mA); // TXD-配置推挽输出,注意先让IO口输出高电平
R16_UART2_DL = R16_UARTx_DL;
R8_UART2_FCR = (2 << 6) | RB_FCR_TX_FIFO_CLR | RB_FCR_RX_FIFO_CLR | RB_FCR_FIFO_EN; // FIFO打开,触发点4字节
R8_UART2_LCR = R8_UARTx_LCR;
R8_UART2_IER = RB_IER_TXD_EN;
R8_UART2_DIV = 1;
}
#endif
#ifdef BSP_USING_UART3
if (uart_device == &uart_device3)
{
GPIOA_SetBits(GPIO_Pin_5);
GPIOA_ModeCfg(GPIO_Pin_4, GPIO_ModeIN_PU); // RXD-配置上拉输入
GPIOA_ModeCfg(GPIO_Pin_5, GPIO_ModeOut_PP_5mA); // TXD-配置推挽输出,注意先让IO口输出高电平
R16_UART3_DL = R16_UARTx_DL;
R8_UART3_FCR = (2 << 6) | RB_FCR_TX_FIFO_CLR | RB_FCR_RX_FIFO_CLR | RB_FCR_FIFO_EN; // FIFO打开,触发点4字节
R8_UART3_LCR = R8_UARTx_LCR;
R8_UART3_IER = RB_IER_TXD_EN;
R8_UART3_DIV = 1;
}
#endif
return RT_EOK;
}
static rt_err_t uart_control(struct rt_serial_device *serial, int cmd, void *arg)
{
struct uart_device *uart_device = serial->parent.user_data;
switch (cmd)
{
case RT_DEVICE_CTRL_CLR_INT:
#ifdef BSP_USING_UART0
if (uart_device == &uart_device0)
{
UART0_INTCfg(DISABLE, RB_IER_RECV_RDY);
NVIC_EnableIRQ(UART0_IRQn);
}
#endif
#ifdef BSP_USING_UART1
if (uart_device == &uart_device1)
{
UART1_INTCfg(DISABLE, RB_IER_RECV_RDY);
NVIC_EnableIRQ(UART1_IRQn);
}
#endif
#ifdef BSP_USING_UART2
if (uart_device == &uart_device2)
{
UART2_INTCfg(DISABLE, RB_IER_RECV_RDY);
NVIC_EnableIRQ(UART2_IRQn);
}
#endif
#ifdef BSP_USING_UART3
if (uart_device == &uart_device3)
{
UART3_INTCfg(DISABLE, RB_IER_RECV_RDY);
NVIC_EnableIRQ(UART3_IRQn);
}
#endif
break;
case RT_DEVICE_CTRL_SET_INT:
#ifdef BSP_USING_UART0
if (uart_device == &uart_device0)
{
UART0_ByteTrigCfg(UART_1BYTE_TRIG);
UART0_INTCfg(ENABLE, RB_IER_RECV_RDY);
NVIC_EnableIRQ(UART0_IRQn);
}
#endif
#ifdef BSP_USING_UART1
if (uart_device == &uart_device1)
{
UART1_ByteTrigCfg(UART_1BYTE_TRIG);
UART1_INTCfg(ENABLE, RB_IER_RECV_RDY);
NVIC_EnableIRQ(UART1_IRQn);
}
#endif
#ifdef BSP_USING_UART2
if (uart_device == &uart_device2)
{
UART2_ByteTrigCfg(UART_1BYTE_TRIG);
UART2_INTCfg(ENABLE, RB_IER_RECV_RDY);
NVIC_EnableIRQ(UART2_IRQn);
}
#endif
#ifdef BSP_USING_UART3
if (uart_device == &uart_device3)
{
UART3_ByteTrigCfg(UART_1BYTE_TRIG);
UART3_INTCfg(ENABLE, RB_IER_RECV_RDY);
NVIC_EnableIRQ(UART3_IRQn);
}
#endif
break;
default:
break;
}
return RT_EOK;
}
static int uart_putc(struct rt_serial_device *serial, char ch)
{
struct uart_device *uart_device = serial->parent.user_data;
#ifdef BSP_USING_UART0
if (uart_device == &uart_device0)
{
while (R8_UART0_TFC >= UART_FIFO_SIZE);
R8_UART0_THR = ch;
}
#endif
#ifdef BSP_USING_UART1
if (uart_device == &uart_device1)
{
while (R8_UART1_TFC >= UART_FIFO_SIZE);
R8_UART1_THR = ch;
}
#endif
#ifdef BSP_USING_UART2
if (uart_device == &uart_device2)
{
while (R8_UART2_TFC >= UART_FIFO_SIZE);
R8_UART2_THR = ch;
}
#endif
#ifdef BSP_USING_UART3
if (uart_device == &uart_device3)
{
while (R8_UART3_TFC >= UART_FIFO_SIZE);
R8_UART3_THR = ch;
}
#endif
return 1;
}
static int uart_getc(struct rt_serial_device *serial)
{
struct uart_device *uart_device = serial->parent.user_data;
#ifdef BSP_USING_UART0
if (uart_device == &uart_device0)
{
if (R8_UART0_RFC > 0)
{
return R8_UART0_RBR;
}
}
#endif
#ifdef BSP_USING_UART1
if (uart_device == &uart_device1)
{
if (R8_UART1_RFC > 0)
{
return R8_UART1_RBR;
}
}
#endif
#ifdef BSP_USING_UART2
if (uart_device == &uart_device2)
{
if (R8_UART2_RFC > 0)
{
return R8_UART2_RBR;
}
}
#endif
#ifdef BSP_USING_UART3
if (uart_device == &uart_device3)
{
if (R8_UART3_RFC > 0)
{
return R8_UART3_RBR;
}
}
#endif
return -1;
}
static const struct rt_uart_ops uart_ops =
{
.configure = uart_configure,
.control = uart_control,
.putc = uart_putc,
.getc = uart_getc,
.dma_transmit = RT_NULL,
};
void uart_isr(struct rt_serial_device *serial, UINT8 flag)
{
switch (flag)
{
case UART_II_RECV_RDY: // 数据达到设置触发点
rt_hw_serial_isr(serial, RT_SERIAL_EVENT_RX_IND);
break;
case UART_II_RECV_TOUT: // 接收超时,暂时一帧数据接收完成
rt_hw_serial_isr(serial, RT_SERIAL_EVENT_RX_TIMEOUT);
break;
case UART_II_THR_EMPTY: // 发送缓存区空,可继续发送
rt_hw_serial_isr(serial, RT_SERIAL_EVENT_TX_DONE);
break;
default:
break;
}
}
#ifdef BSP_USING_UART0
void UART0_IRQHandler(void)
{
rt_interrupt_enter();
uart_isr(&uart_device0.serial, UART0_GetITFlag());
rt_interrupt_leave();
}
#endif
#ifdef BSP_USING_UART1
void UART1_IRQHandler(void)
{
rt_interrupt_enter();
uart_isr(&uart_device1.serial, UART1_GetITFlag());
rt_interrupt_leave();
}
#endif
#ifdef BSP_USING_UART2
void UART2_IRQHandler(void)
{
rt_interrupt_enter();
uart_isr(&uart_device2.serial, UART2_GetITFlag());
rt_interrupt_leave();
}
#endif
#ifdef BSP_USING_UART3
void UART3_IRQHandler(void)
{
rt_interrupt_enter();
uart_isr(&uart_device3.serial, UART3_GetITFlag());
rt_interrupt_leave();
}
#endif
int rt_hw_uart_init(void)
{
struct serial_configure config = RT_SERIAL_CONFIG_DEFAULT;
#ifdef BSP_USING_UART0
uart_device0.serial.config = config;
uart_device0.serial.ops = &uart_ops;
rt_hw_serial_register(&uart_device0.serial, uart_device0.name,
RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX | RT_DEVICE_FLAG_INT_TX,
&uart_device0);
#endif
#ifdef BSP_USING_UART1
uart_device1.serial.config = config;
uart_device1.serial.ops = &uart_ops;
rt_hw_serial_register(&uart_device1.serial, uart_device1.name,
RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX | RT_DEVICE_FLAG_INT_TX,
&uart_device1);
#endif
#ifdef BSP_USING_UART2
uart_device2.serial.config = config;
uart_device2.serial.ops = &uart_ops;
rt_hw_serial_register(&uart_device2.serial, uart_device2.name,
RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX | RT_DEVICE_FLAG_INT_TX,
&uart_device2);
#endif
#ifdef BSP_USING_UART3
uart_device3.serial.config = config;
uart_device3.serial.ops = &uart_ops;
rt_hw_serial_register(&uart_device3.serial, uart_device3.name,
RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX | RT_DEVICE_FLAG_INT_TX,
&uart_device3);
#endif
return RT_EOK;
}
#endif /* BSP_USING_UART */
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2022-02-16 Tuber first version
*/
#ifndef DRV_UART_H__
#define DRV_UART_H__
int rt_hw_uart_init(void);
#endif
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2022-02-16 Tuber first version
*/
#include <rtthread.h>
#include <rtdevice.h>
#include "board.h"
#include "drv_usbh.h"
#ifdef BSP_USING_USBH
static struct rt_completion urb_completion;
//USB接收缓存区
__align(4) UINT8 usb_rx_buf[MAX_PACKET_SIZE]; // IN, must even address
__align(4) UINT8 usb_tx_buf[MAX_PACKET_SIZE]; // OUT, must even address
static struct uhcd uhcd;
static rt_err_t drv_reset_port(rt_uint8_t port)
{
//关闭中断
R8_USB_INT_EN = 0x00;
R8_USB_DEV_AD = (R8_USB_DEV_AD & RB_UDA_GP_BIT) | (0x00 & MASK_USB_ADDR); //设置地址
R8_UHOST_CTRL &= ~RB_UH_PORT_EN; // 关掉端口
//判断设备速度
if (R8_USB_MIS_ST & RB_UMS_DM_LEVEL)
{
//低速
R8_USB_CTRL |= RB_UC_LOW_SPEED; // 默认为低速
R8_UHOST_CTRL = (R8_UHOST_CTRL | RB_UH_LOW_SPEED) | RB_UH_BUS_RESET; // 默认为低速,开始复位
}
else
{
//全速
R8_USB_CTRL &= ~ RB_UC_LOW_SPEED; // 默认为全速
R8_UHOST_CTRL = (R8_UHOST_CTRL & ~RB_UH_LOW_SPEED) | RB_UH_BUS_RESET; // 默认为全速,开始复位
}
rt_thread_mdelay(15); // 复位时间10mS到20mS
R8_UHOST_CTRL = R8_UHOST_CTRL & ~ RB_UH_BUS_RESET; // 结束复位
rt_thread_mdelay(1);
R8_UHOST_CTRL |= RB_UH_PORT_EN; //打开端口
R8_USB_INT_FG = RB_UIF_DETECT; // 清中断标志
//打开中断
R8_USB_INT_EN = RB_UIF_TRANSFER | RB_UIE_DETECT;
return RT_EOK;
}
static int drv_pipe_xfer(upipe_t pipe, rt_uint8_t token, void *buffer, int nbytes, int timeouts)
{
rt_err_t res;
UINT16 i;
UINT16 retry_count = 3;
rt_uint8_t usb_pid, res_pid;
UINT8 *tog = (UINT8 *)pipe->user_data;
//设置目标usb地址
R8_USB_DEV_AD = (R8_USB_DEV_AD & RB_UDA_GP_BIT) | (pipe->inst->address & MASK_USB_ADDR);
//判断是in还是out操作
if (pipe->ep.bEndpointAddress & USB_DIR_IN)
{
usb_pid = USB_PID_IN; //in
R8_UH_TX_LEN = 0x00;
}
else
{
usb_pid = (token == USBH_PID_SETUP) ? USB_PID_SETUP : USB_PID_OUT; //setup/out
rt_memcpy(usb_tx_buf, buffer, nbytes);
R8_UH_TX_LEN = nbytes;
}
//设置数据TOG
switch (usb_pid)
{
case USB_PID_IN:
if (nbytes == 0) *tog = USB_PID_DATA1; //状态反馈
R8_UH_RX_CTRL = (*tog == USB_PID_DATA1) ? RB_UH_R_TOG : 0x00;
break;
case USB_PID_OUT:
if (nbytes == 0) *tog = USB_PID_DATA1; //状态反馈
R8_UH_TX_CTRL = (*tog == USB_PID_DATA1) ? RB_UH_T_TOG : 0x00;
break;
case USB_PID_SETUP:
*(UINT8 *)pipe->inst->pipe_ep0_out->user_data = USB_PID_DATA0;
*(UINT8 *)pipe->inst->pipe_ep0_in->user_data = USB_PID_DATA1;
R8_UH_TX_CTRL = (*tog == USB_PID_DATA1) ? RB_UH_T_TOG : 0x00;
break;
}
//usb枚举的时候加大重试次数,提高usb设备枚举成功率
if ((pipe->ep.bmAttributes & USB_EP_ATTR_TYPE_MASK) == USB_EP_ATTR_CONTROL)
{
retry_count = 1000;
}
for (i = 0; i < retry_count; i++)
{
//传输
R8_UH_EP_PID = (usb_pid << 4) | (pipe->ep.bEndpointAddress & 0x0F);
res = rt_completion_wait(&urb_completion, timeouts);
if (res != RT_EOK)
{
return res;
}
//判断是否需要反转数据
if (R8_USB_INT_ST & RB_UIS_TOG_OK)
{
*tog = (*tog == USB_PID_DATA0) ? USB_PID_DATA1 : USB_PID_DATA0;//翻转
}
res_pid = R8_USB_INT_ST & MASK_UIS_H_RES;
switch (res_pid)
{
case USB_PID_ACK://发送成功
pipe->status = UPIPE_STATUS_OK;
if (pipe->callback != RT_NULL) pipe->callback(pipe);
return nbytes;
case USB_PID_DATA0: //收到数据
case USB_PID_DATA1: //收到数据
pipe->status = UPIPE_STATUS_OK;
if (pipe->callback != RT_NULL) pipe->callback(pipe);
//拷贝数据到buffer
if (usb_pid == USB_PID_IN)
{
rt_memcpy(buffer, usb_rx_buf, R8_USB_RX_LEN);
return R8_USB_RX_LEN;
}
return nbytes;
case USB_PID_NAK: //数据未就绪
if (pipe->ep.bmAttributes == USB_EP_ATTR_INT)
{
rt_thread_delay((pipe->ep.bInterval * RT_TICK_PER_SECOND / 1000) > 0 ? (pipe->ep.bInterval * RT_TICK_PER_SECOND / 1000) : 1);
}
rt_thread_mdelay(1);
continue;//重试
case USB_PID_STALL: //传输停止
pipe->status = UPIPE_STATUS_STALL;
if (pipe->callback != RT_NULL) pipe->callback(pipe);
return 0;
default:
break;
}
}
pipe->status = UPIPE_STATUS_ERROR;
if (pipe->callback != RT_NULL) pipe->callback(pipe);
return -RT_ERROR;
}
static rt_err_t drv_open_pipe(upipe_t pipe)
{
pipe->pipe_index = pipe->inst->address & MASK_USB_ADDR;
pipe->user_data = rt_malloc(sizeof(UINT8));
//默认发送DATA0
if (pipe->ep.bEndpointAddress & USB_DIR_IN)
{
*(UINT8 *)pipe->user_data = USB_PID_DATA0;
}
else
{
*(UINT8 *)pipe->user_data = USB_PID_DATA0;
}
return RT_EOK;
}
static rt_err_t drv_close_pipe(upipe_t pipe)
{
rt_free(pipe->user_data);
return RT_EOK;
}
static struct uhcd_ops uhcd_ops =
{
drv_reset_port,
drv_pipe_xfer,
drv_open_pipe,
drv_close_pipe,
};
static rt_err_t hcd_init(rt_device_t dev)
{
R16_PIN_ANALOG_IE |= RB_PIN_USB_IE;
R8_USB_CTRL = RB_UC_HOST_MODE;
R8_UHOST_CTRL = 0;
R8_USB_DEV_AD = 0x00;
R8_UH_EP_MOD = RB_UH_EP_TX_EN | RB_UH_EP_RX_EN;
R16_UH_RX_DMA = (UINT16)(UINT32)usb_rx_buf;
R16_UH_TX_DMA = (UINT16)(UINT32)usb_tx_buf;
R8_USB_CTRL = RB_UC_HOST_MODE | RB_UC_INT_BUSY | RB_UC_DMA_EN;
R8_UH_SETUP = RB_UH_SOF_EN;
R8_USB_INT_FG = 0xFF;
R8_USB_INT_EN = RB_UIF_TRANSFER | RB_UIE_DETECT;
//开启中断
NVIC_EnableIRQ(USB_IRQn);
rt_completion_init(&urb_completion);
return RT_EOK;
}
void USB_IRQHandler()
{
rt_interrupt_enter();
//USB连接断开中断
if (R8_USB_INT_FG & RB_UIF_DETECT)
{
R8_USB_INT_FG = RB_UIF_DETECT;//清除中断
//检查USB设备连接状态
if ((R8_USB_MIS_ST & RB_UMS_DEV_ATTACH) != 0)
{
rt_usbh_root_hub_connect_handler(&uhcd, 1, RT_FALSE);
rt_kprintf("usb: up\n");
}
else
{
rt_usbh_root_hub_disconnect_handler(&uhcd, 1);
rt_kprintf("usb: down\n");
}
}
if (R8_USB_INT_FG & RB_UIF_TRANSFER)
{
R8_UH_EP_PID = 0x00; //停止发送
R8_USB_INT_FG = RB_UIF_TRANSFER;//清除中断
rt_completion_done(&urb_completion);
}
if (R8_USB_INT_FG & RB_UIF_SUSPEND)
{
R8_USB_INT_FG = RB_UIF_SUSPEND;//清除中断
}
if (R8_USB_INT_FG & RB_UIF_HST_SOF)
{
R8_USB_INT_FG = RB_UIF_HST_SOF;//清除中断
}
if (R8_USB_INT_FG & RB_UIF_FIFO_OV)
{
R8_USB_INT_FG = RB_UIF_FIFO_OV;//清除中断
}
rt_interrupt_leave();
}
int rt_hw_usbh_init(void)
{
rt_err_t res = -RT_ERROR;
rt_memset((void *)&uhcd, 0, sizeof(struct uhcd));
uhcd.parent.type = RT_Device_Class_USBHost;
uhcd.parent.init = hcd_init;
uhcd.ops = &uhcd_ops;
uhcd.num_ports = 1;
res = rt_device_register(&uhcd.parent, "usbh", RT_DEVICE_FLAG_DEACTIVATE);
if (res != RT_EOK)
{
rt_kprintf("register usb host failed res = %d\r\n", res);
return -RT_ERROR;
}
rt_usb_host_init("usbh");
return RT_EOK;
}
INIT_DEVICE_EXPORT(rt_hw_usbh_init);
#endif /* BSP_USING_USBH */
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2022-02-16 Tuber first version
*/
#ifndef __DRV_USBH_H__
#define __DRV_USBH_H__
#include <rtthread.h>
#define USB_PID_SETUP 0x0D
#define USB_PID_IN 0x09
#define USB_PID_OUT 0x01
#define USB_PID_SOF 0x05
#define USB_PID_ACK 0x02
#define USB_PID_NAK 0x0A
#define USB_PID_STALL 0x0E
#define USB_PID_DATA0 0x03
#define USB_PID_DATA1 0x0B
#define USB_PID_PRE 0x0C
int rt_hw_usbh_init(void);
#endif
此差异已折叠。
/**************************************************************************//**
* @file core_cmFunc.h
* @brief CMSIS Cortex-M Core Function Access Header File
* @version V4.00
* @date 28. August 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.
---------------------------------------------------------------------------*/
#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) || (__CORTEX_SC >= 300)
/** \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) || (__CORTEX_SC >= 300) */
#if (__CORTEX_M == 0x04) || (__CORTEX_M == 0x07)
/** \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) || (__CORTEX_M == 0x07) */
#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" : : : "memory");
}
/** \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" : : : "memory");
}
/** \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) : "memory");
}
/** \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) : "sp");
}
/** \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) : "sp");
}
/** \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) : "memory");
}
#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" : : : "memory");
}
/** \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" : : : "memory");
}
/** \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) : "memory");
}
/** \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) : "memory");
}
#endif /* (__CORTEX_M >= 0x03) */
#if (__CORTEX_M == 0x04) || (__CORTEX_M == 0x07)
/** \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;
/* Empty asm statement works as a scheduling barrier */
__ASM volatile ("");
__ASM volatile ("VMRS %0, fpscr" : "=r" (result) );
__ASM volatile ("");
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)
/* Empty asm statement works as a scheduling barrier */
__ASM volatile ("");
__ASM volatile ("VMSR fpscr, %0" : : "r" (fpscr) : "vfpcc");
__ASM volatile ("");
#endif
}
#endif /* (__CORTEX_M == 0x04) || (__CORTEX_M == 0x07) */
#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/
/* IAR iccarm specific functions */
#include <cmsis_iar.h>
#elif defined ( __TMS470__ ) /*---------------- TI CCS Compiler ------------------*/
/* TI CCS specific functions */
#include <cmsis_ccs.h>
#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.
*/
#elif defined ( __CSMC__ ) /*------------------ COSMIC Compiler -------------------*/
/* Cosmic specific functions */
#include <cmsis_csm.h>
#endif
/*@} end of CMSIS_Core_RegAccFunctions */
#endif /* __CORE_CMFUNC_H */
Import('RTT_ROOT')
Import('rtconfig')
from building import *
cwd = GetCurrentDir()
# The set of source files associated with this SConscript file.
src = Split("""
""")
CPPPATH = [cwd + '/StdPeriphDriver/inc', cwd + '/CMSIS/Include']
src += ['Startup/startup_ARMCM0.s']
src += Glob('StdPeriphDriver/*.c')
group = DefineGroup('Libraries', src, depend = [''], CPPPATH = CPPPATH)
Return('group')
\ No newline at end of file
;/**************************************************************************//**
; * @file startup_ARMCM0.s
; * @brief CMSIS Core Device Startup File for
; * ARMCM0 Device Series
; * @version V1.08
; * @date 23. November 2012
; *
; * @note
; *
; ******************************************************************************/
;/* Copyright (c) 2011 - 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.
; ---------------------------------------------------------------------------*/
;/*
;//-------- <<< Use Configuration Wizard in Context Menu >>> ------------------
;*/
; <h> Stack Configuration
; <o> Stack Size (in Bytes) <0x0-0xFFFFFFFF:8>
; </h>
Stack_Size EQU 0x00000400
AREA STACK, NOINIT, READWRITE, ALIGN=3
Stack_Mem SPACE Stack_Size
__initial_sp EQU 0x20008000
; <h> Heap Configuration
; <o> Heap Size (in Bytes) <0x0-0xFFFFFFFF:8>
; </h>
Heap_Size EQU 0x00000400
AREA HEAP, NOINIT, READWRITE, ALIGN=3
__heap_base
Heap_Mem SPACE Heap_Size
__heap_limit
PRESERVE8
THUMB
; Vector Table Mapped to Address 0 at Reset
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 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD SVC_Handler ; SVCall Handler
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD PendSV_Handler ; PendSV Handler
DCD SysTick_Handler ; SysTick Handler
; External Interrupts
DCD TMR0_IRQHandler ; 0: TMR0
DCD GPIO_IRQHandler ; 1: GPIO
DCD SLAVE_IRQHandler ; 2: SLAVE
DCD SPI0_IRQHandler ; 3: SPI0
DCD BB_IRQHandler ; 4: BB
DCD LLE_IRQHandler ; 5: LLE
DCD USB_IRQHandler ; 6: USB
DCD ETH_IRQHandler ; 7: ETH
DCD TMR1_IRQHandler ; 8: TMR1
DCD TMR2_IRQHandler ; 9: TMR2
DCD UART0_IRQHandler ; 10: UART0
DCD UART1_IRQHandler ; 11: UART1
DCD RTC_IRQHandler ; 12: RTC
DCD ADC_IRQHandler ; 13: ADC
DCD SPI1_IRQHandler ; 14: SPI1
DCD LED_IRQHandler ; 15: LED
DCD TMR3_IRQHandler ; 16: TMR3
DCD UART2_IRQHandler ; 17: UART2
DCD UART3_IRQHandler ; 18: UART3
DCD WDT_IRQHandler ; 19: WDT
__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, =0x1007058
;MOV SP, R0
LDR R0, =SystemInit
BLX R0
LDR R0, =__main
BX R0
ENDP
; Dummy Exception Handlers (infinite loops which can be modified)
NMI_Handler PROC
EXPORT NMI_Handler [WEAK]
B .
ENDP
HardFault_Handler\
PROC
EXPORT HardFault_Handler [WEAK]
; B .
ENDP
SVC_Handler PROC
EXPORT SVC_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
EXPORT TMR0_IRQHandler [WEAK]; 0: TMR0
EXPORT GPIO_IRQHandler [WEAK]; 1: GPIO
EXPORT SLAVE_IRQHandler [WEAK]; 2: SLAVE
EXPORT SPI0_IRQHandler [WEAK]; 3: SPI0
EXPORT BB_IRQHandler [WEAK]; 4: BB
EXPORT LLE_IRQHandler [WEAK]; 5: LLE
EXPORT USB_IRQHandler [WEAK]; 6: USB
EXPORT ETH_IRQHandler [WEAK]; 7: ETH
EXPORT TMR1_IRQHandler [WEAK]; 8: TMR1
EXPORT TMR2_IRQHandler [WEAK]; 9: TMR2
EXPORT UART0_IRQHandler [WEAK]; 10: UART0
EXPORT UART1_IRQHandler [WEAK]; 11: UART1
EXPORT RTC_IRQHandler [WEAK]; 12: RTC
EXPORT ADC_IRQHandler [WEAK]; 13: ADC
EXPORT SPI1_IRQHandler [WEAK]; 14: SPI1
EXPORT LED_IRQHandler [WEAK]; 15: LED
EXPORT TMR3_IRQHandler [WEAK]; 16: TMR3
EXPORT UART2_IRQHandler [WEAK]; 17: UART2
EXPORT UART3_IRQHandler [WEAK]; 18: UART3
EXPORT WDT_IRQHandler [WEAK]; 19: WDT
TMR0_IRQHandler ; 0: TMR0
GPIO_IRQHandler ; 1: GPIO
SLAVE_IRQHandler ; 2: SLAVE
SPI0_IRQHandler ; 3: SPI0
BB_IRQHandler ; 4: BB
LLE_IRQHandler ; 5: LLE
USB_IRQHandler ; 6: USB
ETH_IRQHandler ; 7: ETH
TMR1_IRQHandler ; 8: TMR1
TMR2_IRQHandler ; 9: TMR2
UART0_IRQHandler ; 10: UART0
UART1_IRQHandler ; 11: UART1
RTC_IRQHandler ; 12: RTC
ADC_IRQHandler ; 13: ADC
SPI1_IRQHandler ; 14: SPI1
LED_IRQHandler ; 15: LED
TMR3_IRQHandler ; 16: TMR3
UART2_IRQHandler ; 17: UART2
UART3_IRQHandler ; 18: UART3
WDT_IRQHandler ; 19: WDT
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
/********************************** (C) COPYRIGHT *******************************
* File Name : CH57x_adc.c
* Author : WCH
* Version : V1.1
* Date : 2020/04/01
* Description
*******************************************************************************/
#include "CH57x_common.h"
/*******************************************************************************
* Function Name : ADC_DataCalib_Rough
* Description : 采样数据粗调,获取偏差值
* 注意,使用粗调校准,必须保证 PA5(AIN1)设置为浮空输入模式,管脚外部不要有电压
* Input : None
* Return : 偏差值
*******************************************************************************/
signed short ADC_DataCalib_Rough( void ) // 采样数据粗调,获取偏差值
{
UINT16 i;
UINT32 sum=0;
UINT8 ch=0; // 备份通道
UINT8 ctrl=0; // 备份控制寄存器
ch = R8_ADC_CHANNEL;
ctrl = R8_ADC_CFG;
ADC_ChannelCfg( 1 );
R8_ADC_CFG |= RB_ADC_OFS_TEST; // 进入测试模式
R8_ADC_CONVERT = RB_ADC_START;
while( R8_ADC_CONVERT & RB_ADC_START );
for(i=0; i<16; i++)
{
R8_ADC_CONVERT = RB_ADC_START;
while( R8_ADC_CONVERT & RB_ADC_START );
sum += (~R16_ADC_DATA)&RB_ADC_DATA;
}
sum = (sum+8)>>4;
R8_ADC_CFG &= ~RB_ADC_OFS_TEST; // 关闭测试模式
R8_ADC_CHANNEL = ch;
R8_ADC_CFG = ctrl;
return (2048 - sum);
}
void ADC_DataCalib_Fine( PUINT16 dat, ADC_SignalPGATypeDef ga ) // 采样数据细调
{
UINT32 d = (UINT32)*dat;
switch( ga )
{
case ADC_PGA_1_4: // y=0.973x+55.188
*dat = (996*d + 56513 + 512)>>10;
break;
case ADC_PGA_1_2: // y=0.974x+55.26
*dat = (997*d + 56586 + 512)>>10;
break;
case ADC_PGA_0: // y=0.975x+53.63
*dat = (998*d + 54917 + 512)>>10;
break;
case ADC_PGA_2: // y=0.975x+51.58
*dat = (998*d + 52818 + 512)>>10;
break;
}
}
/*******************************************************************************
* Function Name : ADC_ExtSingleChSampInit
* Description : 外部信号单通道采样初始化
* Input : sp:
refer to ADC_SampClkTypeDef
ga:
refer to ADC_SignalPGATypeDef
* Return : None
*******************************************************************************/
void ADC_ExtSingleChSampInit( ADC_SampClkTypeDef sp, ADC_SignalPGATypeDef ga )
{
R8_ADC_CFG = RB_ADC_POWER_ON \
|RB_ADC_BUF_EN \
|( sp<<6 ) \
|( ga<<4 ) ;
}
/*******************************************************************************
* Function Name : ADC_ExtDiffChSampInit
* Description : 外部信号差分通道采样初始化
* Input : sp:
refer to ADC_SampClkTypeDef
ga:
refer to ADC_SignalPGATypeDef
* Return : None
*******************************************************************************/
void ADC_ExtDiffChSampInit( ADC_SampClkTypeDef sp, ADC_SignalPGATypeDef ga )
{
R8_ADC_CFG = RB_ADC_POWER_ON \
|RB_ADC_DIFF_EN \
|( sp<<6 ) \
|( ga<<4 ) ;
}
/*******************************************************************************
* Function Name : ADC_InterTSSampInit
* Description : 内置温度传感器采样初始化
* Input : None
* Return : None
*******************************************************************************/
void ADC_InterTSSampInit( void )
{
R8_TEM_SENSOR |= RB_TEM_SEN_PWR_ON;
R8_ADC_CHANNEL = CH_INTE_VTEMP;
R8_ADC_CFG = RB_ADC_POWER_ON \
|( 2<<4 ) ;
}
/*******************************************************************************
* Function Name : ADC_InterBATSampInit
* Description : 内置电池电压采样初始化
* Input : None
* Return : None
*******************************************************************************/
void ADC_InterBATSampInit( void )
{
R8_ADC_CHANNEL = CH_INTE_VBAT;
R8_ADC_CFG = RB_ADC_POWER_ON \
|RB_ADC_BUF_EN \
|( 0<<4 ) ; // 使用-12dB模式,
}
/*******************************************************************************
* Function Name : TouchKey_ChSampInit
* Description : 触摸按键通道采样初始化
* Input : None
* Return : None
*******************************************************************************/
void TouchKey_ChSampInit( void )
{
R8_ADC_CFG = RB_ADC_POWER_ON | RB_ADC_BUF_EN | ( 2<<4 );
R8_TKEY_CTRL = RB_TKEY_PWR_ON;
}
/*******************************************************************************
* Function Name : ADC_ExcutSingleConver
* Description : ADC执行单次转换
* Input : None
* Return : ADC转换后的数据
*******************************************************************************/
UINT16 ADC_ExcutSingleConver( void )
{
R8_ADC_CONVERT = RB_ADC_START;
while( R8_ADC_CONVERT & RB_ADC_START );
return ( R16_ADC_DATA&RB_ADC_DATA );
}
/*******************************************************************************
* Function Name : TouchKey_ExcutSingleConver
* Description : TouchKey转换后数据
* Input : d: Touchkey充放电时间,高4bit-放电时间,整个8bit-充电时间
* Return : 当前TouchKey等效数据
*******************************************************************************/
UINT16 TouchKey_ExcutSingleConver( UINT8 d )
{
R8_TKEY_CTRL = RB_TKEY_PWR_ON;
R8_TKEY_CNT = d;
while( R8_TKEY_CTRL & RB_TKEY_ACTION );
return ( R16_ADC_DATA&RB_ADC_DATA );
}
/*******************************************************************************
* Function Name : ADC_GetCurrentTS
* Description : 获取当前采样的温度值(℃)
* Input : ts_v:当前温度传感器采样输出
* Return : 转换后的温度值(℃)
*******************************************************************************/
int ADC_GetCurrentTS( UINT16 ts_v )
{
UINT16 vol_ts;
UINT16 D85_tem, D85_vol;
UINT16 D25_tem, D25_vol;
UINT16 temperK;
UINT32 temp;
UINT8 sum, sumck;
int cal;
temperK = 64; // mV/16^C
vol_ts = (ts_v*1060)>>11;
temp = (*((PUINT32)ROM_TMP_25C_ADDR));
D25_tem = temp;
D25_vol = (temp>>16);
if( D25_vol != 0 ){ // 默认系数换算
// T = T85 + (V-V85)*16/D25
cal = (D25_tem*temperK + vol_ts*16 + (temperK>>1) - D25_vol*16) / temperK ;
return ( cal );
}
else{ // 内置系数换算 D25_tem
temp = (*((PUINT32)ROM_TMP_85C_ADDR));
sum = (UINT8)(temp>>24); // 最高字节
sumck = (UINT8)(temp>>16);
sumck += (UINT8)(temp>>8);
sumck += (UINT8)temp;
if( sum != sumck ) return 0xff; // 校验和出错
temperK = D25_tem; // D25_tem = temperK
D85_tem = (UINT16)((temp>>16)&0x00ff);
D85_vol = (UINT16)temp;
// T = T85 + (V-V85)*16/D25
cal = (D85_tem*temperK + vol_ts*16 + (temperK>>1) - D85_vol*16) / temperK ;
return ( cal );
}
}
/********************************** (C) COPYRIGHT *******************************
* File Name : CH57x_gpio.c
* Author : WCH
* Version : V1.0
* Date : 2018/12/15
* Description
*******************************************************************************/
#include "CH57x_common.h"
/*******************************************************************************
* Function Name : GPIOA_ModeCfg
* Description : GPIOA端口引脚模式配置
* Input : pin: PA0-PA15
GPIO_Pin_0 - GPIO_Pin_15
mode:
GPIO_ModeIN_Floating - 浮空输入
GPIO_ModeIN_PU - 上拉输入
GPIO_ModeIN_PD - 下拉输入
GPIO_ModeOut_PP_5mA - 推挽输出最大5mA
GPIO_ModeOut_PP_20mA - 推挽输出最大20mA
* Return : None
*******************************************************************************/
void GPIOA_ModeCfg( UINT32 pin, GPIOModeTypeDef mode )
{
switch(mode)
{
case GPIO_ModeIN_Floating:
R32_PA_PD_DRV &= ~pin;
R32_PA_PU &= ~pin;
R32_PA_DIR &= ~pin;
break;
case GPIO_ModeIN_PU:
R32_PA_PD_DRV &= ~pin;
R32_PA_PU |= pin;
R32_PA_DIR &= ~pin;
break;
case GPIO_ModeIN_PD:
R32_PA_PD_DRV |= pin;
R32_PA_PU &= ~pin;
R32_PA_DIR &= ~pin;
break;
case GPIO_ModeOut_PP_5mA:
R32_PA_PD_DRV &= ~pin;
R32_PA_DIR |= pin;
break;
case GPIO_ModeOut_PP_20mA:
R32_PA_PD_DRV |= pin;
R32_PA_DIR |= pin;
break;
default:
break;
}
}
/*******************************************************************************
* Function Name : GPIOB_ModeCfg
* Description : GPIOB端口引脚模式配置
* Input : pin: PB0-PB23
GPIO_Pin_0 - GPIO_Pin_23
mode:
GPIO_ModeIN_Floating - 浮空输入
GPIO_ModeIN_PU - 上拉输入
GPIO_ModeIN_PD - 下拉输入
GPIO_ModeOut_PP_5mA - 推挽输出最大5mA
GPIO_ModeOut_PP_20mA - 推挽输出最大20mA
* Return : None
*******************************************************************************/
void GPIOB_ModeCfg( UINT32 pin, GPIOModeTypeDef mode )
{
switch(mode)
{
case GPIO_ModeIN_Floating:
R32_PB_PD_DRV &= ~pin;
R32_PB_PU &= ~pin;
R32_PB_DIR &= ~pin;
break;
case GPIO_ModeIN_PU:
R32_PB_PD_DRV &= ~pin;
R32_PB_PU |= pin;
R32_PB_DIR &= ~pin;
break;
case GPIO_ModeIN_PD:
R32_PB_PD_DRV |= pin;
R32_PB_PU &= ~pin;
R32_PB_DIR &= ~pin;
break;
case GPIO_ModeOut_PP_5mA:
R32_PB_PD_DRV &= ~pin;
R32_PB_DIR |= pin;
break;
case GPIO_ModeOut_PP_20mA:
R32_PB_PD_DRV |= pin;
R32_PB_DIR |= pin;
break;
default:
break;
}
}
/*******************************************************************************
* Function Name : GPIOA_ITModeCfg
* Description : GPIOA引脚中断模式配置
* Input : pin: PA0-PA15
GPIO_Pin_0 - GPIO_Pin_15
mode:
GPIO_ITMode_LowLevel - 低电平触发
GPIO_ITMode_HighLevel - 高电平触发
GPIO_ITMode_FallEdge - 下降沿触发
GPIO_ITMode_RiseEdge - 上升沿触发
* Return : None
*******************************************************************************/
void GPIOA_ITModeCfg( UINT32 pin, GPIOITModeTpDef mode )
{
switch( mode )
{
case GPIO_ITMode_LowLevel: // 低电平触发
R16_PA_INT_MODE &= ~pin;
R32_PA_CLR |= pin;
break;
case GPIO_ITMode_HighLevel: // 高电平触发
R16_PA_INT_MODE &= ~pin;
R32_PA_OUT |= pin;
break;
case GPIO_ITMode_FallEdge: // 下降沿触发
R16_PA_INT_MODE |= pin;
R32_PA_CLR |= pin;
break;
case GPIO_ITMode_RiseEdge: // 上升沿触发
R16_PA_INT_MODE |= pin;
R32_PA_OUT |= pin;
break;
default :
break;
}
R16_PA_INT_IF = pin;
R16_PA_INT_EN |= pin;
}
/*******************************************************************************
* Function Name : GPIOB_ITModeCfg
* Description : GPIOB引脚中断模式配置
* Input : pin: PB0-PB15
GPIO_Pin_0 - GPIO_Pin_15
mode:
GPIO_ITMode_LowLevel - 低电平触发
GPIO_ITMode_HighLevel - 高电平触发
GPIO_ITMode_FallEdge - 下降沿触发
GPIO_ITMode_RiseEdge - 上升沿触发
* Return : None
*******************************************************************************/
void GPIOB_ITModeCfg( UINT32 pin, GPIOITModeTpDef mode )
{
switch( mode )
{
case GPIO_ITMode_LowLevel: // 低电平触发
R16_PB_INT_MODE &= ~pin;
R32_PB_CLR |= pin;
break;
case GPIO_ITMode_HighLevel: // 高电平触发
R16_PB_INT_MODE &= ~pin;
R32_PB_OUT |= pin;
break;
case GPIO_ITMode_FallEdge: // 下降沿触发
R16_PB_INT_MODE |= pin;
R32_PB_CLR |= pin;
break;
case GPIO_ITMode_RiseEdge: // 上升沿触发
R16_PB_INT_MODE |= pin;
R32_PB_OUT |= pin;
break;
default :
break;
}
R16_PB_INT_IF = pin;
R16_PB_INT_EN |= pin;
}
/*******************************************************************************
* Function Name : GPIOPinRemap
* Description : 外设功能引脚映射
* Input : s:
ENABLE - 引脚映射
DISABLE - 默认引脚
perph:
RB_PIN_SPI0 - SPI0: PA12/PA13/PA14/PA15 -> PB12/PB13/PB14/PB15
RB_PIN_UART3 - UART3: PA4/PA5 -> PB20/PB21
RB_PIN_UART2 - UART2: PA6/PA7 -> PB22/PB23
RB_PIN_UART1 - UART1: PA8/PA9 -> PB8/PB9
RB_PIN_UART0 - UART0: PB4/PB7 -> PA15/PA14
RB_PIN_TMR3 - TMR3: PA2 -> PB18
RB_PIN_TMR2 - TMR2: PA11 -> PB11
RB_PIN_TMR1 - TMR1: PA10 -> PB10
RB_PIN_TMR0 - TMR0: PA3 -> PB19
* Return : None
*******************************************************************************/
void GPIOPinRemap( UINT8 s, UINT16 perph )
{
if( s ) R16_PIN_ALTERNATE |= perph;
else R16_PIN_ALTERNATE &= ~perph;
}
/*******************************************************************************
* Function Name : GPIOAGPPCfg
* Description : 模拟外设GPIO引脚功能控制
* Input : s:
ENABLE - 打开模拟外设功能,关闭数字功能
DISABLE - 启用数字功能,关闭模拟外设功能
perph:
RB_PIN_ADC0_1_IE - ADC0-1通道
RB_PIN_ADC2_3_IE - ADC2-3通道
RB_PIN_ADC4_5_IE - ADC4-5通道
RB_PIN_ADC6_7_IE - ADC6-7通道
RB_PIN_ADC8_9_IE - ADC8-9通道
RB_PIN_ADC10_11_IE - ADC10-11通道
RB_PIN_ADC12_13_IE - ADC12-13通道
RB_PIN_XT32K_IE - 外部32K引脚
RB_PIN_USB_IE - USB功能信号引脚
RB_PIN_ETH_IE - 以太网功能信号引脚
RB_PIN_SEG0_3_IE - LCD控制器SEG0-3驱动引脚
RB_PIN_SEG4_7_IE - LCD控制器SEG4-7驱动引脚
RB_PIN_SEG8_11_IE - LCD控制器SEG8-11驱动引脚
RB_PIN_SEG12_15_IE - LCD控制器SEG12-15驱动引脚
RB_PIN_SEG16_19_IE - LCD控制器SEG16-19驱动引脚
RB_PIN_SEG20_23_IE - LCD控制器SEG20-23驱动引脚
* Return : None
*******************************************************************************/
void GPIOAGPPCfg( UINT8 s, UINT16 perph )
{
if( s ) R16_PIN_ANALOG_IE |= perph;
else R16_PIN_ANALOG_IE &= ~perph;
}
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册