cotex-m4-emulator2

This commit is contained in:
bj 2021-10-26 11:31:19 +08:00
parent 2f86d928c6
commit 471e2d7920
73 changed files with 64 additions and 33868 deletions

View File

@ -1,10 +1,24 @@
# 从零开始构建矽璓工业物联操作系统使用ARM架构的STM32F407-discovery开发板
# 从零开始构建矽璓工业物联操作系统使用ARM架构的cortex-m4 emulator
[XiUOS](http://xuos.io/) (X Industrial Ubiquitous Operating System) 矽璓工业物联操作系统是一款面向工业物联场景的泛在操作系统,来自泛在操作系统研究计划。所谓泛在操作系统(UOS: Ubiquitous Operating Systems)是支持互联网时代人机物融合泛在计算应用模式的新型操作系统是传统操作系统概念的泛化与延伸。在泛在操作系统技术体系中不同的泛在计算设备和泛在应用场景需要符合各自特性的不同UOSXiUOS即是面向工业物联场景的一种UOS主要由一个极简的微型实时操作系统(RTOS)内核和其上的智能工业物联框架构成,支持工业物联网(IIoT: Industrial Internet of Things)应用
[XiUOS](http://xuos.io/) (X Industrial Ubiquitous Operating System) 矽璓XiUOS是一款面向智慧车间的工业物联网操作系统主要由一个极简的微型实时操作系统内核和其上的工业物联框架构成通过高效管理工业物联网设备、支撑工业物联应用在生产车间内实现智能化的“感知环境、联网传输、知悉识别、控制调整”促进以工业设备和工业控制系统为核心的人、机、物深度互联帮助提升生产线的数字化和智能化水平
>注最新版README请访问[从零开始构建矽璓工业物联操作系统使用ARM架构的STM32F407-discovery开发板](https://blog.csdn.net/AIIT_Ubiquitous/article/details/116209686),如博客内容与本地文档有差异,以网站内容为准。
## 开发环境搭建
## 1. 简介
QEMU 是一个通用的开源模拟器和虚拟化工具。目前QEMU已经可以较完整的支持ARM cortex-m4架构。XiUOS同样支持运行在QEMU上
| 硬件 | 描述 |
| -------- | ------------- |
| 芯片型号 | netduinoplus2 |
| 架构 | cortex-m4 |
| 主频 | 168MHz |
| 片内SRAM | 100+KB |
| 外设支持 | UART、GPIO |
## 2. 开发环境搭建
### 推荐使用:
@ -59,15 +73,16 @@ git clone https://git.trustie.net/xuos/xiuos.git
```
打开源码文件包可以看到以下目录:
| 名称 | 说明 |
| -- | -- |
| application | 应用代码 |
| board | 板级支持包 |
| framework | 应用框架 |
| fs | 文件系统 |
| kernel | 内核源码 |
| resources | 驱动文件 |
| tool | 系统工具 |
| 名称 | 说明 |
| ----------- | ---------- |
| application | 应用代码 |
| board | 板级支持包 |
| framework | 应用框架 |
| fs | 文件系统 |
| kernel | 内核源码 |
| resources | 驱动文件 |
| tool | 系统工具 |
使用VScode打开代码具体操作步骤为在源码文件夹下打开系统终端输入`code .`即可打开VScode开发环境如下图所示
@ -75,6 +90,7 @@ git clone https://git.trustie.net/xuos/xiuos.git
<img src = img/vscode.jpg width =1000>
</div>
### 裁减配置工具的下载
裁减配置工具:
@ -101,113 +117,85 @@ ARM arm-none-eabi(`gcc version 6.3.1`)默认安装到Ubuntu的/usr/bin/arm
$ sudo apt install gcc-arm-none-eabi
```
# 在STM32F407-DISCOVERY上创建第一个应用 --helloworld
## 1. 简介
| 硬件 | 描述 |
| -- | -- |
|芯片型号| Stm32F407VGT6|
|CPU|arm cortex-m|
|主频| 168MHz |
|片内SRAM| 192KB |
|片上FLASH| 1MB |
| 外设 | -- |
| | ADC、DAC、USB、GPIO、UART、SPI、SDIO、RTC、CAN、DMA、MAC、I²C、WDT、Timer等 |
XiUOS板级驱动当前支持使用GPIO、I2C、LCD、USB、RTC、SPI、Timer、UART和WDT等。
## 2. 编译说明
## 3. 编译说明
### 编辑环境:`Ubuntu18.04`
### 编译工具链:`arm-none-eabi-gcc`
使用`VScode`打开工程的方法有多种,本文介绍一种快捷键,在项目目录下将`code .`输入linux系统命令终端即可打开目标项目
修改`applications`文件夹下`main.c`
在输出函数中写入 `Hello, world!!! \n Running on stm32f407-st-discovery`完成代码编辑。
![main](img/main.png)
编译步骤:
1.在VScode命令终端中执行以下命令生成配置文件
```c
make BOARD=stm32f407-st-discovery menuconfig
make BOARD=cortex-m4-emulator menuconfig
```
2.在menuconfig界面配置需要关闭和开启的功能按回车键进入下级菜单按Y键选中需要开启的功能按N键选中需要关闭的功能配置结束后保存并退出本例旨在演示简单的输出例程所以没有需要配置的选项双击快捷键ESC退出配置
![menuconfig1](img/menuconfig1.png)
<div align= "center">
<img src = img/menuconfig.png width =1000>
</div>
退出时选择`yes`保存上面所配置的内容,如下图所示:
![menuconfig2](img/menuconfig2.jpg)
<div align= "center">
<img src = img/menuconfig1.png width =1000>
</div>
3.继续执行以下命令,进行编译
```c
make BOARD=stm32f407-st-discovery
```
make BOARD=cortex-m4-emulator
```
4.如果编译正确无误会产生XiUOS_stm32f407-st-discovery.elf、XiUOS_stm32f407-st-discovery.bin文件。其中XiUOS_stm32f407-st-discovery.bin需要烧写到设备中进行运行
4.如果编译正确无误会产生XiUOS_cortex-m4-emulator.elf、XiUOS_cortex-m4-emulator.bin文件
## 3. 烧写及执行
将 BOARD=stm32f407-st-discovery开发板SWD经 st-link 转接到USB接口然后使用st-flash工具进行烧写bin文件。
![stm32f407-st-discovery](img/stm32f407-st-discovery.png)
## 4. 运行
### 烧写工具
ARMST-LINKST-LINK V2实物如图可在购物网站搜索关键字购买
![st-link](img/st-link.png)
下载并以下执行命令以下命令安装st-link工具(本文使用v1.5.1版本),下载地址为:[http://101.36.126.201:8011/stlink.zip](http://101.36.126.201:8011/stlink.zip)
### 4.1 安装QEMU
```
sudo apt install libusb-dev
sudo apt install libusb-1.0-0-dev
sudo apt install cmake
cd stlink
make
cd build/Release && make install DESTDIR=_install
sudo apt install qemu-system-arm
```
将生成的st-flash在stlink/build/Release/bin文件夹下复制到/usr/bin下就可使用了
### 4.2 运行结果
代码根目录下执行st-flash工具烧录
通过以下命令启动QEMU并加载XiUOS ELF文件
```
sudo st-flash write build/XiUOS_stm32f407-st-discovery.bin 0x8000000
qemu-system-arm -machine netduinoplus2 -nographic -kernel build/XiUOS_cortex-m4-emulator.elf
```
此外推荐用户使用putty作为终端工具安装命令如下
QEMU运行起来后将会在终端上看到信息打印输出
```c
sudo apt install putty
<div align= "center">
<img src = img/terminal.png width =1000>
</div>
### 4.3 调试
通过QEMU可以方便的对XiUOS进行调试首先安装gdb调试工具
```
sudo apt install gdb-multiarch
```
打开putty配置串口信息
并通过以下命令启动QEMU
```c
sudo puty
```
qemu-system-arm -machine netduinoplus2 -nographic -kernel build/XiUOS_cortex-m4-emulator.elf -s -S
```
选择ttyUSB0这个端口号根据具体情况而定配置波特率为115200。
然后要重新开启另一个linux系统终端一个终端执行`riscv-none-embed-gdb`命令
![putty](img/putty.png)
注意:选择正确的终端端口号,最后可以执行以下命令,清除配置文件和编译生成的文件
```c
make BOARD=stm32f407-st-discovery distclean
```
### 3.1 运行结果
如果编译 & 烧写无误,将会在串口终端上看到信息打印输出,(终端串口引脚为PB6、PB7)。
![terminal](img/terminal.png)
gdb-multiarch build/XiUOS_cortex-m4-emulator.elf -ex "target remote localhost:1234"
```

Binary file not shown.

Before

Width:  |  Height:  |  Size: 13 KiB

After

Width:  |  Height:  |  Size: 15 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 35 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 88 KiB

After

Width:  |  Height:  |  Size: 18 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 28 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 97 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 58 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 286 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 178 KiB

After

Width:  |  Height:  |  Size: 52 KiB

View File

@ -1,11 +1,3 @@
menuconfig BSP_USING_CAN
bool "Using CAN device"
default n
select RESOURCES_CAN
if BSP_USING_CAN
source "$BSP_DIR/third_party_driver/can/Kconfig"
endif
menuconfig BSP_USING_DMA
bool "Using DMA device"
default y
@ -21,56 +13,6 @@ if BSP_USING_GPIO
source "$BSP_DIR/third_party_driver/gpio/Kconfig"
endif
menuconfig BSP_USING_I2C
bool "Using I2C device"
default n
select RESOURCES_I2C
if BSP_USING_I2C
source "$BSP_DIR/third_party_driver/i2c/Kconfig"
endif
menuconfig BSP_USING_LCD
bool "Using LCD device"
default n
select BSP_USING_SPI1
select RESOURCES_LCD
if BSP_USING_LCD
source "$BSP_DIR/third_party_driver/lcd/Kconfig"
endif
menuconfig BSP_USING_RTC
bool "Using RTC device"
default n
select RESOURCES_RTC
if BSP_USING_RTC
source "$BSP_DIR/third_party_driver/rtc/Kconfig"
endif
menuconfig BSP_USING_SDIO
bool "Using SDIO device"
default n
select RESOURCES_SDIO
if BSP_USING_SDIO
source "$BSP_DIR/third_party_driver/sdio/Kconfig"
endif
menuconfig BSP_USING_SPI
bool "Using SPI device"
default n
select RESOURCES_SPI
select BSP_USING_DMA
if BSP_USING_SPI
source "$BSP_DIR/third_party_driver/spi/Kconfig"
endif
menuconfig BSP_USING_HWTIMER
bool "Using HWTIMER device"
default n
select RESOURCES_HWTIMER
if BSP_USING_HWTIMER
source "$BSP_DIR/third_party_driver/timer/Kconfig"
endif
menuconfig BSP_USING_UART
bool "Using UART device"
default y
@ -78,28 +20,3 @@ select RESOURCES_SERIAL
if BSP_USING_UART
source "$BSP_DIR/third_party_driver/uart/Kconfig"
endif
menuconfig BSP_USING_USB
bool "Using USB device"
default n
select BSP_USING_USBH
select RESOURCES_USB
select RESOURCES_USB_HOST
select USBH_MSTORAGE
select RESOURCES_USB_DEVICE
if BSP_USING_USB
source "$BSP_DIR/third_party_driver/usb/Kconfig"
endif
menuconfig BSP_USING_LWIP
bool "Using LwIP device"
default n
select RESOURCES_LWIP
menuconfig BSP_USING_WDT
bool "Using WATCHDOG device"
default y
select RESOURCES_WDT
if BSP_USING_WDT
source "$BSP_DIR/third_party_driver/watchdog/Kconfig"
endif

View File

@ -1,12 +0,0 @@
config CAN_BUS_NAME_1
string "can bus name"
default "can1"
config CAN_DRIVER_NAME
string "can driver name"
default "can1_drv"
config CAN_1_DEVICE_NAME_1
string "can bus 1 device 1 name"
default "can1_dev1"

View File

@ -1,4 +0,0 @@
SRC_FILES := hardware_can.c connect_can.c
include $(KERNEL_ROOT)/compiler.mk

View File

@ -1,275 +0,0 @@
/*
* Copyright (c) Guangzhou Xingyi Electronic Technology Co., Ltd
*
* Change Logs:
* Date Author Notes
* 2014-7-4 alientek first version
*/
/**
* @file connect_can.c
* @brief support stm32f407-discovery-board can function and register to bus framework
* @version 1.0
* @author AIIT XUOS Lab
* @date 2021-04-22
*/
/*************************************************
File name: can.c
Description: support can configure and spi bus register function
Others: hardware/can/can.c for references
History:
1. Date: 2021-04-22
Author: AIIT XUOS Lab
Modification:
1. support stm32f407-discovery-board spi configure, write and read
2. support stm32f407-discovery-board spi bus device and driver register
*************************************************/
#include "connect_can.h"
#include "misc.h"
#include "hardware_rcc.h"
#include "hardware_gpio.h"
static struct CanSendConfigure can_send_deconfig =
{
.stdid = 0x55,
.exdid = 0x00,
.ide = 0 ,
.rtr = 0,
.data_lenth = 8
};
static void CanGPIOInit(void)
{
CAN_FilterInitTypeDef can1_filter;
GPIO_InitTypeDef gpio_initstructure;
CAN_InitTypeDef can_initstruction;
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOB, ENABLE);
RCC_APB1PeriphClockCmd(RCC_APB1Periph_CAN1, ENABLE);
gpio_initstructure.GPIO_Pin = GPIO_Pin_9 | GPIO_Pin_8;
gpio_initstructure.GPIO_Mode = GPIO_Mode_AF;
gpio_initstructure.GPIO_OType = GPIO_OType_PP;
gpio_initstructure.GPIO_Speed = GPIO_Speed_100MHz;
gpio_initstructure.GPIO_PuPd = GPIO_PuPd_UP;
GPIO_Init(GPIOB, &gpio_initstructure);
GPIO_PinAFConfig(GPIOB, GPIO_PinSource9, GPIO_AF_CAN1);
GPIO_PinAFConfig(GPIOB, GPIO_PinSource8, GPIO_AF_CAN1);
}
static void Can1NvicConfig(void)
{
NVIC_InitTypeDef can_nvic_config;
can_nvic_config.NVIC_IRQChannel = CAN1_RX0_IRQn;
can_nvic_config.NVIC_IRQChannelPreemptionPriority = 2;
can_nvic_config.NVIC_IRQChannelSubPriority = 2;
can_nvic_config.NVIC_IRQChannelCmd = ENABLE;
CAN_ITConfig(CAN1, CAN_IT_FMP0, ENABLE);
NVIC_Init(&can_nvic_config);
}
static uint32 CanModeInit(void *drv, struct BusConfigureInfo *configure_info)
{
NULL_PARAM_CHECK(drv);
NULL_PARAM_CHECK(configure_info);
CAN_FilterInitTypeDef can1_filter;
CAN_InitTypeDef can_initstruction;
struct CanDriverConfigure * config = ( struct CanDriverConfigure *)configure_info->private_data;
can_initstruction.CAN_TTCM = DISABLE;
can_initstruction.CAN_ABOM = ENABLE;
can_initstruction.CAN_AWUM = DISABLE;
can_initstruction.CAN_NART = ENABLE;
can_initstruction.CAN_TXFP = DISABLE;
can_initstruction.CAN_Mode = config->mode;
can_initstruction.CAN_RFLM = DISABLE;
can_initstruction.CAN_SJW = config->tsjw;
can_initstruction.CAN_BS1 = config->tbs1;
can_initstruction.CAN_BS2 = config->tbs2;
can_initstruction.CAN_Prescaler = config->brp;
CAN_Init(CAN1, &can_initstruction);
can1_filter.CAN_FilterNumber=0;
can1_filter.CAN_FilterMode=CAN_FilterMode_IdMask;
can1_filter.CAN_FilterScale=CAN_FilterScale_32bit;
can1_filter.CAN_FilterIdHigh=0x0000;
can1_filter.CAN_FilterIdLow=0x0000;
can1_filter.CAN_FilterMaskIdHigh=0x0000;
can1_filter.CAN_FilterMaskIdLow=0x0000;
can1_filter.CAN_FilterFIFOAssignment=CAN_Filter_FIFO0;
can1_filter.CAN_FilterActivation=ENABLE;
CAN_FilterInit(&can1_filter);
#ifdef CAN_USING_INTERRUPT
Can1NvicConfig();
#endif
return 0;
}
static uint32 CanSendMsg(void * dev , struct BusBlockWriteParam *write_param )
{
NULL_PARAM_CHECK(write_param);
uint8 *data = (uint8 * ) write_param->buffer;
u8 mbox;
u16 i = 0;
u16 timer_count = 1000;
CanTxMsg tx_data;
tx_data.StdId = 0x55;
tx_data.ExtId = 0x00;
tx_data.IDE = 0;
tx_data.RTR = 0;
tx_data.DLC = write_param->size;
for(i = 0;i<tx_data.DLC;i++) {
tx_data.Data[i] = data[i];
}
mbox = CAN_Transmit(CAN1,&tx_data);
while (CAN_TransmitStatus(CAN1,mbox)== CAN_TxStatus_Failed &&timer_count) {
timer_count--;
}
if (timer_count<=0) {
return ERROR;
}
return EOK;
}
static uint32 CanRecvMsg(void *dev , struct BusBlockReadParam *databuf)
{
NULL_PARAM_CHECK(dev);
int i;
uint8 * buf = (uint8 *)databuf->buffer;
CanRxMsg msg;
if(CAN_MessagePending(CAN1, CAN_FIFO0) == 0)
return 0;
CAN_Receive(CAN1, CAN_FIFO0, &msg);
for(i = 0 ;i<msg.DLC ;i++)
buf[i] = msg.Data[i];
databuf->size = msg.DLC ;
return msg.DLC;
}
static struct CanDevDone dev_done =
{
.open = NONE,
.close = NONE,
.write = CanSendMsg,
.read = CanRecvMsg
};
static struct CanHardwareDevice dev;
#ifdef CAN_USING_INTERRUPT
void CAN1_RX0_IRQHandler(void)
{
CanRxMsg rxmsg;
int i = 0;
CAN_Receive(CAN1, 0, &rxmsg);
for(i = 0;i<8;i++)
KPrintf("rxbuf [%d] = :%d",i,rxmsg.Data[i]);
}
DECLARE_HW_IRQ(CAN1_RX0_IRQn, CAN1_RX0_IRQHandler, NONE);
#endif
static int BoardCanBusInit(struct Stm32Can *stm32can_bus, struct CanDriver *can_driver)
{
x_err_t ret = EOK;
/*Init the can bus */
ret = CanBusInit(&stm32can_bus->can_bus, stm32can_bus->bus_name);
if (EOK != ret) {
KPrintf("Board_can_init canBusInit error %d\n", ret);
return ERROR;
}
/*Init the can driver*/
ret = CanDriverInit(can_driver, CAN_DRIVER_NAME);
if (EOK != ret) {
KPrintf("Board_can_init canDriverInit error %d\n", ret);
return ERROR;
}
/*Attach the can driver to the can bus*/
ret = CanDriverAttachToBus(CAN_DRIVER_NAME, stm32can_bus->bus_name);
if (EOK != ret) {
KPrintf("Board_can_init CanDriverAttachToBus error %d\n", ret);
return ERROR;
}
return ret;
}
static x_err_t HwCanDeviceAttach(const char *bus_name, const char *device_name)
{
NULL_PARAM_CHECK(bus_name);
NULL_PARAM_CHECK(device_name);
x_err_t result;
struct CanHardwareDevice *can_device;
/* attach the device to can bus*/
can_device = (struct CanHardwareDevice *)x_malloc(sizeof(struct CanHardwareDevice));
CHECK(can_device);
memset(can_device, 0, sizeof(struct CanHardwareDevice));
can_device->dev_done = &dev_done;
result = CanDeviceRegister(can_device, NONE, device_name);
if (EOK != result) {
KPrintf("board_can_init canDeviceInit device %s error %d\n", "can1", result);
return ERROR;
}
result = CanDeviceAttachToBus(device_name, bus_name);
if (result != EOK) {
SYS_ERR("%s attach to %s faild, %d\n", device_name, bus_name, result);
}
CHECK(result == EOK);
KPrintf("%s attach to %s done\n", device_name, bus_name);
return result;
}
struct Stm32Can can1;
int Stm32HwCanBusInit(void)
{
x_err_t ret = EOK;
struct Stm32Can *stm32_can_bus;
static struct CanDriver can_driver;
memset(&can_driver, 0, sizeof(struct CanDriver));
can_driver.configure = CanModeInit;
CanGPIOInit();
stm32_can_bus = &can1;
stm32_can_bus->instance = CAN1;
stm32_can_bus->bus_name = CAN_BUS_NAME_1;
stm32_can_bus->can_bus.private_data = &can1;
ret = BoardCanBusInit(stm32_can_bus, &can_driver);
if (EOK != ret) {
KPrintf(" can_bus_init %s error ret %u\n", stm32_can_bus->bus_name, ret);
return ERROR;
}
ret = HwCanDeviceAttach(CAN_BUS_NAME_1,CAN_1_DEVICE_NAME_1);
if (EOK != ret) {
KPrintf(" HwCanDeviceAttach %s error ret %u\n", stm32_can_bus->bus_name, ret);
return ERROR;
}
return EOK;
}

View File

@ -1,12 +0,0 @@
config CAN_BUS_NAME_1
string "can bus name"
default "can1"
config CAN_DRIVER_NAME
string "can driver name"
default "can1_drv"
config CAN_1_DEVICE_NAME_1
string "can bus 1 device 1 name"
default "can1_dev1"

View File

@ -1,4 +0,0 @@
SRC_FILES := hardware_ethernet.c connect_ethernet.c ethernetif.c
include $(KERNEL_ROOT)/compiler.mk

View File

@ -1,363 +0,0 @@
/**
******************************************************************************
* @file stm32f4x7_eth_bsp.c
* @author MCD Application Team
* @version V1.0.0
* @date 31-October-2011
* @brief STM32F4x7 Ethernet hardware configuration.
******************************************************************************
* @attention
*
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
/**
* @file connect_ethernet.c
* @brief Adapted network software protocol stack and hardware operation functions
* @version 1.0
* @author AIIT XUOS Lab
* @date 2021-05-29
*/
/* Includes ------------------------------------------------------------------*/
#include "hardware_syscfg.h"
#include "hardware_gpio.h"
#include "hardware_rcc.h"
#include "misc.h"
#include "hardware_exti.h"
#include "hardware_eth.h"
#include "connect_ethernet.h"
#include <xs_base.h>
#include <xs_sem.h>
#include <xs_isr.h>
__IO uint32_t EthInitStatus = 0;
__IO uint8_t EthLinkStatus = 0;
/* Private function prototypes -----------------------------------------------*/
static void ETH_GPIO_Config(void);
static void ETH_MACDMA_Config(void);
extern int32 s_xSemaphore;
/* Private functions ---------------------------------------------------------*/
/**
* @brief ETH_BSP_Config
* @param None
* @retval None
*/
void ETH_BSP_Config(void)
{
RCC_ClocksTypeDef RCC_Clocks;
/* Configure the GPIO ports for ethernet pins */
ETH_GPIO_Config();
/* Configure the Ethernet MAC/DMA */
ETH_MACDMA_Config();
if (EthInitStatus == 0)
{
while(1);
}
/* Configure Systick clock source as HCLK */
SysTick_CLKSourceConfig(SysTick_CLKSource_HCLK);
/* SystTick configuration: an interrupt every 10ms */
RCC_GetClocksFreq(&RCC_Clocks);
SysTick_Config(RCC_Clocks.HCLK_Frequency / 100);
}
/**
* @brief Configures the Ethernet Interface
* @param None
* @retval None
*/
static void ETH_MACDMA_Config(void)
{
ETH_InitTypeDef ETH_InitStructure;
/* Enable ETHERNET clock */
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_ETH_MAC | RCC_AHB1Periph_ETH_MAC_Tx |
RCC_AHB1Periph_ETH_MAC_Rx, ENABLE);
/* Reset ETHERNET on AHB Bus */
ETH_DeInit();
/* Software reset */
ETH_SoftwareReset();
/* Wait for software reset */
while (ETH_GetSoftwareResetStatus() == SET);
/* ETHERNET Configuration --------------------------------------------------*/
/* Call ETH_StructInit if you don't like to configure all ETH_InitStructure parameter */
ETH_StructInit(&ETH_InitStructure);
/* Fill ETH_InitStructure parametrs */
/*------------------------ MAC -----------------------------------*/
ETH_InitStructure.ETH_AutoNegotiation = ETH_AutoNegotiation_Enable;
ETH_InitStructure.ETH_LoopbackMode = ETH_LoopbackMode_Disable;
ETH_InitStructure.ETH_RetryTransmission = ETH_RetryTransmission_Disable;
ETH_InitStructure.ETH_AutomaticPadCRCStrip = ETH_AutomaticPadCRCStrip_Disable;
ETH_InitStructure.ETH_ReceiveAll = ETH_ReceiveAll_Disable;
ETH_InitStructure.ETH_BroadcastFramesReception = ETH_BroadcastFramesReception_Enable;
ETH_InitStructure.ETH_PromiscuousMode = ETH_PromiscuousMode_Disable;
ETH_InitStructure.ETH_MulticastFramesFilter = ETH_MulticastFramesFilter_Perfect;
ETH_InitStructure.ETH_UnicastFramesFilter = ETH_UnicastFramesFilter_Perfect;
#ifdef CHECKSUM_BY_HARDWARE
ETH_InitStructure.ETH_ChecksumOffload = ETH_ChecksumOffload_Enable;
#endif
/*------------------------ DMA -----------------------------------*/
/* When we use the Checksum offload feature, we need to enable the Store and Forward mode:
the store and forward guarantee that a whole frame is stored in the FIFO, so the MAC can insert/verify the checksum,
if the checksum is OK the DMA can handle the frame otherwise the frame is dropped */
ETH_InitStructure.ETH_DropTCPIPChecksumErrorFrame = ETH_DropTCPIPChecksumErrorFrame_Enable;
ETH_InitStructure.ETH_ReceiveStoreForward = ETH_ReceiveStoreForward_Enable;
ETH_InitStructure.ETH_TransmitStoreForward = ETH_TransmitStoreForward_Enable;
ETH_InitStructure.ETH_ForwardErrorFrames = ETH_ForwardErrorFrames_Disable;
ETH_InitStructure.ETH_ForwardUndersizedGoodFrames = ETH_ForwardUndersizedGoodFrames_Disable;
ETH_InitStructure.ETH_SecondFrameOperate = ETH_SecondFrameOperate_Enable;
ETH_InitStructure.ETH_AddressAlignedBeats = ETH_AddressAlignedBeats_Enable;
ETH_InitStructure.ETH_FixedBurst = ETH_FixedBurst_Enable;
ETH_InitStructure.ETH_RxDMABurstLength = ETH_RxDMABurstLength_32Beat;
ETH_InitStructure.ETH_TxDMABurstLength = ETH_TxDMABurstLength_32Beat;
ETH_InitStructure.ETH_DMAArbitration = ETH_DMAArbitration_RoundRobin_RxTx_2_1;
/* Configure Ethernet */
EthInitStatus = ETH_Init(&ETH_InitStructure, DP83848_PHY_ADDRESS);
}
/**
* @brief Configures the different GPIO ports.
* @param None
* @retval None
*/
void ETH_GPIO_Config(void)
{
GPIO_InitTypeDef GPIO_InitStructure;
/* Enable GPIOs clocks */
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOA |
RCC_AHB1Periph_GPIOB |
RCC_AHB1Periph_GPIOC |
RCC_AHB1Periph_GPIOI |
RCC_AHB1Periph_GPIOG |
RCC_AHB1Periph_GPIOH |
RCC_AHB1Periph_GPIOF, ENABLE);
/* Enable SYSCFG clock */
RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE);
/* Configure MCO (PA8) */
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_8;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_100MHz;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL ;
GPIO_Init(GPIOA, &GPIO_InitStructure);
/* MII/RMII Media interface selection --------------------------------------*/
#ifdef MII_MODE /* Mode MII with STM324xG-EVAL */
#ifdef PHY_CLOCK_MCO
/* Output HSE clock (25MHz) on MCO pin (PA8) to clock the PHY */
RCC_MCO1Config(RCC_MCO1Source_HSE, RCC_MCO1Div_1);
#endif /* PHY_CLOCK_MCO */
SYSCFG_ETH_MediaInterfaceConfig(SYSCFG_ETH_MediaInterface_MII);
#elif defined RMII_MODE /* Mode RMII with STM324xG-EVAL */
SYSCFG_ETH_MediaInterfaceConfig(SYSCFG_ETH_MediaInterface_RMII);
#endif
/* Ethernet pins configuration ************************************************/
/*
ETH_MDIO -------------------------> PA2
ETH_MDC --------------------------> PC1
ETH_PPS_OUT ----------------------> PB5
ETH_MII_CRS ----------------------> PH2
ETH_MII_COL ----------------------> PH3
ETH_MII_RX_ER --------------------> PI10
ETH_MII_RXD2 ---------------------> PH6
ETH_MII_RXD3 ---------------------> PH7
ETH_MII_TX_CLK -------------------> PC3
ETH_MII_TXD2 ---------------------> PC2
ETH_MII_TXD3 ---------------------> PB8
ETH_MII_RX_CLK/ETH_RMII_REF_CLK---> PA1
ETH_MII_RX_DV/ETH_RMII_CRS_DV ----> PA7
ETH_MII_RXD0/ETH_RMII_RXD0 -------> PC4
ETH_MII_RXD1/ETH_RMII_RXD1 -------> PC5
ETH_MII_TX_EN/ETH_RMII_TX_EN -----> PG11
ETH_MII_TXD0/ETH_RMII_TXD0 -------> PG13
ETH_MII_TXD1/ETH_RMII_TXD1 -------> PG14
*/
/* Configure PA1, PA2 and PA7 */
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_1 | GPIO_Pin_2 | GPIO_Pin_7;
GPIO_Init(GPIOA, &GPIO_InitStructure);
GPIO_PinAFConfig(GPIOA, GPIO_PinSource1, GPIO_AF_ETH);
GPIO_PinAFConfig(GPIOA, GPIO_PinSource2, GPIO_AF_ETH);
GPIO_PinAFConfig(GPIOA, GPIO_PinSource7, GPIO_AF_ETH);
/* Configure PB11 and PB12 */
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_11 | GPIO_Pin_12 | GPIO_Pin_13;
GPIO_Init(GPIOB, &GPIO_InitStructure);
GPIO_PinAFConfig(GPIOB, GPIO_PinSource11, GPIO_AF_ETH);
GPIO_PinAFConfig(GPIOB, GPIO_PinSource12, GPIO_AF_ETH);
GPIO_PinAFConfig(GPIOB, GPIO_PinSource13, GPIO_AF_ETH);
/* Configure PC1, PC2, PC3, PC4 and PC5 */
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_1 | GPIO_Pin_4 | GPIO_Pin_5;
GPIO_Init(GPIOC, &GPIO_InitStructure);
GPIO_PinAFConfig(GPIOC, GPIO_PinSource1, GPIO_AF_ETH);
GPIO_PinAFConfig(GPIOC, GPIO_PinSource4, GPIO_AF_ETH);
GPIO_PinAFConfig(GPIOC, GPIO_PinSource5, GPIO_AF_ETH);
}
/**
* @brief Configure the PHY to generate an interrupt on change of link status.
* @param PHYAddress: external PHY address
* @retval None
*/
uint32_t Eth_Link_PHYITConfig(uint16_t PHYAddress)
{
uint32_t tmpreg = 0;
/* Read MICR register */
tmpreg = ETH_ReadPHYRegister(PHYAddress, PHY_MICR);
/* Enable output interrupt events to signal via the INT pin */
tmpreg |= (uint32_t)PHY_MICR_INT_EN | PHY_MICR_INT_OE;
if(!(ETH_WritePHYRegister(PHYAddress, PHY_MICR, tmpreg)))
{
/* Return ERROR in case of write timeout */
return ETH_ERROR;
}
/* Read MISR register */
tmpreg = ETH_ReadPHYRegister(PHYAddress, PHY_MISR);
/* Enable Interrupt on change of link status */
tmpreg |= (uint32_t)PHY_MISR_LINK_INT_EN;
if(!(ETH_WritePHYRegister(PHYAddress, PHY_MISR, tmpreg)))
{
/* Return ERROR in case of write timeout */
return ETH_ERROR;
}
/* Return SUCCESS */
return ETH_SUCCESS;
}
/**
* @brief EXTI configuration for Ethernet link status.
* @param PHYAddress: external PHY address
* @retval None
*/
void Eth_Link_EXTIConfig(void)
{
GPIO_InitTypeDef GPIO_InitStructure;
EXTI_InitTypeDef EXTI_InitStructure;
NVIC_InitTypeDef NVIC_InitStructure;
/* Enable the INT (PB14) Clock */
RCC_AHB1PeriphClockCmd(ETH_LINK_GPIO_CLK, ENABLE);
RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE);
/* Configure INT pin as input */
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_InitStructure.GPIO_Pin = ETH_LINK_PIN;
GPIO_Init(ETH_LINK_GPIO_PORT, &GPIO_InitStructure);
/* Connect EXTI Line to INT Pin */
SYSCFG_EXTILineConfig(ETH_LINK_EXTI_PORT_SOURCE, ETH_LINK_EXTI_PIN_SOURCE);
/* Configure EXTI line */
EXTI_InitStructure.EXTI_Line = ETH_LINK_EXTI_LINE;
EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;
EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Falling;
EXTI_InitStructure.EXTI_LineCmd = ENABLE;
EXTI_Init(&EXTI_InitStructure);
/* Enable and set the EXTI interrupt to the highest priority */
NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2);
NVIC_InitStructure.NVIC_IRQChannel = EXTI15_10_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
}
/**
* @brief This function handles Ethernet link status.
* @param None
* @retval None
*/
void Eth_Link_ITHandler(uint16_t PHYAddress)
{
/* Check whether the link interrupt has occurred or not */
if(((ETH_ReadPHYRegister(PHYAddress, PHY_MISR)) & PHY_LINK_STATUS) != 0)
{
EthLinkStatus = ~EthLinkStatus;
}
}
void assert_failed(uint8_t* file, uint32_t line)
{
/* User can add his own implementation to report the file name and line number,
ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
/* Infinite loop */
while (1)
{}
}
#ifdef BSP_USING_LWIP
void ETHERNET_IRQHandler(int irq_num, void *arg)
{
KPrintf("ethernet irq comes one ...\n");
ETH_DMAClearITPendingBit(ETH_DMA_IT_R);
ETH_DMAClearITPendingBit(ETH_DMA_IT_NIS);
KSemaphoreAbandon(s_xSemaphore);
}
DECLARE_HW_IRQ(ETH_IRQn, ETHERNET_IRQHandler, NONE);
#endif

View File

