mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-12 19:10:32 +03:00
Add USB MSC support to AT32 (#12481)
This commit is contained in:
parent
c14ef06c29
commit
6ff80a471a
21 changed files with 330 additions and 65 deletions
|
@ -144,6 +144,7 @@ void bot_scsi_reset(void *udev)
|
|||
*/
|
||||
void bot_scsi_datain_handler(void *udev, uint8_t ept_num)
|
||||
{
|
||||
UNUSED(ept_num);
|
||||
usbd_core_type *pudev = (usbd_core_type *)udev;
|
||||
msc_type *pmsc = (msc_type *)pudev->class_handler->pdata;
|
||||
switch(pmsc->msc_state)
|
||||
|
@ -173,6 +174,7 @@ void bot_scsi_datain_handler(void *udev, uint8_t ept_num)
|
|||
*/
|
||||
void bot_scsi_dataout_handler(void *udev, uint8_t ept_num)
|
||||
{
|
||||
UNUSED(ept_num);
|
||||
usbd_core_type *pudev = (usbd_core_type *)udev;
|
||||
msc_type *pmsc = (msc_type *)pudev->class_handler->pdata;
|
||||
switch(pmsc->msc_state)
|
||||
|
@ -289,6 +291,7 @@ void bot_scsi_send_csw(void *udev, uint8_t status)
|
|||
*/
|
||||
void bot_scsi_sense_code(void *udev, uint8_t sense_key, uint8_t asc)
|
||||
{
|
||||
UNUSED(udev);
|
||||
sense_data.sense_key = sense_key;
|
||||
sense_data.asc = asc;
|
||||
}
|
||||
|
@ -347,6 +350,8 @@ void bot_scsi_stall(void *udev)
|
|||
*/
|
||||
usb_sts_type bot_scsi_test_unit(void *udev, uint8_t lun)
|
||||
{
|
||||
UNUSED(udev);
|
||||
UNUSED(lun);
|
||||
usb_sts_type status = USB_OK;
|
||||
usbd_core_type *pudev = (usbd_core_type *)udev;
|
||||
msc_type *pmsc = (msc_type *)pudev->class_handler->pdata;
|
||||
|
@ -410,6 +415,7 @@ usb_sts_type bot_scsi_inquiry(void *udev, uint8_t lun)
|
|||
*/
|
||||
usb_sts_type bot_scsi_start_stop(void *udev, uint8_t lun)
|
||||
{
|
||||
UNUSED(lun);
|
||||
usbd_core_type *pudev = (usbd_core_type *)udev;
|
||||
msc_type *pmsc = (msc_type *)pudev->class_handler->pdata;
|
||||
pmsc->data_len = 0;
|
||||
|
@ -424,6 +430,7 @@ usb_sts_type bot_scsi_start_stop(void *udev, uint8_t lun)
|
|||
*/
|
||||
usb_sts_type bot_scsi_allow_medium_removal(void *udev, uint8_t lun)
|
||||
{
|
||||
UNUSED(lun);
|
||||
usbd_core_type *pudev = (usbd_core_type *)udev;
|
||||
msc_type *pmsc = (msc_type *)pudev->class_handler->pdata;
|
||||
pmsc->data_len = 0;
|
||||
|
@ -438,6 +445,7 @@ usb_sts_type bot_scsi_allow_medium_removal(void *udev, uint8_t lun)
|
|||
*/
|
||||
usb_sts_type bot_scsi_mode_sense6(void *udev, uint8_t lun)
|
||||
{
|
||||
UNUSED(lun);
|
||||
uint8_t data_len = 8;
|
||||
usbd_core_type *pudev = (usbd_core_type *)udev;
|
||||
msc_type *pmsc = (msc_type *)pudev->class_handler->pdata;
|
||||
|
@ -447,6 +455,12 @@ usb_sts_type bot_scsi_mode_sense6(void *udev, uint8_t lun)
|
|||
data_len --;
|
||||
pmsc->data[data_len] = mode_sense6_data[data_len];
|
||||
};
|
||||
|
||||
// set bit 7 of the device configuration byte to indicate write protection
|
||||
if (msc_get_readonly(lun)) {
|
||||
pmsc->data[2] |= 1 << 7;
|
||||
}
|
||||
|
||||
return USB_OK;
|
||||
}
|
||||
|
||||
|
@ -458,6 +472,7 @@ usb_sts_type bot_scsi_mode_sense6(void *udev, uint8_t lun)
|
|||
*/
|
||||
usb_sts_type bot_scsi_mode_sense10(void *udev, uint8_t lun)
|
||||
{
|
||||
UNUSED(lun);
|
||||
uint8_t data_len = 8;
|
||||
usbd_core_type *pudev = (usbd_core_type *)udev;
|
||||
msc_type *pmsc = (msc_type *)pudev->class_handler->pdata;
|
||||
|
@ -540,6 +555,7 @@ usb_sts_type bot_scsi_format_capacity(void *udev, uint8_t lun)
|
|||
*/
|
||||
usb_sts_type bot_scsi_request_sense(void *udev, uint8_t lun)
|
||||
{
|
||||
UNUSED(lun);
|
||||
uint32_t trans_len = 0x12;
|
||||
usbd_core_type *pudev = (usbd_core_type *)udev;
|
||||
msc_type *pmsc = (msc_type *)pudev->class_handler->pdata;
|
||||
|
@ -633,7 +649,7 @@ usb_sts_type bot_scsi_read10(void *udev, uint8_t lun)
|
|||
pmsc->data_len = MSC_MAX_DATA_BUF_LEN;
|
||||
|
||||
len = MIN(pmsc->blk_len, MSC_MAX_DATA_BUF_LEN);
|
||||
if( msc_disk_read(lun, pmsc->blk_addr, pmsc->data, len) != USB_OK)
|
||||
if( msc_disk_read(lun, pmsc->blk_addr / pmsc->blk_size[lun], pmsc->data, len / pmsc->blk_size[lun]) != USB_OK)
|
||||
{
|
||||
bot_scsi_sense_code(udev, SENSE_KEY_HARDWARE_ERROR, MEDIUM_NOT_PRESENT);
|
||||
return USB_FAIL;
|
||||
|
@ -698,7 +714,7 @@ usb_sts_type bot_scsi_write10(void *udev, uint8_t lun)
|
|||
else
|
||||
{
|
||||
len = MIN(pmsc->blk_len, MSC_MAX_DATA_BUF_LEN);
|
||||
if(msc_disk_write(lun, pmsc->blk_addr, pmsc->data, len) != USB_OK)
|
||||
if(msc_disk_write(lun, pmsc->blk_addr / pmsc->blk_size[lun], pmsc->data, len / pmsc->blk_size[lun]) != USB_OK)
|
||||
{
|
||||
bot_scsi_sense_code(udev, SENSE_KEY_HARDWARE_ERROR, MEDIUM_NOT_PRESENT);
|
||||
return USB_FAIL;
|
||||
|
|
|
@ -23,7 +23,7 @@
|
|||
*/
|
||||
#include "usbd_core.h"
|
||||
#include "msc_class.h"
|
||||
#include "msc_desc.h"
|
||||
#include <msc_desc.h>
|
||||
#include "msc_bot_scsi.h"
|
||||
|
||||
/** @addtogroup AT32F435_437_middlewares_usbd_class
|
||||
|
@ -183,6 +183,7 @@ static usb_sts_type class_setup_handler(void *udev, usb_setup_type *setup)
|
|||
*/
|
||||
static usb_sts_type class_ept0_tx_handler(void *udev)
|
||||
{
|
||||
UNUSED(udev);
|
||||
usb_sts_type status = USB_OK;
|
||||
|
||||
/* ...user code... */
|
||||
|
@ -199,7 +200,7 @@ static usb_sts_type class_ept0_rx_handler(void *udev)
|
|||
{
|
||||
usb_sts_type status = USB_OK;
|
||||
usbd_core_type *pudev = (usbd_core_type *)udev;
|
||||
uint32_t recv_len = usbd_get_recv_len(pudev, 0);
|
||||
usbd_get_recv_len(pudev, 0);
|
||||
/* ...user code... */
|
||||
return status;
|
||||
}
|
||||
|
@ -240,6 +241,7 @@ static usb_sts_type class_out_handler(void *udev, uint8_t ept_num)
|
|||
*/
|
||||
static usb_sts_type class_sof_handler(void *udev)
|
||||
{
|
||||
UNUSED(udev);
|
||||
usb_sts_type status = USB_OK;
|
||||
|
||||
/* ...user code... */
|
||||
|
@ -255,6 +257,7 @@ static usb_sts_type class_sof_handler(void *udev)
|
|||
*/
|
||||
static usb_sts_type class_event_handler(void *udev, usbd_event_type event)
|
||||
{
|
||||
UNUSED(udev);
|
||||
usb_sts_type status = USB_OK;
|
||||
switch(event)
|
||||
{
|
||||
|
|
|
@ -25,7 +25,7 @@
|
|||
#include "usb_std.h"
|
||||
#include "usbd_sdr.h"
|
||||
#include "usbd_core.h"
|
||||
#include "msc_desc.h"
|
||||
#include <msc_desc.h>
|
||||
|
||||
/** @addtogroup AT32F435_437_middlewares_usbd_class
|
||||
* @{
|
||||
|
|
|
@ -2,5 +2,61 @@
|
|||
# AT32F4 Make file include
|
||||
#
|
||||
|
||||
CMSIS_DIR := $(ROOT)/lib/main/AT32F43x/cmsis
|
||||
STDPERIPH_DIR = $(ROOT)/lib/main/AT32F43x/drivers
|
||||
MIDDLEWARES_DIR = $(ROOT)/lib/main/AT32F43x/middlewares
|
||||
STDPERIPH_SRC = $(wildcard $(STDPERIPH_DIR)/src/*.c) \
|
||||
$(wildcard $(MIDDLEWARES_DIR)/usb_drivers/src/*.c) \
|
||||
$(wildcard $(MIDDLEWARES_DIR)/usbd_class/msc/*.c)
|
||||
|
||||
EXCLUDES = at32f435_437_dvp.c \
|
||||
at32f435_437_can.c \
|
||||
at32f435_437_xmc.c \
|
||||
at32f435_437_emac
|
||||
|
||||
|
||||
STARTUP_SRC = at32/startup_at32f435_437.s
|
||||
STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))
|
||||
|
||||
VPATH := $(VPATH):$(ROOT)/lib/main/AT32F43x/cmsis/cm4/core_support:$(STDPERIPH_DIR)/src:$(STDPERIPH_DIR)/inc:$(SRC_DIR)/startup/at32
|
||||
|
||||
VCP_SRC = $(wildcard $(ROOT)/lib/main/AT32F43x/middlewares/usbd_class/cdc/*.c) \
|
||||
drivers/usb_io.c
|
||||
|
||||
VCP_INCLUDES = $(ROOT)/lib/main/AT32F43x/middlewares/usb_drivers/inc \
|
||||
$(ROOT)/lib/main/AT32F43x/middlewares/usbd_class/cdc
|
||||
|
||||
DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC)
|
||||
|
||||
INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
||||
$(ROOT)/src/main/drivers/at32
|
||||
$(SRC_DIR)/startup/at32 \
|
||||
$(SRC_DIR)/drivers \
|
||||
$(SRC_DIR)/drivers/at32 \
|
||||
$(STDPERIPH_DIR)/inc \
|
||||
$(CMSIS_DIR)/cm4/core_support \
|
||||
$(CMSIS_DIR)/cm4 \
|
||||
$(MIDDLEWARES_DIR)/i2c_application_library \
|
||||
$(MIDDLEWARES_DIR)/usbd_class/msc \
|
||||
$(VCP_INCLUDES)
|
||||
|
||||
LD_SCRIPT = $(LINKER_DIR)/at32_flash_f43xM.ld
|
||||
|
||||
ARCH_FLAGS = -std=c99 -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion
|
||||
DEVICE_FLAGS += -DUSE_ATBSP_DRIVER -DAT32F43x -DHSE_VALUE=$(HSE_VALUE) -DAT32 -DUSE_OTG_HOST_MODE
|
||||
|
||||
MCU_COMMON_SRC = \
|
||||
$(addprefix startup/at32/,$(notdir $(wildcard $(SRC_DIR)/startup/at32/*.c))) \
|
||||
$(addprefix drivers/at32/,$(notdir $(wildcard $(SRC_DIR)/drivers/at32/*.c))) \
|
||||
drivers/accgyro/accgyro_mpu.c \
|
||||
drivers/dshot_bitbang_decode.c \
|
||||
drivers/inverter.c \
|
||||
drivers/pwm_output_dshot_shared.c \
|
||||
$(MIDDLEWARES_DIR)/i2c_application_library/i2c_application.c \
|
||||
drivers/bus_i2c_timing.c \
|
||||
drivers/usb_msc_common.c \
|
||||
msc/usbd_storage.c \
|
||||
msc/usbd_storage_emfat.c \
|
||||
msc/emfat.c \
|
||||
msc/emfat_file.c
|
||||
|
||||
MCU_EXCLUDES =
|
||||
|
|
|
@ -180,6 +180,7 @@ MCU_COMMON_SRC = \
|
|||
drivers/stm32/timer_stdperiph.c \
|
||||
drivers/stm32/timer_stm32f4xx.c \
|
||||
drivers/stm32/transponder_ir_io_stdperiph.c \
|
||||
drivers/stm32/usbd_msc_desc.c \
|
||||
startup/system_stm32f4xx.c
|
||||
|
||||
ifeq ($(PERIPH_DRIVER), HAL)
|
||||
|
@ -204,7 +205,6 @@ endif
|
|||
MSC_SRC = \
|
||||
drivers/usb_msc_common.c \
|
||||
drivers/stm32/usb_msc_f4xx.c \
|
||||
msc/usbd_msc_desc.c \
|
||||
msc/usbd_storage.c \
|
||||
msc/usbd_storage_emfat.c \
|
||||
msc/emfat.c \
|
||||
|
|
|
@ -26,7 +26,8 @@
|
|||
#define BOARD_NAME REVO_AT
|
||||
#define MANUFACTURER_ID OPEN
|
||||
|
||||
#define LED0_PIN PB5
|
||||
#define LED0_PIN PB5
|
||||
#define LED1_PIN PB4
|
||||
|
||||
#define USE_GYRO
|
||||
#define USE_GYRO_SPI_MPU6000
|
||||
|
@ -41,13 +42,12 @@
|
|||
#define USE_GYRO_EXTI
|
||||
#define GYRO_1_EXTI_PIN PC4
|
||||
|
||||
#define SPI1_SCK_PIN PA5
|
||||
#define SPI1_SDI_PIN PA6
|
||||
#define SPI1_SDO_PIN PA7
|
||||
|
||||
#define SPI3_SCK_PIN PC10
|
||||
#define SPI3_SDI_PIN PC11
|
||||
#define SPI3_SDO_PIN PC12
|
||||
#define SPI1_SCK_PIN PA5
|
||||
#define SPI3_SCK_PIN PC10
|
||||
#define SPI1_SDI_PIN PA6
|
||||
#define SPI3_SDI_PIN PC11
|
||||
#define SPI1_SDO_PIN PA7
|
||||
#define SPI3_SDO_PIN PC12
|
||||
|
||||
#define USE_FLASH
|
||||
#define USE_FLASH_M25P16
|
||||
|
@ -60,8 +60,10 @@
|
|||
#define I2C2_SCL_PIN PB10
|
||||
#define I2C2_SDA_PIN PB11
|
||||
|
||||
#define MAG_I2C_INSTANCE I2CDEV_1
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_INSTANCE I2C1
|
||||
#define USE_MAG_HMC5883
|
||||
|
||||
#define BARO_I2C_INSTANCE I2CDEV_1
|
||||
#define USE_BARO
|
||||
#define BARO_I2C_INSTANCE I2C1
|
||||
#define USE_BARO_MS5611
|
||||
|
|
83
src/main/drivers/at32/msc_desc.h
Normal file
83
src/main/drivers/at32/msc_desc.h
Normal file
|
@ -0,0 +1,83 @@
|
|||
/**
|
||||
**************************************************************************
|
||||
* @file msc_desc.h
|
||||
* @brief usb msc descriptor header file
|
||||
**************************************************************************
|
||||
* Copyright notice & Disclaimer
|
||||
*
|
||||
* The software Board Support Package (BSP) that is made available to
|
||||
* download from Artery official website is the copyrighted work of Artery.
|
||||
* Artery authorizes customers to use, copy, and distribute the BSP
|
||||
* software and its related documentation for the purpose of design and
|
||||
* development in conjunction with Artery microcontrollers. Use of the
|
||||
* software is governed by this copyright notice and the following disclaimer.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
|
||||
* GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS,
|
||||
* TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR
|
||||
* STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS,
|
||||
* INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT.
|
||||
*
|
||||
**************************************************************************
|
||||
*/
|
||||
|
||||
/* define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef __MSC_DESC_H
|
||||
#define __MSC_DESC_H
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
#include "msc_class.h"
|
||||
#include "usbd_core.h"
|
||||
|
||||
/** @addtogroup AT32F435_437_middlewares_usbd_class
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @addtogroup USB_msc_desc
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup USB_msc_desc_definition
|
||||
* @{
|
||||
*/
|
||||
|
||||
#define MSC_BCD_NUM 0x0110
|
||||
|
||||
#define USBD_MSC_VENDOR_ID 0x2E3C
|
||||
#define USBD_MSC_PRODUCT_ID 0x5720
|
||||
|
||||
#define USBD_MSC_CONFIG_DESC_SIZE 32
|
||||
#define USBD_MSC_SIZ_STRING_LANGID 4
|
||||
#define USBD_MSC_SIZ_STRING_SERIAL 0x1A
|
||||
|
||||
#define USBD_MSC_DESC_MANUFACTURER_STRING "Artery"
|
||||
#define USBD_MSC_DESC_PRODUCT_STRING "Betaflight FC Mass Storage (FS Mode)"
|
||||
#define USBD_MSC_DESC_CONFIGURATION_STRING "MSC Config"
|
||||
#define USBD_MSC_DESC_INTERFACE_STRING "MSC Interface"
|
||||
|
||||
#define MCU_ID1 (0x1FFFF7E8)
|
||||
#define MCU_ID2 (0x1FFFF7EC)
|
||||
#define MCU_ID3 (0x1FFFF7F0)
|
||||
|
||||
extern usbd_desc_handler msc_desc_handler;
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
29
src/main/drivers/at32/msc_diskio.h
Normal file
29
src/main/drivers/at32/msc_diskio.h
Normal file
|
@ -0,0 +1,29 @@
|
|||
/*
|
||||
* This file is part of Betaflight.
|
||||
*
|
||||
* Betaflight is free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Betaflight is distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
// IO routines from usb_msc_at32F435.c
|
||||
int8_t msc_disk_capacity(uint8_t lun, uint32_t *block_num, uint32_t *block_size);
|
||||
int8_t msc_disk_read(uint8_t lun, uint32_t blk_addr, uint8_t *buf, uint16_t blk_len);
|
||||
int8_t msc_disk_write(uint8_t lun, uint32_t blk_addr, uint8_t *buf, uint16_t blk_len);
|
||||
uint8_t *get_inquiry(uint8_t lun);
|
||||
uint8_t msc_get_readonly(uint8_t lun);
|
||||
|
|
@ -39,7 +39,9 @@ uint32_t persistentObjectRead(persistentObjectId_e id)
|
|||
|
||||
void persistentObjectWrite(persistentObjectId_e id, uint32_t value)
|
||||
{
|
||||
ertc_write_protect_disable();
|
||||
ertc_bpr_data_write((ertc_dt_type)id, value);
|
||||
ertc_write_protect_enable();
|
||||
}
|
||||
|
||||
void persistentObjectRTCEnable(void)
|
||||
|
|
|
@ -68,6 +68,8 @@ typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;
|
|||
|
||||
#endif
|
||||
|
||||
#define USE_USB_MSC
|
||||
|
||||
#define USE_TIMER_MGMT
|
||||
#define USE_TIMER_AF
|
||||
#define USE_DMA_SPEC
|
||||
|
|
|
@ -58,7 +58,7 @@ typedef struct isrVector_s {
|
|||
|
||||
void checkForBootLoaderRequest(void)
|
||||
{
|
||||
uint32_t bootloaderRequest = persistentObjectRead(PERSISTENT_OBJECT_RESET_REASON);
|
||||
volatile uint32_t bootloaderRequest = persistentObjectRead(PERSISTENT_OBJECT_RESET_REASON);
|
||||
|
||||
if (bootloaderRequest != RESET_BOOTLOADER_REQUEST_ROM) {
|
||||
return;
|
||||
|
@ -96,6 +96,10 @@ bool isMPUSoftReset(void)
|
|||
|
||||
void systemInit(void)
|
||||
{
|
||||
persistentObjectInit();
|
||||
|
||||
checkForBootLoaderRequest();
|
||||
|
||||
system_clock_config();//config system clock to 288mhz usb 48mhz
|
||||
|
||||
// Configure NVIC preempt/priority groups
|
||||
|
|
|
@ -43,6 +43,9 @@
|
|||
#include "drivers/time.h"
|
||||
#include "drivers/usb_msc.h"
|
||||
|
||||
#include "msc/usbd_storage.h"
|
||||
#include "msc/usbd_storage_emfat.h"
|
||||
|
||||
#include "pg/sdcard.h"
|
||||
#include "pg/usb.h"
|
||||
|
||||
|
@ -194,4 +197,44 @@ uint8_t mscStart(void)
|
|||
return 0;
|
||||
}
|
||||
|
||||
int8_t msc_disk_capacity(uint8_t lun, uint32_t *block_num, uint32_t *block_size)
|
||||
{
|
||||
return USBD_MSC_EMFAT_fops.GetCapacity(lun, block_num, block_size);
|
||||
}
|
||||
|
||||
int8_t msc_disk_read(
|
||||
uint8_t lun, // logical unit number
|
||||
uint32_t blk_addr, // address of 1st block to be read
|
||||
uint8_t *buf, // Pointer to the buffer to save data
|
||||
uint16_t blk_len) // number of blocks to be read
|
||||
{
|
||||
return USBD_MSC_EMFAT_fops.Read(lun, buf, blk_addr, blk_len);
|
||||
}
|
||||
|
||||
int8_t msc_disk_write(uint8_t lun,
|
||||
uint32_t blk_addr,
|
||||
uint8_t *buf,
|
||||
uint16_t blk_len)
|
||||
{
|
||||
UNUSED(lun);
|
||||
UNUSED(buf);
|
||||
UNUSED(blk_addr);
|
||||
UNUSED(blk_len);
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
uint8_t *get_inquiry(uint8_t lun)
|
||||
{
|
||||
UNUSED(lun);
|
||||
|
||||
return (uint8_t *)USBD_MSC_EMFAT_fops.pInquiry;
|
||||
}
|
||||
|
||||
uint8_t msc_get_readonly(uint8_t lun)
|
||||
{
|
||||
UNUSED(lun);
|
||||
|
||||
return 1;
|
||||
}
|
||||
#endif
|
||||
|
|
61
src/main/drivers/at32/usbd_msc_mem.h
Normal file
61
src/main/drivers/at32/usbd_msc_mem.h
Normal file
|
@ -0,0 +1,61 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file usbd_msc_mem.h
|
||||
* @author MCD Application Team
|
||||
* @version V1.2.0
|
||||
* @date 09-November-2015
|
||||
* @brief header for the STORAGE DISK file file
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (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/software_license_agreement_liberty_v2
|
||||
*
|
||||
* Unless required by applicable law or agreed to in writing, software
|
||||
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
* See the License for the specific language governing permissions and
|
||||
* limitations under the License.
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
/** @defgroup USBD_MEM_Exported_Defines
|
||||
* @{
|
||||
*/
|
||||
#define USBD_STD_INQUIRY_LENGTH 36
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/** @defgroup USBD_MEM_Exported_TypesDefinitions
|
||||
* @{
|
||||
*/
|
||||
|
||||
typedef struct _USBD_STORAGE
|
||||
{
|
||||
int8_t (* Init) (uint8_t lun);
|
||||
int8_t (* GetCapacity) (uint8_t lun, uint32_t *block_num, uint32_t *block_size);
|
||||
int8_t (* IsReady) (uint8_t lun);
|
||||
int8_t (* IsWriteProtected) (uint8_t lun);
|
||||
int8_t (* Read) (uint8_t lun, uint8_t *buf, uint32_t blk_addr, uint16_t blk_len);
|
||||
int8_t (* Write)(uint8_t lun, uint8_t *buf, uint32_t blk_addr, uint16_t blk_len);
|
||||
int8_t (* GetMaxLun)(void);
|
||||
int8_t *pInquiry;
|
||||
|
||||
} USBD_STORAGE_cb_TypeDef;
|
||||
|
||||
/** @defgroup USBD_MEM_Exported_FunctionsPrototype
|
||||
* @{
|
||||
*/
|
||||
extern USBD_STORAGE_cb_TypeDef *USBD_STORAGE_fops;
|
|
@ -147,6 +147,10 @@ bool isMPUSoftReset(void)
|
|||
|
||||
void systemInit(void)
|
||||
{
|
||||
persistentObjectInit();
|
||||
|
||||
checkForBootLoaderRequest();
|
||||
|
||||
SetSysClock();
|
||||
|
||||
// Configure NVIC preempt/priority groups
|
||||
|
|
|
@ -90,6 +90,8 @@ static void checkForBootLoaderRequest(void)
|
|||
|
||||
void systemInit(void)
|
||||
{
|
||||
persistentObjectInit();
|
||||
|
||||
checkForBootLoaderRequest();
|
||||
|
||||
// Mark ITCM-RAM as read-only
|
||||
|
|
|
@ -29,8 +29,10 @@
|
|||
#include "usbd_msc.h"
|
||||
#else
|
||||
#include "usbd_msc_mem.h"
|
||||
#ifndef AT32F435
|
||||
#include "usbd_msc_core.h"
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#include "usbd_storage.h"
|
||||
|
||||
|
|
|
@ -26,8 +26,10 @@
|
|||
#include "usbd_msc.h"
|
||||
#else
|
||||
#include "usbd_msc_mem.h"
|
||||
#ifndef AT32F435
|
||||
#include "usbd_msc_core.h"
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#include "common/time.h"
|
||||
|
||||
|
|
|
@ -62,6 +62,7 @@
|
|||
#define USE_I2C_DEVICE_3
|
||||
|
||||
#define USE_USB_DETECT
|
||||
#define USE_PERSISTENT_MSC_RTC
|
||||
#define USE_VCP
|
||||
|
||||
#define UNIFIED_SERIAL_PORT_COUNT 1
|
||||
|
|
|
@ -1,52 +1,5 @@
|
|||
CMSIS_DIR := $(ROOT)/lib/main/AT32F43x/cmsis
|
||||
TARGET_MCU := AT32F435
|
||||
MCU_FLASH_SIZE := 4032
|
||||
DEVICE_FLAGS = -DAT32F435ZMT7
|
||||
TARGET_MCU_FAMILY := AT32F4
|
||||
|
||||
AT_LIB_DIR = $(ROOT)/lib/main/AT32F43x
|
||||
STDPERIPH_DIR = $(AT_LIB_DIR)/drivers
|
||||
|
||||
STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c))
|
||||
|
||||
EXCLUDES = at32f435_437_dvp.c \
|
||||
at32f435_437_can.c \
|
||||
at32f435_437_xmc.c \
|
||||
at32f435_437_emac
|
||||
|
||||
STARTUP_SRC = at32/startup_at32f435_437.s
|
||||
STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))
|
||||
|
||||
VPATH := $(VPATH):$(AT_LIB_DIR)/cmsis/cm4/core_support:$(STDPERIPH_DIR)/inc:$(SRC_DIR)/startup/at32:$(STDPERIPH_DIR)/src
|
||||
|
||||
INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
||||
$(SRC_DIR)/startup/at32 \
|
||||
$(STDPERIPH_DIR)/inc \
|
||||
$(AT_LIB_DIR)/cmsis/cm4/core_support \
|
||||
$(AT_LIB_DIR)/cmsis/cm4 \
|
||||
$(AT_LIB_DIR)/middlewares/i2c_application_library \
|
||||
$(AT_LIB_DIR)/middlewares/usb_drivers/inc \
|
||||
$(AT_LIB_DIR)/middlewares/usbd_class/cdc
|
||||
|
||||
DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC)
|
||||
|
||||
TARGET_SRC := \
|
||||
$(AT_LIB_DIR)/middlewares/i2c_application_library/i2c_application.c
|
||||
|
||||
LD_SCRIPT = $(LINKER_DIR)/at32_flash_f43xM.ld
|
||||
|
||||
ARCH_FLAGS = -std=c99 -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion
|
||||
DEVICE_FLAGS += -DUSE_ATBSP_DRIVER -DAT32F43x -DHSE_VALUE=$(HSE_VALUE) -DAT32 -DUSE_OTG_HOST_MODE
|
||||
|
||||
MCU_COMMON_SRC = \
|
||||
$(addprefix startup/at32/,$(notdir $(wildcard $(SRC_DIR)/startup/at32/*.c))) \
|
||||
$(addprefix drivers/at32/,$(notdir $(wildcard $(SRC_DIR)/drivers/at32/*.c))) \
|
||||
drivers/bus_i2c_timing.c \
|
||||
drivers/pwm_output_dshot_shared.c
|
||||
|
||||
MCU_EXCLUDES =
|
||||
|
||||
VCP_SRC = \
|
||||
$(addprefix $(AT_LIB_DIR)/middlewares/usbd_class/cdc/,$(notdir $(wildcard $(AT_LIB_DIR)/middlewares/usbd_class/cdc/*.c))) \
|
||||
$(addprefix $(AT_LIB_DIR)/middlewares/usb_drivers/src/,$(notdir $(wildcard $(AT_LIB_DIR)/middlewares/usb_drivers/src/*.c))) \
|
||||
drivers/usb_io.c
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue