未验证 提交 55128eda 编写于 作者: B Bernard Xiong 提交者: GitHub

Merge pull request #3281 from tyustli/usb

[stm32] [drivers] port usb host driver to stm32 new series
......@@ -72,10 +72,10 @@ if GetDepend(['BSP_USING_ON_CHIP_FLASH', 'SOC_SERIES_STM32F7']):
if GetDepend(['BSP_USING_ON_CHIP_FLASH', 'SOC_SERIES_STM32L4']):
src += ['drv_flash/drv_flash_l4.c']
if GetDepend('RT_USING_HWCRYPTO'):
src += ['drv_crypto.c']
if GetDepend(['BSP_USING_WDT']):
src += ['drv_wdt.c']
......@@ -88,6 +88,9 @@ if GetDepend(['BSP_USING_USBD']):
if GetDepend(['BSP_USING_PULSE_ENCODER']):
src += ['drv_pulse_encoder.c']
if GetDepend(['BSP_USING_USBH']):
src += ['drv_usbh.c']
src += ['drv_common.c']
path = [cwd]
......
......@@ -67,6 +67,7 @@ void HAL_ResumeTick(void)
void HAL_Delay(__IO uint32_t Delay)
{
rt_thread_mdelay(Delay);
}
/* re-implement tick interface for STM32 HAL */
......
/*
* 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
*/
#include "drv_usbh.h"
#include "board.h"
static HCD_HandleTypeDef stm32_hhcd_fs;
static struct rt_completion urb_completion;
static volatile rt_bool_t connect_status = RT_FALSE;
void OTG_FS_IRQHandler(void)
{
rt_interrupt_enter();
HAL_HCD_IRQHandler(&stm32_hhcd_fs);
rt_interrupt_leave();
}
void HAL_HCD_Connect_Callback(HCD_HandleTypeDef *hhcd)
{
uhcd_t hcd = (uhcd_t)hhcd->pData;
if (!connect_status)
{
connect_status = RT_TRUE;
RT_DEBUG_LOG(RT_DEBUG_USB, ("usb connected\n"));
rt_usbh_root_hub_connect_handler(hcd, OTG_FS_PORT, RT_FALSE);
}
}
void HAL_HCD_Disconnect_Callback(HCD_HandleTypeDef *hhcd)
{
uhcd_t hcd = (uhcd_t)hhcd->pData;
if (connect_status)
{
connect_status = RT_FALSE;
RT_DEBUG_LOG(RT_DEBUG_USB, ("usb disconnnect\n"));
rt_usbh_root_hub_disconnect_handler(hcd, OTG_FS_PORT);
}
}
void HAL_HCD_HC_NotifyURBChange_Callback(HCD_HandleTypeDef *hhcd, uint8_t chnum, HCD_URBStateTypeDef urb_state)
{
rt_completion_done(&urb_completion);
}
static rt_err_t drv_reset_port(rt_uint8_t port)
{
RT_DEBUG_LOG(RT_DEBUG_USB, ("reset port\n"));
HAL_HCD_ResetPort(&stm32_hhcd_fs);
return RT_EOK;
}
static int drv_pipe_xfer(upipe_t pipe, rt_uint8_t token, void *buffer, int nbytes, int timeouts)
{
int timeout = timeouts;
while (1)
{
if (!connect_status)
{
return -1;
}
rt_completion_init(&urb_completion);
HAL_HCD_HC_SubmitRequest(&stm32_hhcd_fs,
pipe->pipe_index,
(pipe->ep.bEndpointAddress & 0x80) >> 7,
pipe->ep.bmAttributes,
token,
buffer,
nbytes,
0);
rt_completion_wait(&urb_completion, timeout);
rt_thread_mdelay(1);
if (HAL_HCD_HC_GetState(&stm32_hhcd_fs, pipe->pipe_index) == HC_NAK)
{
RT_DEBUG_LOG(RT_DEBUG_USB, ("nak\n"));
if (pipe->ep.bmAttributes == USB_EP_ATTR_INT)
{
rt_thread_delay((pipe->ep.bInterval * RT_TICK_PER_SECOND / 1000) > 0 ? (pipe->ep.bInterval * RT_TICK_PER_SECOND / 1000) : 1);
}
HAL_HCD_HC_Halt(&stm32_hhcd_fs, pipe->pipe_index);
HAL_HCD_HC_Init(&stm32_hhcd_fs,
pipe->pipe_index,
pipe->ep.bEndpointAddress,
pipe->inst->address,
USB_OTG_SPEED_FULL,
pipe->ep.bmAttributes,
pipe->ep.wMaxPacketSize);
continue;
}
else if (HAL_HCD_HC_GetState(&stm32_hhcd_fs, pipe->pipe_index) == HC_STALL)
{
RT_DEBUG_LOG(RT_DEBUG_USB, ("stall\n"));
pipe->status = UPIPE_STATUS_STALL;
if (pipe->callback != RT_NULL)
{
pipe->callback(pipe);
}
return -1;
}
else if (HAL_HCD_HC_GetState(&stm32_hhcd_fs, pipe->pipe_index) == URB_ERROR)
{
RT_DEBUG_LOG(RT_DEBUG_USB, ("error\n"));
pipe->status = UPIPE_STATUS_ERROR;
if (pipe->callback != RT_NULL)
{
pipe->callback(pipe);
}
return -1;
}
else if(URB_DONE == HAL_HCD_HC_GetURBState(&stm32_hhcd_fs, pipe->pipe_index))
{
RT_DEBUG_LOG(RT_DEBUG_USB, ("ok\n"));
pipe->status = UPIPE_STATUS_OK;
if (pipe->callback != RT_NULL)
{
pipe->callback(pipe);
}
size_t size = HAL_HCD_HC_GetXferCount(&stm32_hhcd_fs, pipe->pipe_index);
if (pipe->ep.bEndpointAddress & 0x80)
{
return size;
}
else if (pipe->ep.bEndpointAddress & 0x00)
{
return size;
}
return nbytes;
}
continue;
}
}
static rt_uint16_t pipe_index = 0;
static rt_uint8_t drv_get_free_pipe_index(void)
{
rt_uint8_t idx;
for (idx = 1; idx < 16; idx++)
{
if (!(pipe_index & (0x01 << idx)))
{
pipe_index |= (0x01 << idx);
return idx;
}
}
return 0xff;
}
static void drv_free_pipe_index(rt_uint8_t index)
{
pipe_index &= ~(0x01 << index);
}
static rt_err_t drv_open_pipe(upipe_t pipe)
{
pipe->pipe_index = drv_get_free_pipe_index();
HAL_HCD_HC_Init(&stm32_hhcd_fs,
pipe->pipe_index,
pipe->ep.bEndpointAddress,
pipe->inst->address,
USB_OTG_SPEED_FULL,
pipe->ep.bmAttributes,
pipe->ep.wMaxPacketSize);
/* Set DATA0 PID token*/
if (stm32_hhcd_fs.hc[pipe->pipe_index].ep_is_in)
{
stm32_hhcd_fs.hc[pipe->pipe_index].toggle_in = 0;
}
else
{
stm32_hhcd_fs.hc[pipe->pipe_index].toggle_out = 0;
}
return RT_EOK;
}
static rt_err_t drv_close_pipe(upipe_t pipe)
{
HAL_HCD_HC_Halt(&stm32_hhcd_fs, pipe->pipe_index);
drv_free_pipe_index(pipe->pipe_index);
return RT_EOK;
}
static struct uhcd_ops _uhcd_ops =
{
drv_reset_port,
drv_pipe_xfer,
drv_open_pipe,
drv_close_pipe,
};
static rt_err_t stm32_hcd_init(rt_device_t device)
{
HCD_HandleTypeDef *hhcd = (HCD_HandleTypeDef *)device->user_data;
hhcd->Instance = USB_OTG_FS;
hhcd->Init.Host_channels = 8;
hhcd->Init.speed = HCD_SPEED_FULL;
hhcd->Init.dma_enable = DISABLE;
hhcd->Init.phy_itface = HCD_PHY_EMBEDDED;
hhcd->Init.Sof_enable = DISABLE;
RT_ASSERT(HAL_HCD_Init(hhcd) == HAL_OK);
HAL_HCD_Start(hhcd);
#ifdef USBH_USING_CONTROLLABLE_POWER
rt_pin_mode(USBH_POWER_PIN, PIN_MODE_OUTPUT);
rt_pin_write(USBH_POWER_PIN, PIN_LOW);
#endif
return RT_EOK;
}
int stm_usbh_register(void)
{
rt_err_t res = -RT_ERROR;
uhcd_t uhcd = (uhcd_t)rt_malloc(sizeof(struct uhcd));
if (uhcd == RT_NULL)
{
rt_kprintf("uhcd malloc failed\r\n");
return -RT_ERROR;
}
rt_memset((void *)uhcd, 0, sizeof(struct uhcd));
uhcd->parent.type = RT_Device_Class_USBHost;
uhcd->parent.init = stm32_hcd_init;
uhcd->parent.user_data = &stm32_hhcd_fs;
uhcd->ops = &_uhcd_ops;
uhcd->num_ports = OTG_FS_PORT;
stm32_hhcd_fs.pData = uhcd;
res = rt_device_register(&uhcd->parent, "usbh", RT_DEVICE_FLAG_DEACTIVATE);
if (res != RT_EOK)
{
rt_kprintf("register usb host failed res = %d\r\n", res);
return -RT_ERROR;
}
rt_usb_host_init();
return RT_EOK;
}
INIT_DEVICE_EXPORT(stm_usbh_register);
/*
* Copyright (c) 2006-2018, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2017-12-12 ZYH the first version
* 2019-12-19 tyustli port to stm32 series
*/
#ifndef __DRV_USBH_H__
#define __DRV_USBH_H__
#include <rtthread.h>
#define OTG_FS_PORT 1
int stm_usbh_register(void);
#endif
/************* end of file ************/
[PreviousGenFiles]
HeaderPath=E:/workspace/rt-thread/bsp/stm32/stm32f407-atk-explorer/board/CubeMX_Config/Inc
HeaderPath=F:/rt-thread/bsp/stm32/stm32f407-atk-explorer/board/CubeMX_Config/Inc
HeaderFiles=stm32f4xx_it.h;stm32f4xx_hal_conf.h;main.h;
SourcePath=E:/workspace/rt-thread/bsp/stm32/stm32f407-atk-explorer/board/CubeMX_Config/Src
SourcePath=F:/rt-thread/bsp/stm32/stm32f407-atk-explorer/board/CubeMX_Config/Src
SourceFiles=stm32f4xx_it.c;stm32f4xx_hal_msp.c;main.c;
[PreviousLibFiles]
LibFiles=Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_eth.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_iwdg.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rtc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rtc_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_sdmmc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_sd.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_uart.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ramfunc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cortex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal.h;Drivers/STM32F4xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_eth.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_iwdg.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rtc.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rtc_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_sdmmc.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_sd.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_spi.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_uart.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ramfunc.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_gpio.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cortex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_eth.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_iwdg.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rtc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rtc_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_sdmmc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_sd.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_uart.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ramfunc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cortex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal.h;Drivers/STM32F4xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h;Drivers/CMSIS/Device/ST/STM32F4xx/Include/stm32f407xx.h;Drivers/CMSIS/Device/ST/STM32F4xx/Include/stm32f4xx.h;Drivers/CMSIS/Device/ST/STM32F4xx/Include/system_stm32f4xx.h;Drivers/CMSIS/Device/ST/STM32F4xx/Source/Templates/system_stm32f4xx.c;Drivers/CMSIS/Include/arm_common_tables.h;Drivers/CMSIS/Include/arm_const_structs.h;Drivers/CMSIS/Include/arm_math.h;Drivers/CMSIS/Include/cmsis_armcc.h;Drivers/CMSIS/Include/cmsis_armcc_V6.h;Drivers/CMSIS/Include/cmsis_gcc.h;Drivers/CMSIS/Include/core_cm0.h;Drivers/CMSIS/Include/core_cm0plus.h;Drivers/CMSIS/Include/core_cm3.h;Drivers/CMSIS/Include/core_cm4.h;Drivers/CMSIS/Include/core_cm7.h;Drivers/CMSIS/Include/core_cmFunc.h;Drivers/CMSIS/Include/core_cmInstr.h;Drivers/CMSIS/Include/core_cmSimd.h;Drivers/CMSIS/Include/core_sc000.h;Drivers/CMSIS/Include/core_sc300.h;
LibFiles=Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_eth.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_iwdg.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rtc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rtc_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_sdmmc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_sd.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_uart.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_hcd.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_usb.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ramfunc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cortex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal.h;Drivers/STM32F4xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_eth.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_iwdg.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rtc.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rtc_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_sdmmc.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_sd.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_spi.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_uart.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_hcd.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_usb.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ramfunc.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_gpio.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cortex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_eth.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_iwdg.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rtc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rtc_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_sdmmc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_sd.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_uart.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_hcd.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_usb.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ramfunc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cortex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal.h;Drivers/STM32F4xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h;Drivers/CMSIS/Device/ST/STM32F4xx/Include/stm32f407xx.h;Drivers/CMSIS/Device/ST/STM32F4xx/Include/stm32f4xx.h;Drivers/CMSIS/Device/ST/STM32F4xx/Include/system_stm32f4xx.h;Drivers/CMSIS/Device/ST/STM32F4xx/Source/Templates/system_stm32f4xx.c;Drivers/CMSIS/Include/arm_common_tables.h;Drivers/CMSIS/Include/arm_const_structs.h;Drivers/CMSIS/Include/arm_math.h;Drivers/CMSIS/Include/cmsis_armcc.h;Drivers/CMSIS/Include/cmsis_armcc_V6.h;Drivers/CMSIS/Include/cmsis_gcc.h;Drivers/CMSIS/Include/core_cm0.h;Drivers/CMSIS/Include/core_cm0plus.h;Drivers/CMSIS/Include/core_cm3.h;Drivers/CMSIS/Include/core_cm4.h;Drivers/CMSIS/Include/core_cm7.h;Drivers/CMSIS/Include/core_cmFunc.h;Drivers/CMSIS/Include/core_cmInstr.h;Drivers/CMSIS/Include/core_cmSimd.h;Drivers/CMSIS/Include/core_sc000.h;Drivers/CMSIS/Include/core_sc300.h;
[PreviousUsedKeilFiles]
SourceFiles=..\Src\main.c;..\Src\stm32f4xx_it.c;..\Src\stm32f4xx_hal_msp.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc_ex.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_eth.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_iwdg.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rtc.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rtc_ex.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_sdmmc.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_sd.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_spi.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim_ex.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_uart.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc_ex.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ex.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ramfunc.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_gpio.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma_ex.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr_ex.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cortex.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c;../\Src/system_stm32f4xx.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc_ex.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_eth.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_iwdg.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rtc.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rtc_ex.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_sdmmc.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_sd.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_spi.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim_ex.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_uart.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc_ex.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ex.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ramfunc.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_gpio.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma_ex.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr_ex.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cortex.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c;../\Src/system_stm32f4xx.c;../Drivers/CMSIS/Device/ST/STM32F4xx/Source/Templates/system_stm32f4xx.c;null;
SourceFiles=..\Src\main.c;..\Src\stm32f4xx_it.c;..\Src\stm32f4xx_hal_msp.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc_ex.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_eth.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_iwdg.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rtc.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rtc_ex.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_sdmmc.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_sd.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_spi.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim_ex.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_uart.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_hcd.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_usb.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc_ex.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ex.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ramfunc.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_gpio.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma_ex.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr_ex.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cortex.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c;../\Src/system_stm32f4xx.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc_ex.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_eth.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_iwdg.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rtc.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rtc_ex.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_sdmmc.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_sd.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_spi.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim_ex.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_uart.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_hcd.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_usb.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc_ex.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ex.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ramfunc.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_gpio.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma_ex.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr_ex.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cortex.c;../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c;../\Src/system_stm32f4xx.c;../Drivers/CMSIS/Device/ST/STM32F4xx/Source/Templates/system_stm32f4xx.c;null;
HeaderPath=..\Drivers\STM32F4xx_HAL_Driver\Inc;..\Drivers\STM32F4xx_HAL_Driver\Inc\Legacy;..\Drivers\CMSIS\Device\ST\STM32F4xx\Include;..\Drivers\CMSIS\Include;..\Inc;
CDefines=USE_HAL_DRIVER;STM32F407xx;USE_HAL_DRIVER;STM32F407xx;
......@@ -19,6 +19,7 @@ Mcu.IP13=TIM13
Mcu.IP14=TIM14
Mcu.IP15=USART1
Mcu.IP16=USART3
Mcu.IP17=USB_OTG_FS
Mcu.IP2=IWDG
Mcu.IP3=NVIC
Mcu.IP4=RCC
......@@ -27,7 +28,7 @@ Mcu.IP6=SDIO
Mcu.IP7=SPI1
Mcu.IP8=SPI2
Mcu.IP9=SYS
Mcu.IPNb=17
Mcu.IPNb=18
Mcu.Name=STM32F407Z(E-G)Tx
Mcu.Package=LQFP144
Mcu.Pin0=PC14-OSC32_IN
......@@ -44,35 +45,37 @@ Mcu.Pin18=PC9
Mcu.Pin19=PA9
Mcu.Pin2=PH0-OSC_IN
Mcu.Pin20=PA10
Mcu.Pin21=PA13
Mcu.Pin22=PA14
Mcu.Pin23=PC10
Mcu.Pin24=PC11
Mcu.Pin25=PC12
Mcu.Pin26=PD2
Mcu.Pin27=PG11
Mcu.Pin28=PG13
Mcu.Pin29=PG14
Mcu.Pin21=PA11
Mcu.Pin22=PA12
Mcu.Pin23=PA13
Mcu.Pin24=PA14
Mcu.Pin25=PC10
Mcu.Pin26=PC11
Mcu.Pin27=PC12
Mcu.Pin28=PD2
Mcu.Pin29=PG11
Mcu.Pin3=PH1-OSC_OUT
Mcu.Pin30=PB3
Mcu.Pin31=PB4
Mcu.Pin32=PB5
Mcu.Pin33=PB6
Mcu.Pin34=PB7
Mcu.Pin35=VP_IWDG_VS_IWDG
Mcu.Pin36=VP_RTC_VS_RTC_Activate
Mcu.Pin37=VP_SYS_VS_Systick
Mcu.Pin38=VP_TIM2_VS_ClockSourceINT
Mcu.Pin39=VP_TIM11_VS_ClockSourceINT
Mcu.Pin30=PG13
Mcu.Pin31=PG14
Mcu.Pin32=PB3
Mcu.Pin33=PB4
Mcu.Pin34=PB5
Mcu.Pin35=PB6
Mcu.Pin36=PB7
Mcu.Pin37=VP_IWDG_VS_IWDG
Mcu.Pin38=VP_RTC_VS_RTC_Activate
Mcu.Pin39=VP_SYS_VS_Systick
Mcu.Pin4=PC1
Mcu.Pin40=VP_TIM13_VS_ClockSourceINT
Mcu.Pin41=VP_TIM14_VS_ClockSourceINT
Mcu.Pin40=VP_TIM2_VS_ClockSourceINT
Mcu.Pin41=VP_TIM11_VS_ClockSourceINT
Mcu.Pin42=VP_TIM13_VS_ClockSourceINT
Mcu.Pin43=VP_TIM14_VS_ClockSourceINT
Mcu.Pin5=PC2
Mcu.Pin6=PC3
Mcu.Pin7=PA1
Mcu.Pin8=PA2
Mcu.Pin9=PA3
Mcu.PinsNb=42
Mcu.PinsNb=44
Mcu.ThirdPartyNb=0
Mcu.UserConstants=
Mcu.UserName=STM32F407ZGTx
......@@ -83,6 +86,7 @@ NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:false\:false
NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false
NVIC.MemoryManagement_IRQn=true\:0\:0\:false\:false\:true\:false\:false
NVIC.NonMaskableInt_IRQn=true\:0\:0\:false\:false\:true\:false\:false
NVIC.OTG_FS_IRQn=true\:0\:0\:false\:false\:true\:true\:true
NVIC.PendSV_IRQn=true\:0\:0\:false\:false\:true\:false\:false
NVIC.PriorityGroup=NVIC_PRIORITYGROUP_4
NVIC.SPI1_IRQn=true\:0\:0\:false\:false\:true\:true\:true
......@@ -94,6 +98,10 @@ PA1.Mode=RMII
PA1.Signal=ETH_REF_CLK
PA10.Mode=Asynchronous
PA10.Signal=USART1_RX
PA11.Mode=Host_Only
PA11.Signal=USB_OTG_FS_DM
PA12.Mode=Host_Only
PA12.Signal=USB_OTG_FS_DP
PA13.Mode=Serial_Wire
PA13.Signal=SYS_JTMS-SWDIO
PA14.Mode=Serial_Wire
......@@ -174,7 +182,7 @@ PH0-OSC_IN.Signal=RCC_OSC_IN
PH1-OSC_OUT.Mode=HSE-External-Oscillator
PH1-OSC_OUT.Signal=RCC_OSC_OUT
PinOutPanel.RotationAngle=0
ProjectManager.AskForMigrate=false
ProjectManager.AskForMigrate=true
ProjectManager.BackupPrevious=false
ProjectManager.CompilerOptimize=6
ProjectManager.ComputerToolchain=false
......@@ -260,6 +268,9 @@ USART1.IPParameters=VirtualMode
USART1.VirtualMode=VM_ASYNC
USART3.IPParameters=VirtualMode
USART3.VirtualMode=VM_ASYNC
USB_OTG_FS.IPParameters=VirtualMode,phy_itface
USB_OTG_FS.VirtualMode=Host_Only
USB_OTG_FS.phy_itface=HCD_PHY_EMBEDDED
VP_IWDG_VS_IWDG.Mode=IWDG_Activate
VP_IWDG_VS_IWDG.Signal=IWDG_VS_IWDG
VP_RTC_VS_RTC_Activate.Mode=RTC_Enabled
......
......@@ -81,7 +81,7 @@
/* #define HAL_SMARTCARD_MODULE_ENABLED */
/* #define HAL_WWDG_MODULE_ENABLED */
/* #define HAL_PCD_MODULE_ENABLED */
/* #define HAL_HCD_MODULE_ENABLED */
#define HAL_HCD_MODULE_ENABLED
/* #define HAL_DSI_MODULE_ENABLED */
/* #define HAL_QSPI_MODULE_ENABLED */
/* #define HAL_QSPI_MODULE_ENABLED */
......
......@@ -73,6 +73,7 @@ void PendSV_Handler(void);
void SysTick_Handler(void);
void SPI1_IRQHandler(void);
void USART1_IRQHandler(void);
void OTG_FS_IRQHandler(void);
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */
......
......@@ -84,6 +84,8 @@ TIM_HandleTypeDef htim14;
UART_HandleTypeDef huart1;
UART_HandleTypeDef huart3;
HCD_HandleTypeDef hhcd_USB_OTG_FS;
/* USER CODE BEGIN PV */
/* Private variables ---------------------------------------------------------*/
......@@ -106,6 +108,7 @@ static void MX_SDIO_SD_Init(void);
static void MX_TIM2_Init(void);
static void MX_SPI2_Init(void);
static void MX_TIM4_Init(void);
static void MX_USB_OTG_FS_HCD_Init(void);
/* USER CODE BEGIN PFP */
/* Private function prototypes -----------------------------------------------*/
......@@ -158,6 +161,7 @@ int main(void)
MX_TIM2_Init();
MX_SPI2_Init();
MX_TIM4_Init();
MX_USB_OTG_FS_HCD_Init();
/* USER CODE BEGIN 2 */
/* USER CODE END 2 */
......@@ -758,6 +762,37 @@ static void MX_USART3_UART_Init(void)
}
/**
* @brief USB_OTG_FS Initialization Function
* @param None
* @retval None
*/
static void MX_USB_OTG_FS_HCD_Init(void)
{
/* USER CODE BEGIN USB_OTG_FS_Init 0 */
/* USER CODE END USB_OTG_FS_Init 0 */
/* USER CODE BEGIN USB_OTG_FS_Init 1 */
/* USER CODE END USB_OTG_FS_Init 1 */
hhcd_USB_OTG_FS.Instance = USB_OTG_FS;
hhcd_USB_OTG_FS.Init.Host_channels = 8;
hhcd_USB_OTG_FS.Init.speed = HCD_SPEED_FULL;
hhcd_USB_OTG_FS.Init.dma_enable = DISABLE;
hhcd_USB_OTG_FS.Init.phy_itface = HCD_PHY_EMBEDDED;
hhcd_USB_OTG_FS.Init.Sof_enable = DISABLE;
if (HAL_HCD_Init(&hhcd_USB_OTG_FS) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN USB_OTG_FS_Init 2 */
/* USER CODE END USB_OTG_FS_Init 2 */
}
/**
* @brief GPIO Initialization Function
* @param None
......
......@@ -852,6 +852,79 @@ void HAL_UART_MspDeInit(UART_HandleTypeDef* huart)
}
/**
* @brief HCD MSP Initialization
* This function configures the hardware resources used in this example
* @param hhcd: HCD handle pointer
* @retval None
*/
void HAL_HCD_MspInit(HCD_HandleTypeDef* hhcd)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
if(hhcd->Instance==USB_OTG_FS)
{
/* USER CODE BEGIN USB_OTG_FS_MspInit 0 */
/* USER CODE END USB_OTG_FS_MspInit 0 */
__HAL_RCC_GPIOA_CLK_ENABLE();
/**USB_OTG_FS GPIO Configuration
PA11 ------> USB_OTG_FS_DM
PA12 ------> USB_OTG_FS_DP
*/
GPIO_InitStruct.Pin = GPIO_PIN_11|GPIO_PIN_12;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
/* Peripheral clock enable */
__HAL_RCC_USB_OTG_FS_CLK_ENABLE();
/* USB_OTG_FS interrupt Init */
HAL_NVIC_SetPriority(OTG_FS_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(OTG_FS_IRQn);
/* USER CODE BEGIN USB_OTG_FS_MspInit 1 */
/* USER CODE END USB_OTG_FS_MspInit 1 */
}
}
/**
* @brief HCD MSP De-Initialization
* This function freeze the hardware resources used in this example
* @param hhcd: HCD handle pointer
* @retval None
*/
void HAL_HCD_MspDeInit(HCD_HandleTypeDef* hhcd)
{
if(hhcd->Instance==USB_OTG_FS)
{
/* USER CODE BEGIN USB_OTG_FS_MspDeInit 0 */
/* USER CODE END USB_OTG_FS_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_USB_OTG_FS_CLK_DISABLE();
/**USB_OTG_FS GPIO Configuration
PA11 ------> USB_OTG_FS_DM
PA12 ------> USB_OTG_FS_DP
*/
HAL_GPIO_DeInit(GPIOA, GPIO_PIN_11|GPIO_PIN_12);
/* USB_OTG_FS interrupt DeInit */
HAL_NVIC_DisableIRQ(OTG_FS_IRQn);
/* USER CODE BEGIN USB_OTG_FS_MspDeInit 1 */
/* USER CODE END USB_OTG_FS_MspDeInit 1 */
}
}
/* USER CODE BEGIN 1 */
/* USER CODE END 1 */
......
......@@ -73,6 +73,7 @@
/* External variables --------------------------------------------------------*/
extern SPI_HandleTypeDef hspi1;
extern UART_HandleTypeDef huart1;
extern HCD_HandleTypeDef hhcd_USB_OTG_FS;
/* USER CODE BEGIN EV */
/* USER CODE END EV */
......@@ -241,6 +242,20 @@ void USART1_IRQHandler(void)
/* USER CODE END USART1_IRQn 1 */
}
/**
* @brief This function handles USB On The Go FS global interrupt.
*/
void OTG_FS_IRQHandler(void)
{
/* USER CODE BEGIN OTG_FS_IRQn 0 */
/* USER CODE END OTG_FS_IRQn 0 */
HAL_HCD_IRQHandler(&hhcd_USB_OTG_FS);
/* USER CODE BEGIN OTG_FS_IRQn 1 */
/* USER CODE END OTG_FS_IRQn 1 */
}
/* USER CODE BEGIN 1 */
/* USER CODE END 1 */
......
......@@ -296,6 +296,21 @@ menu "On-chip Peripheral Drivers"
select RT_USING_DFS
default n
menuconfig BSP_USING_USBH
bool "Enable USB Host"
select RT_USING_USB_HOST
default n
if BSP_USING_USBH
menuconfig RT_USBH_MSTORAGE
bool "Enable Udisk Drivers"
default n
if RT_USBH_MSTORAGE
config UDISK_MOUNTPOINT
string "Udisk mount dir"
default "/"
endif
endif
menuconfig BSP_USING_PULSE_ENCODER
bool "Enable Pulse Encoder"
default n
......
......@@ -47,7 +47,7 @@
| MPU9250九轴传感器 | 支持 | |
| SDRAM | 支持 | |
| SD卡 | 支持 | |
| CAN | 暂不支持 | |
| CAN | 支持 | 和 USB Host 引脚冲突,如需使用该外设,请使用 CubeMX 重新配置 |
| **片上外设** | **支持情况** | **备注** |
| GPIO | 支持 | PA0, PA1... PK15 ---> PIN: 0, 1...176 |
| UART | 支持 | UART1/2/3 |
......@@ -61,7 +61,7 @@
| SDIO | 支持 | |
| PWM | 支持 | |
| USB Device | 暂不支持 | 即将支持 |
| USB Host | 暂不支持 | 即将支持 |
| USB Host | 支持 | 和 CAN1 引脚冲突,如需使用该外设,请使用 CubeMX 重新配置 |
| **扩展模块** | **支持情况** | **备注** |
| ATK-ESP8266 模块 | 暂不支持 | 即将支持 |
......
......@@ -38,7 +38,7 @@
#define HAL_ADC_MODULE_ENABLED
/* #define HAL_CRYP_MODULE_ENABLED */
#define HAL_CAN_MODULE_ENABLED
/* #define HAL_CAN_MODULE_ENABLED */
/* #define HAL_CRC_MODULE_ENABLED */
/* #define HAL_CRYP_MODULE_ENABLED */
/* #define HAL_DAC_MODULE_ENABLED */
......@@ -68,7 +68,7 @@
/* #define HAL_SMARTCARD_MODULE_ENABLED */
/* #define HAL_WWDG_MODULE_ENABLED */
/* #define HAL_PCD_MODULE_ENABLED */
/* #define HAL_HCD_MODULE_ENABLED */
#define HAL_HCD_MODULE_ENABLED
/* #define HAL_DSI_MODULE_ENABLED */
/* #define HAL_QSPI_MODULE_ENABLED */
/* #define HAL_QSPI_MODULE_ENABLED */
......
......@@ -72,6 +72,7 @@ void DebugMon_Handler(void);
void PendSV_Handler(void);
void SysTick_Handler(void);
void USART1_IRQHandler(void);
void OTG_FS_IRQHandler(void);
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */
......
......@@ -5,34 +5,32 @@ ADC1.NbrOfConversionFlag=1
ADC1.Rank-0\#ChannelRegularConversion=1
ADC1.SamplingTime-0\#ChannelRegularConversion=ADC_SAMPLETIME_3CYCLES
ADC1.master=1
CAN1.CalculateTimeQuantum=355.55555555555554
CAN1.IPParameters=CalculateTimeQuantum
ETH.IPParameters=MediaInterface
ETH.MediaInterface=ETH_MEDIA_INTERFACE_RMII
File.Version=6
KeepUserPlacement=false
Mcu.Family=STM32F4
Mcu.IP0=ADC1
Mcu.IP1=CAN1
Mcu.IP10=SPI1
Mcu.IP11=SPI2
Mcu.IP12=SPI5
Mcu.IP13=SYS
Mcu.IP14=TIM2
Mcu.IP15=TIM11
Mcu.IP16=TIM13
Mcu.IP17=TIM14
Mcu.IP18=USART1
Mcu.IP19=USART2
Mcu.IP2=ETH
Mcu.IP20=USART3
Mcu.IP3=FMC
Mcu.IP4=IWDG
Mcu.IP5=NVIC
Mcu.IP6=RCC
Mcu.IP7=RTC
Mcu.IP8=SAI1
Mcu.IP9=SDIO
Mcu.IP1=ETH
Mcu.IP10=SPI2
Mcu.IP11=SPI5
Mcu.IP12=SYS
Mcu.IP13=TIM2
Mcu.IP14=TIM11
Mcu.IP15=TIM13
Mcu.IP16=TIM14
Mcu.IP17=USART1
Mcu.IP18=USART2
Mcu.IP19=USART3
Mcu.IP2=FMC
Mcu.IP20=USB_OTG_FS
Mcu.IP3=IWDG
Mcu.IP4=NVIC
Mcu.IP5=RCC
Mcu.IP6=RTC
Mcu.IP7=SAI1
Mcu.IP8=SDIO
Mcu.IP9=SPI1
Mcu.IPNb=21
Mcu.Name=STM32F429I(E-G)Tx
Mcu.Package=LQFP176
......@@ -138,6 +136,7 @@ NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:false\:false
NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false
NVIC.MemoryManagement_IRQn=true\:0\:0\:false\:false\:true\:false\:false
NVIC.NonMaskableInt_IRQn=true\:0\:0\:false\:false\:true\:false\:false
NVIC.OTG_FS_IRQn=true\:0\:0\:false\:false\:true\:true\:true
NVIC.PendSV_IRQn=true\:0\:0\:false\:false\:true\:false\:false
NVIC.PriorityGroup=NVIC_PRIORITYGROUP_4
NVIC.SVCall_IRQn=true\:0\:0\:false\:false\:true\:false\:false
......@@ -148,11 +147,10 @@ PA1.Mode=RMII
PA1.Signal=ETH_REF_CLK
PA10.Mode=Asynchronous
PA10.Signal=USART1_RX
PA11.Locked=true
PA11.Mode=Master
PA11.Signal=CAN1_RX
PA12.Mode=Master
PA12.Signal=CAN1_TX
PA11.Mode=Host_Only
PA11.Signal=USB_OTG_FS_DM
PA12.Mode=Host_Only
PA12.Signal=USB_OTG_FS_DP
PA13.Mode=Serial_Wire
PA13.Signal=SYS_JTMS-SWDIO
PA14.Mode=Serial_Wire
......@@ -300,7 +298,7 @@ ProjectManager.FreePins=false
ProjectManager.HalAssertFull=false
ProjectManager.HeapSize=0x200
ProjectManager.KeepUserCode=true
ProjectManager.LastFirmware=true
ProjectManager.LastFirmware=false
ProjectManager.LibraryCopy=0
ProjectManager.MainLocation=Src
ProjectManager.NoMain=false
......@@ -357,8 +355,7 @@ RCC.VCOSAIOutputFreq_ValueR=50000000
RCC.VcooutputI2S=160000000
RCC.VcooutputI2SQ=160000000
SAI1.ErrorAudioFreq-SAI_A_MasterWithClock=-49.13 %
SAI1.FrameLength-SAI_B_SyncSlave=8
SAI1.IPParameters=Instance-SAI_B_SyncSlave,VirtualMode-SAI_B_SyncSlave,Synchro-SAI_B_SyncSlave,FrameLength-SAI_B_SyncSlave,Instance-SAI_A_MasterWithClock,VirtualMode-SAI_A_MasterWithClock,Synchro-SAI_A_MasterWithClock,MClockEnable-SAI_A_MasterWithClock,RealAudioFreq-SAI_A_MasterWithClock,ErrorAudioFreq-SAI_A_MasterWithClock
SAI1.IPParameters=Instance-SAI_B_SyncSlave,VirtualMode-SAI_B_SyncSlave,Synchro-SAI_B_SyncSlave,Instance-SAI_A_MasterWithClock,VirtualMode-SAI_A_MasterWithClock,Synchro-SAI_A_MasterWithClock,MClockEnable-SAI_A_MasterWithClock,RealAudioFreq-SAI_A_MasterWithClock,ErrorAudioFreq-SAI_A_MasterWithClock
SAI1.Instance-SAI_A_MasterWithClock=SAI$Index_Block_A
SAI1.Instance-SAI_B_SyncSlave=SAI$Index_Block_B
SAI1.MClockEnable-SAI_A_MasterWithClock=SAI_MASTERCLOCK_ENABLE
......@@ -468,6 +465,9 @@ USART2.IPParameters=VirtualMode
USART2.VirtualMode=VM_ASYNC
USART3.IPParameters=VirtualMode
USART3.VirtualMode=VM_ASYNC
USB_OTG_FS.IPParameters=VirtualMode,phy_itface
USB_OTG_FS.VirtualMode=Host_Only
USB_OTG_FS.phy_itface=HCD_PHY_EMBEDDED
VP_IWDG_VS_IWDG.Mode=IWDG_Activate
VP_IWDG_VS_IWDG.Signal=IWDG_VS_IWDG
VP_RTC_VS_RTC_Activate.Mode=RTC_Enabled
......
......@@ -64,8 +64,6 @@
/* Private variables ---------------------------------------------------------*/
ADC_HandleTypeDef hadc1;
CAN_HandleTypeDef hcan1;
ETH_HandleTypeDef heth;
IWDG_HandleTypeDef hiwdg;
......@@ -90,6 +88,8 @@ UART_HandleTypeDef huart1;
UART_HandleTypeDef huart2;
UART_HandleTypeDef huart3;
HCD_HandleTypeDef hhcd_USB_OTG_FS;
SDRAM_HandleTypeDef hsdram1;
/* USER CODE BEGIN PV */
......@@ -114,10 +114,10 @@ static void MX_TIM2_Init(void);
static void MX_SPI1_Init(void);
static void MX_SPI2_Init(void);
static void MX_SPI5_Init(void);
static void MX_CAN1_Init(void);
static void MX_SAI1_Init(void);
static void MX_USART2_UART_Init(void);
static void MX_USART3_UART_Init(void);
static void MX_USB_OTG_FS_HCD_Init(void);
/* USER CODE BEGIN PFP */
/* Private function prototypes -----------------------------------------------*/
......@@ -171,10 +171,10 @@ int main(void)
MX_SPI1_Init();
MX_SPI2_Init();
MX_SPI5_Init();
MX_CAN1_Init();
MX_SAI1_Init();
MX_USART2_UART_Init();
MX_USART3_UART_Init();
MX_USB_OTG_FS_HCD_Init();
/* USER CODE BEGIN 2 */
/* USER CODE END 2 */
......@@ -309,43 +309,6 @@ static void MX_ADC1_Init(void)
}
/**
* @brief CAN1 Initialization Function
* @param None
* @retval None
*/
static void MX_CAN1_Init(void)
{
/* USER CODE BEGIN CAN1_Init 0 */
/* USER CODE END CAN1_Init 0 */
/* USER CODE BEGIN CAN1_Init 1 */
/* USER CODE END CAN1_Init 1 */
hcan1.Instance = CAN1;
hcan1.Init.Prescaler = 16;
hcan1.Init.Mode = CAN_MODE_NORMAL;
hcan1.Init.SyncJumpWidth = CAN_SJW_1TQ;
hcan1.Init.TimeSeg1 = CAN_BS1_1TQ;
hcan1.Init.TimeSeg2 = CAN_BS2_1TQ;
hcan1.Init.TimeTriggeredMode = DISABLE;
hcan1.Init.AutoBusOff = DISABLE;
hcan1.Init.AutoWakeUp = DISABLE;
hcan1.Init.AutoRetransmission = DISABLE;
hcan1.Init.ReceiveFifoLocked = DISABLE;
hcan1.Init.TransmitFifoPriority = DISABLE;
if (HAL_CAN_Init(&hcan1) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN CAN1_Init 2 */
/* USER CODE END CAN1_Init 2 */
}
/**
* @brief ETH Initialization Function
* @param None
......@@ -500,7 +463,7 @@ static void MX_SAI1_Init(void)
hsai_BlockB1.Init.ClockStrobing = SAI_CLOCKSTROBING_FALLINGEDGE;
hsai_BlockB1.Init.OutputDrive = SAI_OUTPUTDRIVE_DISABLE;
hsai_BlockB1.Init.FIFOThreshold = SAI_FIFOTHRESHOLD_EMPTY;
hsai_BlockB1.FrameInit.FrameLength = 8;
hsai_BlockB1.FrameInit.FrameLength = 24;
hsai_BlockB1.FrameInit.ActiveFrameLength = 1;
hsai_BlockB1.FrameInit.FSDefinition = SAI_FS_STARTFRAME;
hsai_BlockB1.FrameInit.FSPolarity = SAI_FS_ACTIVE_LOW;
......@@ -920,6 +883,37 @@ static void MX_USART3_UART_Init(void)
}
/**
* @brief USB_OTG_FS Initialization Function
* @param None
* @retval None
*/
static void MX_USB_OTG_FS_HCD_Init(void)
{
/* USER CODE BEGIN USB_OTG_FS_Init 0 */
/* USER CODE END USB_OTG_FS_Init 0 */
/* USER CODE BEGIN USB_OTG_FS_Init 1 */
/* USER CODE END USB_OTG_FS_Init 1 */
hhcd_USB_OTG_FS.Instance = USB_OTG_FS;
hhcd_USB_OTG_FS.Init.Host_channels = 8;
hhcd_USB_OTG_FS.Init.speed = HCD_SPEED_FULL;
hhcd_USB_OTG_FS.Init.dma_enable = DISABLE;
hhcd_USB_OTG_FS.Init.phy_itface = HCD_PHY_EMBEDDED;
hhcd_USB_OTG_FS.Init.Sof_enable = DISABLE;
if (HAL_HCD_Init(&hhcd_USB_OTG_FS) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN USB_OTG_FS_Init 2 */
/* USER CODE END USB_OTG_FS_Init 2 */
}
/* FMC initialization function */
static void MX_FMC_Init(void)
{
......
......@@ -160,71 +160,6 @@ void HAL_ADC_MspDeInit(ADC_HandleTypeDef* hadc)
}
/**
* @brief CAN MSP Initialization
* This function configures the hardware resources used in this example
* @param hcan: CAN handle pointer
* @retval None
*/
void HAL_CAN_MspInit(CAN_HandleTypeDef* hcan)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
if(hcan->Instance==CAN1)
{
/* USER CODE BEGIN CAN1_MspInit 0 */
/* USER CODE END CAN1_MspInit 0 */
/* Peripheral clock enable */
__HAL_RCC_CAN1_CLK_ENABLE();
__HAL_RCC_GPIOA_CLK_ENABLE();
/**CAN1 GPIO Configuration
PA11 ------> CAN1_RX
PA12 ------> CAN1_TX
*/
GPIO_InitStruct.Pin = GPIO_PIN_11|GPIO_PIN_12;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF9_CAN1;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
/* USER CODE BEGIN CAN1_MspInit 1 */
/* USER CODE END CAN1_MspInit 1 */
}
}
/**
* @brief CAN MSP De-Initialization
* This function freeze the hardware resources used in this example
* @param hcan: CAN handle pointer
* @retval None
*/
void HAL_CAN_MspDeInit(CAN_HandleTypeDef* hcan)
{
if(hcan->Instance==CAN1)
{
/* USER CODE BEGIN CAN1_MspDeInit 0 */
/* USER CODE END CAN1_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_CAN1_CLK_DISABLE();
/**CAN1 GPIO Configuration
PA11 ------> CAN1_RX
PA12 ------> CAN1_TX
*/
HAL_GPIO_DeInit(GPIOA, GPIO_PIN_11|GPIO_PIN_12);
/* USER CODE BEGIN CAN1_MspDeInit 1 */
/* USER CODE END CAN1_MspDeInit 1 */
}
}
/**
* @brief ETH MSP Initialization
* This function configures the hardware resources used in this example
......@@ -909,6 +844,76 @@ void HAL_UART_MspDeInit(UART_HandleTypeDef* huart)
}
/**
* @brief HCD MSP Initialization
* This function configures the hardware resources used in this example
* @param hhcd: HCD handle pointer
* @retval None
*/
void HAL_HCD_MspInit(HCD_HandleTypeDef* hhcd)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
if(hhcd->Instance==USB_OTG_FS)
{
/* USER CODE BEGIN USB_OTG_FS_MspInit 0 */
/* USER CODE END USB_OTG_FS_MspInit 0 */
__HAL_RCC_GPIOA_CLK_ENABLE();
/**USB_OTG_FS GPIO Configuration
PA11 ------> USB_OTG_FS_DM
PA12 ------> USB_OTG_FS_DP
*/
GPIO_InitStruct.Pin = GPIO_PIN_11|GPIO_PIN_12;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
/* Peripheral clock enable */
__HAL_RCC_USB_OTG_FS_CLK_ENABLE();
/* USB_OTG_FS interrupt Init */
HAL_NVIC_SetPriority(OTG_FS_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(OTG_FS_IRQn);
/* USER CODE BEGIN USB_OTG_FS_MspInit 1 */
/* USER CODE END USB_OTG_FS_MspInit 1 */
}
}
/**
* @brief HCD MSP De-Initialization
* This function freeze the hardware resources used in this example
* @param hhcd: HCD handle pointer
* @retval None
*/
void HAL_HCD_MspDeInit(HCD_HandleTypeDef* hhcd)
{
if(hhcd->Instance==USB_OTG_FS)
{
/* USER CODE BEGIN USB_OTG_FS_MspDeInit 0 */
/* USER CODE END USB_OTG_FS_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_USB_OTG_FS_CLK_DISABLE();
/**USB_OTG_FS GPIO Configuration
PA11 ------> USB_OTG_FS_DM
PA12 ------> USB_OTG_FS_DP
*/
HAL_GPIO_DeInit(GPIOA, GPIO_PIN_11|GPIO_PIN_12);
/* USB_OTG_FS interrupt DeInit */
HAL_NVIC_DisableIRQ(OTG_FS_IRQn);
/* USER CODE BEGIN USB_OTG_FS_MspDeInit 1 */
/* USER CODE END USB_OTG_FS_MspDeInit 1 */
}
}
static uint32_t FMC_Initialized = 0;
static void HAL_FMC_MspInit(void){
......
......@@ -72,6 +72,7 @@
/* External variables --------------------------------------------------------*/
extern UART_HandleTypeDef huart1;
extern HCD_HandleTypeDef hhcd_USB_OTG_FS;
/* USER CODE BEGIN EV */
/* USER CODE END EV */
......@@ -226,6 +227,20 @@ void USART1_IRQHandler(void)
/* USER CODE END USART1_IRQn 1 */
}
/**
* @brief This function handles USB On The Go FS global interrupt.
*/
void OTG_FS_IRQHandler(void)
{
/* USER CODE BEGIN OTG_FS_IRQn 0 */
/* USER CODE END OTG_FS_IRQn 0 */
HAL_HCD_IRQHandler(&hhcd_USB_OTG_FS);
/* USER CODE BEGIN OTG_FS_IRQn 1 */
/* USER CODE END OTG_FS_IRQn 1 */
}
/* USER CODE BEGIN 1 */
/* USER CODE END 1 */
......
......@@ -270,6 +270,21 @@ menu "On-chip Peripheral Drivers"
select RT_USING_WDT
default n
menuconfig BSP_USING_USBH
bool "Enable USB Host"
select RT_USING_USB_HOST
default n
if BSP_USING_USBH
menuconfig RT_USBH_MSTORAGE
bool "Enable Udisk Drivers"
default n
if RT_USBH_MSTORAGE
config UDISK_MOUNTPOINT
string "Udisk mount dir"
default "/"
endif
endif
config BSP_USING_SDIO
bool "Enable SDIO"
select RT_USING_SDIO
......
......@@ -28,6 +28,7 @@ Mcu.IP17=TIM14
Mcu.IP18=USART1
Mcu.IP19=USART2
Mcu.IP2=ETH
Mcu.IP20=USB_OTG_FS
Mcu.IP3=FMC
Mcu.IP4=IWDG
Mcu.IP5=LTDC
......@@ -35,13 +36,15 @@ Mcu.IP6=NVIC
Mcu.IP7=QUADSPI
Mcu.IP8=RCC
Mcu.IP9=RTC
Mcu.IPNb=20
Mcu.IPNb=21
Mcu.Name=STM32F767I(G-I)Tx
Mcu.Package=LQFP176
Mcu.Pin0=PC14/OSC32_IN
Mcu.Pin1=PC15/OSC32_OUT
Mcu.Pin10=PF5
Mcu.Pin100=VP_TIM14_VS_ClockSourceINT
Mcu.Pin100=VP_TIM11_VS_ClockSourceINT
Mcu.Pin101=VP_TIM13_VS_ClockSourceINT
Mcu.Pin102=VP_TIM14_VS_ClockSourceINT
Mcu.Pin11=PF6
Mcu.Pin12=PF7
Mcu.Pin13=PF8
......@@ -111,35 +114,35 @@ Mcu.Pin70=PC9
Mcu.Pin71=PA8
Mcu.Pin72=PA9
Mcu.Pin73=PA10
Mcu.Pin74=PA13
Mcu.Pin75=PH14
Mcu.Pin76=PI2
Mcu.Pin77=PA14
Mcu.Pin78=PC10
Mcu.Pin79=PC11
Mcu.Pin74=PA11
Mcu.Pin75=PA12
Mcu.Pin76=PA13
Mcu.Pin77=PH14
Mcu.Pin78=PI2
Mcu.Pin79=PA14
Mcu.Pin8=PF3
Mcu.Pin80=PC12
Mcu.Pin81=PD0
Mcu.Pin82=PD1
Mcu.Pin83=PD2
Mcu.Pin84=PD5
Mcu.Pin85=PD6
Mcu.Pin86=PG12
Mcu.Pin87=PG13
Mcu.Pin88=PG14
Mcu.Pin89=PG15
Mcu.Pin80=PC10
Mcu.Pin81=PC11
Mcu.Pin82=PC12
Mcu.Pin83=PD0
Mcu.Pin84=PD1
Mcu.Pin85=PD2
Mcu.Pin86=PD5
Mcu.Pin87=PD6
Mcu.Pin88=PG12
Mcu.Pin89=PG13
Mcu.Pin9=PF4
Mcu.Pin90=PB6
Mcu.Pin91=PB8
Mcu.Pin92=PB9
Mcu.Pin93=PI5
Mcu.Pin94=VP_IWDG_VS_IWDG
Mcu.Pin95=VP_RTC_VS_RTC_Activate
Mcu.Pin96=VP_SYS_VS_Systick
Mcu.Pin97=VP_TIM3_VS_ClockSourceINT
Mcu.Pin98=VP_TIM11_VS_ClockSourceINT
Mcu.Pin99=VP_TIM13_VS_ClockSourceINT
Mcu.PinsNb=101
Mcu.Pin90=PG14
Mcu.Pin91=PG15
Mcu.Pin92=PB6
Mcu.Pin93=PB8
Mcu.Pin94=PB9
Mcu.Pin95=PI5
Mcu.Pin96=VP_IWDG_VS_IWDG
Mcu.Pin97=VP_RTC_VS_RTC_Activate
Mcu.Pin98=VP_SYS_VS_Systick
Mcu.Pin99=VP_TIM3_VS_ClockSourceINT
Mcu.PinsNb=103
Mcu.ThirdPartyNb=0
Mcu.UserConstants=
Mcu.UserName=STM32F767IGTx
......@@ -150,6 +153,7 @@ NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:false\:false
NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false
NVIC.MemoryManagement_IRQn=true\:0\:0\:false\:false\:true\:false\:false
NVIC.NonMaskableInt_IRQn=true\:0\:0\:false\:false\:true\:false\:false
NVIC.OTG_FS_IRQn=true\:0\:0\:false\:false\:true\:true\:true
NVIC.PendSV_IRQn=true\:0\:0\:false\:false\:true\:false\:false
NVIC.PriorityGroup=NVIC_PRIORITYGROUP_4
NVIC.SVCall_IRQn=true\:0\:0\:false\:false\:true\:false\:false
......@@ -160,6 +164,10 @@ PA1.Signal=ETH_REF_CLK
PA10.Locked=true
PA10.Mode=Asynchronous
PA10.Signal=USART1_RX
PA11.Mode=Host_Only
PA11.Signal=USB_OTG_FS_DM
PA12.Mode=Host_Only
PA12.Signal=USB_OTG_FS_DP
PA13.Mode=Serial_Wire
PA13.Signal=SYS_JTMS-SWDIO
PA14.Mode=Serial_Wire
......@@ -377,7 +385,7 @@ RCC.I2C2Freq_Value=54000000
RCC.I2C3Freq_Value=54000000
RCC.I2C4Freq_Value=54000000
RCC.I2SFreq_Value=96000000
RCC.IPParameters=AHBFreq_Value,APB1CLKDivider,APB1Freq_Value,APB1TimFreq_Value,APB2CLKDivider,APB2Freq_Value,APB2TimFreq_Value,CECFreq_Value,CortexFreq_Value,DFSDMAudioFreq_Value,DFSDMFreq_Value,EthernetFreq_Value,FCLKCortexFreq_Value,FamilyName,HCLKFreq_Value,HSE_VALUE,HSI_VALUE,I2C1Freq_Value,I2C2Freq_Value,I2C3Freq_Value,I2C4Freq_Value,I2SFreq_Value,LCDTFTFreq_Value,LPTIM1Freq_Value,LSI_VALUE,MCO2PinFreq_Value,PLLCLKFreq_Value,PLLI2SPCLKFreq_Value,PLLI2SQCLKFreq_Value,PLLI2SRCLKFreq_Value,PLLI2SRoutputFreq_Value,PLLM,PLLN,PLLQ,PLLQCLKFreq_Value,PLLQoutputFreq_Value,PLLRFreq_Value,PLLSAIN,PLLSAIPCLKFreq_Value,PLLSAIQCLKFreq_Value,PLLSAIR,PLLSAIRCLKFreq_Value,PLLSAIRDiv,PLLSAIoutputFreq_Value,PLLSourceVirtual,RNGFreq_Value,RTCClockSelection,RTCFreq_Value,SAI1Freq_Value,SAI2Freq_Value,SDMMC2Freq_Value,SDMMCClockSelection,SDMMCFreq_Value,SPDIFRXFreq_Value,SYSCLKFreq_VALUE,SYSCLKSource,UART4Freq_Value,UART5Freq_Value,UART7Freq_Value,UART8Freq_Value,USART1Freq_Value,USART2Freq_Value,USART3Freq_Value,USART6Freq_Value,USBFreq_Value,VCOI2SOutputFreq_Value,VCOInputFreq_Value,VCOOutputFreq_Value,VCOSAIOutputFreq_Value
RCC.IPParameters=AHBFreq_Value,APB1CLKDivider,APB1Freq_Value,APB1TimFreq_Value,APB2CLKDivider,APB2Freq_Value,APB2TimFreq_Value,CECFreq_Value,CortexFreq_Value,DFSDMAudioFreq_Value,DFSDMFreq_Value,EthernetFreq_Value,FCLKCortexFreq_Value,FamilyName,HCLKFreq_Value,HSE_VALUE,HSI_VALUE,I2C1Freq_Value,I2C2Freq_Value,I2C3Freq_Value,I2C4Freq_Value,I2SFreq_Value,LCDTFTFreq_Value,LPTIM1Freq_Value,LSI_VALUE,MCO2PinFreq_Value,PLLCLKFreq_Value,PLLI2SPCLKFreq_Value,PLLI2SQCLKFreq_Value,PLLI2SRCLKFreq_Value,PLLI2SRoutputFreq_Value,PLLM,PLLN,PLLQ,PLLQCLKFreq_Value,PLLQoutputFreq_Value,PLLRFreq_Value,PLLSAIN,PLLSAIPCLKFreq_Value,PLLSAIQCLKFreq_Value,PLLSAIR,PLLSAIRCLKFreq_Value,PLLSAIRDiv,PLLSAIoutputFreq_Value,RNGFreq_Value,RTCClockSelection,RTCFreq_Value,SAI1Freq_Value,SAI2Freq_Value,SDMMC2Freq_Value,SDMMCClockSelection,SDMMCFreq_Value,SPDIFRXFreq_Value,SYSCLKFreq_VALUE,SYSCLKSource,UART4Freq_Value,UART5Freq_Value,UART7Freq_Value,UART8Freq_Value,USART1Freq_Value,USART2Freq_Value,USART3Freq_Value,USART6Freq_Value,USBFreq_Value,VCOI2SOutputFreq_Value,VCOInputFreq_Value,VCOOutputFreq_Value,VCOSAIOutputFreq_Value
RCC.LCDTFTFreq_Value=9000000
RCC.LPTIM1Freq_Value=54000000
RCC.LSI_VALUE=32000
......@@ -400,7 +408,6 @@ RCC.PLLSAIR=4
RCC.PLLSAIRCLKFreq_Value=72000000
RCC.PLLSAIRDiv=RCC_PLLSAIDIVR_8
RCC.PLLSAIoutputFreq_Value=144000000
RCC.PLLSourceVirtual=RCC_PLLSOURCE_HSE
RCC.RNGFreq_Value=48000000
RCC.RTCClockSelection=RCC_RTCCLKSOURCE_LSE
RCC.RTCFreq_Value=32768
......@@ -514,6 +521,9 @@ USART1.IPParameters=VirtualMode-Asynchronous
USART1.VirtualMode-Asynchronous=VM_ASYNC
USART2.IPParameters=VirtualMode-Asynchronous
USART2.VirtualMode-Asynchronous=VM_ASYNC
USB_OTG_FS.IPParameters=VirtualMode,phy_itface
USB_OTG_FS.VirtualMode=Host_Only
USB_OTG_FS.phy_itface=HCD_PHY_EMBEDDED
VP_IWDG_VS_IWDG.Mode=IWDG_Activate
VP_IWDG_VS_IWDG.Signal=IWDG_VS_IWDG
VP_RTC_VS_RTC_Activate.Mode=RTC_Enabled
......
......@@ -70,7 +70,7 @@
/* #define HAL_SMARTCARD_MODULE_ENABLED */
/* #define HAL_WWDG_MODULE_ENABLED */
/* #define HAL_PCD_MODULE_ENABLED */
/* #define HAL_HCD_MODULE_ENABLED */
#define HAL_HCD_MODULE_ENABLED
/* #define HAL_DFSDM_MODULE_ENABLED */
/* #define HAL_DSI_MODULE_ENABLED */
/* #define HAL_JPEG_MODULE_ENABLED */
......
......@@ -71,6 +71,7 @@ void SVC_Handler(void);
void DebugMon_Handler(void);
void PendSV_Handler(void);
void SysTick_Handler(void);
void OTG_FS_IRQHandler(void);
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */
......
......@@ -87,6 +87,8 @@ TIM_HandleTypeDef htim14;
UART_HandleTypeDef huart1;
UART_HandleTypeDef huart2;
HCD_HandleTypeDef hhcd_USB_OTG_FS;
SDRAM_HandleTypeDef hsdram1;
/* USER CODE BEGIN PV */
......@@ -112,6 +114,7 @@ static void MX_TIM13_Init(void);
static void MX_TIM14_Init(void);
static void MX_TIM3_Init(void);
static void MX_LTDC_Init(void);
static void MX_USB_OTG_FS_HCD_Init(void);
/* USER CODE BEGIN PFP */
/* USER CODE END PFP */
......@@ -172,6 +175,7 @@ int main(void)
MX_TIM14_Init();
MX_TIM3_Init();
MX_LTDC_Init();
MX_USB_OTG_FS_HCD_Init();
/* USER CODE BEGIN 2 */
/* USER CODE END 2 */
......@@ -883,6 +887,37 @@ static void MX_USART2_UART_Init(void)
}
/**
* @brief USB_OTG_FS Initialization Function
* @param None
* @retval None
*/
static void MX_USB_OTG_FS_HCD_Init(void)
{
/* USER CODE BEGIN USB_OTG_FS_Init 0 */
/* USER CODE END USB_OTG_FS_Init 0 */
/* USER CODE BEGIN USB_OTG_FS_Init 1 */
/* USER CODE END USB_OTG_FS_Init 1 */
hhcd_USB_OTG_FS.Instance = USB_OTG_FS;
hhcd_USB_OTG_FS.Init.Host_channels = 8;
hhcd_USB_OTG_FS.Init.speed = HCD_SPEED_FULL;
hhcd_USB_OTG_FS.Init.dma_enable = DISABLE;
hhcd_USB_OTG_FS.Init.phy_itface = HCD_PHY_EMBEDDED;
hhcd_USB_OTG_FS.Init.Sof_enable = DISABLE;
if (HAL_HCD_Init(&hhcd_USB_OTG_FS) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN USB_OTG_FS_Init 2 */
/* USER CODE END USB_OTG_FS_Init 2 */
}
/* FMC initialization function */
static void MX_FMC_Init(void)
{
......
......@@ -1057,6 +1057,76 @@ void HAL_UART_MspDeInit(UART_HandleTypeDef* huart)
}
/**
* @brief HCD MSP Initialization
* This function configures the hardware resources used in this example
* @param hhcd: HCD handle pointer
* @retval None
*/
void HAL_HCD_MspInit(HCD_HandleTypeDef* hhcd)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
if(hhcd->Instance==USB_OTG_FS)
{
/* USER CODE BEGIN USB_OTG_FS_MspInit 0 */
/* USER CODE END USB_OTG_FS_MspInit 0 */
__HAL_RCC_GPIOA_CLK_ENABLE();
/**USB_OTG_FS GPIO Configuration
PA11 ------> USB_OTG_FS_DM
PA12 ------> USB_OTG_FS_DP
*/
GPIO_InitStruct.Pin = GPIO_PIN_11|GPIO_PIN_12;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
/* Peripheral clock enable */
__HAL_RCC_USB_OTG_FS_CLK_ENABLE();
/* USB_OTG_FS interrupt Init */
HAL_NVIC_SetPriority(OTG_FS_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(OTG_FS_IRQn);
/* USER CODE BEGIN USB_OTG_FS_MspInit 1 */
/* USER CODE END USB_OTG_FS_MspInit 1 */
}
}
/**
* @brief HCD MSP De-Initialization
* This function freeze the hardware resources used in this example
* @param hhcd: HCD handle pointer
* @retval None
*/
void HAL_HCD_MspDeInit(HCD_HandleTypeDef* hhcd)
{
if(hhcd->Instance==USB_OTG_FS)
{
/* USER CODE BEGIN USB_OTG_FS_MspDeInit 0 */
/* USER CODE END USB_OTG_FS_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_USB_OTG_FS_CLK_DISABLE();
/**USB_OTG_FS GPIO Configuration
PA11 ------> USB_OTG_FS_DM
PA12 ------> USB_OTG_FS_DP
*/
HAL_GPIO_DeInit(GPIOA, GPIO_PIN_11|GPIO_PIN_12);
/* USB_OTG_FS interrupt DeInit */
HAL_NVIC_DisableIRQ(OTG_FS_IRQn);
/* USER CODE BEGIN USB_OTG_FS_MspDeInit 1 */
/* USER CODE END USB_OTG_FS_MspDeInit 1 */
}
}
static uint32_t FMC_Initialized = 0;
static void HAL_FMC_MspInit(void){
......
......@@ -71,7 +71,7 @@
/* USER CODE END 0 */
/* External variables --------------------------------------------------------*/
extern HCD_HandleTypeDef hhcd_USB_OTG_FS;
/* USER CODE BEGIN EV */
/* USER CODE END EV */
......@@ -212,6 +212,20 @@ void SysTick_Handler(void)
/* please refer to the startup file (startup_stm32f7xx.s). */
/******************************************************************************/
/**
* @brief This function handles USB On The Go FS global interrupt.
*/
void OTG_FS_IRQHandler(void)
{
/* USER CODE BEGIN OTG_FS_IRQn 0 */
/* USER CODE END OTG_FS_IRQn 0 */
HAL_HCD_IRQHandler(&hhcd_USB_OTG_FS);
/* USER CODE BEGIN OTG_FS_IRQn 1 */
/* USER CODE END OTG_FS_IRQn 1 */
}
/* USER CODE BEGIN 1 */
/* USER CODE END 1 */
......
......@@ -17,7 +17,7 @@ menu "Onboard Peripheral Drivers"
config BSP_USING_RS232
bool "Enable RS232 (uart2 pin conflict with Ethernet)"
select BSP_USING_UART
select BSP_USING_UART
select BSP_USING_UART2
default n
......@@ -246,6 +246,21 @@ menu "On-chip Peripheral Drivers"
select RT_USING_WDT
default n
menuconfig BSP_USING_USBH
bool "Enable USB Host"
select RT_USING_USB_HOST
default n
if BSP_USING_USBH
menuconfig RT_USBH_MSTORAGE
bool "Enable Udisk Drivers"
default n
if RT_USBH_MSTORAGE
config UDISK_MOUNTPOINT
string "Udisk mount dir"
default "/"
endif
endif
config BSP_USING_SDIO
bool "Enable SDIO"
select RT_USING_SDIO
......@@ -255,7 +270,7 @@ menu "On-chip Peripheral Drivers"
config BSP_USING_LTDC
bool "Enable LTDC"
default n
source "../libraries/HAL_Drivers/Kconfig"
endmenu
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册