@ -1,445 +0,0 @@
/**
* @file
* Ethernet Interface Skeleton
*
*/
/*
* Copyright (c) 2001-2004 Swedish Institute of Computer Science.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. The name of the author may not be used to endorse or promote products
* derived from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR IMPLIED
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT
* SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
* EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT
* OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING
* IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY
* OF SUCH DAMAGE.
*
* This file is part of the lwIP TCP/IP stack.
*
* Author: Adam Dunkels <adam@sics.se>
*
*/
/*
* This file is a skeleton for developing Ethernet network interface
* drivers for lwIP. Add code to the low_level functions and do a
* search-and-replace for the word "ethernetif" to replace it with
* something that better describes your network interface.
*/
#include "lwip/opt.h"
#include "lwip/def.h"
#include "lwip/mem.h"
#include "lwip/pbuf.h"
#include "lwip/sys.h"
#include "netif/etharp.h"
#include "err.h"
#include "ethernetif.h"
#include "main.h"
#include <string.h>
#include <hardware_eth.h>
#include <xs_sem.h>
#include <xs_ktask.h>
#include <priv/tcp_priv.h>
#define netifMTU (1500)
#define netifINTERFACE_TASK_STACK_SIZE ( 2048 )
#define netifINTERFACE_TASK_PRIORITY ( configMAX_PRIORITIES - 1 )
#define netifGUARD_BLOCK_TIME ( 250 )
/* The time to block waiting for input. */
#define emacBLOCK_TIME_WAITING_FOR_INPUT ( ( portTickType ) 100 )
/* Define those to better describe your network interface. */
#define IFNAME0 's'
#define IFNAME1 't'
/* MAC ADDRESS: MAC_ADDR0:MAC_ADDR1:MAC_ADDR2:MAC_ADDR3:MAC_ADDR4:MAC_ADDR5 */
#define MAC_ADDR0 2
#define MAC_ADDR1 0
#define MAC_ADDR2 0
#define MAC_ADDR3 0
#define MAC_ADDR4 0
#define MAC_ADDR5 0
static struct netif *s_pxNetIf = NULL;
int32 s_xSemaphore = -1;
/* Ethernet Rx & Tx DMA Descriptors */
extern ETH_DMADESCTypeDef DMARxDscrTab[ETH_RXBUFNB], DMATxDscrTab[ETH_TXBUFNB];
/* Ethernet Receive buffers */
extern uint8_t Rx_Buff[ETH_RXBUFNB][ETH_RX_BUF_SIZE];
/* Ethernet Transmit buffers */
extern uint8_t Tx_Buff[ETH_TXBUFNB][ETH_TX_BUF_SIZE];
/* Global pointers to track current transmit and receive descriptors */
extern ETH_DMADESCTypeDef *DMATxDescToSet;
extern ETH_DMADESCTypeDef *DMARxDescToGet;
/* Global pointer for last received frame infos */
extern ETH_DMA_Rx_Frame_infos *DMA_RX_FRAME_infos;
void ethernetif_input( void * pvParameters );
void LoopGetMacPkg(void * pvParameters);
static void arp_timer(void *arg);
uint32_t TCPTimer = 0;
uint32_t ARPTimer = 0;
__IO uint32_t LocalTime = 0; /* this variable is used to create a time reference incremented by 10ms */
void LwIP_Periodic_Handle(__IO uint32_t localtime)
{
#if LWIP_TCP
/* TCP periodic process every 250 ms */
if (localtime - TCPTimer >= TCP_TMR_INTERVAL)
{
TCPTimer = localtime;
tcp_tmr();
}
#endif
/* ARP periodic process every 5s */
if ((localtime - ARPTimer) >= ARP_TMR_INTERVAL)
{
ARPTimer = localtime;
etharp_tmr();
}
}
void LwIP_Pkt_Handle(struct netif *netif)
{
/* Read a received packet from the Ethernet buffers and send it to the lwIP for handling */
ethernetif_input(netif);
}
void Time_Update_LwIP(void)
{
LocalTime += MS_PER_SYSTICK_F407;
}
/**
* In this function, the hardware should be initialized.
* Called from ethernetif_init().
*
* @param netif the already initialized lwip network interface structure
* for this ethernetif
*/
static void low_level_init(struct netif *netif)
{
uint32_t i;
/* set netif MAC hardware address length */
netif->hwaddr_len = ETHARP_HWADDR_LEN;
/* set netif MAC hardware address */
netif->hwaddr[0] = MAC_ADDR0;
netif->hwaddr[1] = MAC_ADDR1;
netif->hwaddr[2] = MAC_ADDR2;
netif->hwaddr[3] = MAC_ADDR3;
netif->hwaddr[4] = MAC_ADDR4;
netif->hwaddr[5] = MAC_ADDR5;
/* set netif maximum transfer unit */
netif->mtu = 1500;
/* Accept broadcast address and ARP traffic */
netif->flags = NETIF_FLAG_BROADCAST | NETIF_FLAG_ETHARP | NETIF_FLAG_LINK_UP;
s_pxNetIf =netif;
/* create binary semaphore used for informing ethernetif of frame reception */
if (s_xSemaphore < 0)
{
s_xSemaphore = KSemaphoreCreate(0);
}
/* initialize MAC address in ethernet MAC */
ETH_MACAddressConfig(ETH_MAC_Address0, netif->hwaddr);
/* Initialize Tx Descriptors list: Chain Mode */
ETH_DMATxDescChainInit(DMATxDscrTab, &Tx_Buff[0][0], ETH_TXBUFNB);
/* Initialize Rx Descriptors list: Chain Mode */
ETH_DMARxDescChainInit(DMARxDscrTab, &Rx_Buff[0][0], ETH_RXBUFNB);
/* Enable MAC and DMA transmission and reception */
ETH_Start();
/* Enable Ethernet Rx interrrupt */
{
for(i=0; i<ETH_RXBUFNB; i++)
{
ETH_DMARxDescReceiveITConfig(&DMARxDscrTab[i], ENABLE);
}
}
#ifdef CHECKSUM_BY_HARDWARE
/* Enable the checksum insertion for the Tx frames */
{
for(i=0; i<ETH_TXBUFNB; i++)
{
ETH_DMATxDescChecksumInsertionConfig(&DMATxDscrTab[i], ETH_DMATxDesc_ChecksumTCPUDPICMPFull);
}
}
#endif
/* create the task that handles the ETH_MAC */
uint32 thr_id = KTaskCreate((signed char*) "Eth_if",
ethernetif_input,
NULL,
netifINTERFACE_TASK_STACK_SIZE,
15);
if (thr_id >= 0)
{
StartupKTask(thr_id);
}
else
{
KPrintf("Eth create failed !");
}
}
/**
* This function should do the actual transmission of the packet. The packet is
* contained in the pbuf that is passed to the function. This pbuf
* might be chained.
*
* @param netif the lwip network interface structure for this ethernetif
* @param p the MAC packet to send (e.g. IP packet including MAC addresses and type)
* @return ERR_OK if the packet could be sent
* an err_t value if the packet couldn't be sent
*
* @note Returning ERR_MEM here if a DMA queue of your MAC is full can lead to
* strange results. You might consider waiting for space in the DMA queue
* to become availale since the stack doesn't retry to send a packet
* dropped because of memory failure (except for the TCP timers).
*/
static err_t low_level_output(struct netif *netif, struct pbuf *p)
{
static int32 sem = -1;
struct pbuf *q;
uint32_t l = 0;
u8 *buffer ;
if(sem < 0)
{
sem = KSemaphoreCreate(1);
}
KSemaphoreObtain(sem, WAITING_FOREVER);
buffer = (u8 *)(DMATxDescToSet->Buffer1Addr);
for(q = p; q != NULL; q = q->next)
{
memcpy((u8_t*)&buffer[l], q->payload, q->len);
l = l + q->len;
}
ETH_Prepare_Transmit_Descriptors(l);
KSemaphoreAbandon(sem);
return ERR_OK;
}
/**
* Should allocate a pbuf and transfer the bytes of the incoming
* packet from the interface into the pbuf.
*
* @param netif the lwip network interface structure for this ethernetif
* @return a pbuf filled with the received packet (including MAC header)
* NULL on memory error
*/
static struct pbuf * low_level_input(struct netif *netif)
{
struct pbuf *p, *q;
u16_t len;
uint32_t l=0,i =0;
FrameTypeDef frame;
u8 *buffer;
__IO ETH_DMADESCTypeDef *DMARxNextDesc;
p = NULL;
/* Get received frame */
frame = ETH_Get_Received_Frame_interrupt();
/* check that frame has no error */
if ((frame.descriptor->Status & ETH_DMARxDesc_ES) == (uint32_t)RESET)
{
/* Obtain the size of the packet and put it into the "len" variable. */
len = frame.length;
buffer = (u8 *)frame.buffer;
/* We allocate a pbuf chain of pbufs from the pool. */
p = pbuf_alloc(PBUF_RAW, len, PBUF_POOL);
/* Copy received frame from ethernet driver buffer to stack buffer */
if (p != NULL)
{
for (q = p; q != NULL; q = q->next)
{
memcpy((u8_t*)q->payload, (u8_t*)&buffer[l], q->len);
l = l + q->len;
}
}
}
/* Release descriptors to DMA */
/* Check if received frame with multiple DMA buffer segments */
if (DMA_RX_FRAME_infos->Seg_Count > 1)
{
DMARxNextDesc = DMA_RX_FRAME_infos->FS_Rx_Desc;
}
else
{
DMARxNextDesc = frame.descriptor;
}
/* Set Own bit in Rx descriptors: gives the buffers back to DMA */
for (i=0; i<DMA_RX_FRAME_infos->Seg_Count; i++)
{
DMARxNextDesc->Status = ETH_DMARxDesc_OWN;
DMARxNextDesc = (ETH_DMADESCTypeDef *)(DMARxNextDesc->Buffer2NextDescAddr);
}
/* Clear Segment_Count */
DMA_RX_FRAME_infos->Seg_Count =0;
/* When Rx Buffer unavailable flag is set: clear it and resume reception */
if ((ETH->DMASR & ETH_DMASR_RBUS) != (u32)RESET)
{
/* Clear RBUS ETHERNET DMA flag */
ETH->DMASR = ETH_DMASR_RBUS;
/* Resume DMA reception */
ETH->DMARPDR = 0;
}
return p;
}
/**
* This function is the ethernetif_input task, it is processed when a packet
* is ready to be read from the interface. It uses the function low_level_input()
* that should handle the actual reception of bytes from the network
* interface. Then the type of the received packet is determined and
* the appropriate input function is called.
*
* @param netif the lwip network interface structure for this ethernetif
*/
void ethernetif_input( void * pvParameters )
{
struct pbuf *p;
for( ;; )
{
if (KSemaphoreObtain( s_xSemaphore, WAITING_FOREVER)==EOK)
{
p = low_level_input( s_pxNetIf );
if (ERR_OK != s_pxNetIf->input( p, s_pxNetIf))
{
KPrintf("netif input return not OK ! \n");
pbuf_free(p);
p=NULL;
}
}
}
}
void LoopGetMacPkg(void * pvParameters)
{
// Loop Get MAX Pkg
struct netif *netif = (struct netif *)pvParameters;
while (1)
{
/* check if any packet received */
if (ETH_CheckFrameReceived())
{
KPrintf("ETH_CheckFrameReceived invoke !\n");
/* process received ethernet packet */
LwIP_Pkt_Handle(netif);
}
/* handle periodic timers for LwIP */
LwIP_Periodic_Handle(LocalTime);
}
}
/**
* Should be called at the beginning of the program to set up the
* network interface. It calls the function low_level_init() to do the
* actual setup of the hardware.
*
* This function should be passed as a parameter to netif_add().
*
* @param netif the lwip network interface structure for this ethernetif
* @return ERR_OK if the loopif is initialized
* ERR_MEM if private data couldn't be allocated
* any other err_t on error
*/
err_t ethernetif_init(struct netif *netif)
{
LWIP_ASSERT("netif != NULL", (netif != NULL));
#if LWIP_NETIF_HOSTNAME
/* Initialize interface hostname */
netif->hostname = "lwip";
#endif /* LWIP_NETIF_HOSTNAME */
netif->name[0] = IFNAME0;
netif->name[1] = IFNAME1;
netif->output = etharp_output;
netif->linkoutput = low_level_output;
/* initialize the hardware */
low_level_init(netif);
etharp_init();
sys_timeout(ARP_TMR_INTERVAL, arp_timer, NULL);
return ERR_OK;
}
static void arp_timer(void *arg)
{
etharp_tmr();
sys_timeout(ARP_TMR_INTERVAL, arp_timer, NULL);
}

View File

@ -1,11 +0,0 @@
if BSP_USING_I2C
config I2C_BUS_NAME_1
string "i2c bus 1 name"
default "i2c1"
config I2C_DRV_NAME_1
string "i2c bus 1 driver name"
default "i2c1_drv"
config I2C_1_DEVICE_NAME_0
string "i2c bus 1 device 0 name"
default "i2c1_dev0"
endif

View File

@ -1,3 +0,0 @@
SRC_FILES := hardware_i2c.c connect_i2c.c
include $(KERNEL_ROOT)/compiler.mk

View File

@ -1,696 +0,0 @@
/*
* Copyright (c) 2020 RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2012-04-25 weety first version
*/
/**
* @file connect_i2c.c
* @brief support stm32f407-st-discovery-board i2c function and register to bus framework
* @version 1.0
* @author AIIT XUOS Lab
* @date 2021-04-25
*/
/*************************************************
File name: connect_i2c.c
Description: support stm32f407-st-discovery-board i2c configure and i2c bus register function
Others: take RT-Thread v4.0.2/components/drivers/i2c/i2c-bit-ops.c for references
https://github.com/RT-Thread/rt-thread/tree/v4.0.2
History:
1. Date: 2021-04-25
Author: AIIT XUOS Lab
Modification:
1. support stm32f407-st-discovery-board i2c bit configure, write and read
2. support stm32f407-st-discovery-board i2c bus device and driver register
*************************************************/
#include <board.h>
#include "core_cm4.h"
#include "connect_i2c.h"
#ifndef BSP_USING_I2C1
#define BSP_USING_I2C1
#endif
#define I2C_SDA_FUNC_GPIO 25
#define I2C_SCL_FUNC_GPIO 24
static I2cBusParam i2c_bus_param =
{
I2C_SDA_FUNC_GPIO,
I2C_SCL_FUNC_GPIO,
};
static BusType pin;
#define SET_SDA(done, val) done->SetSdaState(done->data, val)
#define SET_SCL(done, val) done->SetSclState(done->data, val)
#define GET_SDA(done) done->GetSdaState(done->data)
#define GET_SCL(done) done->GetSclState(done->data)
#define SdaLow(done) SET_SDA(done, 0)
#define SdaHigh(done) SET_SDA(done, 1)
#define SclLow(done) SET_SCL(done, 0)
static void I2cGpioInit(const I2cBusParam *bus_param)
{
struct PinParam i2c_scl;
struct PinStat i2c_scl_stat;
struct PinParam i2c_sda;
struct PinStat i2c_sda_stat;
struct BusConfigureInfo configure_info;
struct BusBlockWriteParam write_param;
int ret = 0;
pin = BusFind(PIN_BUS_NAME);
if (!pin) {
KPrintf("find %s failed!\n", PIN_BUS_NAME);
return ;
}
pin->owner_driver = BusFindDriver(pin, PIN_DRIVER_NAME);
pin->owner_haldev = BusFindDevice(pin, PIN_DEVICE_NAME);
configure_info.configure_cmd = OPE_INT;
ret = BusDrvConfigure(pin->owner_driver, &configure_info);
if (ret != EOK) {
KPrintf("initialize %s failed!\n", PIN_BUS_NAME);
return ;
}
/* config scl pin as output*/
i2c_scl.cmd = GPIO_CONFIG_MODE;
i2c_scl.pin = bus_param->i2c_scl_pin;
i2c_scl.mode = GPIO_CFG_OUTPUT_OD;
configure_info.configure_cmd = OPE_CFG;
configure_info.private_data = (void *)&i2c_scl;
ret = BusDrvConfigure(pin->owner_driver, &configure_info);
if (ret != EOK) {
KPrintf("config i2c scl pin %d failed!\n", bus_param->i2c_scl_pin);
return ;
}
/* set scl pin as high*/
i2c_scl_stat.pin = bus_param->i2c_scl_pin;
i2c_scl_stat.val = GPIO_HIGH;
write_param.buffer = (void *)&i2c_sda_stat;
BusDevWriteData(pin->owner_haldev, &write_param);
/* config sda pin as output*/
i2c_sda.cmd = GPIO_CONFIG_MODE;
i2c_sda.pin = bus_param->i2c_sda_pin;
i2c_sda.mode = GPIO_CFG_OUTPUT_OD;
configure_info.configure_cmd = OPE_CFG;
configure_info.private_data = (void *)&i2c_sda;
ret = BusDrvConfigure(pin->owner_driver, &configure_info);
if (ret != EOK) {
KPrintf("config i2c sda pin %d failed!\n", bus_param->i2c_sda_pin);
return ;
}
/* set sda pin as high*/
i2c_sda_stat.pin = bus_param->i2c_sda_pin;
i2c_sda_stat.val = GPIO_HIGH;
write_param.buffer = (void *)&i2c_sda_stat;
BusDevWriteData(pin->owner_haldev, &write_param);
}
static void SetSdaState(void *data, uint8 sda_state)
{
struct PinStat i2c_sda_stat;
struct BusBlockWriteParam write_param;
I2cBusParam *bus_param = (I2cBusParam *)data;
if (sda_state) {
i2c_sda_stat.pin = bus_param->i2c_sda_pin;
i2c_sda_stat.val = GPIO_HIGH;
write_param.buffer = (void *)&i2c_sda_stat;
BusDevWriteData(pin->owner_haldev, &write_param);
} else {
i2c_sda_stat.pin = bus_param->i2c_sda_pin;
i2c_sda_stat.val = GPIO_LOW;
write_param.buffer = (void *)&i2c_sda_stat;
BusDevWriteData(pin->owner_haldev, &write_param);
}
}
static void SetSclState(void *data, uint8 scl_state)
{
struct PinStat i2c_scl_stat;
struct BusBlockWriteParam write_param;
I2cBusParam *bus_param = (I2cBusParam *)data;
if (scl_state) {
i2c_scl_stat.pin = bus_param->i2c_scl_pin;
i2c_scl_stat.val = GPIO_HIGH;
write_param.buffer = (void *)&i2c_scl_stat;
BusDevWriteData(pin->owner_haldev, &write_param);
} else {
i2c_scl_stat.pin = bus_param->i2c_scl_pin;
i2c_scl_stat.val = GPIO_LOW;
write_param.buffer = (void *)&i2c_scl_stat;
BusDevWriteData(pin->owner_haldev, &write_param);
}
}
static uint8 GetSdaState(void *data)
{
struct PinStat i2c_sda_stat;
struct BusBlockReadParam read_param;
I2cBusParam *bus_param = (I2cBusParam *)data;
i2c_sda_stat.pin = bus_param->i2c_sda_pin;
read_param.buffer = (void *)&i2c_sda_stat;
return BusDevReadData(pin->owner_haldev, &read_param);
}
static uint8 GetSclState(void *data)
{
struct PinStat i2c_scl_stat;
struct BusBlockReadParam read_param;
I2cBusParam *bus_param = (I2cBusParam *)data;
i2c_scl_stat.pin = bus_param->i2c_scl_pin;
read_param.buffer = (void *)&i2c_scl_stat;
return BusDevReadData(pin->owner_haldev, &read_param);
}
static int Stm32Udelay(uint32 us)
{
uint32 ticks;
uint32 told, tnow, tcnt = 0;
uint32 reload = SysTick->LOAD;
ticks = us * reload / (1000000 / TICK_PER_SECOND);
told = SysTick->VAL;
while (1) {
tnow = SysTick->VAL;
if (tnow != told) {
if (tnow < told) {
tcnt += told - tnow;
} else {
tcnt += reload - tnow + told;
}
told = tnow;
if (tcnt >= ticks) {
return 0;
break;
}
}
}
}
static const struct I2cHalDrvDone i2c_hal_drv_done =
{
.data = (&i2c_bus_param),
.SetSdaState = SetSdaState,
.SetSclState = SetSclState,
.GetSdaState = GetSdaState,
.GetSclState = GetSclState,
.udelay = Stm32Udelay,
.delay_us = 1,
.timeout = 100
};
static x_err_t I2cBusReset(const I2cBusParam *bus_param)
{
int32 i = 0;
if (GPIO_LOW == GetSdaState((void *)bus_param)) {
while (i++ < 9) {
SetSclState((void *)bus_param,GPIO_HIGH);
Stm32Udelay(100);
SetSclState((void *)bus_param,GPIO_LOW);
Stm32Udelay(100);
}
}
if (GPIO_LOW == GetSdaState((void *)bus_param)) {
return -ERROR;
}
return EOK;
}
static __inline void I2cDelay(struct I2cHalDrvDone *done)
{
done->udelay((done->delay_us + 1) >> 1);
}
static __inline void I2cDelay2(struct I2cHalDrvDone *done)
{
done->udelay(done->delay_us);
}
static x_err_t SclHigh(struct I2cHalDrvDone *done)
{
x_ticks_t start;
SET_SCL(done, 1);
if (!done->GetSclState)
goto done;
start = CurrentTicksGain();
while (!GET_SCL(done))
{
if ((CurrentTicksGain() - start) > done->timeout)
return -ETIMEOUT;
DelayKTask((done->timeout + 1) >> 1);
}
done:
I2cDelay(done);
return EOK;
}
static void I2cStart(struct I2cHalDrvDone *done)
{
SdaLow(done);
I2cDelay(done);
SclLow(done);
}
static void I2cRestart(struct I2cHalDrvDone *done)
{
SdaHigh(done);
SclHigh(done);
I2cDelay(done);
SdaLow(done);
I2cDelay(done);
SclLow(done);
}
static void I2cStop(struct I2cHalDrvDone *done)
{
SdaLow(done);
I2cDelay(done);
SclHigh(done);
I2cDelay(done);
SdaHigh(done);
I2cDelay2(done);
}
static __inline x_bool I2cWaitack(struct I2cHalDrvDone *done)
{
x_bool ack;
SdaHigh(done);
GET_SDA(done);
I2cDelay(done);
if (SclHigh(done) < 0) {
KPrintf("wait ack timeout");
return -ETIMEOUT;
}
ack = !GET_SDA(done);
SclLow(done);
return ack;
}
static int32 I2cWriteb(struct I2cBus *bus, uint8 data)
{
int32 i;
uint8 bit;
struct I2cHalDrvDone *done = (struct I2cHalDrvDone *)bus->private_data;
for (i = 7; i >= 0; i--) {
SclLow(done);
bit = (data >> i) & 1;
SET_SDA(done, bit);
I2cDelay(done);
if (SclHigh(done) < 0) {
KPrintf("I2cWriteb: 0x%02x, "
"wait scl pin high timeout at bit %d",
data, i);
return -ETIMEOUT;
}
}
SclLow(done);
I2cDelay(done);
return I2cWaitack(done);
}
static int32 I2cReadb(struct I2cBus *bus)
{
uint8 i;
uint8 data = 0;
struct I2cHalDrvDone *done = (struct I2cHalDrvDone *)bus->private_data;
SdaHigh(done);
GET_SDA(done);
I2cDelay(done);
for (i = 0; i < 8; i++) {
data <<= 1;
if (SclHigh(done) < 0) {
KPrintf("I2cReadb: wait scl pin high "
"timeout at bit %d", 7 - i);
return -ETIMEOUT;
}
if (GET_SDA(done))
data |= 1;
SclLow(done);
I2cDelay2(done);
}
return data;
}
static x_size_t I2cSendBytes(struct I2cBus *bus, struct I2cDataStandard *msg)
{
int32 ret;
x_size_t bytes = 0;
const uint8 *ptr = msg->buf;
int32 count = msg->len;
uint16 ignore_nack = msg->flags & I2C_IGNORE_NACK;
while (count > 0) {
ret = I2cWriteb(bus, *ptr);
if ((ret > 0) || (ignore_nack && (ret == 0))) {
count --;
ptr ++;
bytes ++;
} else if (ret == 0) {
return 0;
} else {
KPrintf("send bytes: error %d", ret);
return ret;
}
}
return bytes;
}
static x_err_t I2cSendAckOrNack(struct I2cBus *bus, int ack)
{
struct I2cHalDrvDone *done = (struct I2cHalDrvDone *)bus->private_data;
if (ack)
SET_SDA(done, 0);
I2cDelay(done);
if (SclHigh(done) < 0) {
KPrintf("ACK or NACK timeout.");
return -ETIMEOUT;
}
SclLow(done);
return EOK;
}
static x_size_t I2cRecvBytes(struct I2cBus *bus, struct I2cDataStandard *msg)
{
int32 val;
int32 bytes = 0;
uint8 *ptr = msg->buf;
int32 count = msg->len;
const uint32 flags = msg->flags;
while (count > 0) {
val = I2cReadb(bus);
if (val >= 0) {
*ptr = val;
bytes ++;
} else {
break;
}
ptr ++;
count --;
if (!(flags & I2C_NO_READ_ACK)){
val = I2cSendAckOrNack(bus, count);
if (val < 0)
return val;
}
}
return bytes;
}
static int32 I2cSendAddress(struct I2cBus *bus, uint8 addr, int32 retries)
{
struct I2cHalDrvDone *done = (struct I2cHalDrvDone *)bus->private_data;
int32 i;
x_err_t ret = 0;
for (i = 0; i <= retries; i++) {
ret = I2cWriteb(bus, addr);
if (ret == 1 || i == retries)
break;
I2cStop(done);
I2cDelay2(done);
I2cStart(done);
}
return ret;
}
static x_err_t I2cBitSendAddress(struct I2cBus *bus, struct I2cDataStandard *msg)
{
uint16 flags = msg->flags;
uint16 ignore_nack = msg->flags & I2C_IGNORE_NACK;
struct I2cHalDrvDone *done = (struct I2cHalDrvDone *)bus->private_data;
uint8 addr1, addr2;
int32 retries;
x_err_t ret;
retries = ignore_nack ? 0 : msg->retries;
if (flags & I2C_ADDR_10BIT) {
addr1 = 0xf0 | ((msg->addr >> 7) & 0x06);
addr2 = msg->addr & 0xff;
ret = I2cSendAddress(bus, addr1, retries);
if ((ret != 1) && !ignore_nack){
return -EPIO;
}
ret = I2cWriteb(bus, addr2);
if ((ret != 1) && !ignore_nack){
return -EPIO;
}
if (flags & I2C_RD) {
I2cRestart(done);
addr1 |= 0x01;
ret = I2cSendAddress(bus, addr1, retries);
if ((ret != 1) && !ignore_nack) {
return -EPIO;
}
}
} else {
addr1 = msg->addr << 1;
if (flags & I2C_RD)
addr1 |= 1;
ret = I2cSendAddress(bus, addr1, retries);
if ((ret != 1) && !ignore_nack)
return -EPIO;
}
return EOK;
}
static uint32 I2cWriteData(struct I2cHardwareDevice *i2c_dev, struct I2cDataStandard *msg)
{
struct I2cBus *bus = (struct I2cBus *)i2c_dev->haldev.owner_bus;
bus->private_data = i2c_dev->haldev.owner_bus->private_data;
struct I2cHalDrvDone *done = (struct I2cHalDrvDone *)bus->private_data;
int32 ret;
int32 i = 0;
uint16 ignore_nack;
I2cStart(done);
while (NONE != msg) {
ignore_nack = msg->flags & I2C_IGNORE_NACK;
if (!(msg->flags & I2C_NO_START)) {
if (i) {
I2cRestart(done);
}
ret = I2cBitSendAddress(bus, msg);
if ((ret != EOK) && !ignore_nack) {
goto out;
}
}
if (msg->flags & I2C_WR) {
ret = I2cSendBytes(bus, msg);
if (ret >= 1)
//KPrintf("write %d byte%s", ret, ret == 1 ? "" : "s");
if (ret < msg->len){
if (ret >= 0)
ret = -ERROR;
goto out;
}
}
msg = msg->next;
i++;
}
ret = i;
out:
I2cStop(done);
return ret;
}
static uint32 I2cReadData(struct I2cHardwareDevice *i2c_dev, struct I2cDataStandard *msg)
{
struct I2cBus *bus = (struct I2cBus *)i2c_dev->haldev.owner_bus;
bus->private_data = i2c_dev->haldev.owner_bus->private_data;
struct I2cHalDrvDone *done = (struct I2cHalDrvDone *)bus->private_data;
int32 ret;
int32 i = 0;
uint16 ignore_nack;
I2cStart(done);
while (NONE != msg) {
ignore_nack = msg->flags & I2C_IGNORE_NACK;
if (!(msg->flags & I2C_NO_START)) {
if (i) {
I2cRestart(done);
}
ret = I2cBitSendAddress(bus, msg);
if ((ret != EOK) && !ignore_nack) {
goto out;
}
}
if (msg->flags & I2C_RD) {
ret = I2cRecvBytes(bus, msg);
if (ret >= 1)
//KPrintf("read %d byte%s", ret, ret == 1 ? "" : "s");
if (ret < msg->len){
if (ret >= 0)
ret = -EPIO;
goto out;
}
}
msg = msg->next;
i++;
}
ret = i;
out:
I2cStop(done);
return ret;
}
/*manage the i2c device operations*/
static const struct I2cDevDone i2c_dev_done =
{
.dev_open = NONE,
.dev_close = NONE,
.dev_write = I2cWriteData,
.dev_read = I2cReadData,
};
/*Init i2c bus*/
static int BoardI2cBusInit(struct I2cBus *i2c_bus, struct I2cDriver *i2c_driver)
{
x_err_t ret = EOK;
/*Init the i2c bus */
i2c_bus->private_data = (void *)&i2c_hal_drv_done;
ret = I2cBusInit(i2c_bus, I2C_BUS_NAME_1);
if (EOK != ret) {
KPrintf("board_i2c_init I2cBusInit error %d\n", ret);
return ERROR;
}
/*Init the i2c driver*/
i2c_driver->private_data = (void *)&i2c_hal_drv_done;
ret = I2cDriverInit(i2c_driver, I2C_DRV_NAME_1);
if (EOK != ret) {
KPrintf("board_i2c_init I2cDriverInit error %d\n", ret);
return ERROR;
}
/*Attach the i2c driver to the i2c bus*/
ret = I2cDriverAttachToBus(I2C_DRV_NAME_1, I2C_BUS_NAME_1);
if (EOK != ret) {
KPrintf("board_i2c_init I2cDriverAttachToBus error %d\n", ret);
return ERROR;
}
return ret;
}
/*Attach the i2c device to the i2c bus*/
static int BoardI2cDevBend(void)
{
x_err_t ret = EOK;
static struct I2cHardwareDevice i2c_device0;
memset(&i2c_device0, 0, sizeof(struct I2cHardwareDevice));
i2c_device0.i2c_dev_done = &i2c_dev_done;
ret = I2cDeviceRegister(&i2c_device0, NONE, I2C_1_DEVICE_NAME_0);
if (EOK != ret) {
KPrintf("board_i2c_init I2cDeviceInit device %s error %d\n", I2C_1_DEVICE_NAME_0, ret);
return ERROR;
}
ret = I2cDeviceAttachToBus(I2C_1_DEVICE_NAME_0, I2C_BUS_NAME_1);
if (EOK != ret) {
KPrintf("board_i2c_init I2cDeviceAttachToBus device %s error %d\n", I2C_1_DEVICE_NAME_0, ret);
return ERROR;
}
return ret;
}
/*STM32F407 BOARD I2C INIT*/
int Stm32HwI2cInit(void)
{
x_err_t ret = EOK;
static struct I2cBus i2c_bus;
memset(&i2c_bus, 0, sizeof(struct I2cBus));
static struct I2cDriver i2c_driver;
memset(&i2c_driver, 0, sizeof(struct I2cDriver));
#ifdef BSP_USING_I2C1
I2cGpioInit(&i2c_bus_param);
ret = BoardI2cBusInit(&i2c_bus, &i2c_driver);
if (EOK != ret) {
KPrintf("board_i2c_Init error ret %u\n", ret);
return ERROR;
}
ret = BoardI2cDevBend();
if (EOK != ret) {
KPrintf("board_i2c_Init error ret %u\n", ret);
return ERROR;
}
I2cBusReset(&i2c_bus_param);
#endif
return ret;
}

View File

@ -1,4 +0,0 @@
SRC_FILES := hardware_fsmc.c
include $(KERNEL_ROOT)/compiler.mk

View File

@ -1,11 +0,0 @@
if BSP_USING_RTC
config RTC_BUS_NAME
string "rtc bus name"
default "rtc"
config RTC_DRV_NAME
string "rtc bus driver name"
default "rtc_drv"
config RTC_DEVICE_NAME
string "rtc bus device name"
default "rtc_dev"
endif

View File

@ -1,3 +0,0 @@
SRC_FILES := hardware_rtc.c connect_rtc.c
include $(KERNEL_ROOT)/compiler.mk

View File

@ -1,268 +0,0 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
/**
* @file connect_rtc.c
* @brief support stm32f407-st-discovery-board rtc function and register to bus framework
* @version 1.0
* @author AIIT XUOS Lab
* @date 2021-04-25
*/
#include <time.h>
#include <stm32f4xx.h>
#include "connect_rtc.h"
#include "hardware_rtc.h"
#include "hardware_rcc.h"
#include "hardware_pwr.h"
#define RTC_BACKUP_REGISTER 0x32F2
static int GetWeekDay(int year, int month, int day)
{
if (month==1||month==2) {
year -=1;
month +=12;
}
return (day+1+2*month+3*(month+1)/5+year+(year/4)-year/100+year/400)%7+1;
}
static uint32 RtcConfigure(void *drv, struct BusConfigureInfo *configure_info)
{
NULL_PARAM_CHECK(drv);
struct RtcDriver *rtc_drv = (struct RtcDriver *)drv;
struct RtcDrvConfigureParam *drv_param = (struct RtcDrvConfigureParam *)configure_info->private_data;
int cmd = drv_param->rtc_operation_cmd;
time_t *time = drv_param->time;
switch (cmd)
{
case OPER_RTC_GET_TIME:
{
struct tm ct;
RTC_TimeTypeDef t;
RTC_DateTypeDef d;
memset(&ct,0,sizeof(struct tm));
RTC_GetTime(RTC_Format_BIN,&t);
RTC_GetDate(RTC_Format_BIN,&d);
ct.tm_year = d.RTC_Year + 100;
ct.tm_mon = d.RTC_Month - 1;
ct.tm_mday = d.RTC_Date;
ct.tm_wday = d.RTC_WeekDay;
ct.tm_hour = t.RTC_Hours;
ct.tm_min = t.RTC_Minutes;
ct.tm_sec = t.RTC_Seconds;
*time = mktime(&ct);
}
break;
case OPER_RTC_SET_TIME:
{
struct tm *ct;
struct tm tm_new;
x_base lock;
RTC_TimeTypeDef RTC_TimeStructure;
RTC_InitTypeDef RTC_InitStructure;
RTC_DateTypeDef RTC_DateStructure;
lock = CriticalAreaLock();
ct = localtime(time);
memcpy(&tm_new, ct, sizeof(struct tm));
CriticalAreaUnLock(lock);
RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR, ENABLE);
PWR_BackupAccessCmd(ENABLE);
RTC_InitStructure.RTC_AsynchPrediv = 0x7F;
RTC_InitStructure.RTC_SynchPrediv = 0xFF;
RTC_InitStructure.RTC_HourFormat = RTC_HourFormat_24;
RTC_Init(&RTC_InitStructure);
RTC_DateStructure.RTC_Year = tm_new.tm_year - 100;
RTC_DateStructure.RTC_Month = tm_new.tm_mon + 1;
RTC_DateStructure.RTC_Date = tm_new.tm_mday;
RTC_DateStructure.RTC_WeekDay = GetWeekDay(tm_new.tm_year+1900,tm_new.tm_mon+1,tm_new.tm_mday);
RTC_SetDate(RTC_Format_BIN, &RTC_DateStructure);
if (tm_new.tm_hour > 11){
RTC_TimeStructure.RTC_H12 = RTC_H12_PM;
}
else{
RTC_TimeStructure.RTC_H12 = RTC_H12_AM;
}
RTC_TimeStructure.RTC_Hours = tm_new.tm_hour;
RTC_TimeStructure.RTC_Minutes = tm_new.tm_min;
RTC_TimeStructure.RTC_Seconds = tm_new.tm_sec;
RTC_SetTime(RTC_Format_BIN, &RTC_TimeStructure);
RTC_WriteBackupRegister(RTC_BKP_DR0, 0x32F2);
}
break;
}
return EOK;
}
int RtcConfiguration(void)
{
RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR, ENABLE);
PWR_BackupAccessCmd(ENABLE);
#if defined (RTC_CLOCK_SOURCE_LSI)
RCC_LSICmd(ENABLE);
while(RCC_GetFlagStatus(RCC_FLAG_LSIRDY) == RESET);
RCC_RTCCLKConfig(RCC_RTCCLKSource_LSI);
/* ck_spre(1Hz) = RTCCLK(LSI) /(uwAsynchPrediv + 1)*(uwSynchPrediv + 1)*/
//uwSynchPrediv = 0xFF;
//uwAsynchPrediv = 0x7F;
#elif defined (RTC_CLOCK_SOURCE_LSE)
RCC_LSEConfig(RCC_LSE_ON);
while(RCC_GetFlagStatus(RCC_FLAG_LSERDY) == RESET);
RCC_RTCCLKConfig(RCC_RTCCLKSource_LSE);
#else
#error Please select the RTC Clock source inside the main.c file
#endif
RCC_RTCCLKCmd(ENABLE);
RTC_WaitForSynchro();
return 0;
}
/*manage the rtc device operations*/
static const struct RtcDevDone dev_done =
{
.open = NONE,
.close = NONE,
.write = NONE,
.read = NONE,
};
static int BoardRtcBusInit(struct RtcBus *rtc_bus, struct RtcDriver *rtc_driver)
{
x_err_t ret = EOK;
/*Init the rtc bus */
ret = RtcBusInit(rtc_bus, RTC_BUS_NAME);
if (EOK != ret) {
KPrintf("hw_rtc_init RtcBusInit error %d\n", ret);
return ERROR;
}
/*Init the rtc driver*/
ret = RtcDriverInit(rtc_driver, RTC_DRV_NAME);
if (EOK != ret) {
KPrintf("hw_rtc_init RtcDriverInit error %d\n", ret);
return ERROR;
}
/*Attach the rtc driver to the rtc bus*/
ret = RtcDriverAttachToBus(RTC_DRV_NAME, RTC_BUS_NAME);
if (EOK != ret) {
KPrintf("hw_rtc_init RtcDriverAttachToBus error %d\n", ret);
return ERROR;
}
return ret;
}
/*Attach the rtc device to the rtc bus*/
static int BoardRtcDevBend(void)
{
x_err_t ret = EOK;
static struct RtcHardwareDevice rtc_device;
memset(&rtc_device, 0, sizeof(struct RtcHardwareDevice));
rtc_device.dev_done = &(dev_done);
ret = RtcDeviceRegister(&rtc_device, NONE, RTC_DEVICE_NAME);
if (EOK != ret) {
KPrintf("hw_rtc_init RtcDeviceInit device %s error %d\n", RTC_DEVICE_NAME, ret);
return ERROR;
}
ret = RtcDeviceAttachToBus(RTC_DEVICE_NAME, RTC_BUS_NAME);
if (EOK != ret) {
KPrintf("hw_rtc_init RtcDeviceAttachToBus device %s error %d\n", RTC_DEVICE_NAME, ret);
return ERROR;
}
return ret;
}
int Stm32HwRtcInit(void)
{
x_err_t ret = EOK;
static struct RtcBus rtc_bus;
memset(&rtc_bus, 0, sizeof(struct RtcBus));
static struct RtcDriver rtc_driver;
memset(&rtc_driver, 0, sizeof(struct RtcDriver));
rtc_driver.configure = &(RtcConfigure);
ret = BoardRtcBusInit(&rtc_bus, &rtc_driver);
if (EOK != ret) {
KPrintf("hw_rtc_init error ret %u\n", ret);
return ERROR;
}
ret = BoardRtcDevBend();
if (EOK != ret) {
KPrintf("hw_rtc_init error ret %u\n", ret);
return ERROR;
}
if (RTC_BACKUP_REGISTER != RTC_ReadBackupRegister(RTC_BKP_DR0)) {
if (0 != RtcConfiguration()) {
KPrintf("hw_rtc_init RtcConfiguration error...\n");
return ERROR;
}
} else {
RTC_WaitForSynchro();
}
return ret;
}
#ifdef TOOL_SHELL
void ShowTime(void)
{
RTC_TimeTypeDef time;
RTC_DateTypeDef date;
RTC_GetDate(RTC_Format_BIN,&date);
RTC_GetTime(RTC_Format_BIN, &time);
KPrintf("Now Time = 20%02d %02d %02d[%02d]-%0.2d:%0.2d:%0.2d \r\n", \
date.RTC_Year,
date.RTC_Month,
date.RTC_Date,
date.RTC_WeekDay,
time.RTC_Hours,
time.RTC_Minutes,
time.RTC_Seconds);
}
SHELL_EXPORT_CMD(SHELL_CMD_PERMISSION(0)|SHELL_CMD_TYPE(SHELL_TYPE_CMD_FUNC)|SHELL_CMD_PARAM_NUM(0),
ShowTime, ShowTime, Arm test rtc function show time);
#endif

View File

@ -1,13 +0,0 @@
if BSP_USING_SDIO
config SDIO_BUS_NAME
string "sdio bus name"
default "sdio"
config SDIO_DRIVER_NAME
string "sdio driver name"
default "sdio_drv"
config SDIO_DEVICE_NAME
string "sdio device name"
default "sdio_dev"
endif

View File

@ -1,4 +0,0 @@
SRC_FILES := connect_sdio.c sdio_sd.c hardware_sdio.c
include $(KERNEL_ROOT)/compiler.mk

View File

@ -1,240 +0,0 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
/**
* @file connect_sdio.c
* @brief support sdio function using bus driver framework
* @version 1.0
* @author AIIT XUOS Lab
* @date 2021-04-22
*/
/*************************************************
File name: connect_sdio.c
Description: support sdio function using bus driver framework
Others: hardware/sdio/sdio.c for references
History:
1. Date: 2021-04-22
Author: AIIT XUOS Lab
Modification: Support stm32f407-discovery-board sdio configure, write and read functions
*************************************************/
#include <device.h>
#include "connect_sdio.h"
#include "sdio_sd.h"
#ifndef SDCARD_SECTOR_SIZE
#define SDCARD_SECTOR_SIZE 512
#endif
static uint32 SdioConfigure(void *drv, struct BusConfigureInfo *configure_info)
{
NULL_PARAM_CHECK(drv);
NULL_PARAM_CHECK(configure_info);
if (configure_info->configure_cmd == OPER_BLK_GETGEOME) {
NULL_PARAM_CHECK(configure_info->private_data);
struct DeviceBlockArrange *args = (struct DeviceBlockArrange *)configure_info->private_data;
SD_GetCardInfo(&SDCardInfo);
args->size_perbank = SDCardInfo.CardBlockSize;
args->block_size = SDCardInfo.CardBlockSize;
if(SDCardInfo.CardType == SDIO_HIGH_CAPACITY_SD_CARD)
args->bank_num = (SDCardInfo.SD_csd.DeviceSize + 1) * 1024;
else
args->bank_num = SDCardInfo.CardCapacity;
}
return EOK;
}
static int sd_lock = -1;
static uint32 SDBuffer[512/sizeof(uint32_t)];
static uint32 SdioOpen(void *dev)
{
NULL_PARAM_CHECK(dev);
if(sd_lock >= 0) {
KSemaphoreDelete(sd_lock);
}
sd_lock = KSemaphoreCreate(1);
if (sd_lock < 0){
return ERROR;
}
return EOK;
}
static uint32 SdioClose(void *dev)
{
NULL_PARAM_CHECK(dev);
KSemaphoreDelete(sd_lock);
return EOK;
}
static uint32 SdioRead(void *dev, struct BusBlockReadParam *read_param)
{
uint8 ret = SD_OK;
KSemaphoreObtain(sd_lock, WAITING_FOREVER);
if (((uint32)read_param->buffer & 0x03) != 0) {
uint64_t sector;
uint8_t* temp;
sector = (uint64_t)read_param->pos * SDCARD_SECTOR_SIZE;
temp = (uint8_t*)read_param->buffer;
for (uint8 i = 0; i < read_param->size; i++) {
ret = SD_ReadBlock((uint8_t *)SDBuffer, sector, 1);
if(ret != SD_OK) {
KPrintf("read failed: %d, buffer 0x%08x\n", ret, temp);
return 0;
}
#if defined (SD_DMA_MODE)
ret = SD_WaitReadOperation();
if (ret != SD_OK) {
KPrintf("read failed: %d, buffer 0x%08x\n", ret, temp);
return 0;
}
#endif
memcpy(temp, SDBuffer, SDCARD_SECTOR_SIZE);
sector += SDCARD_SECTOR_SIZE;
temp += SDCARD_SECTOR_SIZE;
}
} else {
ret = SD_ReadBlock((uint8_t *)read_param->buffer, (uint64_t)read_param->pos * SDCARD_SECTOR_SIZE, read_param->size);
if (ret != SD_OK) {
KPrintf("read failed: %d, buffer 0x%08x\n", ret, (uint8_t *)read_param->buffer);
return 0;
}
#if defined (SD_DMA_MODE)
ret = SD_WaitReadOperation();
if (ret != SD_OK) {
KPrintf("read failed: %d, buffer 0x%08x\n", ret, (uint8_t *)read_param->buffer);
return 0;
}
#endif
}
KSemaphoreAbandon(sd_lock);
return read_param->size;
}
static uint32 SdioWrite(void *dev, struct BusBlockWriteParam *write_param)
{
uint8 ret = SD_OK;
KSemaphoreObtain(sd_lock, WAITING_FOREVER);
if (((uint32)write_param->buffer & 0x03) != 0) {
uint64_t sector;
uint8_t* temp;
sector = (uint64_t)write_param->pos * SDCARD_SECTOR_SIZE;
temp = (uint8_t*)write_param->buffer;
for (uint8 i = 0; i < write_param->size; i++) {
memcpy(SDBuffer, temp, SDCARD_SECTOR_SIZE);
ret = SD_WriteBlock((uint8_t *)SDBuffer, sector, 1);
if(ret != SD_OK) {
KPrintf("write failed: %d, buffer 0x%08x\n", ret, temp);
return 0;
}
#if defined (SD_DMA_MODE)
ret = SD_WaitWriteOperation();
if (ret != SD_OK) {
KPrintf("write failed: %d, buffer 0x%08x\n", ret, temp);
return 0;
}
#endif
sector += SDCARD_SECTOR_SIZE;
temp += SDCARD_SECTOR_SIZE;
}
} else {
ret = SD_WriteBlock((uint8_t *)write_param->buffer, (uint64_t)write_param->pos * SDCARD_SECTOR_SIZE, write_param->size);
if (ret != SD_OK) {
KPrintf("write failed: %d, buffer 0x%08x\n", ret, (uint8_t *)write_param->buffer);
return 0;
}
#if defined (SD_DMA_MODE)
ret = SD_WaitWriteOperation();
if (ret != SD_OK){
KPrintf("write failed: %d, buffer 0x%08x\n", ret, (uint8_t *)write_param->buffer);
return 0;
}
#endif
}
KSemaphoreAbandon(sd_lock);
return write_param->size;
}
static struct SdioDevDone dev_done =
{
SdioOpen,
SdioClose,
SdioWrite,
SdioRead,
};
int HwSdioInit(void)
{
static struct SdioBus bus;
static struct SdioDriver drv;
static struct SdioHardwareDevice dev;
x_err_t ret = EOK;
ret = SD_Init();
if (ret != SD_OK) {
KPrintf("SD init failed!");
return ERROR;
}
ret = SdioBusInit(&bus, SDIO_BUS_NAME);
if (ret != EOK) {
KPrintf("Sdio bus init error %d\n", ret);
return ERROR;
}
ret = SdioDriverInit(&drv, SDIO_DRIVER_NAME);
if (ret != EOK) {
KPrintf("Sdio driver init error %d\n", ret);
return ERROR;
}
ret = SdioDriverAttachToBus(SDIO_DRIVER_NAME, SDIO_BUS_NAME);
if (ret != EOK) {
KPrintf("Sdio driver attach error %d\n", ret);
return ERROR;
}
dev.dev_done = &dev_done;
ret = SdioDeviceRegister(&dev, SDIO_DEVICE_NAME);
if (ret != EOK) {
KPrintf("Sdio device register error %d\n", ret);
return ERROR;
}
ret = SdioDeviceAttachToBus(SDIO_DEVICE_NAME, SDIO_BUS_NAME);
if (ret != EOK) {
KPrintf("Sdio device register error %d\n", ret);
return ERROR;
}
return ret;
}

View File

@ -1,399 +0,0 @@
/*
* Copyright (c) Guangzhou Xingyi Electronic Technology Co., Ltd
*
* Change Logs:
* Date Author Notes
* 2014-7-4 alientek first version
*/
/**
* @file sdio_sd.h
* @brief define std sdio function and struct
* @version 1.0
* @author AIIT XUOS Lab
* @date 2021-04-22
*/
/*************************************************
File name: sdio_sd.h
Description: define std sdio function and struct
Others: hardware/sdio/sdio.h for references
History:
1. Date: 2021-04-22
Author: AIIT XUOS Lab
Modification: Support stm32f407-discovery-board sdio using source files
*************************************************/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __SDIO_SDCARD_H
#define __SDIO_SDCARD_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f4xx.h"
/* Exported types ------------------------------------------------------------*/
/**
* @brief SDIO Intialization Frequency (400KHz max)
*/
#define SDIO_INIT_CLK_DIV ((uint8_t)0xB4)
/**
* @brief SDIO Data Transfer Frequency (25MHz max)
*/
/*!< SDIOCLK = HCLK, SDIO_CK = HCLK/(2 + SDIO_TRANSFER_CLK_DIV) */
// #define SDIO_TRANSFER_CLK_DIV ((uint8_t)0x01)
#define SDIO_TRANSFER_CLK_DIV ((uint8_t)0x4)
/* Uncomment the following line to select the SDIO Data transfer mode */
#define SD_DMA_MODE ((uint32_t)0x00000000)
//#define SD_POLLING_MODE ((uint32_t)0x00000002)
typedef enum
{
/**
* @brief SDIO specific error defines
*/
SD_CMD_CRC_FAIL = (1), /*!< Command response received (but CRC check failed) */
SD_DATA_CRC_FAIL = (2), /*!< Data bock sent/received (CRC check Failed) */
SD_CMD_RSP_TIMEOUT = (3), /*!< Command response timeout */
SD_DATA_TIMEOUT = (4), /*!< Data time out */
SD_TX_UNDERRUN = (5), /*!< Transmit FIFO under-run */
SD_RX_OVERRUN = (6), /*!< Receive FIFO over-run */
SD_START_BIT_ERR = (7), /*!< Start bit not detected on all data signals in widE bus mode */
SD_CMD_OUT_OF_RANGE = (8), /*!< CMD's argument was out of range.*/
SD_ADDR_MISALIGNED = (9), /*!< Misaligned address */
SD_BLOCK_LEN_ERR = (10), /*!< Transferred block length is not allowed for the card or the number of transferred bytes does not match the block length */
SD_ERASE_SEQ_ERR = (11), /*!< An error in the sequence of erase command occurs.*/
SD_BAD_ERASE_PARAM = (12), /*!< An Invalid selection for erase groups */
SD_WRITE_PROT_VIOLATION = (13), /*!< Attempt to program a write protect block */
SD_LOCK_UNLOCK_FAILED = (14), /*!< Sequence or password error has been detected in unlock command or if there was an attempt to access a locked card */
SD_COM_CRC_FAILED = (15), /*!< CRC check of the previous command failed */
SD_ILLEGAL_CMD = (16), /*!< Command is not legal for the card state */
SD_CARD_ECC_FAILED = (17), /*!< Card internal ECC was applied but failed to correct the data */
SD_CC_ERROR = (18), /*!< Internal card controller error */
SD_GENERAL_UNKNOWN_ERROR = (19), /*!< General or Unknown error */
SD_STREAM_READ_UNDERRUN = (20), /*!< The card could not sustain data transfer in stream read operation. */
SD_STREAM_WRITE_OVERRUN = (21), /*!< The card could not sustain data programming in stream mode */
SD_CID_CSD_OVERWRITE = (22), /*!< CID/CSD overwrite error */
SD_WP_ERASE_SKIP = (23), /*!< only partial address space was erased */
SD_CARD_ECC_DISABLED = (24), /*!< Command has been executed without using internal ECC */
SD_ERASE_RESET = (25), /*!< Erase sequence was cleared before executing because an out of erase sequence command was received */
SD_AKE_SEQ_ERROR = (26), /*!< Error in sequence of authentication. */
SD_INVALID_VOLTRANGE = (27),
SD_ADDR_OUT_OF_RANGE = (28),
SD_SWITCH_ERROR = (29),
SD_SDIO_DISABLED = (30),
SD_SDIO_FUNCTION_BUSY = (31),
SD_SDIO_FUNCTION_FAILED = (32),
SD_SDIO_UNKNOWN_FUNCTION = (33),
/**
* @brief Standard error defines
*/
SD_INTERNAL_ERROR,
SD_NOT_CONFIGURED,
SD_REQUEST_PENDING,
SD_REQUEST_NOT_APPLICABLE,
SD_INVALID_PARAMETER,
SD_UNSUPPORTED_FEATURE,
SD_UNSUPPORTED_HW,
SD_ERROR,
SD_OK = 0
} SD_Error;
/**
* @brief SDIO Transfer state
*/
typedef enum
{
SD_TRANSFER_OK = 0,
SD_TRANSFER_BUSY = 1,
SD_TRANSFER_ERROR
} SDTransferState;
/**
* @brief SD Card States
*/
typedef enum
{
SD_CARD_READY = ((uint32_t)0x00000001),
SD_CARD_IDENTIFICATION = ((uint32_t)0x00000002),
SD_CARD_STANDBY = ((uint32_t)0x00000003),
SD_CARD_TRANSFER = ((uint32_t)0x00000004),
SD_CARD_SENDING = ((uint32_t)0x00000005),
SD_CARD_RECEIVING = ((uint32_t)0x00000006),
SD_CARD_PROGRAMMING = ((uint32_t)0x00000007),
SD_CARD_DISCONNECTED = ((uint32_t)0x00000008),
SD_CARD_ERROR = ((uint32_t)0x000000FF)
}SDCardState;
/**
* @brief Card Specific Data: CSD Register
*/
typedef struct
{
__IO uint8_t CSDStruct; /*!< CSD structure */
__IO uint8_t SysSpecVersion; /*!< System specification version */
__IO uint8_t Reserved1; /*!< Reserved */
__IO uint8_t TAAC; /*!< Data read access-time 1 */
__IO uint8_t NSAC; /*!< Data read access-time 2 in CLK cycles */
__IO uint8_t MaxBusClkFrec; /*!< Max. bus clock frequency */
__IO uint16_t CardComdClasses; /*!< Card command classes */
__IO uint8_t RdBlockLen; /*!< Max. read data block length */
__IO uint8_t PartBlockRead; /*!< Partial blocks for read allowed */
__IO uint8_t WrBlockMisalign; /*!< Write block misalignment */
__IO uint8_t RdBlockMisalign; /*!< Read block misalignment */
__IO uint8_t DSRImpl; /*!< DSR implemented */
__IO uint8_t Reserved2; /*!< Reserved */
__IO uint32_t DeviceSize; /*!< Device Size */
__IO uint8_t MaxRdCurrentVDDMin; /*!< Max. read current @ VDD min */
__IO uint8_t MaxRdCurrentVDDMax; /*!< Max. read current @ VDD max */
__IO uint8_t MaxWrCurrentVDDMin; /*!< Max. write current @ VDD min */
__IO uint8_t MaxWrCurrentVDDMax; /*!< Max. write current @ VDD max */
__IO uint8_t DeviceSizeMul; /*!< Device size multiplier */
__IO uint8_t EraseGrSize; /*!< Erase group size */
__IO uint8_t EraseGrMul; /*!< Erase group size multiplier */
__IO uint8_t WrProtectGrSize; /*!< Write protect group size */
__IO uint8_t WrProtectGrEnable; /*!< Write protect group enable */
__IO uint8_t ManDeflECC; /*!< Manufacturer default ECC */
__IO uint8_t WrSpeedFact; /*!< Write speed factor */
__IO uint8_t MaxWrBlockLen; /*!< Max. write data block length */
__IO uint8_t WriteBlockPaPartial; /*!< Partial blocks for write allowed */
__IO uint8_t Reserved3; /*!< Reserded */
__IO uint8_t ContentProtectAppli; /*!< Content protection application */
__IO uint8_t FileFormatGrouop; /*!< File format group */
__IO uint8_t CopyFlag; /*!< Copy flag (OTP) */
__IO uint8_t PermWrProtect; /*!< Permanent write protection */
__IO uint8_t TempWrProtect; /*!< Temporary write protection */
__IO uint8_t FileFormat; /*!< File Format */
__IO uint8_t ECC; /*!< ECC code */
__IO uint8_t CSD_CRC; /*!< CSD CRC */
__IO uint8_t Reserved4; /*!< always 1*/
} SD_CSD;
/**
* @brief Card Identification Data: CID Register
*/
typedef struct
{
__IO uint8_t ManufacturerID; /*!< ManufacturerID */
__IO uint16_t OEM_AppliID; /*!< OEM/Application ID */
__IO uint32_t ProdName1; /*!< Product Name part1 */
__IO uint8_t ProdName2; /*!< Product Name part2*/
__IO uint8_t ProdRev; /*!< Product Revision */
__IO uint32_t ProdSN; /*!< Product Serial Number */
__IO uint8_t Reserved1; /*!< Reserved1 */
__IO uint16_t ManufactDate; /*!< Manufacturing Date */
__IO uint8_t CID_CRC; /*!< CID CRC */
__IO uint8_t Reserved2; /*!< always 1 */
} SD_CID;
/**
* @brief SD Card Status
*/
typedef struct
{
__IO uint8_t DAT_BUS_WIDTH;
__IO uint8_t SECURED_MODE;
__IO uint16_t SD_CARD_TYPE;
__IO uint32_t SIZE_OF_PROTECTED_AREA;
__IO uint8_t SPEED_CLASS;
__IO uint8_t PERFORMANCE_MOVE;
__IO uint8_t AU_SIZE;
__IO uint16_t ERASE_SIZE;
__IO uint8_t ERASE_TIMEOUT;
__IO uint8_t ERASE_OFFSET;
} SD_CardStatus;
/**
* @brief SD Card information
*/
typedef struct
{
SD_CSD SD_csd;
SD_CID SD_cid;
uint32_t CardCapacity; /*!< Card Capacity */
uint32_t CardBlockSize; /*!< Card Block Size */
uint16_t RCA;
uint8_t CardType;
} SD_CardInfo;
#define SDIO_FIFO_ADDRESS SDIO_BASE+0x80 //SDIO_FIOF address =SDIO address+0x80 to SDIO address+0xfc
#define SD_SDIO_DMA DMA2
#define SD_SDIO_DMA_CLK RCC_AHB1Periph_DMA2
//#define SD_SDIO_DMA_STREAM3 3
#define SD_SDIO_DMA_STREAM6 6
#ifdef SD_SDIO_DMA_STREAM3
#define SD_SDIO_DMA_STREAM DMA2_Stream3
#define SD_SDIO_DMA_CHANNEL DMA_Channel_4
#define SD_SDIO_DMA_FLAG_FEIF DMA_FLAG_FEIF3
#define SD_SDIO_DMA_FLAG_DMEIF DMA_FLAG_DMEIF3
#define SD_SDIO_DMA_FLAG_TEIF DMA_FLAG_TEIF3
#define SD_SDIO_DMA_FLAG_HTIF DMA_FLAG_HTIF3
#define SD_SDIO_DMA_FLAG_TCIF DMA_FLAG_TCIF3
#define SD_SDIO_DMA_IRQn DMA2_Stream3_IRQn
#define SD_SDIO_DMA_IRQHANDLER DMA2_Stream3_IRQHandler
#elif defined SD_SDIO_DMA_STREAM6
#define SD_SDIO_DMA_STREAM DMA2_Stream6
#define SD_SDIO_DMA_CHANNEL DMA_Channel_4
#define SD_SDIO_DMA_FLAG_FEIF DMA_FLAG_FEIF6
#define SD_SDIO_DMA_FLAG_DMEIF DMA_FLAG_DMEIF6
#define SD_SDIO_DMA_FLAG_TEIF DMA_FLAG_TEIF6
#define SD_SDIO_DMA_FLAG_HTIF DMA_FLAG_HTIF6
#define SD_SDIO_DMA_FLAG_TCIF DMA_FLAG_TCIF6
#define SD_SDIO_DMA_IRQn DMA2_Stream6_IRQn
#define SD_SDIO_DMA_IRQHANDLER DMA2_Stream6_IRQHandler
#endif /* SD_SDIO_DMA_STREAM3 */
/**
* @brief SDIO Commands Index
*/
#define SD_CMD_GO_IDLE_STATE ((uint8_t)0)
#define SD_CMD_SEND_OP_COND ((uint8_t)1)
#define SD_CMD_ALL_SEND_CID ((uint8_t)2)
#define SD_CMD_SET_REL_ADDR ((uint8_t)3) /*!< SDIO_SEND_REL_ADDR for SD Card */
#define SD_CMD_SET_DSR ((uint8_t)4)
#define SD_CMD_SDIO_SEN_OP_COND ((uint8_t)5)
#define SD_CMD_HS_SWITCH ((uint8_t)6)
#define SD_CMD_SEL_DESEL_CARD ((uint8_t)7)
#define SD_CMD_HS_SEND_EXT_CSD ((uint8_t)8)
#define SD_CMD_SEND_CSD ((uint8_t)9)
#define SD_CMD_SEND_CID ((uint8_t)10)
#define SD_CMD_READ_DAT_UNTIL_STOP ((uint8_t)11) /*!< SD Card doesn't support it */
#define SD_CMD_STOP_TRANSMISSION ((uint8_t)12)
#define SD_CMD_SEND_STATUS ((uint8_t)13)
#define SD_CMD_HS_BUSTEST_READ ((uint8_t)14)
#define SD_CMD_GO_INACTIVE_STATE ((uint8_t)15)
#define SD_CMD_SET_BLOCKLEN ((uint8_t)16)
#define SD_CMD_READ_SINGLE_BLOCK ((uint8_t)17)
#define SD_CMD_READ_MULT_BLOCK ((uint8_t)18)
#define SD_CMD_HS_BUSTEST_WRITE ((uint8_t)19)
#define SD_CMD_WRITE_DAT_UNTIL_STOP ((uint8_t)20) /*!< SD Card doesn't support it */
#define SD_CMD_SET_BLOCK_COUNT ((uint8_t)23) /*!< SD Card doesn't support it */
#define SD_CMD_WRITE_SINGLE_BLOCK ((uint8_t)24)
#define SD_CMD_WRITE_MULT_BLOCK ((uint8_t)25)
#define SD_CMD_PROG_CID ((uint8_t)26) /*!< reserved for manufacturers */
#define SD_CMD_PROG_CSD ((uint8_t)27)
#define SD_CMD_SET_WRITE_PROT ((uint8_t)28)
#define SD_CMD_CLR_WRITE_PROT ((uint8_t)29)
#define SD_CMD_SEND_WRITE_PROT ((uint8_t)30)
#define SD_CMD_SD_ERASE_GRP_START ((uint8_t)32) /*!< To set the address of the first write
block to be erased. (For SD card only) */
#define SD_CMD_SD_ERASE_GRP_END ((uint8_t)33) /*!< To set the address of the last write block of the
continuous range to be erased. (For SD card only) */
#define SD_CMD_ERASE_GRP_START ((uint8_t)35) /*!< To set the address of the first write block to be erased.
(For MMC card only spec 3.31) */
#define SD_CMD_ERASE_GRP_END ((uint8_t)36) /*!< To set the address of the last write block of the
continuous range to be erased. (For MMC card only spec 3.31) */
#define SD_CMD_ERASE ((uint8_t)38)
#define SD_CMD_FAST_IO ((uint8_t)39) /*!< SD Card doesn't support it */
#define SD_CMD_GO_IRQ_STATE ((uint8_t)40) /*!< SD Card doesn't support it */
#define SD_CMD_LOCK_UNLOCK ((uint8_t)42)
#define SD_CMD_APP_CMD ((uint8_t)55)
#define SD_CMD_GEN_CMD ((uint8_t)56)
#define SD_CMD_NO_CMD ((uint8_t)64)
/**
* @brief Following commands are SD Card Specific commands.
* SDIO_APP_CMD CMD55 should be sent before sending these commands.
*/
#define SD_CMD_APP_SD_SET_BUSWIDTH ((uint8_t)6) /*!< For SD Card only */
#define SD_CMD_SD_APP_STAUS ((uint8_t)13) /*!< For SD Card only */
#define SD_CMD_SD_APP_SEND_NUM_WRITE_BLOCKS ((uint8_t)22) /*!< For SD Card only */
#define SD_CMD_SD_APP_OP_COND ((uint8_t)41) /*!< For SD Card only */
#define SD_CMD_SD_APP_SET_CLR_CARD_DETECT ((uint8_t)42) /*!< For SD Card only */
#define SD_CMD_SD_APP_SEND_SCR ((uint8_t)51) /*!< For SD Card only */
#define SD_CMD_SDIO_RW_DIRECT ((uint8_t)52) /*!< For SD I/O Card only */
#define SD_CMD_SDIO_RW_EXTENDED ((uint8_t)53) /*!< For SD I/O Card only */
/**
* @brief Following commands are SD Card Specific security commands.
* SDIO_APP_CMD should be sent before sending these commands.
*/
#define SD_CMD_SD_APP_GET_MKB ((uint8_t)43) /*!< For SD Card only */
#define SD_CMD_SD_APP_GET_MID ((uint8_t)44) /*!< For SD Card only */
#define SD_CMD_SD_APP_SET_CER_RN1 ((uint8_t)45) /*!< For SD Card only */
#define SD_CMD_SD_APP_GET_CER_RN2 ((uint8_t)46) /*!< For SD Card only */
#define SD_CMD_SD_APP_SET_CER_RES2 ((uint8_t)47) /*!< For SD Card only */
#define SD_CMD_SD_APP_GET_CER_RES1 ((uint8_t)48) /*!< For SD Card only */
#define SD_CMD_SD_APP_SECURE_READ_MULTIPLE_BLOCK ((uint8_t)18) /*!< For SD Card only */
#define SD_CMD_SD_APP_SECURE_WRITE_MULTIPLE_BLOCK ((uint8_t)25) /*!< For SD Card only */
#define SD_CMD_SD_APP_SECURE_ERASE ((uint8_t)38) /*!< For SD Card only */
#define SD_CMD_SD_APP_CHANGE_SECURE_AREA ((uint8_t)49) /*!< For SD Card only */
#define SD_CMD_SD_APP_SECURE_WRITE_MKB ((uint8_t)48) /*!< For SD Card only */
/**
* @brief SD detection on its memory slot
*/
#define SD_PRESENT ((uint8_t)0x01)
#define SD_NOT_PRESENT ((uint8_t)0x00)
/**
* @brief Supported SD Memory Cards
*/
#define SDIO_STD_CAPACITY_SD_CARD_V1_1 ((uint32_t)0x00000000)
#define SDIO_STD_CAPACITY_SD_CARD_V2_0 ((uint32_t)0x00000001)
#define SDIO_HIGH_CAPACITY_SD_CARD ((uint32_t)0x00000002)
#define SDIO_MULTIMEDIA_CARD ((uint32_t)0x00000003)
#define SDIO_SECURE_DIGITAL_IO_CARD ((uint32_t)0x00000004)
#define SDIO_HIGH_SPEED_MULTIMEDIA_CARD ((uint32_t)0x00000005)
#define SDIO_SECURE_DIGITAL_IO_COMBO_CARD ((uint32_t)0x00000006)
#define SDIO_HIGH_CAPACITY_MMC_CARD ((uint32_t)0x00000007)
/* Exported functions ------------------------------------------------------- */
void SD_DeInit(void);
SD_Error SD_Init(void);
SDTransferState SD_GetStatus(void);
SDCardState SD_GetState(void);
uint8_t SD_Detect(void);
SD_Error SD_PowerON(void);
SD_Error SD_PowerOFF(void);
SD_Error SD_InitializeCards(void);
SD_Error SD_GetCardInfo(SD_CardInfo *cardinfo);
SD_Error SD_GetCardStatus(SD_CardStatus *cardstatus);
SD_Error SD_EnableWideBusOperation(uint32_t WideMode);
SD_Error SD_SelectDeselect(uint32_t addr);
SD_Error SD_ReadBlock(uint8_t *readbuff, uint32_t ReadAddr, uint16_t BlockSize);
SD_Error SD_ReadMultiBlocks(uint8_t *readbuff, uint32_t ReadAddr, uint16_t BlockSize, uint32_t NumberOfBlocks);
SD_Error SD_WriteBlock(uint8_t *writebuff, uint32_t WriteAddr, uint16_t BlockSize);
SD_Error SD_WriteMultiBlocks(uint8_t *writebuff, uint32_t WriteAddr, uint16_t BlockSize, uint32_t NumberOfBlocks);
SDTransferState SD_GetTransferState(void);
SD_Error SD_StopTransfer(void);
SD_Error SD_Erase(uint32_t startaddr, uint32_t endaddr);
SD_Error SD_SendStatus(uint32_t *pcardstatus);
SD_Error SD_SendSDStatus(uint32_t *psdstatus);
SD_Error SD_ProcessIRQSrc(void);
SD_Error SD_WaitReadOperation(void);
SD_Error SD_WaitWriteOperation(void);
void SD_ProcessDMAIRQ(void);
void NVIC_Configuration(void);
SD_Error SD_LBA_ReadBlocks(uint8_t *readbuff, uint32_t BlockAddr, uint32_t NumberOfBlocks);
SD_Error SD_LBA_WriteBlocks(uint8_t *writebuff, uint32_t BlockAddr, uint32_t NumberOfBlocks);
extern SD_CardInfo SDCardInfo;
#ifdef __cplusplus
}
#endif
#endif /* __SDCARD_H */

View File

@ -1,66 +0,0 @@
config BSP_USING_SPI1
bool "Using spi1 "
default y
if BSP_USING_SPI1
config SPI_BUS_NAME_1
string "spi bus 1 name"
default "spi1"
config SPI_1_DRV_NAME
string "spi bus 1 driver name"
default "spi1_drv"
config BSP_SPI1_CLK_PIN
int "spi1 clk pin number"
default 29
config BSP_SPI1_D0_PIN
int "spi1 d0 pin number"
default 30
config BSP_SPI1_D1_PIN
int "spi1 d1 pin number"
default 31
menuconfig BSP_SPI1_USING_SS0
bool "SPI1 Enable SS0"
default y
if BSP_SPI1_USING_SS0
config SPI_1_DEVICE_NAME_0
string "spi bus 1 device 0 name"
default "spi1_dev0"
config BSP_SPI1_SS0_PIN
int "spi1 ss0 pin number"
default 32
endif
menuconfig BSP_SPI1_USING_SS1
bool "SPI1 Enable SS1"
default y
if BSP_SPI1_USING_SS1
config SPI_1_DEVICE_NAME_1
string "spi bus 1 device 1 name"
default "spi1_dev1"
config BSP_SPI1_SS1_PIN
int "spi1 ss1 pin number"
default 33
endif
menuconfig BSP_SPI1_USING_SS2
bool "SPI1 Enable SS2"
default n
if BSP_SPI1_USING_SS2
config SPI_1_DEVICE_NAME_2
string "spi bus 1 device 2 name"
default "spi1_dev2"
config BSP_SPI1_SS2_PIN
int "spi1 ss2 pin number"
default 26
endif
menuconfig BSP_SPI1_USING_SS3
bool "SPI1 Enable SS3"
default n
if BSP_SPI1_USING_SS3
config SPI_1_DEVICE_NAME_3
string "spi bus 1 device 3 name"
default "spi1_dev3"
config BSP_SPI1_SS3_PIN
int "spi1 ss3 pin number"
default 27
endif
endif

View File

@ -1,7 +0,0 @@
SRC_FILES := hardware_spi.c connect_spi.c
ifeq ($(CONFIG_RESOURCES_SPI_SFUD),y)
SRC_FILES += connect_flash_spi.c
endif
include $(KERNEL_ROOT)/compiler.mk

View File

@ -1,56 +0,0 @@
/*
* Copyright (c) 2020 RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2018-11-27 SummerGift add spi flash port file
*/
/**
* @file connect_flash_spi.c
* @brief support stm32f407-st-discovery-board spi flash function and register to bus framework
* @version 1.0
* @author AIIT XUOS Lab
* @date 2021-04-25
*/
/*************************************************
File name: connect_flash_spi.c
Description: support stm32f407-st-discovery-board spi flash bus register function
Others: take RT-Thread v4.0.2/bsp/stm32/stm32f407-atk-explorer/board/ports/spi-flash-init.c
https://github.com/RT-Thread/rt-thread/tree/v4.0.2
History:
1. Date: 2021-04-25
Author: AIIT XUOS Lab
Modification:
1. support stm32f407-st-discovery-board spi flash register to spi bus
2. support stm32f407-st-discovery-board spi flash init
*************************************************/
#include "hardware_gpio.h"
#include "connect_spi.h"
#include "flash_spi.h"
int FlashW25qxxSpiDeviceInit(void)
{
#ifdef BSP_USING_SPI1
__IO uint32_t tmpreg = 0x00U;
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOBEN;
tmpreg = RCC->AHB1ENR & RCC_AHB1ENR_GPIOBEN;
(void)tmpreg;
if (EOK != HwSpiDeviceAttach(SPI_BUS_NAME_1, "spi1_dev0", GPIOB, GPIO_Pin_0)) {
return ERROR;
}
if (NONE == SpiFlashInit(SPI_BUS_NAME_1, "spi1_dev0", SPI_1_DRV_NAME, "spi1_W25Q64")) {
return ERROR;
}
#endif
return EOK;
}

View File

@ -1,19 +0,0 @@
if BSP_USING_HWTIMER
config HWTIMER_BUS_NAME_2
string "hwtimer bus name"
default "hwtim2"
menuconfig ENABLE_TIM2
bool "enable TIM2"
default y
if ENABLE_TIM2
config HWTIMER_2_DEVICE_NAME_2
string "TIM2 dev name"
default "hwtim2_dev2"
config HWTIMER_DRIVER_NAME_2
string "TIM2 drv name"
default "hwtim2_drv"
endif
endif

View File

@ -1,3 +0,0 @@
SRC_FILES := connect_hwtimer.c hardware_tim.c
include $(KERNEL_ROOT)/compiler.mk

View File

@ -1,186 +0,0 @@
/*
* Copyright (c) 2006-2018, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2018-12-10 zylx first version
* 2020-06-16 thread-liu Porting for stm32mp1
* 2020-08-25 linyongkang Fix the timer clock frequency doubling problem
* 2020-10-14 Dozingfiretruck Porting for stm32wbxx
*/
/**
* @file connect_hwtimer.c
* @brief support stm32f407-st-discovery-board hwtimer function and register to bus framework
* @version 1.0
* @author AIIT XUOS Lab
* @date 2021-04-25
*/
/*************************************************
File name: connect_hwtimer.c
Description: support stm32f407-st-discovery-board hwtimer configure and spi bus register function
Others: take RT-Thread v4.0.2/bsp/stm32/libraries/HAL_Drivers/drv_hwtimer.c for references
https://github.com/RT-Thread/rt-thread/tree/v4.0.2
History:
1. Date: 2021-04-25
Author: AIIT XUOS Lab
Modification:
1. support stm32f407-st-discovery-board hwtimer configure
2. support stm32f407-st-discovery-board hwtimer bus device and driver register
*************************************************/
#include <board.h>
#include <xiuos.h>
#include <hardware_tim.h>
#include <misc.h>
#include <hardware_rcc.h>
#include "connect_hwtimer.h"
static struct HwtimerCallBackInfo *ptim2_cb_info = NULL;
#ifdef ENABLE_TIM2
void TIM2_IRQHandler(int irq_num, void *arg)
{
TIM_ClearITPendingBit(TIM2, TIM_IT_Update);
KPrintf("hwtimer 2 ... come ...\n");
if (ptim2_cb_info) {
if (ptim2_cb_info->timeout_callback) {
ptim2_cb_info->timeout_callback(ptim2_cb_info->param);
}
}
}
DECLARE_HW_IRQ(TIM2_IRQn, TIM2_IRQHandler, NONE);
#endif
uint32 HwtimerOpen(void *dev)
{
struct HwtimerHardwareDevice *hwtimer_dev = dev;
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE);
TIM_DeInit(TIM2);
TIM_TimeBaseInitTypeDef timer_def;
timer_def.TIM_Period = (hwtimer_dev->hwtimer_param.period_millisecond) * 10 - 1;
timer_def.TIM_Prescaler = 8400 - 1;
timer_def.TIM_CounterMode = TIM_CounterMode_Up;
timer_def.TIM_ClockDivision = TIM_CKD_DIV1;
timer_def.TIM_RepetitionCounter = 0;
TIM_TimeBaseInit(TIM2, &timer_def);
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_InitStructure.NVIC_IRQChannel = TIM2_IRQn; /*Configure the timer interrupt line*/
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0x01; /*Configure preemption priority*/
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0x01; /*Configure sub-priority*/
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; /*Enable interrupt line*/
NVIC_Init(&NVIC_InitStructure);
ptim2_cb_info = &hwtimer_dev->hwtimer_param.cb_info;
TIM_ITConfig(TIM2, TIM_IT_Update, ENABLE);
TIM_Cmd(TIM2, ENABLE);
return EOK;
}
uint32 HwtimerClose(void *dev)
{
TIM_Cmd(TIM2, DISABLE);
return EOK;
}
/*manage the hwtimer device operations*/
static const struct HwtimerDevDone dev_done =
{
.open = HwtimerOpen,
.close = HwtimerClose,
.write = NONE,
.read = NONE,
};
/*Init hwtimer bus*/
static int BoardHwtimerBusInit(struct HwtimerBus *hwtimer_bus, struct HwtimerDriver *hwtimer_driver)
{
x_err_t ret = EOK;
/*Init the hwtimer bus */
ret = HwtimerBusInit(hwtimer_bus, HWTIMER_BUS_NAME_2);
if (EOK != ret) {
KPrintf("board_hwtimer_init HwtimerBusInit error %d\n", ret);
return ERROR;
}
#ifdef ENABLE_TIM2
/*Init the hwtimer driver*/
hwtimer_driver->configure = NONE;
ret = HwtimerDriverInit(hwtimer_driver, HWTIMER_DRIVER_NAME_2);
if (EOK != ret) {
KPrintf("board_hwtimer_init HwtimerDriverInit error %d\n", ret);
return ERROR;
}
/*Attach the hwtimer driver to the hwtimer bus*/
ret = HwtimerDriverAttachToBus(HWTIMER_DRIVER_NAME_2, HWTIMER_BUS_NAME_2);
if (EOK != ret) {
KPrintf("board_hwtimer_init USEDriverAttachToBus error %d\n", ret);
return ERROR;
}
#endif
return ret;
}
/*Attach the hwtimer device to the hwtimer bus*/
static int BoardHwtimerDevBend(void)
{
#ifdef ENABLE_TIM2
x_err_t ret = EOK;
static struct HwtimerHardwareDevice hwtimer_device_2;
memset(&hwtimer_device_2, 0, sizeof(struct HwtimerHardwareDevice));
hwtimer_device_2.dev_done = &dev_done;
ret = HwtimerDeviceRegister(&hwtimer_device_2, NONE, HWTIMER_2_DEVICE_NAME_2);
if (EOK != ret) {
KPrintf("board_hwtimer_init HWTIMERDeviceInit device %s error %d\n", HWTIMER_2_DEVICE_NAME_2, ret);
return ERROR;
}
ret = HwtimerDeviceAttachToBus(HWTIMER_2_DEVICE_NAME_2, HWTIMER_BUS_NAME_2);
if (EOK != ret) {
KPrintf("board_hwtimer_init HwtimerDeviceAttachToBus device %s error %d\n", HWTIMER_2_DEVICE_NAME_2, ret);
return ERROR;
}
return ret;
#endif
}
/*ARM-32 BOARD HWTIMER INIT*/
int Stm32HwTimerInit(void)
{
x_err_t ret = EOK;
static struct HwtimerBus hwtimer_bus;
memset(&hwtimer_bus, 0, sizeof(struct HwtimerBus));
static struct HwtimerDriver hwtimer_driver;
memset(&hwtimer_driver, 0, sizeof(struct HwtimerDriver));
ret = BoardHwtimerBusInit(&hwtimer_bus, &hwtimer_driver);
if (EOK != ret) {
KPrintf("board_hwtimer_Init error ret %u\n", ret);
return ERROR;
}
ret = BoardHwtimerDevBend();
if (EOK != ret) {
KPrintf("board_hwtimer_Init error ret %u\n", ret);
return ERROR;
}
return ret;
}

View File

@ -1,12 +0,0 @@
config BSP_USING_USBH
bool "Using usb host"
default y
config USB_BUS_NAME
string "usb bus name"
default "usb"
config USB_DRIVER_NAME
string "usb bus driver name"
default "usb_drv"
config USB_DEVICE_NAME
string "usb bus device name"
default "usb_dev"

View File

@ -1,4 +0,0 @@
SRC_FILES := usb_bsp.c usbh.c connect_usb.c
SRC_FILES += STM32_USB_OTG_Driver/src/usb_core.c STM32_USB_OTG_Driver/src/usb_hcd.c STM32_USB_OTG_Driver/src/usb_hcd_int.c
include $(KERNEL_ROOT)/compiler.mk

View File

@ -1,105 +0,0 @@
/**
******************************************************************************
* @file usb_bsp.h
* @author xiuos Team
* @version V1.0.0
* @date 2020-9-3
* @brief Specific api's relative to the used hardware platform
******************************************************************************
* @file usb_bsp.h
* @author MCD Application Team
* @version V1.0.0
* @date 30-September-2011
* ************************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2015 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* <http://www.st.com/SLA0044>
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USB_BSP__H__
#define __USB_BSP__H__
/* Includes ------------------------------------------------------------------*/
#include "usb_core.h"
/** @addtogroup USB_OTG_DRIVER
* @{
*/
/** @defgroup USB_BSP
* @brief This file is the
* @{
*/
/** @defgroup USB_BSP_Exported_Defines
* @{
*/
/**
* @}
*/
/** @defgroup USB_BSP_Exported_Types
* @{
*/
/**
* @}
*/
/** @defgroup USB_BSP_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USB_BSP_Exported_Variables
* @{
*/
/**
* @}
*/
/** @defgroup USB_BSP_Exported_FunctionsPrototype
* @{
*/
void BSP_Init(void);
void USB_OTG_BSP_Init (USB_OTG_CORE_HANDLE *pdev);
void USB_OTG_BSP_uDelay (const uint32_t usec);
void USB_OTG_BSP_mDelay (const uint32_t msec);
void USB_OTG_BSP_ENABLE_INTERRUPT (USB_OTG_CORE_HANDLE *pdev);
void USB_OTG_BSP_TimerIRQ (void);
#ifdef USE_HOST_MODE
void USB_OTG_BSP_ConfigVBUS(USB_OTG_CORE_HANDLE *pdev);
void USB_OTG_BSP_DriveVBUS(USB_OTG_CORE_HANDLE *pdev,uint8_t state);
void USB_OTG_BSP_Resume(USB_OTG_CORE_HANDLE *pdev) ;
void USB_OTG_BSP_Suspend(USB_OTG_CORE_HANDLE *pdev);
#endif /* USE_HOST_MODE */
/**
* @}
*/
#endif /* __USB_BSP__H__ */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,293 +0,0 @@
/**
******************************************************************************
* @file usb_conf.h
* @author xiuos Team
* @version V1.0.0
* @date 2020-9-3
* @brief General low level driver configuration
******************************************************************************
* @file usb_conf.h
* @author MCD Application Team
* @version V1.0.0
* @date 30-September-2011
* ************************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2015 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* <http://www.st.com/SLA0044>
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USB_CONF__H__
#define __USB_CONF__H__
/* Includes ------------------------------------------------------------------*/
#include <stm32f4xx.h>
/** @addtogroup USB_OTG_DRIVER
* @{
*/
/** @defgroup USB_CONF
* @brief USB low level driver configuration file
* @{
*/
/** @defgroup USB_CONF_Exported_Defines
* @{
*/
/* USB Core and PHY interface configuration.
Tip: To avoid modifying these defines each time you need to change the USB
configuration, you can declare the needed define in your toolchain
compiler preprocessor.
*/
/****************** USB OTG FS PHY CONFIGURATION *******************************
* The USB OTG FS Core supports one on-chip Full Speed PHY.
*
* The USE_EMBEDDED_PHY symbol is defined in the project compiler preprocessor
* when FS core is used.
*******************************************************************************/
#ifndef USE_USB_OTG_FS
#define USE_USB_OTG_FS
#endif /* USE_USB_OTG_FS */
#ifdef USE_USB_OTG_FS
#define USB_OTG_FS_CORE
#endif
/****************** USB OTG HS PHY CONFIGURATION *******************************
* The USB OTG HS Core supports two PHY interfaces:
* (i) An ULPI interface for the external High Speed PHY: the USB HS Core will
* operate in High speed mode
* (ii) An on-chip Full Speed PHY: the USB HS Core will operate in Full speed mode
*
* You can select the PHY to be used using one of these two defines:
* (i) USE_ULPI_PHY: if the USB OTG HS Core is to be used in High speed mode
* (ii) USE_EMBEDDED_PHY: if the USB OTG HS Core is to be used in Full speed mode
*
* Notes:
* - The USE_ULPI_PHY symbol is defined in the project compiler preprocessor as
* default PHY when HS core is used.
* - On STM322xG-EVAL and STM324xG-EVAL boards, only configuration(i) is available.
* Configuration (ii) need a different hardware, for more details refer to your
* STM32 device datasheet.
*******************************************************************************/
#ifndef USE_USB_OTG_HS
//#define USE_USB_OTG_HS
#endif /* USE_USB_OTG_HS */
#ifndef USE_ULPI_PHY
//#define USE_ULPI_PHY
#endif /* USE_ULPI_PHY */
#ifndef USE_EMBEDDED_PHY
//#define USE_EMBEDDED_PHY
#endif /* USE_EMBEDDED_PHY */
#ifdef USE_USB_OTG_HS
#define USB_OTG_HS_CORE
#endif
/*******************************************************************************
* FIFO Size Configuration in Device mode
*
* (i) Receive data FIFO size = RAM for setup packets +
* OUT endpoint control information +
* data OUT packets + miscellaneous
* Space = ONE 32-bits words
* --> RAM for setup packets = 10 spaces
* (n is the nbr of CTRL EPs the device core supports)
* --> OUT EP CTRL info = 1 space
* (one space for status information written to the FIFO along with each
* received packet)
* --> data OUT packets = (Largest Packet Size / 4) + 1 spaces
* (MINIMUM to receive packets)
* --> OR data OUT packets = at least 2*(Largest Packet Size / 4) + 1 spaces
* (if high-bandwidth EP is enabled or multiple isochronous EPs)
* --> miscellaneous = 1 space per OUT EP
* (one space for transfer complete status information also pushed to the
* FIFO with each endpoint's last packet)
*
* (ii)MINIMUM RAM space required for each IN EP Tx FIFO = MAX packet size for
* that particular IN EP. More space allocated in the IN EP Tx FIFO results
* in a better performance on the USB and can hide latencies on the AHB.
*
* (iii) TXn min size = 16 words. (n : Transmit FIFO index)
* (iv) When a TxFIFO is not used, the Configuration should be as follows:
* case 1 : n > m and Txn is not used (n,m : Transmit FIFO indexes)
* --> Txm can use the space allocated for Txn.
* case2 : n < m and Txn is not used (n,m : Transmit FIFO indexes)
* --> Txn should be configured with the minimum space of 16 words
* (v) The FIFO is used optimally when used TxFIFOs are allocated in the top
* of the FIFO.Ex: use EP1 and EP2 as IN instead of EP1 and EP3 as IN ones.
*******************************************************************************/
/*******************************************************************************
* FIFO Size Configuration in Host mode
*
* (i) Receive data FIFO size = (Largest Packet Size / 4) + 1 or
* 2x (Largest Packet Size / 4) + 1, If a
* high-bandwidth channel or multiple isochronous
* channels are enabled
*
* (ii) For the host nonperiodic Transmit FIFO is the largest maximum packet size
* for all supported nonperiodic OUT channels. Typically, a space
* corresponding to two Largest Packet Size is recommended.
*
* (iii) The minimum amount of RAM required for Host periodic Transmit FIFO is
* the largest maximum packet size for all supported periodic OUT channels.
* If there is at least one High Bandwidth Isochronous OUT endpoint,
* then the space must be at least two times the maximum packet size for
* that channel.
*******************************************************************************/
/****************** USB OTG HS CONFIGURATION **********************************/
#ifdef USB_OTG_HS_CORE
#define RX_FIFO_HS_SIZE 512
#define TX0_FIFO_HS_SIZE 512
#define TX1_FIFO_HS_SIZE 512
#define TX2_FIFO_HS_SIZE 0
#define TX3_FIFO_HS_SIZE 0
#define TX4_FIFO_HS_SIZE 0
#define TX5_FIFO_HS_SIZE 0
#define TXH_NP_HS_FIFOSIZ 96
#define TXH_P_HS_FIFOSIZ 96
// #define USB_OTG_HS_LOW_PWR_MGMT_SUPPORT
// #define USB_OTG_HS_SOF_OUTPUT_ENABLED
// #define USB_OTG_INTERNAL_VBUS_ENABLED
#define USB_OTG_EXTERNAL_VBUS_ENABLED
#ifdef USE_ULPI_PHY
#define USB_OTG_ULPI_PHY_ENABLED
#endif
#ifdef USE_EMBEDDED_PHY
#define USB_OTG_EMBEDDED_PHY_ENABLED
#endif
#define USB_OTG_HS_INTERNAL_DMA_ENABLED
#define USB_OTG_HS_DEDICATED_EP1_ENABLED
#endif
/****************** USB OTG FS CONFIGURATION **********************************/
#ifdef USB_OTG_FS_CORE
#define RX_FIFO_FS_SIZE 128
#define TX0_FIFO_FS_SIZE 64
#define TX1_FIFO_FS_SIZE 128
#define TX2_FIFO_FS_SIZE 0
#define TX3_FIFO_FS_SIZE 0
#define TXH_NP_FS_FIFOSIZ 96
#define TXH_P_FS_FIFOSIZ 96
// #define USB_OTG_FS_LOW_PWR_MGMT_SUPPORT
// #define USB_OTG_FS_SOF_OUTPUT_ENABLED
#endif
/****************** USB OTG MISC CONFIGURATION ********************************/
//#define VBUS_SENSING_ENABLED
/****************** USB OTG MODE CONFIGURATION ********************************/
#define USE_HOST_MODE
// #define USE_DEVICE_MODE
//#define USE_OTG_MODE
#ifndef USB_OTG_FS_CORE
#ifndef USB_OTG_HS_CORE
#error "USB_OTG_HS_CORE or USB_OTG_FS_CORE should be defined"
#endif
#endif
#ifndef USE_DEVICE_MODE
#ifndef USE_HOST_MODE
#error "USE_DEVICE_MODE or USE_HOST_MODE should be defined"
#endif
#endif
#ifndef USE_USB_OTG_HS
#ifndef USE_USB_OTG_FS
#error "USE_USB_OTG_HS or USE_USB_OTG_FS should be defined"
#endif
#else //USE_USB_OTG_HS
#ifndef USE_ULPI_PHY
#ifndef USE_EMBEDDED_PHY
#error "USE_ULPI_PHY or USE_EMBEDDED_PHY should be defined"
#endif
#endif
#endif
/****************** C Compilers dependant keywords ****************************/
/* In HS mode and when the DMA is used, all variables and data structures dealing
with the DMA during the transaction process should be 4-bytes aligned */
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#if defined (__GNUC__) /* GNU Compiler */
#define __ALIGN_END __attribute__ ((aligned (4)))
#define __ALIGN_BEGIN
#else
#define __ALIGN_END
#endif /* __GNUC__ */
#else
#define __ALIGN_BEGIN
#define __ALIGN_END
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
#if defined ( __GNUC__ ) /* GNU Compiler */
#define __packed __attribute__ ((__packed__))
#endif
/**
* @}
*/
/** @defgroup USB_CONF_Exported_Types
* @{
*/
/**
* @}
*/
/** @defgroup USB_CONF_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USB_CONF_Exported_Variables
* @{
*/
/**
* @}
*/
/** @defgroup USB_CONF_Exported_FunctionsPrototype
* @{
*/
/**
* @}
*/
#endif //__USB_CONF__H__
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,294 +0,0 @@
/**
******************************************************************************
* @file usb_conf_template.h
* @author xiuos Team
* @version V1.0.0
* @date 2020-9-3
* @brief General low level driver configuration
******************************************************************************
* @file usb_conf_template.h
* @author MCD Application Team
* @version V1.0.0
* @date 30-September-2011
* ********************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2015 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* <http://www.st.com/SLA0044>
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USB_CONF__H__
#define __USB_CONF__H__
/* Includes ------------------------------------------------------------------*/
#include "usb_conf.h"
/** @addtogroup USB_OTG_DRIVER
* @{
*/
/** @defgroup USB_CONF
* @brief USB low level driver configuration file
* @{
*/
/** @defgroup USB_CONF_Exported_Defines
* @{
*/
/* USB Core and PHY interface configuration.
Tip: To avoid modifying these defines each time you need to change the USB
configuration, you can declare the needed define in your toolchain
compiler preprocessor.
*/
/****************** USB OTG FS PHY CONFIGURATION *******************************
* The USB OTG FS Core supports one on-chip Full Speed PHY.
*
* The USE_EMBEDDED_PHY symbol is defined in the project compiler preprocessor
* when FS core is used.
*******************************************************************************/
#ifndef USE_USB_OTG_FS
//#define USE_USB_OTG_FS
#endif /* USE_USB_OTG_FS */
#ifdef USE_USB_OTG_FS
#define USB_OTG_FS_CORE
#endif
/****************** USB OTG HS PHY CONFIGURATION *******************************
* The USB OTG HS Core supports two PHY interfaces:
* (i) An ULPI interface for the external High Speed PHY: the USB HS Core will
* operate in High speed mode
* (ii) An on-chip Full Speed PHY: the USB HS Core will operate in Full speed mode
*
* You can select the PHY to be used using one of these two defines:
* (i) USE_ULPI_PHY: if the USB OTG HS Core is to be used in High speed mode
* (ii) USE_EMBEDDED_PHY: if the USB OTG HS Core is to be used in Full speed mode
*
* Notes:
* - The USE_ULPI_PHY symbol is defined in the project compiler preprocessor as
* default PHY when HS core is used.
* - On STM322xG-EVAL and STM324xG-EVAL boards, only configuration(i) is available.
* Configuration (ii) need a different hardware, for more details refer to your
* STM32 device datasheet.
*******************************************************************************/
#ifndef USE_USB_OTG_HS
//#define USE_USB_OTG_HS
#endif /* USE_USB_OTG_HS */
#ifndef USE_ULPI_PHY
//#define USE_ULPI_PHY
#endif /* USE_ULPI_PHY */
#ifndef USE_EMBEDDED_PHY
//#define USE_EMBEDDED_PHY
#endif /* USE_EMBEDDED_PHY */
#ifdef USE_USB_OTG_HS
#define USB_OTG_HS_CORE
#endif
/*******************************************************************************
* FIFO Size Configuration in Device mode
*
* (i) Receive data FIFO size = RAM for setup packets +
* OUT endpoint control information +
* data OUT packets + miscellaneous
* Space = ONE 32-bits words
* --> RAM for setup packets = 10 spaces
* (n is the nbr of CTRL EPs the device core supports)
* --> OUT EP CTRL info = 1 space
* (one space for status information written to the FIFO along with each
* received packet)
* --> data OUT packets = (Largest Packet Size / 4) + 1 spaces
* (MINIMUM to receive packets)
* --> OR data OUT packets = at least 2*(Largest Packet Size / 4) + 1 spaces
* (if high-bandwidth EP is enabled or multiple isochronous EPs)
* --> miscellaneous = 1 space per OUT EP
* (one space for transfer complete status information also pushed to the
* FIFO with each endpoint's last packet)
*
* (ii)MINIMUM RAM space required for each IN EP Tx FIFO = MAX packet size for
* that particular IN EP. More space allocated in the IN EP Tx FIFO results
* in a better performance on the USB and can hide latencies on the AHB.
*
* (iii) TXn min size = 16 words. (n : Transmit FIFO index)
* (iv) When a TxFIFO is not used, the Configuration should be as follows:
* case 1 : n > m and Txn is not used (n,m : Transmit FIFO indexes)
* --> Txm can use the space allocated for Txn.
* case2 : n < m and Txn is not used (n,m : Transmit FIFO indexes)
* --> Txn should be configured with the minimum space of 16 words
* (v) The FIFO is used optimally when used TxFIFOs are allocated in the top
* of the FIFO.Ex: use EP1 and EP2 as IN instead of EP1 and EP3 as IN ones.
*******************************************************************************/
/*******************************************************************************
* FIFO Size Configuration in Host mode
*
* (i) Receive data FIFO size = (Largest Packet Size / 4) + 1 or
* 2x (Largest Packet Size / 4) + 1, If a
* high-bandwidth channel or multiple isochronous
* channels are enabled
*
* (ii) For the host nonperiodic Transmit FIFO is the largest maximum packet size
* for all supported nonperiodic OUT channels. Typically, a space
* corresponding to two Largest Packet Size is recommended.
*
* (iii) The minimum amount of RAM required for Host periodic Transmit FIFO is
* the largest maximum packet size for all supported periodic OUT channels.
* If there is at least one High Bandwidth Isochronous OUT endpoint,
* then the space must be at least two times the maximum packet size for
* that channel.
*******************************************************************************/
/****************** USB OTG HS CONFIGURATION **********************************/
#ifdef USB_OTG_HS_CORE
#define RX_FIFO_HS_SIZE 512
#define TX0_FIFO_HS_SIZE 512
#define TX1_FIFO_HS_SIZE 512
#define TX2_FIFO_HS_SIZE 0
#define TX3_FIFO_HS_SIZE 0
#define TX4_FIFO_HS_SIZE 0
#define TX5_FIFO_HS_SIZE 0
#define TXH_NP_HS_FIFOSIZ 96
#define TXH_P_HS_FIFOSIZ 96
// #define USB_OTG_HS_LOW_PWR_MGMT_SUPPORT
// #define USB_OTG_HS_SOF_OUTPUT_ENABLED
// #define USB_OTG_INTERNAL_VBUS_ENABLED
#define USB_OTG_EXTERNAL_VBUS_ENABLED
#ifdef USE_ULPI_PHY
#define USB_OTG_ULPI_PHY_ENABLED
#endif
#ifdef USE_EMBEDDED_PHY
#define USB_OTG_EMBEDDED_PHY_ENABLED
#endif
#define USB_OTG_HS_INTERNAL_DMA_ENABLED
#define USB_OTG_HS_DEDICATED_EP1_ENABLED
#endif
/****************** USB OTG FS CONFIGURATION **********************************/
#ifdef USB_OTG_FS_CORE
#define RX_FIFO_FS_SIZE 128
#define TX0_FIFO_FS_SIZE 64
#define TX1_FIFO_FS_SIZE 128
#define TX2_FIFO_FS_SIZE 0
#define TX3_FIFO_FS_SIZE 0
#define TXH_NP_HS_FIFOSIZ 96
#define TXH_P_HS_FIFOSIZ 96
// #define USB_OTG_FS_LOW_PWR_MGMT_SUPPORT
// #define USB_OTG_FS_SOF_OUTPUT_ENABLED
#endif
/****************** USB OTG MISC CONFIGURATION ********************************/
//#define VBUS_SENSING_ENABLED
/****************** USB OTG MODE CONFIGURATION ********************************/
//#define USE_HOST_MODE
#define USE_DEVICE_MODE
//#define USE_OTG_MODE
#ifndef USB_OTG_FS_CORE
#ifndef USB_OTG_HS_CORE
#error "USB_OTG_HS_CORE or USB_OTG_FS_CORE should be defined"
#endif
#endif
#ifndef USE_DEVICE_MODE
#ifndef USE_HOST_MODE
#error "USE_DEVICE_MODE or USE_HOST_MODE should be defined"
#endif
#endif
#ifndef USE_USB_OTG_HS
#ifndef USE_USB_OTG_FS
#error "USE_USB_OTG_HS or USE_USB_OTG_FS should be defined"
#endif
#else //USE_USB_OTG_HS
#ifndef USE_ULPI_PHY
#ifndef USE_EMBEDDED_PHY
#error "USE_ULPI_PHY or USE_EMBEDDED_PHY should be defined"
#endif
#endif
#endif
/****************** C Compilers dependant keywords ****************************/
/* In HS mode and when the DMA is used, all variables and data structures dealing
with the DMA during the transaction process should be 4-bytes aligned */
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#if defined (__GNUC__) /* GNU Compiler */
#define __ALIGN_END __attribute__ ((aligned (4)))
#define __ALIGN_BEGIN
#else
#define __ALIGN_END
#endif /* __GNUC__ */
#else
#define __ALIGN_BEGIN
#define __ALIGN_END
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
/* __packed keyword used to decrease the data type alignment to 1-byte */
#if defined ( __GNUC__ ) /* GNU Compiler */
#define __packed __attribute__ ((__packed__))
#endif
/**
* @}
*/
/** @defgroup USB_CONF_Exported_Types
* @{
*/
/**
* @}
*/
/** @defgroup USB_CONF_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USB_CONF_Exported_Variables
* @{
*/
/**
* @}
*/
/** @defgroup USB_CONF_Exported_FunctionsPrototype
* @{
*/
/**
* @}
*/
#endif //__USB_CONF__H__
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,412 +0,0 @@
/**
******************************************************************************
* @file usb_core.h
* @author xiuos Team
* @version V1.0.0
* @date 2020-9-3
* @brief This file is based on usb_core.h
* Header of the Core Layer
******************************************************************************
* @file usb_core.h
* @author MCD Application Team
* @version V1.0.0
* @date 30-September-2011
* ********************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2015 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* <http://www.st.com/SLA0044>
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USB_CORE_H__
#define __USB_CORE_H__
/* Includes ------------------------------------------------------------------*/
#include "usb_conf.h"
#include "usb_regs.h"
#include "usb_defines.h"
/** @addtogroup USB_OTG_DRIVER
* @{
*/
/** @defgroup USB_CORE
* @brief usb otg driver core layer
* @{
*/
/** @defgroup USB_CORE_Exported_Defines
* @{
*/
#define USB_OTG_EP0_IDLE 0
#define USB_OTG_EP0_SETUP 1
#define USB_OTG_EP0_DATA_IN 2
#define USB_OTG_EP0_DATA_OUT 3
#define USB_OTG_EP0_STATUS_IN 4
#define USB_OTG_EP0_STATUS_OUT 5
#define USB_OTG_EP0_STALL 6
#define USB_OTG_EP_TX_DIS 0x0000
#define USB_OTG_EP_TX_STALL 0x0010
#define USB_OTG_EP_TX_NAK 0x0020
#define USB_OTG_EP_TX_VALID 0x0030
#define USB_OTG_EP_RX_DIS 0x0000
#define USB_OTG_EP_RX_STALL 0x1000
#define USB_OTG_EP_RX_NAK 0x2000
#define USB_OTG_EP_RX_VALID 0x3000
/**
* @}
*/
#define MAX_DATA_LENGTH 0x200
/** @defgroup USB_CORE_Exported_Types
* @{
*/
typedef enum {
USB_OTG_OK = 0,
USB_OTG_FAIL
}USB_OTG_STS;
typedef enum {
HC_IDLE = 0,
HC_XFRC,
HC_HALTED,
HC_NAK,
HC_NYET,
HC_STALL,
HC_XACTERR,
HC_BBLERR,
HC_DATATGLERR,
}HC_STATUS;
typedef enum {
URB_IDLE = 0,
URB_DONE,
URB_NOTREADY,
URB_ERROR,
URB_STALL
}URB_STATE;
typedef enum {
CTRL_START = 0,
CTRL_XFRC,
CTRL_HALTED,
CTRL_NAK,
CTRL_STALL,
CTRL_XACTERR,
CTRL_BBLERR,
CTRL_DATATGLERR,
CTRL_FAIL
}CTRL_STATUS;
typedef struct USB_OTG_hc
{
uint8_t DevAddr ;
uint8_t ep_num;
uint8_t ep_is_in;
uint8_t speed;
uint8_t do_ping;
uint8_t ep_type;
uint16_t max_packet;
uint8_t data_pid;
uint8_t *xfer_buff;
uint32_t XferLen;
uint32_t xfer_count;
uint8_t toggle_in;
uint8_t toggle_out;
uint32_t dma_addr;
}
USB_OTG_HC , *PUSB_OTG_HC;
typedef struct USB_OTG_ep
{
uint8_t num;
uint8_t is_in;
uint8_t is_stall;
uint8_t type;
uint8_t data_pid_start;
uint8_t even_odd_frame;
uint16_t tx_fifo_num;
uint32_t maxpacket;
/* transaction level variables*/
uint8_t *xfer_buff;
uint32_t dma_addr;
uint32_t XferLen;
uint32_t xfer_count;
/* Transfer level variables*/
uint32_t rem_data_len;
uint32_t total_data_len;
uint32_t ctl_data_len;
}
USB_OTG_EP , *PUSB_OTG_EP;
typedef struct USB_OTG_core_cfg
{
uint8_t host_channels;
uint8_t dev_endpoints;
uint8_t speed;
uint8_t dma_enable;
uint16_t mps;
uint16_t TotalFifoSize;
uint8_t phy_itface;
uint8_t Sof_output;
uint8_t low_power;
uint8_t coreID;
}
USB_OTG_CORE_CFGS, *PUSB_OTG_CORE_CFGS;
typedef struct usb_setup_req {
uint8_t bmRequest;
uint8_t bRequest;
uint16_t wValue;
uint16_t wIndex;
uint16_t wLength;
} USB_SETUP_REQ;
typedef struct _Device_TypeDef
{
uint8_t *(*GetDeviceDescriptor)( uint8_t speed , uint16_t *length);
uint8_t *(*GetLangIDStrDescriptor)( uint8_t speed , uint16_t *length);
uint8_t *(*GetManufacturerStrDescriptor)( uint8_t speed , uint16_t *length);
uint8_t *(*GetProductStrDescriptor)( uint8_t speed , uint16_t *length);
uint8_t *(*GetSerialStrDescriptor)( uint8_t speed , uint16_t *length);
uint8_t *(*GetConfigurationStrDescriptor)( uint8_t speed , uint16_t *length);
uint8_t *(*GetInterfaceStrDescriptor)( uint8_t speed , uint16_t *length);
#if (USBD_LPM_ENABLED == 1)
uint8_t *(*GetBOSDescriptor)( uint8_t speed , uint16_t *length);
#endif
} USBD_DEVICE, *pUSBD_DEVICE;
typedef struct _Device_cb
{
uint8_t (*Init) (void *pdev , uint8_t cfgidx);
uint8_t (*DeInit) (void *pdev , uint8_t cfgidx);
/* Control Endpoints*/
uint8_t (*Setup) (void *pdev , USB_SETUP_REQ *req);
uint8_t (*EP0_TxSent) (void *pdev );
uint8_t (*EP0_RxReady) (void *pdev );
/* Class Specific Endpoints*/
uint8_t (*DataIn) (void *pdev , uint8_t epnum);
uint8_t (*DataOut) (void *pdev , uint8_t epnum);
uint8_t (*SOF) (void *pdev);
uint8_t (*IsoINIncomplete) (void *pdev);
uint8_t (*IsoOUTIncomplete) (void *pdev);
uint8_t *(*GetConfigDescriptor)( uint8_t speed , uint16_t *length);
#ifdef USB_OTG_HS_CORE
uint8_t *(*GetOtherConfigDescriptor)( uint8_t speed , uint16_t *length);
#endif
#ifdef USB_SUPPORT_USER_STRING_DESC
uint8_t *(*GetUsrStrDescriptor)( uint8_t speed ,uint8_t index, uint16_t *length);
#endif
} USBD_Class_cb_TypeDef;
typedef struct _USBD_USR_PROP
{
void (*Init)(void);
void (*DeviceReset)(uint8_t speed);
void (*DeviceConfigured)(void);
void (*DeviceSuspended)(void);
void (*DeviceResumed)(void);
void (*DeviceConnected)(void);
void (*DeviceDisconnected)(void);
}
USBD_Usr_cb_TypeDef;
typedef struct _DCD
{
uint8_t device_config;
uint8_t device_state;
uint8_t device_status;
uint8_t device_old_status;
uint8_t device_address;
uint8_t connection_status;
uint8_t test_mode;
uint32_t DevRemoteWakeup;
USB_OTG_EP in_ep [USB_OTG_MAX_TX_FIFOS];
USB_OTG_EP out_ep [USB_OTG_MAX_TX_FIFOS];
uint8_t setup_packet [8*3];
USBD_Class_cb_TypeDef *class_cb;
USBD_Usr_cb_TypeDef *usr_cb;
USBD_DEVICE *usr_device;
uint8_t *pConfig_descriptor;
}
DCD_DEV , *DCD_PDEV;
typedef struct _HCD
{
uint8_t Rx_Buffer [MAX_DATA_LENGTH];
__IO uint32_t ConnSts;
__IO uint32_t PortEnabled;
__IO uint32_t ErrCnt[USB_OTG_MAX_TX_FIFOS];
__IO uint32_t XferCnt[USB_OTG_MAX_TX_FIFOS];
__IO HC_STATUS HC_Status[USB_OTG_MAX_TX_FIFOS];
__IO URB_STATE URB_State[USB_OTG_MAX_TX_FIFOS];
USB_OTG_HC hc [USB_OTG_MAX_TX_FIFOS];
uint16_t channel [USB_OTG_MAX_TX_FIFOS];
}
HCD_DEV , *USB_OTG_USBH_PDEV;
typedef struct _OTG
{
uint8_t OTG_State;
uint8_t OTG_PrevState;
uint8_t OTG_Mode;
}
OTG_DEV , *USB_OTG_USBO_PDEV;
typedef struct USB_OTG_handle
{
USB_OTG_CORE_CFGS cfg;
USB_OTG_CORE_REGS regs;
#ifdef USE_DEVICE_MODE
DCD_DEV dev;
#endif
#ifdef USE_HOST_MODE
HCD_DEV host;
#endif
#ifdef USE_OTG_MODE
OTG_DEV otg;
#endif
void *data;
}
USB_OTG_CORE_HANDLE , *PUSB_OTG_CORE_HANDLE;
/**
* @}
*/
/** @defgroup USB_CORE_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USB_CORE_Exported_Variables
* @{
*/
/**
* @}
*/
/** @defgroup USB_CORE_Exported_FunctionsPrototype
* @{
*/
USB_OTG_STS USB_OTG_CoreInit (USB_OTG_CORE_HANDLE *pdev);
USB_OTG_STS USB_OTG_SelectCore (USB_OTG_CORE_HANDLE *pdev,
USB_OTG_CORE_ID_TypeDef coreID);
USB_OTG_STS USB_OTG_EnableGlobalInt (USB_OTG_CORE_HANDLE *pdev);
USB_OTG_STS USB_OTG_DisableGlobalInt(USB_OTG_CORE_HANDLE *pdev);
void* USB_OTG_ReadPacket (USB_OTG_CORE_HANDLE *pdev ,
uint8_t *dest,
uint16_t len);
USB_OTG_STS USB_OTG_WritePacket (USB_OTG_CORE_HANDLE *pdev ,
uint8_t *src,
uint8_t ch_ep_num,
uint16_t len);
USB_OTG_STS USB_OTG_FlushTxFifo (USB_OTG_CORE_HANDLE *pdev , uint32_t num);
USB_OTG_STS USB_OTG_FlushRxFifo (USB_OTG_CORE_HANDLE *pdev);
uint32_t USB_OTG_ReadCoreItr (USB_OTG_CORE_HANDLE *pdev);
uint32_t USB_OTG_ReadOtgItr (USB_OTG_CORE_HANDLE *pdev);
uint8_t USB_OTG_IsHostMode (USB_OTG_CORE_HANDLE *pdev);
uint8_t USB_OTG_IsDeviceMode (USB_OTG_CORE_HANDLE *pdev);
uint32_t USB_OTG_GetMode (USB_OTG_CORE_HANDLE *pdev);
USB_OTG_STS USB_OTG_PhyInit (USB_OTG_CORE_HANDLE *pdev);
USB_OTG_STS USB_OTG_SetCurrentMode (USB_OTG_CORE_HANDLE *pdev,
uint8_t mode);
/*********************** HOST APIs ********************************************/
#ifdef USE_HOST_MODE
USB_OTG_STS USB_OTG_CoreInitHost (USB_OTG_CORE_HANDLE *pdev);
USB_OTG_STS USB_OTG_EnableHostInt (USB_OTG_CORE_HANDLE *pdev);
USB_OTG_STS USB_OTG_HC_Init (USB_OTG_CORE_HANDLE *pdev, uint8_t hc_num);
USB_OTG_STS USB_OTG_HC_Halt (USB_OTG_CORE_HANDLE *pdev, uint8_t hc_num);
USB_OTG_STS USB_OTG_HC_StartXfer (USB_OTG_CORE_HANDLE *pdev, uint8_t hc_num);
USB_OTG_STS USB_OTG_HC_DoPing (USB_OTG_CORE_HANDLE *pdev , uint8_t hc_num);
uint32_t USB_OTG_ReadHostAllChannels_intr (USB_OTG_CORE_HANDLE *pdev);
uint32_t USB_OTG_ResetPort (USB_OTG_CORE_HANDLE *pdev);
uint32_t USB_OTG_ReadHPRT0 (USB_OTG_CORE_HANDLE *pdev);
void USB_OTG_DriveVbus (USB_OTG_CORE_HANDLE *pdev, uint8_t state);
void USB_OTG_InitFSLSPClkSel (USB_OTG_CORE_HANDLE *pdev ,uint8_t freq);
uint8_t USB_OTG_IsEvenFrame (USB_OTG_CORE_HANDLE *pdev) ;
void USB_OTG_StopHost (USB_OTG_CORE_HANDLE *pdev);
#endif
/********************* DEVICE APIs ********************************************/
#ifdef USE_DEVICE_MODE
USB_OTG_STS USB_OTG_CoreInitDev (USB_OTG_CORE_HANDLE *pdev);
USB_OTG_STS USB_OTG_EnableDevInt (USB_OTG_CORE_HANDLE *pdev);
uint32_t USB_OTG_ReadDevAllInEPItr (USB_OTG_CORE_HANDLE *pdev);
enum USB_OTG_SPEED USB_OTG_GetDeviceSpeed (USB_OTG_CORE_HANDLE *pdev);
USB_OTG_STS USB_OTG_EP0Activate (USB_OTG_CORE_HANDLE *pdev);
USB_OTG_STS USB_OTG_EPActivate (USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep);
USB_OTG_STS USB_OTG_EPDeactivate(USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep);
USB_OTG_STS USB_OTG_EPStartXfer (USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep);
USB_OTG_STS USB_OTG_EP0StartXfer(USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep);
USB_OTG_STS USB_OTG_EPSetStall (USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep);
USB_OTG_STS USB_OTG_EPClearStall (USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep);
uint32_t USB_OTG_ReadDevAllOutEp_itr (USB_OTG_CORE_HANDLE *pdev);
uint32_t USB_OTG_ReadDevOutEP_itr (USB_OTG_CORE_HANDLE *pdev , uint8_t epnum);
uint32_t USB_OTG_ReadDevAllInEPItr (USB_OTG_CORE_HANDLE *pdev);
void USB_OTG_InitDevSpeed (USB_OTG_CORE_HANDLE *pdev , uint8_t speed);
uint8_t USBH_IsEvenFrame (USB_OTG_CORE_HANDLE *pdev);
void USB_OTG_EP0_OutStart(USB_OTG_CORE_HANDLE *pdev);
void USB_OTG_ActiveRemoteWakeup(USB_OTG_CORE_HANDLE *pdev);
void USB_OTG_UngateClock(USB_OTG_CORE_HANDLE *pdev);
void USB_OTG_StopDevice(USB_OTG_CORE_HANDLE *pdev);
void USB_OTG_SetEPStatus (USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep , uint32_t Status);
uint32_t USB_OTG_GetEPStatus(USB_OTG_CORE_HANDLE *pdev ,USB_OTG_EP *ep);
#endif
/**
* @}
*/
#endif /* __USB_CORE_H__ */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,164 +0,0 @@
/**
******************************************************************************
* @file usb_dcd.h
* @author xiuos Team
* @version V1.0.0
* @date 2020-9-3
* @brief This file is based on usb_dcd.h
* Peripheral Driver Header file
******************************************************************************
* @file usb_dcd.h
* @author MCD Application Team
* @version V1.0.0
* @date 30-September-2011
* ********************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2015 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* <http://www.st.com/SLA0044>
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __DCD_H__
#define __DCD_H__
/* Includes ------------------------------------------------------------------*/
#include "usb_core.h"
/** @addtogroup USB_OTG_DRIVER
* @{
*/
/** @defgroup USB_DCD
* @brief This file is the
* @{
*/
/** @defgroup USB_DCD_Exported_Defines
* @{
*/
#define USB_OTG_EP_CONTROL 0
#define USB_OTG_EP_ISOC 1
#define USB_OTG_EP_BULK 2
#define USB_OTG_EP_INT 3
#define USB_OTG_EP_MASK 3
/* Device Status */
#define USB_OTG_DEFAULT 1
#define USB_OTG_ADDRESSED 2
#define USB_OTG_CONFIGURED 3
#define USB_OTG_SUSPENDED 4
/**
* @}
*/
/** @defgroup USB_DCD_Exported_Types
* @{
*/
/********************************************************************************
Data structure type
********************************************************************************/
typedef struct
{
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bEndpointAddress;
uint8_t bmAttributes;
uint16_t wMaxPacketSize;
uint8_t bInterval;
}
EP_DESCRIPTOR , *PEP_DESCRIPTOR;
/**
* @}
*/
/** @defgroup USB_DCD_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USB_DCD_Exported_Variables
* @{
*/
/**
* @}
*/
/** @defgroup USB_DCD_Exported_FunctionsPrototype
* @{
*/
/********************************************************************************
EXPORTED FUNCTION FROM THE USB-OTG LAYER
********************************************************************************/
void DCD_Init(USB_OTG_CORE_HANDLE *pdev ,
USB_OTG_CORE_ID_TypeDef coreID);
void DCD_DevConnect (USB_OTG_CORE_HANDLE *pdev);
void DCD_DevDisconnect (USB_OTG_CORE_HANDLE *pdev);
void DCD_EP_SetAddress (USB_OTG_CORE_HANDLE *pdev,
uint8_t address);
uint32_t DCD_EP_Open(USB_OTG_CORE_HANDLE *pdev ,
uint8_t EpAddr,
uint16_t ep_mps,
uint8_t ep_type);
uint32_t DCD_EP_Close (USB_OTG_CORE_HANDLE *pdev,
uint8_t EpAddr);
uint32_t DCD_EP_PrepareRx ( USB_OTG_CORE_HANDLE *pdev,
uint8_t EpAddr,
uint8_t *pbuf,
uint16_t BufLen);
uint32_t DCD_EP_Tx (USB_OTG_CORE_HANDLE *pdev,
uint8_t EpAddr,
uint8_t *pbuf,
uint32_t BufLen);
uint32_t DCD_EP_Stall (USB_OTG_CORE_HANDLE *pdev,
uint8_t epnum);
uint32_t DCD_EP_ClrStall (USB_OTG_CORE_HANDLE *pdev,
uint8_t epnum);
uint32_t DCD_EP_Flush (USB_OTG_CORE_HANDLE *pdev,
uint8_t epnum);
uint32_t DCD_Handle_ISR(USB_OTG_CORE_HANDLE *pdev);
uint32_t DCD_GetEPStatus(USB_OTG_CORE_HANDLE *pdev ,
uint8_t epnum);
void DCD_SetEPStatus (USB_OTG_CORE_HANDLE *pdev ,
uint8_t epnum ,
uint32_t Status);
/**
* @}
*/
#endif /* __DCD_H__ */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,128 +0,0 @@
/**
******************************************************************************
* @file usb_dcd_int.h
* @author xiuos Team
* @version V1.0.0
* @date 2020-9-3
* @brief This file is based on usb_dcd_int.h
* Peripheral Device Interface Layer
******************************************************************************
* @file usb_dcd_int.h
* @author MCD Application Team
* @version V1.0.0
* @date 30-September-2011
* ********************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2015 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* <http://www.st.com/SLA0044>
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef USB_DCD_INT_H__
#define USB_DCD_INT_H__
/* Includes ------------------------------------------------------------------*/
#include "usb_dcd.h"
/** @addtogroup USB_OTG_DRIVER
* @{
*/
/** @defgroup USB_DCD_INT
* @brief This file is the
* @{
*/
/** @defgroup USB_DCD_INT_Exported_Defines
* @{
*/
typedef struct _USBD_DCD_INT
{
uint8_t (* DataOutStage) (USB_OTG_CORE_HANDLE *pdev , uint8_t epnum);
uint8_t (* DataInStage) (USB_OTG_CORE_HANDLE *pdev , uint8_t epnum);
uint8_t (* SetupStage) (USB_OTG_CORE_HANDLE *pdev);
uint8_t (* SOF) (USB_OTG_CORE_HANDLE *pdev);
uint8_t (* Reset) (USB_OTG_CORE_HANDLE *pdev);
uint8_t (* Suspend) (USB_OTG_CORE_HANDLE *pdev);
uint8_t (* Resume) (USB_OTG_CORE_HANDLE *pdev);
uint8_t (* IsoINIncomplete) (USB_OTG_CORE_HANDLE *pdev);
uint8_t (* IsoOUTIncomplete) (USB_OTG_CORE_HANDLE *pdev);
uint8_t (* DevConnected) (USB_OTG_CORE_HANDLE *pdev);
uint8_t (* DevDisconnected) (USB_OTG_CORE_HANDLE *pdev);
}USBD_DCD_INT_cb_TypeDef;
extern USBD_DCD_INT_cb_TypeDef *USBD_DCD_INT_fops;
/**
* @}
*/
/** @defgroup USB_DCD_INT_Exported_Types
* @{
*/
/**
* @}
*/
/** @defgroup USB_DCD_INT_Exported_Macros
* @{
*/
#define CLEAR_IN_EP_INTR(epnum,intr) \
diepint.d32=0; \
diepint.b.intr = 1; \
USB_OTG_WRITE_REG32(&pdev->regs.INEP_REGS[epnum]->DIEPINT,diepint.d32);
#define CLEAR_OUT_EP_INTR(epnum,intr) \
doepint.d32=0; \
doepint.b.intr = 1; \
USB_OTG_WRITE_REG32(&pdev->regs.OUTEP_REGS[(epnum)]->DOEPINT,doepint.d32);
/**
* @}
*/
/** @defgroup USB_DCD_INT_Exported_Variables
* @{
*/
/**
* @}
*/
/** @defgroup USB_DCD_INT_Exported_FunctionsPrototype
* @{
*/
uint32_t USBD_OTG_ISR_Handler (USB_OTG_CORE_HANDLE *pdev);
uint32_t USBD_OTG_EP1OUT_ISR_Handler (USB_OTG_CORE_HANDLE *pdev);
uint32_t USBD_OTG_EP1IN_ISR_Handler (USB_OTG_CORE_HANDLE *pdev);
/**
* @}
*/
#endif /* USB_DCD_INT_H__ */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,271 +0,0 @@
/**
******************************************************************************
* @file usb_defines.h
* @author xiuos Team
* @version V1.0.0
* @date 2020-9-3
* @brief Header of the Core Layer
******************************************************************************
* @file usb_defines.h
* @author MCD Application Team
* @version V1.0.0
* @date 30-September-2011
* ********************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2015 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* <http://www.st.com/SLA0044>
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USB_DEF_H__
#define __USB_DEF_H__
/* Includes ------------------------------------------------------------------*/
#include "usb_conf.h"
/** @addtogroup USB_OTG_DRIVER
* @{
*/
/** @defgroup USB_DEFINES
* @brief This file is the
* @{
*/
/** @defgroup USB_DEFINES_Exported_Defines
* @{
*/
/**
* @}
*/
/** @defgroup _CORE_DEFINES_
* @{
*/
#define USB_OTG_SPEED_PARAM_HIGH 0
#define USB_OTG_SPEED_PARAM_HIGH_IN_FULL 1
#define USB_OTG_SPEED_PARAM_FULL 3
#define USB_OTG_SPEED_HIGH 0
#define USB_OTG_SPEED_FULL 1
#define USB_OTG_ULPI_PHY 1
#define USB_OTG_EMBEDDED_PHY 2
/**
* @}
*/
/** @defgroup _GLOBAL_DEFINES_
* @{
*/
#define GAHBCFG_TXFEMPTYLVL_EMPTY 1
#define GAHBCFG_TXFEMPTYLVL_HALFEMPTY 0
#define GAHBCFG_GLBINT_ENABLE 1
#define GAHBCFG_INT_DMA_BURST_SINGLE 0
#define GAHBCFG_INT_DMA_BURST_INCR 1
#define GAHBCFG_INT_DMA_BURST_INCR4 3
#define GAHBCFG_INT_DMA_BURST_INCR8 5
#define GAHBCFG_INT_DMA_BURST_INCR16 7
#define GAHBCFG_DMAENABLE 1
#define GAHBCFG_TXFEMPTYLVL_EMPTY 1
#define GAHBCFG_TXFEMPTYLVL_HALFEMPTY 0
#define GRXSTS_PKTSTS_IN 2
#define GRXSTS_PKTSTS_IN_XFER_COMP 3
#define GRXSTS_PKTSTS_DATA_TOGGLE_ERR 5
#define GRXSTS_PKTSTS_CH_HALTED 7
/**
* @}
*/
/** @defgroup _OnTheGo_DEFINES_
* @{
*/
#define MODE_HNP_SRP_CAPABLE 0
#define MODE_SRP_ONLY_CAPABLE 1
#define MODE_NO_HNP_SRP_CAPABLE 2
#define MODE_SRP_CAPABLE_DEVICE 3
#define MODE_NO_SRP_CAPABLE_DEVICE 4
#define MODE_SRP_CAPABLE_HOST 5
#define MODE_NO_SRP_CAPABLE_HOST 6
#define A_HOST 1
#define A_SUSPEND 2
#define A_PERIPHERAL 3
#define B_PERIPHERAL 4
#define B_HOST 5
#define DEVICE_MODE 0
#define HOST_MODE 1
#define OTG_MODE 2
/**
* @}
*/
/** @defgroup __DEVICE_DEFINES_
* @{
*/
#define DSTS_ENUMSPD_HS_PHY_30MHZ_OR_60MHZ 0
#define DSTS_ENUMSPD_FS_PHY_30MHZ_OR_60MHZ 1
#define DSTS_ENUMSPD_LS_PHY_6MHZ 2
#define DSTS_ENUMSPD_FS_PHY_48MHZ 3
#define DCFG_FRAME_INTERVAL_80 0
#define DCFG_FRAME_INTERVAL_85 1
#define DCFG_FRAME_INTERVAL_90 2
#define DCFG_FRAME_INTERVAL_95 3
#define DEP0CTL_MPS_64 0
#define DEP0CTL_MPS_32 1
#define DEP0CTL_MPS_16 2
#define DEP0CTL_MPS_8 3
#define EP_SPEED_LOW 0
#define EP_SPEED_FULL 1
#define EP_SPEED_HIGH 2
#define EP_TYPE_CTRL 0
#define EP_TYPE_ISOC 1
#define EP_TYPE_BULK 2
#define EP_TYPE_INTR 3
#define EP_TYPE_MSK 3
#define STS_GOUT_NAK 1
#define STS_DATA_UPDT 2
#define STS_XFER_COMP 3
#define STS_SETUP_COMP 4
#define STS_SETUP_UPDT 6
/**
* @}
*/
/** @defgroup __HOST_DEFINES_
* @{
*/
#define HC_PID_DATA0 0
#define HC_PID_DATA2 1
#define HC_PID_DATA1 2
#define HC_PID_SETUP 3
#define HPRT0_PRTSPD_HIGH_SPEED 0
#define HPRT0_PRTSPD_FULL_SPEED 1
#define HPRT0_PRTSPD_LOW_SPEED 2
#define HCFG_30_60_MHZ 0
#define HCFG_48_MHZ 1
#define HCFG_6_MHZ 2
#define HCCHAR_CTRL 0
#define HCCHAR_ISOC 1
#define HCCHAR_BULK 2
#define HCCHAR_INTR 3
#ifndef MIN
#define MIN(a, b) (((a) < (b)) ? (a) : (b))
#endif
/**
* @}
*/
/** @defgroup USB_DEFINES_Exported_Types
* @{
*/
typedef enum
{
USB_OTG_HS_CORE_ID = 0,
USB_OTG_FS_CORE_ID = 1
}USB_OTG_CORE_ID_TypeDef;
/**
* @}
*/
/** @defgroup USB_DEFINES_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USB_DEFINES_Exported_Variables
* @{
*/
/**
* @}
*/
/** @defgroup USB_DEFINES_Exported_FunctionsPrototype
* @{
*/
/**
* @}
*/
/** @defgroup Internal_Macro's
* @{
*/
#define USB_OTG_READ_REG32(reg) (*(__IO uint32_t *)(reg))
// #define DEBUG_USB_REG
#ifndef DEBUG_USB_REG
#define USB_OTG_WRITE_REG32(reg,value) (*(__IO uint32_t *)(reg) = (value))
#else
#define DO_USB_OTG_WRITE_REG32(reg,value) (*(__IO uint32_t *)(reg) = (value))
#define USB_OTG_WRITE_REG32(reg,value) \
do { \
uint32_t tmpreg = USB_OTG_READ_REG32(reg); \
rt_kprintf( \
"%s:\n" \
" writing register " #reg " at address 0x%p:\n", \
__func__, reg \
); \
rt_kprintf(" written value: 0x%08X\n", value); \
rt_kprintf(" old value: 0x%08X\n", tmpreg); \
DO_USB_OTG_WRITE_REG32(reg, value); \
rt_kprintf(" new value: 0x%08X\n", USB_OTG_READ_REG32(reg)); \
} while (0)
#endif
#define USB_OTG_MODIFY_REG32(reg,clear_mask,set_mask) \
USB_OTG_WRITE_REG32((reg), (((USB_OTG_READ_REG32(reg)) & ~(clear_mask)) | (set_mask)) )
/********************************************************************************
ENUMERATION TYPE
********************************************************************************/
enum USB_OTG_SPEED {
USB_SPEED_UNKNOWN = 0,
USB_SPEED_LOW,
USB_SPEED_FULL,
USB_SPEED_HIGH
};
#endif /* __USB_DEFINES__H__ */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,110 +0,0 @@
/**
******************************************************************************
* @file usb_hcd.h
* @author xiuos Team
* @version V1.0.0
* @date 2020-9-3
* @brief This file is based on usb_hcd.h
* Host layer Header file
******************************************************************************
* @file usb_hcd.h
* @author MCD Application Team
* @version V1.0.0
* @date 30-September-2011
* ********************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2015 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* <http://www.st.com/SLA0044>
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USB_HCD_H__
#define __USB_HCD_H__
/* Includes ------------------------------------------------------------------*/
#include "usb_regs.h"
#include "usb_core.h"
/** @addtogroup USB_OTG_DRIVER
* @{
*/
/** @defgroup USB_HCD
* @brief This file is the
* @{
*/
/** @defgroup USB_HCD_Exported_Defines
* @{
*/
/**
* @}
*/
/** @defgroup USB_HCD_Exported_Types
* @{
*/
/**
* @}
*/
/** @defgroup USB_HCD_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USB_HCD_Exported_Variables
* @{
*/
/**
* @}
*/
/** @defgroup USB_HCD_Exported_FunctionsPrototype
* @{
*/
uint32_t HCD_Init (USB_OTG_CORE_HANDLE *pdev ,
USB_OTG_CORE_ID_TypeDef coreID);
uint32_t HCD_HC_Init (USB_OTG_CORE_HANDLE *pdev ,
uint8_t hc_num);
uint32_t HCD_SubmitRequest (USB_OTG_CORE_HANDLE *pdev ,
uint8_t hc_num) ;
uint32_t HCD_GetCurrentSpeed (USB_OTG_CORE_HANDLE *pdev);
uint32_t HCD_ResetPort (USB_OTG_CORE_HANDLE *pdev);
uint32_t HCD_IsDeviceConnected (USB_OTG_CORE_HANDLE *pdev);
uint32_t HCD_IsPortEnabled (USB_OTG_CORE_HANDLE *pdev);
uint32_t HCD_GetCurrentFrame (USB_OTG_CORE_HANDLE *pdev) ;
URB_STATE HCD_GetURB_State (USB_OTG_CORE_HANDLE *pdev, uint8_t ch_num);
uint32_t HCD_GetXferCnt (USB_OTG_CORE_HANDLE *pdev, uint8_t ch_num);
HC_STATUS HCD_GetHCState (USB_OTG_CORE_HANDLE *pdev, uint8_t ch_num) ;
/**
* @}
*/
#endif //__USB_HCD_H__
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,144 +0,0 @@
/**
******************************************************************************
* @file usb_hcd_int.h
* @author xiuos Team
* @version V1.0.0
* @date 2020-9-3
* @brief This file is based on usb_hcd_int.h
* Peripheral Device Interface Layer
******************************************************************************
* @file usb_hcd_int.h
* @author MCD Application Team
* @version V1.0.0
* @date 30-September-2011
* ********************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2015 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* <http://www.st.com/SLA0044>
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __HCD_INT_H__
#define __HCD_INT_H__
/* Includes ------------------------------------------------------------------*/
#include "usb_hcd.h"
/** @addtogroup USB_OTG_DRIVER
* @{
*/
/** @defgroup USB_HCD_INT
* @brief This file is the
* @{
*/
/** @defgroup USB_HCD_INT_Exported_Defines
* @{
*/
/**
* @}
*/
/** @defgroup USB_HCD_INT_Exported_Types
* @{
*/
typedef struct _USBH_HCD_INT
{
uint8_t (* SOF) (USB_OTG_CORE_HANDLE *pdev);
uint8_t (* DevConnected) (USB_OTG_CORE_HANDLE *pdev);
uint8_t (* DevDisconnected) (USB_OTG_CORE_HANDLE *pdev);
uint8_t (* DevPortEnabled) (USB_OTG_CORE_HANDLE *pdev);
uint8_t (* DevPortDisabled) (USB_OTG_CORE_HANDLE *pdev);
uint8_t (* URBChangeNotify) (USB_OTG_CORE_HANDLE *pdev);
}USBH_HCD_INT_cb_TypeDef;
extern USBH_HCD_INT_cb_TypeDef *USBH_HCD_INT_fops;
/**
* @}
*/
/** @defgroup USB_HCD_INT_Exported_Macros
* @{
*/
#define CLEAR_HC_INT(HC_REGS, intr) \
{\
USB_OTG_HCINTn_TypeDef hcint_clear; \
hcint_clear.d32 = 0; \
hcint_clear.b.intr = 1; \
USB_OTG_WRITE_REG32(&((HC_REGS)->HCINT), hcint_clear.d32);\
}\
#define MASK_HOST_INT_CHH(hc_num) { USB_OTG_HCINTMSK_TypeDef INTMSK; \
INTMSK.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[hc_num]->HCINTMSK); \
INTMSK.b.chhltd = 0; \
USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCINTMSK, INTMSK.d32);}
#define UNMASK_HOST_INT_CHH(hc_num) { USB_OTG_HCINTMSK_TypeDef INTMSK; \
INTMSK.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[hc_num]->HCINTMSK); \
INTMSK.b.chhltd = 1; \
USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCINTMSK, INTMSK.d32);}
#define MASK_HOST_INT_ACK(hc_num) { USB_OTG_HCINTMSK_TypeDef INTMSK; \
INTMSK.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[hc_num]->HCINTMSK); \
INTMSK.b.ack = 0; \
USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCINTMSK, GINTMSK.d32);}
#define UNMASK_HOST_INT_ACK(hc_num) { USB_OTG_HCGINTMSK_TypeDef INTMSK; \
INTMSK.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[hc_num]->HCINTMSK); \
INTMSK.b.ack = 1; \
USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCINTMSK, INTMSK.d32);}
/**
* @}
*/
/** @defgroup USB_HCD_INT_Exported_Variables
* @{
*/
/**
* @}
*/
/** @defgroup USB_HCD_INT_Exported_FunctionsPrototype
* @{
*/
/* Callbacks handler */
void ConnectCallback_Handler(USB_OTG_CORE_HANDLE *pdev);
void Disconnect_Callback_Handler(USB_OTG_CORE_HANDLE *pdev);
void Overcurrent_Callback_Handler(USB_OTG_CORE_HANDLE *pdev);
uint32_t USBH_OTG_ISR_Handler (USB_OTG_CORE_HANDLE *pdev);
/**
* @}
*/
#endif //__HCD_INT_H__
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,99 +0,0 @@
/**
******************************************************************************
* @file usb_otg.h
* @author xiuos Team
* @version V1.0.0
* @date 2020-9-3
* @brief This file is based on usb_otg.h
* OTG Core Header
******************************************************************************
* @file usb_otg.h
* @author MCD Application Team
* @version V1.0.0
* @date 30-September-2011
* ********************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2015 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* <http://www.st.com/SLA0044>
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USB_OTG__
#define __USB_OTG__
/** @addtogroup USB_OTG_DRIVER
* @{
*/
/** @defgroup USB_OTG
* @brief This file is the
* @{
*/
/** @defgroup USB_OTG_Exported_Defines
* @{
*/
void USB_OTG_InitiateSRP(void);
void USB_OTG_InitiateHNP(uint8_t state , uint8_t mode);
void USB_OTG_Switchback (USB_OTG_CORE_HANDLE *pdev);
uint32_t USB_OTG_GetCurrentState (USB_OTG_CORE_HANDLE *pdev);
/**
* @}
*/
/** @defgroup USB_OTG_Exported_Types
* @{
*/
/**
* @}
*/
/** @defgroup USB_OTG_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USB_OTG_Exported_Variables
* @{
*/
/**
* @}
*/
/** @defgroup USB_OTG_Exported_FunctionsPrototype
* @{
*/
/**
* @}
*/
#endif //__USB_OTG__
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,206 +0,0 @@
/**
******************************************************************************
* @file usb_bsp_template.c
* @author xiuos Team
* @version V1.0.0
* @date 2020-9-3
* @brief This file is based on usb_bsp.c
* This file is responsible to offer board support package and is
* configurable by user.
******************************************************************************
* @file usb_bsp.c
* @author MCD Application Team
* @version V1.0.0
* @date 30-September-2011
* ********************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2015 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* <http://www.st.com/SLA0044>
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "usb_bsp.h"
/** @addtogroup USB_OTG_DRIVER
* @{
*/
/** @defgroup USB_BSP
* @brief This file is responsible to offer board support package
* @{
*/
/** @defgroup USB_BSP_Private_Defines
* @{
*/
/**
* @}
*/
/** @defgroup USB_BSP_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @defgroup USB_BSP_Private_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USBH_BSP_Private_Variables
* @{
*/
/**
* @}
*/
/** @defgroup USBH_BSP_Private_FunctionPrototypes
* @{
*/
/**
* @}
*/
/** @defgroup USB_BSP_Private_Functions
* @{
*/
/**
* @brief USB_OTG_BSP_Init
* Initializes BSP configurations
* @param None
* @retval None
*/
void USB_OTG_BSP_Init(void)
{
}
/**
* @brief USB_OTG_BSP_ENABLE_INTERRUPT
* Enable USB Global interrupt
* @param None
* @retval None
*/
void USB_OTG_BSP_ENABLE_INTERRUPT(void)
{
}
/**
* @brief BSP_Drive_VBUS
* Drives the Vbus signal through IO
* @param speed : Full, Low
* @param state : VBUS states
* @retval None
*/
void USB_OTG_BSP_DriveVBUS(uint32_t speed, uint8_t state)
{
}
/**
* @brief USB_OTG_BSP_ConfigVBUS
* Configures the IO for the Vbus and OverCurrent
* @param Speed : Full, Low
* @retval None
*/
void USB_OTG_BSP_ConfigVBUS(uint32_t speed)
{
}
/**
* @brief USB_OTG_BSP_TimeInit
* Initialises delay unit Systick timer /Timer2
* @param None
* @retval None
*/
void USB_OTG_BSP_TimeInit ( void )
{
}
/**
* @brief USB_OTG_BSP_uDelay
* This function provides delay time in micro sec
* @param usec : Value of delay required in micro sec
* @retval None
*/
void USB_OTG_BSP_uDelay (const uint32_t usec)
{
uint32_t count = 0;
const uint32_t utime = (120 * usec / 7);
do
{
if ( ++count > utime )
{
return ;
}
}
while (1);
}
/**
* @brief USB_OTG_BSP_mDelay
* This function provides delay time in milli sec
* @param msec : Value of delay required in milli sec
* @retval None
*/
void USB_OTG_BSP_mDelay (const uint32_t msec)
{
USB_OTG_BSP_uDelay(msec * 1000);
}
/**
* @brief USB_OTG_BSP_TimerIRQ
* Time base IRQ
* @param None
* @retval None
*/
void USB_OTG_BSP_TimerIRQ (void)
{
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,488 +0,0 @@
/**
******************************************************************************
* @file usb_dcd.c
* @author xiuos Team
* @version V1.0.0
* @date 2020-9-3
* @brief This file is based on usb_dcd.c
* Peripheral Device Interface Layer
******************************************************************************
* @file usb_dcd.c
* @author MCD Application Team
* @version V1.0.0
* @date 30-September-2011
* ********************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2015 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* <http://www.st.com/SLA0044>
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "usb_dcd.h"
#include "usb_bsp.h"
/** @addtogroup USB_OTG_DRIVER
* @{
*/
/** @defgroup USB_DCD
* @brief This file is the interface between EFSL ans Host mass-storage class
* @{
*/
/** @defgroup USB_DCD_Private_Defines
* @{
*/
/**
* @}
*/
/** @defgroup USB_DCD_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @defgroup USB_DCD_Private_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USB_DCD_Private_Variables
* @{
*/
/**
* @}
*/
/** @defgroup USB_DCD_Private_FunctionPrototypes
* @{
*/
/**
* @}
*/
/** @defgroup USB_DCD_Private_Functions
* @{
*/
void DCD_Init(USB_OTG_CORE_HANDLE *pdev ,
USB_OTG_CORE_ID_TypeDef coreID)
{
uint32_t i;
USB_OTG_EP *ep;
USB_OTG_SelectCore (pdev , coreID);
pdev->dev.device_status = USB_OTG_DEFAULT;
pdev->dev.device_address = 0;
/* Init ep structure */
for (i = 0; i < pdev->cfg.dev_endpoints ; i++)
{
ep = &pdev->dev.in_ep[i];
/* Init ep structure */
ep->is_in = 1;
ep->num = i;
ep->tx_fifo_num = i;
/* Control until ep is activated */
ep->type = EP_TYPE_CTRL;
ep->maxpacket = USB_OTG_MAX_EP0_SIZE;
ep->xfer_buff = 0;
ep->XferLen = 0;
}
for (i = 0; i < pdev->cfg.dev_endpoints; i++)
{
ep = &pdev->dev.out_ep[i];
/* Init ep structure */
ep->is_in = 0;
ep->num = i;
ep->tx_fifo_num = i;
/* Control until ep is activated */
ep->type = EP_TYPE_CTRL;
ep->maxpacket = USB_OTG_MAX_EP0_SIZE;
ep->xfer_buff = 0;
ep->XferLen = 0;
}
USB_OTG_DisableGlobalInt(pdev);
#if defined (STM32F446xx) || defined (STM32F469_479xx)
/* Force Device Mode*/
USB_OTG_SetCurrentMode(pdev, DEVICE_MODE);
/*Init the Core (common init.) */
USB_OTG_CoreInit(pdev);
#else
/*Init the Core (common init.) */
USB_OTG_CoreInit(pdev);
/* Force Device Mode*/
USB_OTG_SetCurrentMode(pdev, DEVICE_MODE);
#endif
/* Init Device */
USB_OTG_CoreInitDev(pdev);
/* Enable USB Global interrupt */
USB_OTG_EnableGlobalInt(pdev);
}
/**
* @brief Configure an EP
* @param pdev : Device instance
* @param epdesc : Endpoint Descriptor
* @retval : status
*/
uint32_t DCD_EP_Open(USB_OTG_CORE_HANDLE *pdev ,
uint8_t EpAddr,
uint16_t ep_mps,
uint8_t ep_type)
{
USB_OTG_EP *ep;
if ((EpAddr & 0x80) == 0x80)
{
ep = &pdev->dev.in_ep[EpAddr & 0x7F];
}
else
{
ep = &pdev->dev.out_ep[EpAddr & 0x7F];
}
ep->num = EpAddr & 0x7F;
ep->is_in = (0x80 & EpAddr) != 0;
ep->maxpacket = ep_mps;
ep->type = ep_type;
if (ep->is_in)
{
/* Assign a Tx FIFO */
ep->tx_fifo_num = ep->num;
}
/* Set initial data PID. */
if (ep_type == USB_OTG_EP_BULK )
{
ep->data_pid_start = 0;
}
USB_OTG_EPActivate(pdev , ep );
return 0;
}
/**
* @brief called when an EP is disabled
* @param pdev: device instance
* @param EpAddr: endpoint address
* @retval : status
*/
uint32_t DCD_EP_Close(USB_OTG_CORE_HANDLE *pdev , uint8_t EpAddr)
{
USB_OTG_EP *ep;
if ((EpAddr&0x80) == 0x80)
{
ep = &pdev->dev.in_ep[EpAddr & 0x7F];
}
else
{
ep = &pdev->dev.out_ep[EpAddr & 0x7F];
}
ep->num = EpAddr & 0x7F;
ep->is_in = (0x80 & EpAddr) != 0;
USB_OTG_EPDeactivate(pdev , ep );
return 0;
}
/**
* @brief DCD_EP_PrepareRx
* @param pdev: device instance
* @param EpAddr: endpoint address
* @param pbuf: pointer to Rx buffer
* @param BufLen: data length
* @retval : status
*/
uint32_t DCD_EP_PrepareRx( USB_OTG_CORE_HANDLE *pdev,
uint8_t EpAddr,
uint8_t *pbuf,
uint16_t BufLen)
{
USB_OTG_EP *ep;
ep = &pdev->dev.out_ep[EpAddr & 0x7F];
/*setup and start the Xfer */
ep->xfer_buff = pbuf;
ep->XferLen = BufLen;
ep->xfer_count = 0;
ep->is_in = 0;
ep->num = EpAddr & 0x7F;
if (pdev->cfg.dma_enable == 1)
{
ep->dma_addr = (uint32_t)pbuf;
}
if ( ep->num == 0 )
{
USB_OTG_EP0StartXfer(pdev , ep);
}
else
{
USB_OTG_EPStartXfer(pdev, ep );
}
return 0;
}
/**
* @brief Transmit data over USB
* @param pdev: device instance
* @param EpAddr: endpoint address
* @param pbuf: pointer to Tx buffer
* @param BufLen: data length
* @retval : status
*/
uint32_t DCD_EP_Tx ( USB_OTG_CORE_HANDLE *pdev,
uint8_t EpAddr,
uint8_t *pbuf,
uint32_t BufLen)
{
USB_OTG_EP *ep;
ep = &pdev->dev.in_ep[EpAddr & 0x7F];
/* Setup and start the Transfer */
ep->is_in = 1;
ep->num = EpAddr & 0x7F;
ep->xfer_buff = pbuf;
ep->dma_addr = (uint32_t)pbuf;
ep->xfer_count = 0;
ep->XferLen = BufLen;
if ( ep->num == 0 )
{
USB_OTG_EP0StartXfer(pdev , ep);
}
else
{
USB_OTG_EPStartXfer(pdev, ep );
}
return 0;
}
/**
* @brief Stall an endpoint.
* @param pdev: device instance
* @param epnum: endpoint address
* @retval : status
*/
uint32_t DCD_EP_Stall (USB_OTG_CORE_HANDLE *pdev, uint8_t epnum)
{
USB_OTG_EP *ep;
if ((0x80 & epnum) == 0x80)
{
ep = &pdev->dev.in_ep[epnum & 0x7F];
}
else
{
ep = &pdev->dev.out_ep[epnum];
}
ep->is_stall = 1;
ep->num = epnum & 0x7F;
ep->is_in = ((epnum & 0x80) == 0x80);
USB_OTG_EPSetStall(pdev , ep);
return (0);
}
/**
* @brief Clear stall condition on endpoints.
* @param pdev: device instance
* @param epnum: endpoint address
* @retval : status
*/
uint32_t DCD_EP_ClrStall (USB_OTG_CORE_HANDLE *pdev, uint8_t epnum)
{
USB_OTG_EP *ep;
if ((0x80 & epnum) == 0x80)
{
ep = &pdev->dev.in_ep[epnum & 0x7F];
}
else
{
ep = &pdev->dev.out_ep[epnum];
}
ep->is_stall = 0;
ep->num = epnum & 0x7F;
ep->is_in = ((epnum & 0x80) == 0x80);
USB_OTG_EPClearStall(pdev , ep);
return (0);
}
/**
* @brief This Function flushes the FIFOs.
* @param pdev: device instance
* @param epnum: endpoint address
* @retval : status
*/
uint32_t DCD_EP_Flush (USB_OTG_CORE_HANDLE *pdev , uint8_t epnum)
{
if ((epnum & 0x80) == 0x80)
{
USB_OTG_FlushTxFifo(pdev, epnum & 0x7F);
}
else
{
USB_OTG_FlushRxFifo(pdev);
}
return (0);
}
/**
* @brief This Function set USB device address
* @param pdev: device instance
* @param address: new device address
* @retval : status
*/
void DCD_EP_SetAddress (USB_OTG_CORE_HANDLE *pdev, uint8_t address)
{
USB_OTG_DCFG_TypeDef dcfg;
dcfg.d32 = 0;
dcfg.b.devaddr = address;
USB_OTG_MODIFY_REG32( &pdev->regs.DREGS->DCFG, 0, dcfg.d32);
}
/**
* @brief Connect device (enable internal pull-up)
* @param pdev: device instance
* @retval : None
*/
void DCD_DevConnect (USB_OTG_CORE_HANDLE *pdev)
{
#ifndef USE_OTG_MODE
USB_OTG_DCTL_TypeDef dctl;
dctl.d32 = USB_OTG_READ_REG32(&pdev->regs.DREGS->DCTL);
/* Connect device */
dctl.b.sftdiscon = 0;
USB_OTG_WRITE_REG32(&pdev->regs.DREGS->DCTL, dctl.d32);
USB_OTG_BSP_mDelay(3);
#endif
}
/**
* @brief Disconnect device (disable internal pull-up)
* @param pdev: device instance
* @retval : None
*/
void DCD_DevDisconnect (USB_OTG_CORE_HANDLE *pdev)
{
#ifndef USE_OTG_MODE
USB_OTG_DCTL_TypeDef dctl;
dctl.d32 = USB_OTG_READ_REG32(&pdev->regs.DREGS->DCTL);
/* Disconnect device for 3ms */
dctl.b.sftdiscon = 1;
USB_OTG_WRITE_REG32(&pdev->regs.DREGS->DCTL, dctl.d32);
USB_OTG_BSP_mDelay(3);
#endif
}
/**
* @brief returns the EP Status
* @param pdev : Selected device
* epnum : endpoint address
* @retval : EP status
*/
uint32_t DCD_GetEPStatus(USB_OTG_CORE_HANDLE *pdev ,uint8_t epnum)
{
USB_OTG_EP *ep;
uint32_t Status = 0;
if ((0x80 & epnum) == 0x80)
{
ep = &pdev->dev.in_ep[epnum & 0x7F];
}
else
{
ep = &pdev->dev.out_ep[epnum];
}
Status = USB_OTG_GetEPStatus(pdev ,ep);
/* Return the current status */
return Status;
}
/**
* @brief Set the EP Status
* @param pdev : Selected device
* Status : new Status
* epnum : EP address
* @retval : None
*/
void DCD_SetEPStatus (USB_OTG_CORE_HANDLE *pdev , uint8_t epnum , uint32_t Status)
{
USB_OTG_EP *ep;
if ((0x80 & epnum) == 0x80)
{
ep = &pdev->dev.in_ep[epnum & 0x7F];
}
else
{
ep = &pdev->dev.out_ep[epnum];
}
USB_OTG_SetEPStatus(pdev ,ep , Status);
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,943 +0,0 @@
/**
******************************************************************************
* @file usb_dcd_int.c
* @author xiuos Team
* @version V1.0.0
* @date 2020-9-3
* @brief This file is based on usb_dcd_int.c
* Peripheral Device interrupt subroutines
******************************************************************************
* @file usb_dcd_int.c
* @author MCD Application Team
* @version V1.0.0
* @date 30-September-2011
* ********************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2015 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* <http://www.st.com/SLA0044>
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "usb_dcd_int.h"
/** @addtogroup USB_OTG_DRIVER
* @{
*/
/** @defgroup USB_DCD_INT
* @brief This file contains the interrupt subroutines for the Device mode.
* @{
*/
/** @defgroup USB_DCD_INT_Private_Defines
* @{
*/
/**
* @}
*/
/** @defgroup USB_DCD_INT_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @defgroup USB_DCD_INT_Private_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USB_DCD_INT_Private_Variables
* @{
*/
/**
* @}
*/
/** @defgroup USB_DCD_INT_Private_FunctionPrototypes
* @{
*/
/* static functions */
static uint32_t DCD_ReadDevInEP (USB_OTG_CORE_HANDLE *pdev, uint8_t epnum);
/* Interrupt Handlers */
static uint32_t DCD_HandleInEP_ISR(USB_OTG_CORE_HANDLE *pdev);
static uint32_t DCD_HandleOutEP_ISR(USB_OTG_CORE_HANDLE *pdev);
static uint32_t DCD_HandleSof_ISR(USB_OTG_CORE_HANDLE *pdev);
static uint32_t DCD_HandleRxStatusQueueLevel_ISR(USB_OTG_CORE_HANDLE *pdev);
static uint32_t DCD_WriteEmptyTxFifo(USB_OTG_CORE_HANDLE *pdev , uint32_t epnum);
static uint32_t DCD_HandleUsbReset_ISR(USB_OTG_CORE_HANDLE *pdev);
static uint32_t DCD_HandleEnumDone_ISR(USB_OTG_CORE_HANDLE *pdev);
static uint32_t DCD_HandleResume_ISR(USB_OTG_CORE_HANDLE *pdev);
static uint32_t DCD_HandleUSBSuspend_ISR(USB_OTG_CORE_HANDLE *pdev);
static uint32_t DCD_IsoINIncomplete_ISR(USB_OTG_CORE_HANDLE *pdev);
static uint32_t DCD_IsoOUTIncomplete_ISR(USB_OTG_CORE_HANDLE *pdev);
#ifdef VBUS_SENSING_ENABLED
static uint32_t DCD_SessionRequest_ISR(USB_OTG_CORE_HANDLE *pdev);
static uint32_t DCD_OTG_ISR(USB_OTG_CORE_HANDLE *pdev);
#endif
/**
* @}
*/
/** @defgroup USB_DCD_INT_Private_Functions
* @{
*/
#ifdef USB_OTG_HS_DEDICATED_EP1_ENABLED
/**
* @brief USBD_OTG_EP1OUT_ISR_Handler
* handles all USB Interrupts
* @param pdev: device instance
* @retval status
*/
uint32_t USBD_OTG_EP1OUT_ISR_Handler (USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_DOEPINTn_TypeDef doepint;
USB_OTG_DEPXFRSIZ_TypeDef deptsiz;
doepint.d32 = USB_OTG_READ_REG32(&pdev->regs.OUTEP_REGS[1]->DOEPINT);
doepint.d32&= USB_OTG_READ_REG32(&pdev->regs.DREGS->DOUTEP1MSK);
/* Transfer complete */
if ( doepint.b.xfercompl )
{
/* Clear the bit in DOEPINTn for this interrupt */
CLEAR_OUT_EP_INTR(1, xfercompl);
if (pdev->cfg.dma_enable == 1)
{
deptsiz.d32 = USB_OTG_READ_REG32(&(pdev->regs.OUTEP_REGS[1]->DOEPTSIZ));
pdev->dev.out_ep[1].xfer_count = pdev->dev.out_ep[1].XferLen- \
deptsiz.b.xfersize;
}
/* Inform upper layer: data ready */
/* RX COMPLETE */
USBD_DCD_INT_fops->DataOutStage(pdev , 1);
}
/* Endpoint disable */
if ( doepint.b.epdisabled )
{
/* Clear the bit in DOEPINTn for this interrupt */
CLEAR_OUT_EP_INTR(1, epdisabled);
}
return 1;
}
/**
* @brief USBD_OTG_EP1IN_ISR_Handler
* handles all USB Interrupts
* @param pdev: device instance
* @retval status
*/
uint32_t USBD_OTG_EP1IN_ISR_Handler (USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_DIEPINTn_TypeDef diepint;
uint32_t fifoemptymsk, msk, emp;
msk = USB_OTG_READ_REG32(&pdev->regs.DREGS->DINEP1MSK);
emp = USB_OTG_READ_REG32(&pdev->regs.DREGS->DIEPEMPMSK);
msk |= ((emp >> 1 ) & 0x1) << 7;
diepint.d32 = USB_OTG_READ_REG32(&pdev->regs.INEP_REGS[1]->DIEPINT) & msk;
if ( diepint.b.xfercompl )
{
fifoemptymsk = 0x1 << 1;
USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DIEPEMPMSK, fifoemptymsk, 0);
CLEAR_IN_EP_INTR(1, xfercompl);
/* TX COMPLETE */
USBD_DCD_INT_fops->DataInStage(pdev , 1);
}
if ( diepint.b.epdisabled )
{
CLEAR_IN_EP_INTR(1, epdisabled);
}
if ( diepint.b.timeout )
{
CLEAR_IN_EP_INTR(1, timeout);
}
if (diepint.b.intktxfemp)
{
CLEAR_IN_EP_INTR(1, intktxfemp);
}
if (diepint.b.inepnakeff)
{
CLEAR_IN_EP_INTR(1, inepnakeff);
}
if (diepint.b.emptyintr)
{
DCD_WriteEmptyTxFifo(pdev , 1);
}
return 1;
}
#endif
/**
* @brief STM32_USBF_OTG_ISR_Handler
* handles all USB Interrupts
* @param pdev: device instance
* @retval status
*/
uint32_t USBD_OTG_ISR_Handler (USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_GINTSTS_TypeDef gintr_status;
uint32_t retval = 0;
if (USB_OTG_IsDeviceMode(pdev)) /* ensure that we are in device mode */
{
gintr_status.d32 = USB_OTG_ReadCoreItr(pdev);
if (!gintr_status.d32) /* avoid spurious interrupt */
{
return 0;
}
if (gintr_status.b.outepintr)
{
retval |= DCD_HandleOutEP_ISR(pdev);
}
if (gintr_status.b.inepint)
{
retval |= DCD_HandleInEP_ISR(pdev);
}
if (gintr_status.b.modemismatch)
{
USB_OTG_GINTSTS_TypeDef gintsts;
/* Clear interrupt */
gintsts.d32 = 0;
gintsts.b.modemismatch = 1;
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32);
}
if (gintr_status.b.wkupintr)
{
retval |= DCD_HandleResume_ISR(pdev);
}
if (gintr_status.b.usbsuspend)
{
retval |= DCD_HandleUSBSuspend_ISR(pdev);
}
if (gintr_status.b.sofintr)
{
retval |= DCD_HandleSof_ISR(pdev);
}
if (gintr_status.b.rxstsqlvl)
{
retval |= DCD_HandleRxStatusQueueLevel_ISR(pdev);
}
if (gintr_status.b.usbreset)
{
retval |= DCD_HandleUsbReset_ISR(pdev);
}
if (gintr_status.b.enumdone)
{
retval |= DCD_HandleEnumDone_ISR(pdev);
}
if (gintr_status.b.incomplisoin)
{
retval |= DCD_IsoINIncomplete_ISR(pdev);
}
if (gintr_status.b.incomplisoout)
{
retval |= DCD_IsoOUTIncomplete_ISR(pdev);
}
#ifdef VBUS_SENSING_ENABLED
if (gintr_status.b.sessreqintr)
{
retval |= DCD_SessionRequest_ISR(pdev);
}
if (gintr_status.b.otgintr)
{
retval |= DCD_OTG_ISR(pdev);
}
#endif
}
return retval;
}
#ifdef VBUS_SENSING_ENABLED
/**
* @brief DCD_SessionRequest_ISR
* Indicates that the USB_OTG controller has detected a connection
* @param pdev: device instance
* @retval status
*/
static uint32_t DCD_SessionRequest_ISR(USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_GINTSTS_TypeDef gintsts;
USBD_DCD_INT_fops->DevConnected (pdev);
/* Clear interrupt */
gintsts.d32 = 0;
gintsts.b.sessreqintr = 1;
USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GINTSTS, gintsts.d32);
return 1;
}
/**
* @brief DCD_OTG_ISR
* Indicates that the USB_OTG controller has detected an OTG event:
* used to detect the end of session i.e. disconnection
* @param pdev: device instance
* @retval status
*/
static uint32_t DCD_OTG_ISR(USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_GOTGINT_TypeDef gotgint;
gotgint.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GOTGINT);
if (gotgint.b.sesenddet)
{
USBD_DCD_INT_fops->DevDisconnected (pdev);
}
/* Clear OTG interrupt */
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GOTGINT, gotgint.d32);
return 1;
}
#endif
/**
* @brief DCD_HandleResume_ISR
* Indicates that the USB_OTG controller has detected a resume or
* remote Wake-up sequence
* @param pdev: device instance
* @retval status
*/
static uint32_t DCD_HandleResume_ISR(USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_GINTSTS_TypeDef gintsts;
USB_OTG_DCTL_TypeDef devctl;
USB_OTG_PCGCCTL_TypeDef power;
if(pdev->cfg.low_power)
{
/* un-gate USB Core clock */
power.d32 = USB_OTG_READ_REG32(pdev->regs.PCGCCTL);
power.b.gatehclk = 0;
power.b.stoppclk = 0;
USB_OTG_WRITE_REG32(pdev->regs.PCGCCTL, power.d32);
}
/* Clear the Remote Wake-up Signaling */
devctl.d32 = 0;
devctl.b.rmtwkupsig = 1;
USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DCTL, devctl.d32, 0);
/* Inform upper layer by the Resume Event */
USBD_DCD_INT_fops->Resume (pdev);
/* Clear interrupt */
gintsts.d32 = 0;
gintsts.b.wkupintr = 1;
USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GINTSTS, gintsts.d32);
return 1;
}
/**
* @brief USB_OTG_HandleUSBSuspend_ISR
* Indicates that SUSPEND state has been detected on the USB
* @param pdev: device instance
* @retval status
*/
static uint32_t DCD_HandleUSBSuspend_ISR(USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_GINTSTS_TypeDef gintsts;
USB_OTG_PCGCCTL_TypeDef power;
USB_OTG_DSTS_TypeDef dsts;
__IO uint8_t prev_status = 0;
prev_status = pdev->dev.device_status;
USBD_DCD_INT_fops->Suspend (pdev);
dsts.d32 = USB_OTG_READ_REG32(&pdev->regs.DREGS->DSTS);
/* Clear interrupt */
gintsts.d32 = 0;
gintsts.b.usbsuspend = 1;
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32);
if((pdev->cfg.low_power) && (dsts.b.suspsts == 1) &&
(pdev->dev.connection_status == 1) &&
(prev_status == USB_OTG_CONFIGURED))
{
/* switch-off the clocks */
power.d32 = 0;
power.b.stoppclk = 1;
USB_OTG_MODIFY_REG32(pdev->regs.PCGCCTL, 0, power.d32);
power.b.gatehclk = 1;
USB_OTG_MODIFY_REG32(pdev->regs.PCGCCTL, 0, power.d32);
/* Request to enter Sleep mode after exit from current ISR */
SCB->SCR |= (SCB_SCR_SLEEPDEEP_Msk | SCB_SCR_SLEEPONEXIT_Msk);
}
return 1;
}
/**
* @brief DCD_HandleInEP_ISR
* Indicates that an IN EP has a pending Interrupt
* @param pdev: device instance
* @retval status
*/
static uint32_t DCD_HandleInEP_ISR(USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_DIEPINTn_TypeDef diepint;
uint32_t ep_intr;
uint32_t epnum = 0;
uint32_t fifoemptymsk;
diepint.d32 = 0;
ep_intr = USB_OTG_ReadDevAllInEPItr(pdev);
while ( ep_intr )
{
if ((ep_intr & 0x1) == 0x01) /* In ITR */
{
diepint.d32 = DCD_ReadDevInEP(pdev , epnum); /* Get In ITR status */
if ( diepint.b.xfercompl )
{
fifoemptymsk = 0x1 << epnum;
USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DIEPEMPMSK, fifoemptymsk, 0);
CLEAR_IN_EP_INTR(epnum, xfercompl);
/* TX COMPLETE */
USBD_DCD_INT_fops->DataInStage(pdev , epnum);
if (pdev->cfg.dma_enable == 1)
{
if((epnum == 0) && (pdev->dev.device_state == USB_OTG_EP0_STATUS_IN))
{
/* prepare to rx more setup packets */
USB_OTG_EP0_OutStart(pdev);
}
}
}
if ( diepint.b.timeout )
{
CLEAR_IN_EP_INTR(epnum, timeout);
}
if (diepint.b.intktxfemp)
{
CLEAR_IN_EP_INTR(epnum, intktxfemp);
}
if (diepint.b.inepnakeff)
{
CLEAR_IN_EP_INTR(epnum, inepnakeff);
}
if ( diepint.b.epdisabled )
{
CLEAR_IN_EP_INTR(epnum, epdisabled);
}
if (diepint.b.emptyintr)
{
DCD_WriteEmptyTxFifo(pdev , epnum);
}
}
epnum++;
ep_intr >>= 1;
}
return 1;
}
/**
* @brief DCD_HandleOutEP_ISR
* Indicates that an OUT EP has a pending Interrupt
* @param pdev: device instance
* @retval status
*/
static uint32_t DCD_HandleOutEP_ISR(USB_OTG_CORE_HANDLE *pdev)
{
uint32_t ep_intr;
USB_OTG_DOEPINTn_TypeDef doepint;
USB_OTG_DEPXFRSIZ_TypeDef deptsiz;
uint32_t epnum = 0;
doepint.d32 = 0;
/* Read in the device interrupt bits */
ep_intr = USB_OTG_ReadDevAllOutEp_itr(pdev);
while ( ep_intr )
{
if (ep_intr&0x1)
{
doepint.d32 = USB_OTG_ReadDevOutEP_itr(pdev, epnum);
/* Transfer complete */
if ( doepint.b.xfercompl )
{
/* Clear the bit in DOEPINTn for this interrupt */
CLEAR_OUT_EP_INTR(epnum, xfercompl);
if (pdev->cfg.dma_enable == 1)
{
deptsiz.d32 = USB_OTG_READ_REG32(&(pdev->regs.OUTEP_REGS[epnum]->DOEPTSIZ));
/*ToDo : handle more than one single MPS size packet */
pdev->dev.out_ep[epnum].xfer_count = pdev->dev.out_ep[epnum].maxpacket - \
deptsiz.b.xfersize;
}
/* Inform upper layer: data ready */
/* RX COMPLETE */
USBD_DCD_INT_fops->DataOutStage(pdev , epnum);
if (pdev->cfg.dma_enable == 1)
{
if((epnum == 0) && (pdev->dev.device_state == USB_OTG_EP0_STATUS_OUT))
{
/* prepare to rx more setup packets */
USB_OTG_EP0_OutStart(pdev);
}
}
}
/* Endpoint disable */
if ( doepint.b.epdisabled )
{
/* Clear the bit in DOEPINTn for this interrupt */
CLEAR_OUT_EP_INTR(epnum, epdisabled);
}
/* Setup Phase Done (control EPs) */
if ( doepint.b.setup )
{
/* inform the upper layer that a setup packet is available */
/* SETUP COMPLETE */
USBD_DCD_INT_fops->SetupStage(pdev);
CLEAR_OUT_EP_INTR(epnum, setup);
}
}
epnum++;
ep_intr >>= 1;
}
return 1;
}
/**
* @brief DCD_HandleSof_ISR
* Handles the SOF Interrupts
* @param pdev: device instance
* @retval status
*/
static uint32_t DCD_HandleSof_ISR(USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_GINTSTS_TypeDef GINTSTS;
USBD_DCD_INT_fops->SOF(pdev);
/* Clear interrupt */
GINTSTS.d32 = 0;
GINTSTS.b.sofintr = 1;
USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GINTSTS, GINTSTS.d32);
return 1;
}
/**
* @brief DCD_HandleRxStatusQueueLevel_ISR
* Handles the Rx Status Queue Level Interrupt
* @param pdev: device instance
* @retval status
*/
static uint32_t DCD_HandleRxStatusQueueLevel_ISR(USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_GINTMSK_TypeDef int_mask;
USB_OTG_DRXSTS_TypeDef status;
USB_OTG_EP *ep;
/* Disable the Rx Status Queue Level interrupt */
int_mask.d32 = 0;
int_mask.b.rxstsqlvl = 1;
USB_OTG_MODIFY_REG32( &pdev->regs.GREGS->GINTMSK, int_mask.d32, 0);
/* Get the Status from the top of the FIFO */
status.d32 = USB_OTG_READ_REG32( &pdev->regs.GREGS->GRXSTSP );
ep = &pdev->dev.out_ep[status.b.epnum];
switch (status.b.pktsts)
{
case STS_GOUT_NAK:
break;
case STS_DATA_UPDT:
if (status.b.bcnt)
{
USB_OTG_ReadPacket(pdev,ep->xfer_buff, status.b.bcnt);
ep->xfer_buff += status.b.bcnt;
ep->xfer_count += status.b.bcnt;
}
break;
case STS_XFER_COMP:
break;
case STS_SETUP_COMP:
break;
case STS_SETUP_UPDT:
/* Copy the setup packet received in FIFO into the setup buffer in RAM */
USB_OTG_ReadPacket(pdev , pdev->dev.setup_packet, 8);
ep->xfer_count += status.b.bcnt;
break;
default:
break;
}
/* Enable the Rx Status Queue Level interrupt */
USB_OTG_MODIFY_REG32( &pdev->regs.GREGS->GINTMSK, 0, int_mask.d32);
return 1;
}
/**
* @brief DCD_WriteEmptyTxFifo
* check FIFO for the next packet to be loaded
* @param pdev: device instance
* @retval status
*/
static uint32_t DCD_WriteEmptyTxFifo(USB_OTG_CORE_HANDLE *pdev, uint32_t epnum)
{
USB_OTG_DTXFSTSn_TypeDef txstatus;
USB_OTG_EP *ep;
uint32_t len = 0;
uint32_t len32b;
txstatus.d32 = 0;
uint32_t fifoemptymsk;
ep = &pdev->dev.in_ep[epnum];
len = ep->XferLen - ep->xfer_count;
if (len > ep->maxpacket)
{
len = ep->maxpacket;
}
len32b = (len + 3) / 4;
txstatus.d32 = USB_OTG_READ_REG32( &pdev->regs.INEP_REGS[epnum]->DTXFSTS);
while (txstatus.b.txfspcavail > len32b &&
ep->xfer_count < ep->XferLen &&
ep->XferLen != 0)
{
/* Write the FIFO */
len = ep->XferLen - ep->xfer_count;
if (len > ep->maxpacket)
{
len = ep->maxpacket;
}
len32b = (len + 3) / 4;
USB_OTG_WritePacket (pdev , ep->xfer_buff, epnum, len);
ep->xfer_buff += len;
ep->xfer_count += len;
txstatus.d32 = USB_OTG_READ_REG32(&pdev->regs.INEP_REGS[epnum]->DTXFSTS);
/* Mask the TxFIFOEmpty interrupt */
if (ep->XferLen == ep->xfer_count)
{
fifoemptymsk = 0x1 << ep->num;
USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DIEPEMPMSK,
fifoemptymsk, 0);
}
}
return 1;
}
/**
* @brief DCD_HandleUsbReset_ISR
* This interrupt occurs when a USB Reset is detected
* @param pdev: device instance
* @retval status
*/
static uint32_t DCD_HandleUsbReset_ISR(USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_DAINT_TypeDef daintmsk;
USB_OTG_DOEPMSK_TypeDef doepmsk;
USB_OTG_DIEPMSK_TypeDef diepmsk;
USB_OTG_DCFG_TypeDef dcfg;
USB_OTG_DCTL_TypeDef dctl;
USB_OTG_GINTSTS_TypeDef gintsts;
uint32_t i;
dctl.d32 = 0;
daintmsk.d32 = 0;
doepmsk.d32 = 0;
diepmsk.d32 = 0;
dcfg.d32 = 0;
gintsts.d32 = 0;
/* Clear the Remote Wake-up Signaling */
dctl.b.rmtwkupsig = 1;
USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DCTL, dctl.d32, 0 );
/* Flush the Tx FIFO */
USB_OTG_FlushTxFifo(pdev , 0 );
for (i = 0; i < pdev->cfg.dev_endpoints ; i++)
{
USB_OTG_WRITE_REG32( &pdev->regs.INEP_REGS[i]->DIEPINT, 0xFF);
USB_OTG_WRITE_REG32( &pdev->regs.OUTEP_REGS[i]->DOEPINT, 0xFF);
}
USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DAINT, 0xFFFFFFFF );
daintmsk.ep.in = 1;
daintmsk.ep.out = 1;
USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DAINTMSK, daintmsk.d32 );
doepmsk.b.setup = 1;
doepmsk.b.xfercompl = 1;
doepmsk.b.epdisabled = 1;
USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DOEPMSK, doepmsk.d32 );
#ifdef USB_OTG_HS_DEDICATED_EP1_ENABLED
USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DOUTEP1MSK, doepmsk.d32 );
#endif
diepmsk.b.xfercompl = 1;
diepmsk.b.timeout = 1;
diepmsk.b.epdisabled = 1;
USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DIEPMSK, diepmsk.d32 );
#ifdef USB_OTG_HS_DEDICATED_EP1_ENABLED
USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DINEP1MSK, diepmsk.d32 );
#endif
/* Reset Device Address */
dcfg.d32 = USB_OTG_READ_REG32( &pdev->regs.DREGS->DCFG);
dcfg.b.devaddr = 0;
USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DCFG, dcfg.d32);
/* setup EP0 to receive SETUP packets */
USB_OTG_EP0_OutStart(pdev);
/* Clear interrupt */
gintsts.d32 = 0;
gintsts.b.usbreset = 1;
USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GINTSTS, gintsts.d32);
/*Reset internal state machine */
USBD_DCD_INT_fops->Reset(pdev);
return 1;
}
/**
* @brief DCD_HandleEnumDone_ISR
* Read the device status register and set the device speed
* @param pdev: device instance
* @retval status
*/
static uint32_t DCD_HandleEnumDone_ISR(USB_OTG_CORE_HANDLE *pdev)
{
uint32_t hclk = 168000000;
USB_OTG_GINTSTS_TypeDef gintsts;
USB_OTG_GUSBCFG_TypeDef gusbcfg;
RCC_ClocksTypeDef RCC_Clocks;
USB_OTG_EP0Activate(pdev);
/* Get HCLK frequency */
RCC_GetClocksFreq(&RCC_Clocks);
hclk = RCC_Clocks.HCLK_Frequency;
/* Clear default TRDT value and Set USB turn-around time based on device speed and PHY interface. */
gusbcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GUSBCFG);
gusbcfg.b.usbtrdtim = 0;
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GUSBCFG, gusbcfg.d32);
/* Full or High speed */
if ( USB_OTG_GetDeviceSpeed(pdev) == USB_SPEED_HIGH)
{
pdev->cfg.speed = USB_OTG_SPEED_HIGH;
pdev->cfg.mps = USB_OTG_HS_MAX_PACKET_SIZE ;
/*USBTRD min For HS device*/
gusbcfg.b.usbtrdtim = 9;
}
else
{
pdev->cfg.speed = USB_OTG_SPEED_FULL;
pdev->cfg.mps = USB_OTG_FS_MAX_PACKET_SIZE ;
/* The USBTRD is configured according to the tables below, depending on AHB frequency
used by application. In the low AHB frequency range it is used to stretch enough the USB response
time to IN tokens, the USB turnaround time, so to compensate for the longer AHB read access
latency to the Data FIFO */
if((hclk >= 15000000)&&(hclk < 16000000))
{
/* hclk Clock Range between 15-16 MHz */
gusbcfg.b.usbtrdtim = 0xE;
}
else if((hclk >= 16000000)&&(hclk < 17100000))
{
/* hclk Clock Range between 16-17.1 MHz */
gusbcfg.b.usbtrdtim = 0xD;
}
else if((hclk >= 17100000)&&(hclk < 18400000))
{
/* hclk Clock Range between 17-18.4 MHz */
gusbcfg.b.usbtrdtim = 0xC;
}
else if((hclk >= 18400000)&&(hclk < 20000000))
{
/* hclk Clock Range between 18.4-20 MHz */
gusbcfg.b.usbtrdtim = 0xB;
}
else if((hclk >= 20000000)&&(hclk < 21800000))
{
/* hclk Clock Range between 20-21.8 MHz */
gusbcfg.b.usbtrdtim = 0xA;
}
else if((hclk >= 21800000)&&(hclk < 24000000))
{
/* hclk Clock Range between 21.8-24 MHz */
gusbcfg.b.usbtrdtim = 0x9;
}
else if((hclk >= 24000000)&&(hclk < 26600000))
{
/* hclk Clock Range between 24-26.6 MHz */
gusbcfg.b.usbtrdtim = 0x8;
}
else if((hclk >= 26600000)&&(hclk < 30000000))
{
/* hclk Clock Range between 26.6-30 MHz */
gusbcfg.b.usbtrdtim = 0x7;
}
else if((hclk >= 30000000)&&(hclk < 34300000))
{
/* hclk Clock Range between 30-34.3 MHz */
gusbcfg.b.usbtrdtim= 0x6;
}
else /* if(hclk >= 34300000) */
{
/* hclk Clock Range between 34.3-168 MHz */
gusbcfg.b.usbtrdtim = 0x5;
}
}
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GUSBCFG, gusbcfg.d32);
/* Clear interrupt */
gintsts.d32 = 0;
gintsts.b.enumdone = 1;
USB_OTG_WRITE_REG32( &pdev->regs.GREGS->GINTSTS, gintsts.d32 );
return 1;
}
/**
* @brief DCD_IsoINIncomplete_ISR
* handle the ISO IN incomplete interrupt
* @param pdev: device instance
* @retval status
*/
static uint32_t DCD_IsoINIncomplete_ISR(USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_GINTSTS_TypeDef gintsts;
gintsts.d32 = 0;
USBD_DCD_INT_fops->IsoINIncomplete (pdev);
/* Clear interrupt */
gintsts.b.incomplisoin = 1;
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32);
return 1;
}
/**
* @brief DCD_IsoOUTIncomplete_ISR
* handle the ISO OUT incomplete interrupt
* @param pdev: device instance
* @retval status
*/
static uint32_t DCD_IsoOUTIncomplete_ISR(USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_GINTSTS_TypeDef gintsts;
gintsts.d32 = 0;
USBD_DCD_INT_fops->IsoOUTIncomplete (pdev);
/* Clear interrupt */
gintsts.b.incomplisoout = 1;
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32);
return 1;
}
/**
* @brief DCD_ReadDevInEP
* Reads ep flags
* @param pdev: device instance
* @retval status
*/
static uint32_t DCD_ReadDevInEP (USB_OTG_CORE_HANDLE *pdev, uint8_t epnum)
{
uint32_t v, msk, emp;
msk = USB_OTG_READ_REG32(&pdev->regs.DREGS->DIEPMSK);
emp = USB_OTG_READ_REG32(&pdev->regs.DREGS->DIEPEMPMSK);
msk |= ((emp >> epnum) & 0x1) << 7;
v = USB_OTG_READ_REG32(&pdev->regs.INEP_REGS[epnum]->DIEPINT) & msk;
return v;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,275 +0,0 @@
/**
******************************************************************************
* @file usb_hcd.c
* @author xiuos Team
* @version V1.0.0
* @date 2020-9-3
* @brief This file is based on usb_hcd.c
* Host Interface Layer
******************************************************************************
* @file usb_hcd.c
* @author MCD Application Team
* @version V1.0.0
* @date 30-September-2011
* ********************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2015 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* <http://www.st.com/SLA0044>
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "usb_core.h"
#include "usb_hcd.h"
#include "usb_conf.h"
#include "usb_bsp.h"
/** @addtogroup USB_OTG_DRIVER
* @{
*/
/** @defgroup USB_HCD
* @brief This file is the interface between EFSL ans Host mass-storage class
* @{
*/
/** @defgroup USB_HCD_Private_Defines
* @{
*/
/**
* @}
*/
/** @defgroup USB_HCD_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @defgroup USB_HCD_Private_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USB_HCD_Private_Variables
* @{
*/
/**
* @}
*/
/** @defgroup USB_HCD_Private_FunctionPrototypes
* @{
*/
/**
* @}
*/
/** @defgroup USB_HCD_Private_Functions
* @{
*/
/**
* @brief HCD_Init
* Initialize the HOST portion of the driver.
* @param pdev: Selected device
* @param base_address: OTG base address
* @retval Status
*/
uint32_t HCD_Init(USB_OTG_CORE_HANDLE *pdev ,
USB_OTG_CORE_ID_TypeDef coreID)
{
uint8_t i = 0;
pdev->host.ConnSts = 0;
for (i= 0; i< USB_OTG_MAX_TX_FIFOS; i++)
{
pdev->host.ErrCnt[i] = 0;
pdev->host.XferCnt[i] = 0;
pdev->host.HC_Status[i] = HC_IDLE;
}
pdev->host.hc[0].max_packet = 8;
USB_OTG_SelectCore(pdev, coreID);
#ifndef DUAL_ROLE_MODE_ENABLED
USB_OTG_DisableGlobalInt(pdev);
USB_OTG_CoreInit(pdev);
/* Force Host Mode*/
USB_OTG_SetCurrentMode(pdev , HOST_MODE);
USB_OTG_CoreInitHost(pdev);
USB_OTG_EnableGlobalInt(pdev);
#endif
return 0;
}
/**
* @brief HCD_GetCurrentSpeed
* Get Current device Speed.
* @param pdev : Selected device
* @retval Status
*/
uint32_t HCD_GetCurrentSpeed (USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_HPRT0_TypeDef HPRT0;
HPRT0.d32 = USB_OTG_READ_REG32(pdev->regs.HPRT0);
return HPRT0.b.prtspd;
}
/**
* @brief HCD_ResetPort
* Issues the reset command to device
* @param pdev : Selected device
* @retval Status
*/
uint32_t HCD_ResetPort(USB_OTG_CORE_HANDLE *pdev)
{
/*
Before starting to drive a USB reset, the application waits for the OTG
interrupt triggered by the denounce done bit (DBCDNE bit in OTG_FS_GOTGINT),
which indicates that the bus is stable again after the electrical denounce
caused by the attachment of a pull-up resistor on DP (FS) or DM (LS).
*/
USB_OTG_ResetPort(pdev);
return 0;
}
/**
* @brief HCD_IsDeviceConnected
* Check if the device is connected.
* @param pdev : Selected device
* @retval Device connection status. 1 -> connected and 0 -> disconnected
*
*/
uint32_t HCD_IsDeviceConnected(USB_OTG_CORE_HANDLE *pdev)
{
return (pdev->host.ConnSts);
}
/**
* @brief HCD_IsPortEnabled
* This function checks if port is enabled
* @param pdev : Selected device
* @retval Frame number
*
*/
uint32_t HCD_IsPortEnabled(USB_OTG_CORE_HANDLE *pdev)
{
return (pdev->host.PortEnabled);
}
/**
* @brief HCD_GetCurrentFrame
* This function returns the frame number for sof packet
* @param pdev : Selected device
* @retval Frame number
*
*/
uint32_t HCD_GetCurrentFrame (USB_OTG_CORE_HANDLE *pdev)
{
return (USB_OTG_READ_REG32(&pdev->regs.HREGS->HFNUM) & 0xFFFF) ;
}
/**
* @brief HCD_GetURB_State
* This function returns the last URBstate
* @param pdev: Selected device
* @retval URB_STATE
*
*/
URB_STATE HCD_GetURB_State (USB_OTG_CORE_HANDLE *pdev , uint8_t ch_num)
{
return pdev->host.URB_State[ch_num] ;
}
/**
* @brief HCD_GetXferCnt
* This function returns the last URBstate
* @param pdev: Selected device
* @retval No. of data bytes transferred
*
*/
uint32_t HCD_GetXferCnt (USB_OTG_CORE_HANDLE *pdev, uint8_t ch_num)
{
return pdev->host.XferCnt[ch_num] ;
}
/**
* @brief HCD_GetHCState
* This function returns the HC Status
* @param pdev: Selected device
* @retval HC_STATUS
*
*/
HC_STATUS HCD_GetHCState (USB_OTG_CORE_HANDLE *pdev , uint8_t ch_num)
{
return pdev->host.HC_Status[ch_num] ;
}
/**
* @brief HCD_HC_Init
* This function prepare a HC and start a transfer
* @param pdev: Selected device
* @param hc_num: Channel number
* @retval status
*/
uint32_t HCD_HC_Init (USB_OTG_CORE_HANDLE *pdev , uint8_t hc_num)
{
return USB_OTG_HC_Init(pdev, hc_num);
}
/**
* @brief HCD_SubmitRequest
* This function prepare a HC and start a transfer
* @param pdev: Selected device
* @param hc_num: Channel number
* @retval status
*/
uint32_t HCD_SubmitRequest (USB_OTG_CORE_HANDLE *pdev , uint8_t hc_num)
{
pdev->host.URB_State[hc_num] = URB_IDLE;
pdev->host.hc[hc_num].xfer_count = 0 ;
return USB_OTG_HC_StartXfer(pdev, hc_num);
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,846 +0,0 @@
/**
******************************************************************************
* @file usb_hcd_int.c
* @author xiuos Team
* @version V1.0.0
* @date 2020-9-3
* @brief This file is based on usb_hcd_int.c
* Host driver interrupt subroutines
******************************************************************************
* @file usb_hcd_int.c
* @author MCD Application Team
* @version V1.0.0
* @date 30-September-2011
* ********************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2015 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* <http://www.st.com/SLA0044>
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "usb_core.h"
#include "usb_defines.h"
#include "usb_hcd_int.h"
#if defined (__GNUC__) /*!< GNU Compiler */
#pragma GCC optimize ("O0")
#endif
/** @addtogroup USB_OTG_DRIVER
* @{
*/
/** @defgroup USB_HCD_INT
* @brief This file contains the interrupt subroutines for the Host mode.
* @{
*/
/** @defgroup USB_HCD_INT_Private_Defines
* @{
*/
/**
* @}
*/
/** @defgroup USB_HCD_INT_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @defgroup USB_HCD_INT_Private_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USB_HCD_INT_Private_Variables
* @{
*/
/**
* @}
*/
/** @defgroup USB_HCD_INT_Private_FunctionPrototypes
* @{
*/
static uint32_t USB_OTG_USBH_handle_sof_ISR(USB_OTG_CORE_HANDLE *pdev);
static uint32_t USB_OTG_USBH_handle_port_ISR(USB_OTG_CORE_HANDLE *pdev);
static uint32_t USB_OTG_USBH_handle_hc_ISR (USB_OTG_CORE_HANDLE *pdev);
static uint32_t USB_OTG_USBH_handle_hc_n_In_ISR (USB_OTG_CORE_HANDLE *pdev ,
uint32_t num);
static uint32_t USB_OTG_USBH_handle_hc_n_Out_ISR (USB_OTG_CORE_HANDLE *pdev ,
uint32_t num);
static uint32_t USB_OTG_USBH_handle_rx_qlvl_ISR (USB_OTG_CORE_HANDLE *pdev);
static uint32_t USB_OTG_USBH_handle_nptxfempty_ISR (USB_OTG_CORE_HANDLE *pdev);
static uint32_t USB_OTG_USBH_handle_ptxfempty_ISR (USB_OTG_CORE_HANDLE *pdev);
static uint32_t USB_OTG_USBH_handle_Disconnect_ISR (USB_OTG_CORE_HANDLE *pdev);
static uint32_t USB_OTG_USBH_handle_IncompletePeriodicXfer_ISR (USB_OTG_CORE_HANDLE *pdev);
/**
* @}
*/
/** @defgroup USB_HCD_INT_Private_Functions
* @{
*/
/**
* @brief HOST_Handle_ISR
* This function handles all USB Host Interrupts
* @param pdev: Selected device
* @retval status
*/
uint32_t USBH_OTG_ISR_Handler (USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_GINTSTS_TypeDef gintsts;
uint32_t retval = 0;
gintsts.d32 = 0;
/* Check if HOST Mode */
if (USB_OTG_IsHostMode(pdev))
{
gintsts.d32 = USB_OTG_ReadCoreItr(pdev);
if (!gintsts.d32)
{
return 0;
}
if (gintsts.b.sofintr)
{
retval |= USB_OTG_USBH_handle_sof_ISR (pdev);
}
if (gintsts.b.rxstsqlvl)
{
retval |= USB_OTG_USBH_handle_rx_qlvl_ISR (pdev);
}
if (gintsts.b.nptxfempty)
{
retval |= USB_OTG_USBH_handle_nptxfempty_ISR (pdev);
}
if (gintsts.b.ptxfempty)
{
retval |= USB_OTG_USBH_handle_ptxfempty_ISR (pdev);
}
if (gintsts.b.hcintr)
{
retval |= USB_OTG_USBH_handle_hc_ISR (pdev);
}
if (gintsts.b.portintr)
{
retval |= USB_OTG_USBH_handle_port_ISR (pdev);
}
if (gintsts.b.disconnect)
{
retval |= USB_OTG_USBH_handle_Disconnect_ISR (pdev);
}
if (gintsts.b.incomplisoout)
{
retval |= USB_OTG_USBH_handle_IncompletePeriodicXfer_ISR (pdev);
}
}
return retval;
}
/**
* @brief USB_OTG_USBH_handle_hc_ISR
* This function indicates that one or more host channels has a pending
* @param pdev: Selected device
* @retval status
*/
static uint32_t USB_OTG_USBH_handle_hc_ISR (USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_HAINT_TypeDef haint;
USB_OTG_HCCHAR_TypeDef hcchar;
uint32_t i = 0;
uint32_t retval = 0;
/* Clear appropriate bits in HCINTn to clear the interrupt bit in
* GINTSTS */
haint.d32 = USB_OTG_ReadHostAllChannels_intr(pdev);
for (i = 0; i < pdev->cfg.host_channels ; i++)
{
if (haint.b.chint & (1 << i))
{
hcchar.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[i]->HCCHAR);
if (hcchar.b.epdir)
{
retval |= USB_OTG_USBH_handle_hc_n_In_ISR (pdev, i);
}
else
{
retval |= USB_OTG_USBH_handle_hc_n_Out_ISR (pdev, i);
}
}
}
return retval;
}
/**
* @brief USB_OTG_otg_hcd_handle_sof_intr
* Handles the start-of-frame interrupt in host mode.
* @param pdev: Selected device
* @retval status
*/
static uint32_t USB_OTG_USBH_handle_sof_ISR (USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_GINTSTS_TypeDef gintsts;
gintsts.d32 = 0;
USBH_HCD_INT_fops->SOF(pdev);
/* Clear interrupt */
gintsts.b.sofintr = 1;
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32);
return 1;
}
/**
* @brief USB_OTG_USBH_handle_Disconnect_ISR
* Handles disconnect event.
* @param pdev: Selected device
* @retval status
*/
static uint32_t USB_OTG_USBH_handle_Disconnect_ISR (USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_GINTSTS_TypeDef gintsts;
gintsts.d32 = 0;
USBH_HCD_INT_fops->DevDisconnected(pdev);
/* Clear interrupt */
gintsts.b.disconnect = 1;
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32);
return 1;
}
/**
* @brief USB_OTG_USBH_handle_nptxfempty_ISR
* Handles non periodic tx fifo empty.
* @param pdev: Selected device
* @retval status
*/
static uint32_t USB_OTG_USBH_handle_nptxfempty_ISR (USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_GINTMSK_TypeDef intmsk;
USB_OTG_HNPTXSTS_TypeDef hnptxsts;
uint16_t len_words , len;
hnptxsts.b.nptxqtop.chnum = 0U;
hnptxsts.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->HNPTXSTS);
len_words = (pdev->host.hc[hnptxsts.b.nptxqtop.chnum].XferLen + 3) / 4;
while ((hnptxsts.b.nptxfspcavail > len_words)&&
(pdev->host.hc[hnptxsts.b.nptxqtop.chnum].XferLen != 0))
{
len = hnptxsts.b.nptxfspcavail * 4;
if (len > pdev->host.hc[hnptxsts.b.nptxqtop.chnum].XferLen)
{
/* Last packet */
len = pdev->host.hc[hnptxsts.b.nptxqtop.chnum].XferLen;
intmsk.d32 = 0;
intmsk.b.nptxfempty = 1;
USB_OTG_MODIFY_REG32( &pdev->regs.GREGS->GINTMSK, intmsk.d32, 0);
}
len_words = (pdev->host.hc[hnptxsts.b.nptxqtop.chnum].XferLen + 3) / 4;
USB_OTG_WritePacket (pdev , pdev->host.hc[hnptxsts.b.nptxqtop.chnum].xfer_buff, hnptxsts.b.nptxqtop.chnum, len);
pdev->host.hc[hnptxsts.b.nptxqtop.chnum].xfer_buff += len;
pdev->host.hc[hnptxsts.b.nptxqtop.chnum].XferLen -= len;
pdev->host.hc[hnptxsts.b.nptxqtop.chnum].xfer_count += len;
hnptxsts.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->HNPTXSTS);
}
return 1;
}
/**
* @brief USB_OTG_USBH_handle_ptxfempty_ISR
* Handles periodic tx fifo empty
* @param pdev: Selected device
* @retval status
*/
static uint32_t USB_OTG_USBH_handle_ptxfempty_ISR (USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_GINTMSK_TypeDef intmsk;
USB_OTG_HPTXSTS_TypeDef hptxsts;
uint16_t len_words , len;
hptxsts.b.ptxqtop.chnum = 0U;
hptxsts.d32 = USB_OTG_READ_REG32(&pdev->regs.HREGS->HPTXSTS);
len_words = (pdev->host.hc[hptxsts.b.ptxqtop.chnum].XferLen + 3) / 4;
while ((hptxsts.b.ptxfspcavail > len_words)&&
(pdev->host.hc[hptxsts.b.ptxqtop.chnum].XferLen != 0))
{
len = hptxsts.b.ptxfspcavail * 4;
if (len > pdev->host.hc[hptxsts.b.ptxqtop.chnum].XferLen)
{
len = pdev->host.hc[hptxsts.b.ptxqtop.chnum].XferLen;
/* Last packet */
intmsk.d32 = 0;
intmsk.b.ptxfempty = 1;
USB_OTG_MODIFY_REG32( &pdev->regs.GREGS->GINTMSK, intmsk.d32, 0);
}
len_words = (pdev->host.hc[hptxsts.b.ptxqtop.chnum].XferLen + 3) / 4;
USB_OTG_WritePacket (pdev , pdev->host.hc[hptxsts.b.ptxqtop.chnum].xfer_buff, hptxsts.b.ptxqtop.chnum, len);
pdev->host.hc[hptxsts.b.ptxqtop.chnum].xfer_buff += len;
pdev->host.hc[hptxsts.b.ptxqtop.chnum].XferLen -= len;
pdev->host.hc[hptxsts.b.ptxqtop.chnum].xfer_count += len;
hptxsts.d32 = USB_OTG_READ_REG32(&pdev->regs.HREGS->HPTXSTS);
}
return 1;
}
/**
* @brief USB_OTG_USBH_handle_port_ISR
* This function determines which interrupt conditions have occurred
* @param pdev: Selected device
* @retval status
*/
static uint32_t USB_OTG_USBH_handle_port_ISR (USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_HPRT0_TypeDef hprt0;
USB_OTG_HPRT0_TypeDef hprt0_dup;
USB_OTG_HCFG_TypeDef hcfg;
uint32_t retval = 0;
USB_OTG_GINTMSK_TypeDef intmsk;
intmsk.d32 = 0;
hcfg.d32 = 0;
hprt0.d32 = 0;
hprt0_dup.d32 = 0;
hprt0.d32 = USB_OTG_READ_REG32(pdev->regs.HPRT0);
hprt0_dup.d32 = USB_OTG_READ_REG32(pdev->regs.HPRT0);
/* Clear the interrupt bits in GINTSTS */
hprt0_dup.b.prtena = 0;
hprt0_dup.b.prtconndet = 0;
hprt0_dup.b.prtenchng = 0;
hprt0_dup.b.prtovrcurrchng = 0;
/* Port Connect Detected */
if (hprt0.b.prtconndet)
{
hprt0_dup.b.prtconndet = 1;
USBH_HCD_INT_fops->DevConnected(pdev);
retval |= 1;
}
/* Port Enable Changed */
if (hprt0.b.prtenchng)
{
hprt0_dup.b.prtenchng = 1;
if (hprt0.b.prtena == 1)
{
if ((hprt0.b.prtspd == HPRT0_PRTSPD_LOW_SPEED) ||
(hprt0.b.prtspd == HPRT0_PRTSPD_FULL_SPEED))
{
hcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.HREGS->HCFG);
if (hprt0.b.prtspd == HPRT0_PRTSPD_LOW_SPEED)
{
USB_OTG_WRITE_REG32(&pdev->regs.HREGS->HFIR, 6000 );
if (hcfg.b.fslspclksel != HCFG_6_MHZ)
{
if(pdev->cfg.phy_itface == USB_OTG_EMBEDDED_PHY)
{
USB_OTG_InitFSLSPClkSel(pdev , HCFG_6_MHZ);
}
else
{
USB_OTG_WRITE_REG32(&pdev->regs.HREGS->HFIR, 48000 );
if (hcfg.b.fslspclksel != HCFG_48_MHZ)
{
USB_OTG_InitFSLSPClkSel(pdev ,HCFG_48_MHZ );
}
}
}
}
}
USBH_HCD_INT_fops->DevPortEnabled(pdev);
/*unmask disconnect interrupt */
intmsk.d32 = 0;
intmsk.b.disconnect = 1;
USB_OTG_MODIFY_REG32(&pdev->regs.GREGS->GINTMSK, intmsk.d32, intmsk.d32);
}
else
{
USBH_HCD_INT_fops->DevPortDisabled(pdev);
}
}
/* Overcurrent Change Interrupt */
if (hprt0.b.prtovrcurrchng)
{
hprt0_dup.b.prtovrcurrchng = 1;
retval |= 1;
}
/* Clear Port Interrupts */
USB_OTG_WRITE_REG32(pdev->regs.HPRT0, hprt0_dup.d32);
return retval;
}
/**
* @brief USB_OTG_USBH_handle_hc_n_Out_ISR
* Handles interrupt for a specific Host Channel
* @param pdev: Selected device
* @param hc_num: Channel number
* @retval status
*/
uint32_t USB_OTG_USBH_handle_hc_n_Out_ISR (USB_OTG_CORE_HANDLE *pdev , uint32_t num)
{
USB_OTG_HCINTn_TypeDef hcint;
USB_OTG_HCINTMSK_TypeDef hcintmsk;
USB_OTG_HC_REGS *hcreg;
USB_OTG_HCCHAR_TypeDef hcchar;
hcreg = pdev->regs.HC_REGS[num];
hcint.d32 = USB_OTG_READ_REG32(&hcreg->HCINT);
hcintmsk.d32 = USB_OTG_READ_REG32(&hcreg->HCINTMSK);
hcint.d32 = hcint.d32 & hcintmsk.d32;
hcchar.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[num]->HCCHAR);
if (hcint.b.ahberr)
{
CLEAR_HC_INT(hcreg ,ahberr);
UNMASK_HOST_INT_CHH (num);
}
else if (hcint.b.ack)
{
CLEAR_HC_INT(hcreg , ack);
}
else if (hcint.b.frmovrun)
{
UNMASK_HOST_INT_CHH (num);
USB_OTG_HC_Halt(pdev, num);
CLEAR_HC_INT(hcreg ,frmovrun);
}
else if (hcint.b.xfercompl)
{
pdev->host.ErrCnt[num] = 0;
UNMASK_HOST_INT_CHH (num);
USB_OTG_HC_Halt(pdev, num);
CLEAR_HC_INT(hcreg , xfercompl);
pdev->host.HC_Status[num] = HC_XFRC;
}
else if (hcint.b.stall)
{
CLEAR_HC_INT(hcreg , stall);
UNMASK_HOST_INT_CHH (num);
USB_OTG_HC_Halt(pdev, num);
pdev->host.HC_Status[num] = HC_STALL;
}
else if (hcint.b.nak)
{
pdev->host.ErrCnt[num] = 0;
UNMASK_HOST_INT_CHH (num);
if (pdev->cfg.dma_enable == 0)
{
USB_OTG_HC_Halt(pdev, num);
}
CLEAR_HC_INT(hcreg , nak);
pdev->host.HC_Status[num] = HC_NAK;
}
else if (hcint.b.xacterr)
{
UNMASK_HOST_INT_CHH (num);
USB_OTG_HC_Halt(pdev, num);
pdev->host.HC_Status[num] = HC_XACTERR;
CLEAR_HC_INT(hcreg , xacterr);
}
else if (hcint.b.nyet)
{
pdev->host.ErrCnt[num] = 0;
UNMASK_HOST_INT_CHH (num);
if (pdev->cfg.dma_enable == 0)
{
USB_OTG_HC_Halt(pdev, num);
}
CLEAR_HC_INT(hcreg , nyet);
pdev->host.HC_Status[num] = HC_NYET;
}
else if (hcint.b.datatglerr)
{
UNMASK_HOST_INT_CHH (num);
USB_OTG_HC_Halt(pdev, num);
CLEAR_HC_INT(hcreg , nak);
pdev->host.HC_Status[num] = HC_DATATGLERR;
CLEAR_HC_INT(hcreg , datatglerr);
}
else if (hcint.b.chhltd)
{
MASK_HOST_INT_CHH (num);
if(pdev->host.HC_Status[num] == HC_XFRC)
{
pdev->host.URB_State[num] = URB_DONE;
if (hcchar.b.eptype == EP_TYPE_BULK)
{
pdev->host.hc[num].toggle_out ^= 1;
}
}
else if(pdev->host.HC_Status[num] == HC_NAK)
{
pdev->host.URB_State[num] = URB_NOTREADY;
}
else if(pdev->host.HC_Status[num] == HC_NYET)
{
if(pdev->host.hc[num].do_ping == 1)
{
USB_OTG_HC_DoPing(pdev, num);
}
pdev->host.URB_State[num] = URB_NOTREADY;
}
else if(pdev->host.HC_Status[num] == HC_STALL)
{
pdev->host.URB_State[num] = URB_STALL;
}
else if(pdev->host.HC_Status[num] == HC_XACTERR)
{
{
pdev->host.URB_State[num] = URB_ERROR;
}
}
CLEAR_HC_INT(hcreg , chhltd);
USBH_HCD_INT_fops->URBChangeNotify(pdev);
}
return 1;
}
/**
* @brief USB_OTG_USBH_handle_hc_n_In_ISR
* Handles interrupt for a specific Host Channel
* @param pdev: Selected device
* @param hc_num: Channel number
* @retval status
*/
uint32_t USB_OTG_USBH_handle_hc_n_In_ISR (USB_OTG_CORE_HANDLE *pdev , uint32_t num)
{
USB_OTG_HCINTn_TypeDef hcint;
USB_OTG_HCINTMSK_TypeDef hcintmsk;
USB_OTG_HCCHAR_TypeDef hcchar;
USB_OTG_HCTSIZn_TypeDef hctsiz;
USB_OTG_HC_REGS *hcreg;
hcreg = pdev->regs.HC_REGS[num];
hcint.d32 = USB_OTG_READ_REG32(&hcreg->HCINT);
hcintmsk.d32 = USB_OTG_READ_REG32(&hcreg->HCINTMSK);
hcint.d32 = hcint.d32 & hcintmsk.d32;
hcchar.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[num]->HCCHAR);
hcintmsk.d32 = 0;
if (hcint.b.ahberr)
{
CLEAR_HC_INT(hcreg ,ahberr);
UNMASK_HOST_INT_CHH (num);
}
else if (hcint.b.ack)
{
CLEAR_HC_INT(hcreg ,ack);
}
else if (hcint.b.stall)
{
UNMASK_HOST_INT_CHH (num);
pdev->host.HC_Status[num] = HC_STALL;
CLEAR_HC_INT(hcreg , nak); /* Clear the NAK Condition */
CLEAR_HC_INT(hcreg , stall); /* Clear the STALL Condition */
hcint.b.nak = 0; /* NOTE: When there is a 'stall', reset also nak,
else, the pdev->host.HC_Status = HC_STALL
will be overwritten by 'nak' in code below */
USB_OTG_HC_Halt(pdev, num);
}
else if (hcint.b.datatglerr)
{
UNMASK_HOST_INT_CHH (num);
USB_OTG_HC_Halt(pdev, num);
CLEAR_HC_INT(hcreg , nak);
pdev->host.HC_Status[num] = HC_DATATGLERR;
CLEAR_HC_INT(hcreg , datatglerr);
}
if (hcint.b.frmovrun)
{
UNMASK_HOST_INT_CHH (num);
USB_OTG_HC_Halt(pdev, num);
CLEAR_HC_INT(hcreg ,frmovrun);
}
else if (hcint.b.xfercompl)
{
if (pdev->cfg.dma_enable == 1)
{
hctsiz.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[num]->HCTSIZ);
pdev->host.XferCnt[num] = pdev->host.hc[num].XferLen - hctsiz.b.xfersize;
}
pdev->host.HC_Status[num] = HC_XFRC;
pdev->host.ErrCnt [num]= 0;
CLEAR_HC_INT(hcreg , xfercompl);
if ((hcchar.b.eptype == EP_TYPE_CTRL)||
(hcchar.b.eptype == EP_TYPE_BULK))
{
UNMASK_HOST_INT_CHH (num);
USB_OTG_HC_Halt(pdev, num);
CLEAR_HC_INT(hcreg , nak);
pdev->host.hc[num].toggle_in ^= 1;
}
else if(hcchar.b.eptype == EP_TYPE_INTR)
{
hcchar.b.oddfrm = 1;
USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[num]->HCCHAR, hcchar.d32);
pdev->host.URB_State[num] = URB_DONE;
USBH_HCD_INT_fops->URBChangeNotify(pdev);
}
}
else if (hcint.b.chhltd)
{
MASK_HOST_INT_CHH (num);
if(pdev->host.HC_Status[num] == HC_XFRC)
{
pdev->host.URB_State[num] = URB_DONE;
}
else if (pdev->host.HC_Status[num] == HC_STALL)
{
pdev->host.URB_State[num] = URB_STALL;
}
else if((pdev->host.HC_Status[num] == HC_XACTERR) ||
(pdev->host.HC_Status[num] == HC_DATATGLERR))
{
pdev->host.ErrCnt[num] = 0;
pdev->host.URB_State[num] = URB_ERROR;
}
else if(hcchar.b.eptype == EP_TYPE_INTR)
{
pdev->host.hc[num].toggle_in ^= 1;
}
CLEAR_HC_INT(hcreg , chhltd);
USBH_HCD_INT_fops->URBChangeNotify(pdev);
}
else if (hcint.b.xacterr)
{
UNMASK_HOST_INT_CHH (num);
pdev->host.HC_Status[num] = HC_XACTERR;
USB_OTG_HC_Halt(pdev, num);
CLEAR_HC_INT(hcreg , xacterr);
}
else if (hcint.b.nak)
{
if(hcchar.b.eptype == EP_TYPE_INTR)
{
UNMASK_HOST_INT_CHH (num);
if (pdev->cfg.dma_enable == 0)
{
USB_OTG_HC_Halt(pdev, num);
}
}
pdev->host.HC_Status[num] = HC_NAK;
CLEAR_HC_INT(hcreg , nak);
if ((hcchar.b.eptype == EP_TYPE_CTRL)||
(hcchar.b.eptype == EP_TYPE_BULK))
{
/* re-activate the channel */
hcchar.b.chen = 1;
hcchar.b.chdis = 0;
USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[num]->HCCHAR, hcchar.d32);
}
}
return 1;
}
/**
* @brief USB_OTG_USBH_handle_rx_qlvl_ISR
* Handles the Rx Status Queue Level Interrupt
* @param pdev: Selected device
* @retval status
*/
static uint32_t USB_OTG_USBH_handle_rx_qlvl_ISR (USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_GRXFSTS_TypeDef grxsts;
USB_OTG_GINTMSK_TypeDef intmsk;
USB_OTG_HCTSIZn_TypeDef hctsiz;
USB_OTG_HCCHAR_TypeDef hcchar;
__IO uint8_t channelnum =0;
uint32_t count;
/* Disable the Rx Status Queue Level interrupt */
intmsk.d32 = 0;
intmsk.b.rxstsqlvl = 1;
USB_OTG_MODIFY_REG32( &pdev->regs.GREGS->GINTMSK, intmsk.d32, 0);
grxsts.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GRXSTSP);
channelnum = grxsts.b.chnum;
hcchar.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[channelnum]->HCCHAR);
switch (grxsts.b.pktsts)
{
case GRXSTS_PKTSTS_IN:
/* Read the data into the host buffer. */
if ((grxsts.b.bcnt > 0) && (pdev->host.hc[channelnum].xfer_buff != (void *)0))
{
USB_OTG_ReadPacket(pdev, pdev->host.hc[channelnum].xfer_buff, grxsts.b.bcnt);
/*manage multiple Xfer */
pdev->host.hc[grxsts.b.chnum].xfer_buff += grxsts.b.bcnt;
pdev->host.hc[grxsts.b.chnum].xfer_count += grxsts.b.bcnt;
count = pdev->host.hc[channelnum].xfer_count;
pdev->host.XferCnt[channelnum] = count;
hctsiz.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[channelnum]->HCTSIZ);
if(hctsiz.b.pktcnt > 0)
{
/* re-activate the channel when more packets are expected */
hcchar.b.chen = 1;
hcchar.b.chdis = 0;
USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[channelnum]->HCCHAR, hcchar.d32);
}
}
break;
case GRXSTS_PKTSTS_IN_XFER_COMP:
case GRXSTS_PKTSTS_DATA_TOGGLE_ERR:
case GRXSTS_PKTSTS_CH_HALTED:
default:
break;
}
/* Enable the Rx Status Queue Level interrupt */
intmsk.b.rxstsqlvl = 1;
USB_OTG_MODIFY_REG32(&pdev->regs.GREGS->GINTMSK, 0, intmsk.d32);
return 1;
}
/**
* @brief USB_OTG_USBH_handle_IncompletePeriodicXfer_ISR
* Handles the incomplete Periodic transfer Interrupt
* @param pdev: Selected device
* @retval status
*/
static uint32_t USB_OTG_USBH_handle_IncompletePeriodicXfer_ISR (USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_GINTSTS_TypeDef gintsts;
USB_OTG_HCCHAR_TypeDef hcchar;
hcchar.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[0]->HCCHAR);
hcchar.b.chen = 1;
hcchar.b.chdis = 1;
USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[0]->HCCHAR, hcchar.d32);
gintsts.d32 = 0;
/* Clear interrupt */
gintsts.b.incomplisoout = 1;
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32);
return 1;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,418 +0,0 @@
/**
******************************************************************************
* @file usb_otg.c
* @author xiuos Team
* @version V1.0.0
* @date 2020-9-3
* @brief This file is based on usb_otg.c
* OTG Core Layer
******************************************************************************
* @file usb_otg.c
* @author MCD Application Team
* @version V1.0.0
* @date 30-September-2011
* ********************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2015 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* <http://www.st.com/SLA0044>
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "usb_defines.h"
#include "usb_regs.h"
#include "usb_core.h"
#include "usb_otg.h"
/** @addtogroup USB_OTG_DRIVER
* @{
*/
/** @defgroup USB_OTG
* @brief This file is the interface between EFSL ans Host mass-storage class
* @{
*/
/** @defgroup USB_OTG_Private_Defines
* @{
*/
/**
* @}
*/
/** @defgroup USB_OTG_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @defgroup USB_OTG_Private_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USB_OTG_Private_Variables
* @{
*/
/**
* @}
*/
/** @defgroup USB_OTG_Private_FunctionPrototypes
* @{
*/
uint32_t USB_OTG_HandleOTG_ISR(USB_OTG_CORE_HANDLE *pdev);
static uint32_t USB_OTG_HandleConnectorIDStatusChange_ISR(USB_OTG_CORE_HANDLE *pdev);
static uint32_t USB_OTG_HandleSessionRequest_ISR(USB_OTG_CORE_HANDLE *pdev);
static uint32_t USB_OTG_Read_itr(USB_OTG_CORE_HANDLE *pdev);
/**
* @}
*/
/** @defgroup USB_OTG_Private_Functions
* @{
*/
/* OTG Interrupt Handler */
/**
* @brief STM32_USBO_OTG_ISR_Handler
*
* @param None
* @retval : None
*/
uint32_t STM32_USBO_OTG_ISR_Handler(USB_OTG_CORE_HANDLE *pdev)
{
uint32_t retval = 0;
USB_OTG_GINTSTS_TypeDef gintsts ;
gintsts.d32 = 0;
gintsts.d32 = USB_OTG_Read_itr(pdev);
if (gintsts.d32 == 0)
{
return 0;
}
if (gintsts.b.otgintr)
{
retval |= USB_OTG_HandleOTG_ISR(pdev);
}
if (gintsts.b.conidstschng)
{
retval |= USB_OTG_HandleConnectorIDStatusChange_ISR(pdev);
}
if (gintsts.b.sessreqintr)
{
retval |= USB_OTG_HandleSessionRequest_ISR(pdev);
}
return retval;
}
/**
* @brief USB_OTG_Read_itr
* returns the Core Interrupt register
* @param None
* @retval : status
*/
static uint32_t USB_OTG_Read_itr(USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_GINTSTS_TypeDef gintsts;
USB_OTG_GINTMSK_TypeDef gintmsk;
USB_OTG_GINTMSK_TypeDef gintmsk_common;
gintsts.d32 = 0;
gintmsk.d32 = 0;
gintmsk_common.d32 = 0;
/* OTG interrupts */
gintmsk_common.b.sessreqintr = 1;
gintmsk_common.b.conidstschng = 1;
gintmsk_common.b.otgintr = 1;
gintsts.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GINTSTS);
gintmsk.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GINTMSK);
return ((gintsts.d32 & gintmsk.d32 ) & gintmsk_common.d32);
}
/**
* @brief USB_OTG_HandleOTG_ISR
* handles the OTG Interrupts
* @param None
* @retval : status
*/
uint32_t USB_OTG_HandleOTG_ISR(USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_GOTGINT_TypeDef gotgint;
USB_OTG_GOTGCTL_TypeDef gotgctl;
gotgint.d32 = 0;
gotgctl.d32 = 0;
gotgint.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GOTGINT);
gotgctl.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GOTGCTL);
if (gotgint.b.sesenddet)
{
gotgctl.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GOTGCTL);
if (USB_OTG_IsDeviceMode(pdev))
{
}
else if (USB_OTG_IsHostMode(pdev))
{
}
}
/* ----> SRP SUCCESS or FAILURE INTERRUPT <---- */
if (gotgint.b.sesreqsucstschng)
{
gotgctl.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GOTGCTL);
if (gotgctl.b.sesreqscs) /* Session request success */
{
if (USB_OTG_IsDeviceMode(pdev))
{
}
/* Clear Session Request */
gotgctl.d32 = 0;
gotgctl.b.sesreq = 1;
USB_OTG_MODIFY_REG32(&pdev->regs.GREGS->GOTGCTL, gotgctl.d32, 0);
}
else /* Session request failure */
{
if (USB_OTG_IsDeviceMode(pdev))
{
}
}
}
/* ----> HNP SUCCESS or FAILURE INTERRUPT <---- */
if (gotgint.b.hstnegsucstschng)
{
gotgctl.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GOTGCTL);
if (gotgctl.b.hstnegscs) /* Host negotiation success */
{
if (USB_OTG_IsHostMode(pdev)) /* The core AUTOMATICALLY sets the Host mode */
{
}
}
else /* Host negotiation failure */
{
}
gotgint.b.hstnegsucstschng = 1; /* Ack "Host Negotiation Success Status Change" interrupt. */
}
/* ----> HOST NEGOTIATION DETECTED INTERRUPT <---- */
if (gotgint.b.hstnegdet)
{
if (USB_OTG_IsDeviceMode(pdev)) /* The core AUTOMATICALLY sets the Host mode */
{
}
else
{
}
}
if (gotgint.b.adevtoutchng)
{}
if (gotgint.b.debdone)
{
USB_OTG_ResetPort(pdev);
}
/* Clear OTG INT */
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GOTGINT, gotgint.d32);
return 1;
}
/**
* @brief USB_OTG_HandleConnectorIDStatusChange_ISR
* handles the Connector ID Status Change Interrupt
* @param None
* @retval : status
*/
static uint32_t USB_OTG_HandleConnectorIDStatusChange_ISR(USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_GINTMSK_TypeDef gintmsk;
USB_OTG_GOTGCTL_TypeDef gotgctl;
USB_OTG_GINTSTS_TypeDef gintsts;
gintsts.d32 = 0 ;
gintmsk.d32 = 0 ;
gotgctl.d32 = 0 ;
gintmsk.b.sofintr = 1;
USB_OTG_MODIFY_REG32(&pdev->regs.GREGS->GINTMSK, gintmsk.d32, 0);
gotgctl.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GOTGCTL);
/* B-Device connector (Device Mode) */
if (gotgctl.b.conidsts)
{
USB_OTG_DisableGlobalInt(pdev);
USB_OTG_CoreInitDev(pdev);
USB_OTG_EnableGlobalInt(pdev);
pdev->otg.OTG_State = B_PERIPHERAL;
}
else
{
USB_OTG_DisableGlobalInt(pdev);
USB_OTG_CoreInitHost(pdev);
USB_OTG_EnableGlobalInt(pdev);
pdev->otg.OTG_State = A_HOST;
}
/* Set flag and clear interrupt */
gintsts.b.conidstschng = 1;
USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GINTSTS, gintsts.d32);
return 1;
}
/**
* @brief USB_OTG_HandleSessionRequest_ISR
* Initiating the Session Request Protocol
* @param None
* @retval : status
*/
static uint32_t USB_OTG_HandleSessionRequest_ISR(USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_GINTSTS_TypeDef gintsts;
USB_OTG_GOTGCTL_TypeDef gotgctl;
gotgctl.d32 = 0;
gintsts.d32 = 0;
gotgctl.d32 = USB_OTG_READ_REG32( &pdev->regs.GREGS->GOTGCTL );
if (USB_OTG_IsDeviceMode(pdev) && (gotgctl.b.bsesvld))
{
}
else if (gotgctl.b.asesvld)
{
}
/* Clear interrupt */
gintsts.d32 = 0;
gintsts.b.sessreqintr = 1;
USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GINTSTS, gintsts.d32);
return 1;
}
/**
* @brief USB_OTG_InitiateSRP
* Initiate an srp session
* @param None
* @retval : None
*/
void USB_OTG_InitiateSRP(USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_GOTGCTL_TypeDef otgctl;
otgctl.d32 = 0;
otgctl.d32 = USB_OTG_READ_REG32( &pdev->regs.GREGS->GOTGCTL );
if (otgctl.b.sesreq)
{
return; /* SRP in progress */
}
otgctl.b.sesreq = 1;
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GOTGCTL, otgctl.d32);
}
/**
* @brief USB_OTG_InitiateHNP
* Initiate HNP
* @param None
* @retval : None
*/
void USB_OTG_InitiateHNP(USB_OTG_CORE_HANDLE *pdev , uint8_t state, uint8_t mode)
{
USB_OTG_GOTGCTL_TypeDef otgctl;
USB_OTG_HPRT0_TypeDef hprt0;
otgctl.d32 = 0;
hprt0.d32 = 0;
otgctl.d32 = USB_OTG_READ_REG32( &pdev->regs.GREGS->GOTGCTL );
if (mode)
{ /* Device mode */
if (state)
{
otgctl.b.devhnpen = 1; /* B-Dev has been enabled to perform HNP */
otgctl.b.hnpreq = 1; /* Initiate an HNP req. to the connected USB host*/
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GOTGCTL, otgctl.d32);
}
}
else
{ /* Host mode */
if (state)
{
otgctl.b.hstsethnpen = 1; /* A-Dev has enabled B-device for HNP */
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GOTGCTL, otgctl.d32);
/* Suspend the bus so that B-dev will disconnect indicating the initial condition for HNP to DWC_Core */
hprt0.d32 = USB_OTG_ReadHPRT0(pdev);
hprt0.b.prtsusp = 1; /* The core clear this bit when disconnect interrupt generated (GINTSTS.DisconnInt = '1') */
USB_OTG_WRITE_REG32(pdev->regs.HPRT0, hprt0.d32);
}
}
}
/**
* @brief USB_OTG_GetCurrentState
* Return current OTG State
* @param None
* @retval : None
*/
uint32_t USB_OTG_GetCurrentState (USB_OTG_CORE_HANDLE *pdev)
{
return pdev->otg.OTG_State;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,125 +0,0 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
/**
* @file connect_usb.c
* @brief support stm32f407-st-discovery-board usb function and register to bus framework
* @version 1.0
* @author AIIT XUOS Lab
* @date 2021-04-25
*/
#include <board.h>
#include "core_cm4.h"
#include "connect_usb.h"
#include "bus_usb.h"
#include "dev_usb.h"
uint32 UdiskRead_new_api(void *dev, struct BusBlockReadParam *read_param);
uint32 UdiskWirte_new_api(void *dev, struct BusBlockWriteParam *write_param);
static uint32 UdiskOpenNewApi(void *dev)
{
return EOK;
}
static uint32 UdiskCloseNewApi(void *dev)
{
return EOK;
}
/*manage the usb device operations*/
static const struct UsbDevDone dev_done =
{
.open = UdiskOpenNewApi,
.close = UdiskCloseNewApi,
.write = UdiskWirte_new_api,
.read = UdiskRead_new_api,
};
/*Init usb bus*/
static int BoardUsbBusInit(struct UsbBus *usb_bus, struct UsbDriver *usb_driver)
{
x_err_t ret = EOK;
/*Init the usb bus */
ret = UsbBusInit(usb_bus, USB_BUS_NAME);
if (EOK != ret) {
KPrintf("board_usb_init UsbBusInit error %d\n", ret);
return ERROR;
}
/*Init the usb driver*/
ret = UsbDriverInit(usb_driver, USB_DRIVER_NAME);
if (EOK != ret) {
KPrintf("board_usb_init UsbDriverInit error %d\n", ret);
return ERROR;
}
/*Attach the usb driver to the usb bus*/
ret = UsbDriverAttachToBus(USB_DRIVER_NAME, USB_BUS_NAME);
if (EOK != ret) {
KPrintf("board_usb_init USEDriverAttachToBus error %d\n", ret);
return ERROR;
}
return ret;
}
/*Attach the usb device to the usb bus*/
static int BoardUsbDevBend(void)
{
x_err_t ret = EOK;
static struct UsbHardwareDevice usb_device1;
memset(&usb_device1, 0, sizeof(struct UsbHardwareDevice));
usb_device1.dev_done = &dev_done;
ret = USBDeviceRegister(&usb_device1, NONE, USB_DEVICE_NAME);
if (EOK != ret) {
KPrintf("board_usb_init USBDeviceInit device %s error %d\n", USB_DEVICE_NAME, ret);
return ERROR;
}
ret = USBDeviceAttachToBus(USB_DEVICE_NAME, USB_BUS_NAME);
if (EOK != ret) {
KPrintf("board_usb_init USBDeviceAttachToBus device %s error %d\n", USB_DEVICE_NAME, ret);
return ERROR;
}
return ret;
}
/*ARM-32 BOARD USB INIT*/
int Stm32HwUsbInit(void)
{
x_err_t ret = EOK;
static struct UsbBus usb_bus;
memset(&usb_bus, 0, sizeof(struct UsbBus));
static struct UsbDriver usb_driver;
memset(&usb_driver, 0, sizeof(struct UsbDriver));
ret = BoardUsbBusInit(&usb_bus, &usb_driver);
if (EOK != ret) {
KPrintf("board_usb_Init error ret %u\n", ret);
return ERROR;
}
ret = BoardUsbDevBend();
if (EOK != ret) {
KPrintf("board_usb_Init error ret %u\n", ret);
return ERROR;
}
return ret;
}

View File

@ -1,236 +0,0 @@
/**
******************************************************************************
* @file usb_bsp.c
* @author xiuos Team
* @version V1.0.0
* @date 2020-9-3
* @brief This file is based on usb_bsp.c
* This file is responsible to offer board support package and is
* configurable by user.
******************************************************************************
* @file usb_bsp.c
* @author MCD Application Team
* @version V1.0.0
* @date 30-September-2011
* ********************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2015 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* <http://www.st.com/SLA0044>
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "usb_bsp.h"
#include <xiuos.h>
#include <hardware_gpio.h>
#include <hardware_rcc.h>
#include <stm32f4xx.h>
#include <misc.h>
/** @addtogroup USB_OTG_DRIVER
* @{
*/
/** @defgroup USB_BSP
* @brief This file is responsible to offer board support package
* @{
*/
/** @defgroup USB_BSP_Private_Defines
* @{
*/
/**
* @}
*/
/** @defgroup USB_BSP_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @defgroup USB_BSP_Private_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USBH_BSP_Private_Variables
* @{
*/
/**
* @}
*/
/** @defgroup USBH_BSP_Private_FunctionPrototypes
* @{
*/
/**
* @}
*/
/** @defgroup USB_BSP_Private_Functions
* @{
*/
/**
* @brief USB_OTG_BSP_Init
* Initializes BSP configurations
* @param None
* @retval None
*/
int USB_OTG_BSP_Init_count = 0;
void USB_OTG_BSP_Init(USB_OTG_CORE_HANDLE *pdev)
{
GPIO_InitTypeDef gpio_initstructure;
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOA, ENABLE);
RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_OTG_FS, ENABLE);
gpio_initstructure.GPIO_Pin = GPIO_Pin_11 | GPIO_Pin_12;
gpio_initstructure.GPIO_Mode = GPIO_Mode_AF;
gpio_initstructure.GPIO_OType = GPIO_OType_PP;
gpio_initstructure.GPIO_Speed = GPIO_Speed_100MHz;
gpio_initstructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_Init(GPIOA, &gpio_initstructure);
GPIO_PinAFConfig(GPIOA,GPIO_PinSource11, GPIO_AF_OTG_FS);
GPIO_PinAFConfig(GPIOA,GPIO_PinSource12, GPIO_AF_OTG_FS);
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOC, ENABLE);
gpio_initstructure.GPIO_Pin = GPIO_Pin_0;
gpio_initstructure.GPIO_Mode = GPIO_Mode_OUT;
gpio_initstructure.GPIO_OType = GPIO_OType_PP;
gpio_initstructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_Init(GPIOC, &gpio_initstructure);
}
/**
* @brief USB_OTG_BSP_ENABLE_INTERRUPT
* Enable USB Global interrupt
* @param None
* @retval None
*/
void USB_OTG_BSP_ENABLE_INTERRUPT(USB_OTG_CORE_HANDLE *pdev)
{
isrManager.done->enableIrq(OTG_FS_IRQn);
}
/**
* @brief BSP_Drive_VBUS
* Drives the Vbus signal through IO
* @param speed : Full, Low
* @param state : VBUS states
* @retval None
*/
void USB_OTG_BSP_DriveVBUS(USB_OTG_CORE_HANDLE *pdev,uint8_t state)
{
if (state == 1)
GPIO_ResetBits(GPIOC, GPIO_Pin_0);
else
GPIO_SetBits(GPIOC, GPIO_Pin_0);
}
/**
* @brief USB_OTG_BSP_ConfigVBUS
* Configures the IO for the Vbus and OverCurrent
* @param Speed : Full, Low
* @retval None
*/
void USB_OTG_BSP_ConfigVBUS(USB_OTG_CORE_HANDLE *pdev)
{
}
/**
* @brief USB_OTG_BSP_TimeInit
* Initialises delay unit Systick timer /Timer2
* @param None
* @retval None
*/
void USB_OTG_BSP_TimeInit ( void )
{
}
/**
* @brief USB_OTG_BSP_uDelay
* This function provides delay time in micro sec
* @param usec : Value of delay required in micro sec
* @retval None
*/
void USB_OTG_BSP_uDelay (const uint32_t usec)
{
uint32_t count = 0;
const uint32_t utime = (120 * usec / 7);
do {
if ( ++count > utime ) {
return ;
}
}
while (1);
}
/**
* @brief USB_OTG_BSP_mDelay
* This function provides delay time in milli sec
* @param msec : Value of delay required in milli sec
* @retval None
*/
void USB_OTG_BSP_mDelay (const uint32_t msec)
{
DelayKTask(msec * TICK_PER_SECOND / 1000);
}
/**
* @brief USB_OTG_BSP_TimerIRQ
* Time base IRQ
* @param None
* @retval None
*/
void USB_OTG_BSP_TimerIRQ (void)
{
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,409 +0,0 @@
/*
* Copyright (c) 2006-2018, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2017-10-30 ZYH the first version
* 2019-12-19 tyustli port to stm32 series
*/
/**
* @file usbh.c
* @brief support stm32f407-st-discovery-board usb function
* @version 1.0
* @author AIIT XUOS Lab
* @date 2021-04-25
*/
/*************************************************
File name: usbh.c
Description: support stm32f407-st-discovery-board usb configure
Others: take RT-Thread v4.0.2/bsp/stm32/libraries/HAL_Drivers/drv_usbh.c for references
https://github.com/RT-Thread/rt-thread/tree/v4.0.2
History:
1. Date: 2021-04-25
Author: AIIT XUOS Lab
Modification:
1. support stm32f407-st-discovery-board usb irq configure
2. support stm32f407-st-discovery-board usb host register
*************************************************/
#include <xiuos.h>
#include <usb_host.h>
#include <hardware_gpio.h>
#include <hardware_rcc.h>
#include <stm32f4xx.h>
#include <misc.h>
#include "usb_bsp.h"
#include "usb_hcd.h"
#include "usb_hcd_int.h"
static USB_OTG_CORE_HANDLE USB_OTG_Core;
static int UrbCompletionSem;
void OTG_FS_IRQHandler(int irq_num, void *arg)
{
USBH_OTG_ISR_Handler(&USB_OTG_Core);
}
DECLARE_HW_IRQ(OTG_FS_IRQn, OTG_FS_IRQHandler, NONE);
static uint8_t SOF_cb(USB_OTG_CORE_HANDLE *pdev)
{
return 0;
}
static uint8_t DevConnected_cb(USB_OTG_CORE_HANDLE *pdev)
{
UhcdPointer hcd = pdev->data;
if (!pdev->host.ConnSts) {
pdev->host.ConnSts = 1;
UsbhRootHubConnectHandler(hcd, 1, RET_FALSE);
}
return 0;
}
static uint8_t DevDisconnected_cb(USB_OTG_CORE_HANDLE *pdev)
{
UhcdPointer hcd = pdev->data;
if (pdev->host.ConnSts) {
pdev->host.ConnSts = 0;
UsbhRootHubDisconnectHandler(hcd, 1);
}
return 0;
}
static uint8_t URBChangeNotify_cb(USB_OTG_CORE_HANDLE *pdev)
{
KSemaphoreAbandon(UrbCompletionSem);
return 0;
}
static uint8_t DevPortEnabled_cb(USB_OTG_CORE_HANDLE *pdev)
{
pdev->host.PortEnabled = 1;
return 0;
}
static uint8_t DevPortDisabled_cb(USB_OTG_CORE_HANDLE *pdev)
{
pdev->host.PortEnabled = 0;
return 0;
}
static USBH_HCD_INT_cb_TypeDef USBH_HCD_INT_cb = {
.SOF = SOF_cb,
.DevConnected = DevConnected_cb,
.DevDisconnected = DevDisconnected_cb,
.DevPortEnabled = DevPortEnabled_cb,
.DevPortDisabled = DevPortDisabled_cb,
.URBChangeNotify = URBChangeNotify_cb,
};
USBH_HCD_INT_cb_TypeDef *USBH_HCD_INT_fops = &USBH_HCD_INT_cb;
static void STM32USBHostChannelOpen(USB_OTG_CORE_HANDLE *pdev, uint8_t hc_num, uint8_t epnum,
uint8_t dev_address, uint8_t speed, uint8_t ep_type, uint16_t mps)
{
pdev->host.hc[hc_num].ep_num = epnum & 0x7F;
pdev->host.hc[hc_num].ep_is_in = (epnum & 0x80 ) == 0x80;
pdev->host.hc[hc_num].DevAddr = dev_address;
pdev->host.hc[hc_num].ep_type = ep_type;
pdev->host.hc[hc_num].max_packet = mps;
pdev->host.hc[hc_num].speed = speed;
pdev->host.hc[hc_num].toggle_in = 0;
pdev->host.hc[hc_num].toggle_out = 0;
if(speed == HPRT0_PRTSPD_HIGH_SPEED) {
pdev->host.hc[hc_num].do_ping = 1;
}
USB_OTG_HC_Init(pdev, hc_num) ;
}
static x_err_t STM32USBHostResetPort(uint8 port)
{
SYS_KDEBUG_LOG(SYS_DEBUG_USB, ("reset port\n"));
HCD_ResetPort(&USB_OTG_Core);
return EOK;
}
x_err_t STM32USBHostChannelSubmitRequest(USB_OTG_CORE_HANDLE *hhcd,
uint8_t ch_num,
uint8_t direction,
uint8_t ep_type,
uint8_t token,
uint8_t *pbuff,
uint16_t length,
uint8_t do_ping)
{
SYS_KDEBUG_LOG(SYS_DEBUG_USB,
("%s: ch_num: %d, direction: %d, ", __func__, ch_num, direction));
hhcd->host.hc[ch_num].ep_is_in = direction;
hhcd->host.hc[ch_num].ep_type = ep_type;
if (token == 0U)
hhcd->host.hc[ch_num].data_pid = HC_PID_SETUP;
else
hhcd->host.hc[ch_num].data_pid = HC_PID_DATA1;
/* Manage Data Toggle */
switch (ep_type) {
case EP_TYPE_CTRL:
SYS_KDEBUG_LOG(SYS_DEBUG_USB, ("EP_TYPE_CTRL\n"));
if ((token == 1U) && (direction == 0U)) {
if (length == 0U)
hhcd->host.hc[ch_num].toggle_out = 1U;
if (hhcd->host.hc[ch_num].toggle_out == 0U)
hhcd->host.hc[ch_num].data_pid = HC_PID_DATA0;
else
hhcd->host.hc[ch_num].data_pid = HC_PID_DATA1;
}
break;
case EP_TYPE_BULK:
SYS_KDEBUG_LOG(SYS_DEBUG_USB, ("EP_TYPE_BULK\n"));
if (direction == 0U) {
if (hhcd->host.hc[ch_num].toggle_out == 0U)
hhcd->host.hc[ch_num].data_pid = HC_PID_DATA0;
else
hhcd->host.hc[ch_num].data_pid = HC_PID_DATA1;
} else {
if (hhcd->host.hc[ch_num].toggle_in == 0U)
hhcd->host.hc[ch_num].data_pid = HC_PID_DATA0;
else
hhcd->host.hc[ch_num].data_pid = HC_PID_DATA1;
}
break;
case EP_TYPE_INTR:
SYS_KDEBUG_LOG(SYS_DEBUG_USB, ("EP_TYPE_INTR\n"));
if (direction == 0U) {
if (hhcd->host.hc[ch_num].toggle_out == 0U)
hhcd->host.hc[ch_num].data_pid = HC_PID_DATA0;
else
hhcd->host.hc[ch_num].data_pid = HC_PID_DATA1;
} else {
if (hhcd->host.hc[ch_num].toggle_in == 0U)
hhcd->host.hc[ch_num].data_pid = HC_PID_DATA0;
else
hhcd->host.hc[ch_num].data_pid = HC_PID_DATA1;
}
break;
case EP_TYPE_ISOC:
SYS_KDEBUG_LOG(SYS_DEBUG_USB, ("EP_TYPE_ISOC\n"));
hhcd->host.hc[ch_num].data_pid = HC_PID_DATA0;
break;
default:
break;
}
hhcd->host.hc[ch_num].xfer_buff = pbuff;
hhcd->host.hc[ch_num].XferLen = length;
hhcd->host.HC_Status[ch_num] = HC_IDLE;
return HCD_SubmitRequest(hhcd, ch_num);
}
static int STM32USBHostPipeXfer(upipe_t pipe, uint8 token, void *buffer, int nbytes, int timeouts)
{
int timeout = timeouts;
int interval = 1;
int retry = 0;
while (1) {
if (!USB_OTG_Core.host.ConnSts)
return -1;
// UrbCompletionSem = KSemaphoreCreate( 0);
KSemaphoreSetValue(UrbCompletionSem, 0);
STM32USBHostChannelSubmitRequest(
&USB_OTG_Core,
pipe->pipe_index,
(pipe->ep.bEndpointAddress & 0x80) >> 7,
pipe->ep.bmAttributes,
token,
buffer,
nbytes,
0
);
MdelayKTask(interval);
KSemaphoreObtain(UrbCompletionSem, timeout);
if (HCD_GetHCState(&USB_OTG_Core, pipe->pipe_index) == HC_NAK) {
SYS_KDEBUG_LOG(SYS_DEBUG_USB, ("nak\n"));
if (pipe->ep.bmAttributes == USB_EP_ATTR_INT)
DelayKTask((pipe->ep.bInterval * TICK_PER_SECOND / 1000) > 0 ? (pipe->ep.bInterval * TICK_PER_SECOND / 1000) : 1);
if (interval < 10) {
interval += 1;
continue;
}
USB_OTG_HC_Halt(&USB_OTG_Core, pipe->pipe_index);
STM32USBHostChannelOpen(
&USB_OTG_Core,
pipe->pipe_index,
pipe->ep.bEndpointAddress,
pipe->inst->address,
USB_OTG_SPEED_FULL,
pipe->ep.bmAttributes,
pipe->ep.wMaxPacketSize
);
if (++retry >= 10) {
SYS_KDEBUG_LOG(SYS_DEBUG_USB, ("NAK retry limit exceeded\n"));
return -1;
}
continue;
} else if (HCD_GetHCState(&USB_OTG_Core, pipe->pipe_index) == HC_STALL) {
SYS_KDEBUG_LOG(SYS_DEBUG_USB, ("stall\n"));
pipe->status = UPIPE_STATUS_STALL;
if (pipe->callback != NONE)
pipe->callback(pipe);
return -1;
} else if (HCD_GetHCState(&USB_OTG_Core, pipe->pipe_index) == URB_ERROR) {
SYS_KDEBUG_LOG(SYS_DEBUG_USB, ("error\n"));
pipe->status = UPIPE_STATUS_ERROR;
if (pipe->callback != NONE)
pipe->callback(pipe);
return -1;
} else if (URB_DONE == HCD_GetHCState(&USB_OTG_Core, pipe->pipe_index)) {
SYS_KDEBUG_LOG(SYS_DEBUG_USB, ("ok\n"));
pipe->status = UPIPE_STATUS_OK;
if (pipe->callback != NONE)
pipe->callback(pipe);
// size_t size = HAL_HCD_HC_GetXferCount(&USB_OTG_Core, pipe->pipe_index);
size_t size = USB_OTG_Core.host.XferCnt[pipe->pipe_index];
if (pipe->ep.bEndpointAddress & 0x80)
return size;
else if (pipe->ep.bEndpointAddress & 0x00)
return size;
return nbytes;
}
continue;
}
}
static uint16 pipe_bitmap;
static uint8 STM32USBHostAllocPipe()
{
for (int i = 1; i < 16; i++)
if ((pipe_bitmap & (1 << i)) == 0) {
pipe_bitmap |= (1 << i);
return i;
}
return 0xff;
}
static void STM32USBHostFreePipe(int i)
{
pipe_bitmap &= ~(1 << i);
}
static x_err_t STM32USBHostOpenPipe(upipe_t pipe)
{
pipe->pipe_index = STM32USBHostAllocPipe();
STM32USBHostChannelOpen(&USB_OTG_Core, pipe->pipe_index, pipe->ep.bEndpointAddress,
pipe->inst->address, USB_OTG_SPEED_FULL, pipe->ep.bmAttributes,
pipe->ep.wMaxPacketSize);
if (USB_OTG_Core.host.hc[pipe->pipe_index].ep_is_in)
USB_OTG_Core.host.hc[pipe->pipe_index].toggle_in = 0;
else
USB_OTG_Core.host.hc[pipe->pipe_index].toggle_out = 0;
return EOK;
}
static x_err_t STM32USBHostClosePipe(upipe_t pipe)
{
USB_OTG_HC_Halt(&USB_OTG_Core, pipe->pipe_index);
STM32USBHostFreePipe(pipe->pipe_index);
return EOK;
}
/* implement these */
static struct uhcd_ops USBHostOps = {
.reset_port = STM32USBHostResetPort,
.pipe_xfer = STM32USBHostPipeXfer,
.open_pipe = STM32USBHostOpenPipe,
.close_pipe = STM32USBHostClosePipe
};
static x_err_t STM32USBHostInit()
{
KPrintf("\nINITIALIZING HOST......\n");
USB_OTG_BSP_Init(&USB_OTG_Core);
HCD_Init(&USB_OTG_Core, USB_OTG_FS_CORE_ID);
// RegisterHwIrq(OTG_FS_IRQn, OTG_FS_IRQHandler, NONE);
USB_OTG_BSP_ENABLE_INTERRUPT(&USB_OTG_Core);
UrbCompletionSem = KSemaphoreCreate( 0);
return EOK;
}
int STM32USBHostRegister()
{
UhcdPointer uhcd = (UhcdPointer)x_malloc(sizeof(struct uhcd));
memset(uhcd, 0, sizeof(struct uhcd));
uhcd->ops = &USBHostOps;
uhcd->NumPorts = 1;
USB_OTG_Core.data = uhcd;
UsbHostInit(uhcd);
STM32USBHostInit();
return EOK;
}
long dump_usb_regs()
{
volatile uint32_t *p = (volatile uint32_t *)0x50000000;
while ((uint32_t)p < 0x50000000 + 80 * 4) {
KPrintf("0x%03X: 0x%08X\n", (uint32_t)p - 0x50000000, *p);
p++;
}
return 0;
}
SHELL_EXPORT_CMD(SHELL_CMD_PERMISSION(0)|SHELL_CMD_TYPE(SHELL_TYPE_CMD_FUNC)|SHELL_CMD_PARAM_NUM(0),dump_usb_regs, dump_usb_regs, dump USB registers );
long dump_hc_regs()
{
for (int i = 0; i < USB_OTG_MAX_TX_FIFOS; i++) {
USB_OTG_HC_REGS *regs = USB_OTG_Core.regs.HC_REGS[i];
KPrintf("EP No.%d:\n", i);
KPrintf(" HCCHAR: 0x%08X\n", regs->HCCHAR);
KPrintf(" HCSPLT: 0x%08X\n", regs->HCSPLT);
KPrintf(" HCINT: 0x%08X\n", regs->HCINT);
KPrintf(" HCINTMSK: 0x%08X\n", regs->HCINTMSK);
KPrintf(" HCTSIZ: 0x%08X\n", regs->HCTSIZ);
KPrintf(" HCDMA: 0x%08X\n", regs->HCDMA);
}
return 0;
}
SHELL_EXPORT_CMD(SHELL_CMD_PERMISSION(0)|SHELL_CMD_TYPE(SHELL_TYPE_CMD_FUNC)|SHELL_CMD_PARAM_NUM(0),dump_hc_regs, dump_hc_regs, dump_hc_regs );

View File

@ -1,14 +0,0 @@
if BSP_USING_WDT
config WDT_BUS_NAME
string "watchdog bus name"
default "wdt"
config WDT_DRIVER_NAME
string "watchdog driver name"
default "wdt_drv"
config WDT_DEVICE_NAME
string "watchdog device name"
default "wdt_dev"
endif

View File

@ -1,5 +0,0 @@
SRC_FILES := hardware_wdg.c connect_wdg.c
include $(KERNEL_ROOT)/compiler.mk

View File

@ -1,132 +0,0 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
/**
* @file connect_wdt.c
* @brief support stm32f407-st-discovery-board watchdog function and register to bus framework
* @version 1.0
* @author AIIT XUOS Lab
* @date 2021-04-25
*/
#include <device.h>
#include "hardware_iwdg.h"
#include "connect_wdg.h"
/**
* This function Watchdog configuration function
*
* @param arg Watchdog device Parameters
*
* @return EOK
*/
static int WdgSet(uint16_t arg)
{
IWDG_Enable();
IWDG_WriteAccessCmd(IWDG_WriteAccess_Enable);
IWDG_SetPrescaler(IWDG_Prescaler_16);
IWDG_SetReload(arg);
while(IWDG_GetFlagStatus(IWDG_FLAG_RVU) != RESET);
IWDG_ReloadCounter();
return 0;
}
/**
* This function Watchdog initialization
*
* @param dev Watchdog driver structure handle
*
* @return EOK
*/
static uint32 WdtOpen(void *dev)
{
WdgSet(4000);
return EOK;
}
/**
* This function Watchdog control function
*
* @param drv Watchdog driver structure handle
*
* @param args Watchdog driver Parameters
*
* @return EOK
*/
static uint32 WdtConfigure(void *drv, struct BusConfigureInfo *args)
{
switch (args->configure_cmd)
{
case OPER_WDT_SET_TIMEOUT:
if (WdgSet((uint16_t)*(int *)args->private_data) != 0) {
return ERROR;
}
break;
case OPER_WDT_KEEPALIVE:
IWDG_ReloadCounter();
break;
default:
return ERROR;
}
return EOK;
}
static const struct WdtDevDone dev_done =
{
WdtOpen,
NONE,
NONE,
NONE,
};
/**
* This function Watchdog initialization
*
* @return EOK
*/
int HwWdtInit(void)
{
x_err_t ret = EOK;
static struct WdtBus wdt;
static struct WdtDriver drv;
static struct WdtHardwareDevice dev;
ret = WdtBusInit(&wdt, WDT_BUS_NAME);
if(ret != EOK){
KPrintf("Watchdog bus init error %d\n", ret);
return ERROR;
}
drv.configure = WdtConfigure;
ret = WdtDriverInit(&drv, WDT_DRIVER_NAME);
if (ret != EOK) {
KPrintf("Watchdog driver init error %d\n", ret);
return ERROR;
}
ret = WdtDriverAttachToBus(WDT_DRIVER_NAME, WDT_BUS_NAME);
if (ret != EOK) {
KPrintf("Watchdog driver attach error %d\n", ret);
return ERROR;
}
dev.dev_done = &dev_done;
ret = WdtDeviceRegister(&dev, WDT_DEVICE_NAME);
if (ret != EOK) {
KPrintf("Watchdog device register error %d\n", ret);
return ERROR;
}
ret = WdtDeviceAttachToBus(WDT_DEVICE_NAME, WDT_BUS_NAME);
if (ret != EOK) {
KPrintf("Watchdog device register error %d\n", ret);
return ERROR;
}
}

View File

@ -1,283 +0,0 @@
/**
******************************************************************************
* @file stm32f4xx_iwdg.c
* @author MCD Application Team
* @version V1.0.0
* @date 30-September-2011
* @brief This file provides firmware functions to manage the following
* functionalities of the Independent watchdog (IWDG) peripheral:
* - Prescaler and Counter configuration
* - IWDG activation
* - Flag management
*
* @verbatim
*
* ===================================================================
* IWDG features
* ===================================================================
*
* The IWDG can be started by either software or hardware (configurable
* through option byte).
*
* The IWDG is clocked by its own dedicated low-speed clock (LSI) and
* thus stays active even if the main clock fails.
* Once the IWDG is started, the LSI is forced ON and cannot be disabled
* (LSI cannot be disabled too), and the counter starts counting down from
* the reset value of 0xFFF. When it reaches the end of count value (0x000)
* a system reset is generated.
* The IWDG counter should be reloaded at regular intervals to prevent
* an MCU reset.
*
* The IWDG is implemented in the VDD voltage domain that is still functional
* in STOP and STANDBY mode (IWDG reset can wake-up from STANDBY).
*
* IWDGRST flag in RCC_CSR register can be used to inform when a IWDG
* reset occurs.
*
* Min-max timeout value @32KHz (LSI): ~125us / ~32.7s
* The IWDG timeout may vary due to LSI frequency dispersion. STM32F4xx
* devices provide the capability to measure the LSI frequency (LSI clock
* connected internally to TIM5 CH4 input capture). The measured value
* can be used to have an IWDG timeout with an acceptable accuracy.
* For more information, please refer to the STM32F4xx Reference manual
*
*
* ===================================================================
* How to use this driver
* ===================================================================
* 1. Enable write access to IWDG_PR and IWDG_RLR registers using
* IWDG_WriteAccessCmd(IWDG_WriteAccess_Enable) function
*
* 2. Configure the IWDG prescaler using IWDG_SetPrescaler() function
*
* 3. Configure the IWDG counter value using IWDG_SetReload() function.
* This value will be loaded in the IWDG counter each time the counter
* is reloaded, then the IWDG will start counting down from this value.
*
* 4. Start the IWDG using IWDG_Enable() function, when the IWDG is used
* in software mode (no need to enable the LSI, it will be enabled
* by hardware)
*
* 5. Then the application program must reload the IWDG counter at regular
* intervals during normal operation to prevent an MCU reset, using
* IWDG_ReloadCounter() function.
*
* @endverbatim
*
******************************************************************************
* @attention
*
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/**
* @file: hardware_wdg.c
* @brief: support hardware wdg function
* @version: 1.0
* @author: AIIT XUOS Lab
* @date: 2021/4/25
*/
/*************************************************
File name: hardware_wdg.c
Description: support hardware wdg function
Others:
History:
1. Date: 2021-04-25
Author: AIIT XUOS Lab
Modification:
1. rename stm32f4xx_iwdg.c for XiUOS
*************************************************/
/* Includes ------------------------------------------------------------------*/
#include <hardware_iwdg.h>
#include <stm32_assert_template.h>
/** @addtogroup STM32F4xx_StdPeriph_Driver
* @{
*/
/** @defgroup IWDG
* @brief IWDG driver modules
* @{
*/
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* KR register bit mask */
#define KR_KEY_RELOAD ((uint16_t)0xAAAA)
#define KR_KEY_ENABLE ((uint16_t)0xCCCC)
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup IWDG_Private_Functions
* @{
*/
/** @defgroup IWDG_Group1 Prescaler and Counter configuration functions
* @brief Prescaler and Counter configuration functions
*
@verbatim
===============================================================================
Prescaler and Counter configuration functions
===============================================================================
@endverbatim
* @{
*/
/**
* @brief Enables or disables write access to IWDG_PR and IWDG_RLR registers.
* @param IWDG_WriteAccess: new state of write access to IWDG_PR and IWDG_RLR registers.
* This parameter can be one of the following values:
* @arg IWDG_WriteAccess_Enable: Enable write access to IWDG_PR and IWDG_RLR registers
* @arg IWDG_WriteAccess_Disable: Disable write access to IWDG_PR and IWDG_RLR registers
* @retval None
*/
void IWDG_WriteAccessCmd(uint16_t IWDG_WriteAccess)
{
/* Check the parameters */
assert_param(IS_IWDG_WRITE_ACCESS(IWDG_WriteAccess));
IWDG->KR = IWDG_WriteAccess;
}
/**
* @brief Sets IWDG Prescaler value.
* @param IWDG_Prescaler: specifies the IWDG Prescaler value.
* This parameter can be one of the following values:
* @arg IWDG_Prescaler_4: IWDG prescaler set to 4
* @arg IWDG_Prescaler_8: IWDG prescaler set to 8
* @arg IWDG_Prescaler_16: IWDG prescaler set to 16
* @arg IWDG_Prescaler_32: IWDG prescaler set to 32
* @arg IWDG_Prescaler_64: IWDG prescaler set to 64
* @arg IWDG_Prescaler_128: IWDG prescaler set to 128
* @arg IWDG_Prescaler_256: IWDG prescaler set to 256
* @retval None
*/
void IWDG_SetPrescaler(uint8_t IWDG_Prescaler)
{
/* Check the parameters */
assert_param(IS_IWDG_PRESCALER(IWDG_Prescaler));
IWDG->PR = IWDG_Prescaler;
}
/**
* @brief Sets IWDG Reload value.
* @param Reload: specifies the IWDG Reload value.
* This parameter must be a number between 0 and 0x0FFF.
* @retval None
*/
void IWDG_SetReload(uint16_t Reload)
{
/* Check the parameters */
assert_param(IS_IWDG_RELOAD(Reload));
IWDG->RLR = Reload;
}
/**
* @brief Reloads IWDG counter with value defined in the reload register
* (write access to IWDG_PR and IWDG_RLR registers disabled).
* @param None
* @retval None
*/
void IWDG_ReloadCounter(void)
{
IWDG->KR = KR_KEY_RELOAD;
}
/**
* @}
*/
/** @defgroup IWDG_Group2 IWDG activation function
* @brief IWDG activation function
*
@verbatim
===============================================================================
IWDG activation function
===============================================================================
@endverbatim
* @{
*/
/**
* @brief Enables IWDG (write access to IWDG_PR and IWDG_RLR registers disabled).
* @param None
* @retval None
*/
void IWDG_Enable(void)
{
IWDG->KR = KR_KEY_ENABLE;
}
/**
* @}
*/
/** @defgroup IWDG_Group3 Flag management function
* @brief Flag management function
*
@verbatim
===============================================================================
Flag management function
===============================================================================
@endverbatim
* @{
*/
/**
* @brief Checks whether the specified IWDG flag is set or not.
* @param IWDG_FLAG: specifies the flag to check.
* This parameter can be one of the following values:
* @arg IWDG_FLAG_PVU: Prescaler Value Update on going
* @arg IWDG_FLAG_RVU: Reload Value Update on going
* @retval The new state of IWDG_FLAG (SET or RESET).
*/
FlagStatus IWDG_GetFlagStatus(uint16_t IWDG_FLAG)
{
FlagStatus bitstatus = RESET;
/* Check the parameters */
assert_param(IS_IWDG_FLAG(IWDG_FLAG));
if ((IWDG->SR & IWDG_FLAG) != (uint32_t)RESET)
{
bitstatus = SET;
}
else
{
bitstatus = RESET;
}
/* Return the flag status */
return bitstatus;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/