Explorar el Código

Adding Mass Storage to the F4 target

Enabled High Speed USB to the F4 target. In alpha stage. There is
something wrong with SDIO interrupt when going into MSC mode.
A static global variable `transend`` doesn't seem to get updated but the
flag for the interrupt is set the sets it is raised.

For now the code is polling the interrupt handler so the flag can be
cleared and the `transend` variable set.

Search for this comment:

`// \todo Figure out why the SDIO interrupt isn't firing`

To find where the interrupt handler is being polled.
Morio hace 1 año
padre
commit
17067a29a6

+ 241 - 0
lib/ZuluSCSI_platform_GD32F450/ZuluSCSI_platform_msc.cpp

@@ -0,0 +1,241 @@
+/**
+ * Copyright (c) 2023-2024 zigzagjoe
+ * 
+ * ZuluSCSI™ firmware is licensed under the GPL version 3 or any later version. 
+ * 
+ * https://www.gnu.org/licenses/gpl-3.0.html
+ * ----
+ * This program is free software: you can redistribute it and/or modify
+ * it 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. 
+ * 
+ * This program is distributed in the hope that it 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 program.  If not, see <https://www.gnu.org/licenses/>.
+**/
+
+#ifdef PLATFORM_MASS_STORAGE
+
+#include <SdFat.h>
+#include "ZuluSCSI_platform.h"
+#include "ZuluSCSI_log.h"
+#include "ZuluSCSI_msc.h"
+#include "ZuluSCSI_settings.h"
+#include "usb_serial.h"
+
+/* gd32 USB code is all C linked */
+extern "C" {
+  #include <drv_usb_hw.h>
+  #include <usbd_core.h>
+  #include <drv_usbd_int.h>
+
+  #include "usb_conf.h"
+  #include "usbd_msc_core.h"
+  #include "usbd_msc_mem.h"
+  #include "usbd_msc_bbb.h"
+}
+
+
+/* local function prototypes ('static') */
+static int8_t storageInit(uint8_t Lun);
+static int8_t storageIsReady(uint8_t Lun);
+static int8_t storageIsWriteProtected(uint8_t Lun);
+static int8_t storageGetMaxLun(void);
+static int8_t storageRead(uint8_t Lun,
+                           uint8_t *buf,
+                           uint32_t BlkAddr,
+                           uint16_t BlkLen);
+static int8_t storageWrite(uint8_t Lun,
+                            uint8_t *buf,
+                            uint32_t BlkAddr,
+                            uint16_t BlkLen);
+
+usbd_mem_cb USBD_SD_fops = {
+    .mem_init      = storageInit,
+    .mem_ready     = storageIsReady,
+    .mem_protected = storageIsWriteProtected,
+    .mem_read      = storageRead,
+    .mem_write     = storageWrite,
+    .mem_maxlun    = storageGetMaxLun,
+
+    .mem_inquiry_data = {(uint8_t *)storageInquiryData},
+    .mem_block_size   = {SD_SECTOR_SIZE},
+    .mem_block_len    = {0}
+};
+
+usbd_mem_cb *usbd_mem_fops = &USBD_SD_fops;
+
+// shared with usb serial
+extern usb_core_driver cdc_acm;
+
+// external global SD variable
+extern SdFs SD;
+
+// private globals
+static bool unitReady = false;
+
+/* returns true if card reader mode should be entered. sd card is available. */
+bool platform_sense_msc() {
+
+  // kill usb serial.
+  usbd_disconnect (&cdc_acm);
+  // set the MSC storage size
+  usbd_mem_fops->mem_block_len[0] = SD.card()->sectorCount();
+  unitReady = true;
+  
+  // init the MSC class, uses ISR and other global routines from usb_serial.cpp
+  usbd_init(&cdc_acm, USB_CORE_ENUM_HS, &msc_desc, &msc_class);
+
+  logmsg("Waiting for USB enumeration to expose SD card as a mass storage device");
+
+  // wait for up to a second to be begin to be enumerated
+  uint32_t start = millis();
+  while ((uint32_t)(millis() - start) < CR_ENUM_TIMEOUT)
+    if (cdc_acm.dev.cur_status >= USBD_ADDRESSED)
+      return true;
+
+  //if not, disconnect MSC class...
+  usbd_disconnect (&cdc_acm);
+
+  // and bring serial back for later.
+  usb_serial_init();
+
+  return false;
+}
+
+/* perform MSC-specific init tasks */
+void platform_enter_msc() {
+  dbgmsg("USB MSC buffer size: ", (uint32_t) MSC_MEDIA_PACKET_SIZE);
+
+  // give the host a moment to finish enumerate and "load" media
+  uint32_t start = millis();
+  while ((USBD_CONFIGURED != cdc_acm.dev.cur_status) && ((uint32_t)(millis() - start) < CR_ENUM_TIMEOUT) ) 
+    delay(100);
+}
+
+/* return true while remaining in msc mode, and perform periodic tasks */
+bool platform_run_msc() {
+  usbd_msc_handler *msc = (usbd_msc_handler *)cdc_acm.dev.class_data[USBD_MSC_INTERFACE];
+
+  // stupid windows doesn't send start_stop_unit events if it is ejected via safely remove devices. 
+  // it just stops talking to the device so we don't know we've been ejected....
+  // other OSes always send the start_stop_unit, windows does too when ejected from explorer.
+  // so we watch for the OS suspending device and assume we're done in USB mode if so.
+  // this will also trigger if the host were to suspend usb device due to going to sleep
+  // however, I hope no sane OS would sleep mid transfer or with a dirty filesystem. 
+  // Note: Mac OS X apparently not sane.
+  uint8_t is_suspended = cdc_acm.dev.cur_status == (uint8_t)USBD_SUSPENDED;
+
+  return (! msc->scsi_disk_pop) && !is_suspended;
+}
+
+void platform_exit_msc() {
+  unitReady = false;
+
+  // disconnect msc....
+  usbd_disconnect (&cdc_acm);
+
+  // catch our breath....
+  delay(200);
+  
+  // ... and bring usb serial up
+  usb_serial_init();
+}
+
+/*!
+    \brief      initialize the storage medium
+    \param[in]  Lun: logical unit number
+    \param[out] none
+    \retval     status
+*/
+static int8_t storageInit(uint8_t Lun)
+{
+    return 0;
+}
+
+/*!
+    \brief      check whether the medium is ready
+    \param[in]  Lun: logical unit number
+    \param[out] none
+    \retval     status
+*/
+static int8_t storageIsReady(uint8_t Lun)
+{
+    return ! unitReady; // 0 = success / unit is ready
+}
+
+/*!
+    \brief      check whether the medium is write-protected
+    \param[in]  Lun: logical unit number
+    \param[out] none
+    \retval     status
+*/
+static int8_t storageIsWriteProtected(uint8_t Lun)
+{
+    return ! unitReady; // 0 = read/write
+}
+
+/*!
+    \brief      read data from the medium
+    \param[in]  Lun: logical unit number
+    \param[in]  buf: pointer to the buffer to save data
+    \param[in]  BlkAddr: address of 1st block to be read
+    \param[in]  BlkLen: number of blocks to be read
+    \param[out] none
+    \retval     status
+*/
+static int8_t storageRead(uint8_t Lun,
+                           uint8_t *buf,
+                           uint32_t BlkAddr,
+                           uint16_t BlkLen)
+{
+    // divide by sector size to convert address to LBA
+    bool rc = SD.card()->readSectors(BlkAddr/SD_SECTOR_SIZE, buf, BlkLen);
+
+    // only blink fast on reads; writes will override this
+    if (MSC_LEDMode == LED_SOLIDON)
+      MSC_LEDMode = LED_BLINK_FAST;
+      
+    return !rc;
+}
+
+/*!
+    \brief      write data to the medium
+    \param[in]  Lun: logical unit number
+    \param[in]  buf: pointer to the buffer to write
+    \param[in]  BlkAddr: address of 1st block to be written
+    \param[in]  BlkLen: number of blocks to be write
+    \param[out] none
+    \retval     status
+*/
+static int8_t storageWrite(uint8_t Lun,
+                            uint8_t *buf,
+                            uint32_t BlkAddr,
+                            uint16_t BlkLen)
+{
+    // divide by sector size to convert address to LBA
+    bool rc = SD.card()->writeSectors(BlkAddr/SD_SECTOR_SIZE, buf, BlkLen);
+
+    // always slow blink
+    MSC_LEDMode = LED_BLINK_SLOW;
+
+    return !rc;
+}
+
+/*!
+    \brief      get number of supported logical unit
+    \param[in]  none
+    \param[out] none
+    \retval     number of logical unit
+*/
+static int8_t storageGetMaxLun(void)
+{
+    return 0; // number of LUNs supported - 1
+}
+
+#endif // PLATFORM_MASS_STORAGE

+ 59 - 0
lib/ZuluSCSI_platform_GD32F450/ZuluSCSI_platform_msc.h

@@ -0,0 +1,59 @@
+/**
+ * Copyright (c) 2023-2024 zigzagjoe
+ * 
+ * ZuluSCSI™ firmware is licensed under the GPL version 3 or any later version. 
+ * 
+ * https://www.gnu.org/licenses/gpl-3.0.html
+ * ----
+ * This program is free software: you can redistribute it and/or modify
+ * it 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. 
+ * 
+ * This program is distributed in the hope that it 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 program.  If not, see <https://www.gnu.org/licenses/>.
+**/
+
+#ifdef PLATFORM_MASS_STORAGE
+#pragma once
+
+#include "usbd_msc_mem.h"
+
+// private constants/enums
+#define SD_SECTOR_SIZE 512
+
+/* USB Mass storage Standard Inquiry Data */
+const uint8_t storageInquiryData[] = {
+    /* LUN 0 */
+    0x00,
+    0x80,
+    0x00,
+    0x01,
+    (USBD_STD_INQUIRY_LENGTH - 5U),
+    0x00,
+    0x00,
+    0x00,
+    'R', 'a', 'b', 'b', 'i', 't', 'H', 'C', /* Manufacturer : 8 bytes */
+    'Z', 'u', 'l', 'u', 'S', 'C', 'S', 'I', /* Product      : 16 Bytes */
+    ' ', 'F', '4', ' ', ' ', ' ', ' ', ' ',
+    '1', '.', '4' ,'0',                     /* Version      : 4 Bytes */
+};
+
+/* return true if USB presence detected / eligble to enter CR mode */
+bool platform_sense_msc();
+
+/* perform MSC-specific init tasks */
+void platform_enter_msc();
+
+/* return true if we should remain in card reader mode. called in a loop. */
+bool platform_run_msc();
+
+/* perform any cleanup tasks for the MSC-specific functionality */
+void platform_exit_msc();
+
+#endif

+ 10 - 0
lib/ZuluSCSI_platform_GD32F450/gd32_sdio_sdcard.c

@@ -707,6 +707,7 @@ sd_error_enum sd_multiblocks_read(uint32_t *preadbuffer, uint64_t readaddr, uint
             sdio_interrupt_enable(SDIO_INT_DTCRCERR | SDIO_INT_DTTMOUT | SDIO_INT_RXORE | SDIO_INT_DTEND | SDIO_INT_STBITE);
             sdio_dma_enable();
             dma_receive_config(preadbuffer, totalnumber_bytes);
+            
             uint32_t start = millis();
             while((RESET == dma_flag_get(DMA1, DMA_CH3, DMA_FLAG_FTF))) {
                 if((uint32_t)(millis() - start) > 1000) {
@@ -720,6 +721,9 @@ sd_error_enum sd_multiblocks_read(uint32_t *preadbuffer, uint64_t readaddr, uint
                     {
                         callback(complete);
                     }
+                    // \todo Figure out why the SDIO interrupt isn't firing
+                    // Forcing interrupt processing because interrupt doesn't seem to fire
+                    // sd_interrupts_process();
                 }
             }
             while((0 == transend) && (SD_OK == transerror)) {
@@ -727,6 +731,9 @@ sd_error_enum sd_multiblocks_read(uint32_t *preadbuffer, uint64_t readaddr, uint
                 {
                     callback(totalnumber_bytes);
                 }
+                // \todo Figure out why the SDIO interrupt isn't firing
+                // Forcing interrupt processing because interrupt doesn't seem to fire
+                sd_interrupts_process();
             }
             if(SD_OK != transerror) {
                 return transerror;
@@ -1144,6 +1151,9 @@ sd_error_enum sd_multiblocks_write(uint32_t *pwritebuffer, uint64_t writeaddr, u
                 {
                     callback(totalnumber_bytes);
                 }
+                // \todo Figure out why the SDIO interrupt isn't firing
+                // Forcing interrupt processing because interrupt doesn't seem to fire
+                sd_interrupts_process();
             }
             if(SD_OK != transerror) {
                 return transerror;

+ 2 - 2
lib/ZuluSCSI_platform_GD32F450/usb_conf.h

@@ -162,8 +162,8 @@ OF SUCH DAMAGE.
 
 #ifdef USB_HS_INTERNAL_DMA_ENABLED
     #if defined (__GNUC__)         /* GNU Compiler */
-        #define __ALIGN_END __attribute__ ((aligned (4)))
-        #define __ALIGN_BEGIN
+        #define __ALIGN_BEGIN __attribute__ ((aligned (4)))
+        #define __ALIGN_END
     #else
         #define __ALIGN_END
 

+ 0 - 3
lib/ZuluSCSI_platform_GD32F450/usb_hs.cpp

@@ -119,13 +119,10 @@ void usb_mdelay(const uint32_t msec)
     delay(msec);
 }
 
-
-
 void USBHS_IRQHandler(void)
 {
     usbd_isr(&cdc_acm);
 }
-
 #ifdef USB_HS_DEDICATED_EP1_ENABLED
 
 /*!

+ 1 - 13
lib/ZuluSCSI_platform_GD32F450/usb_hs.h

@@ -25,16 +25,4 @@
 
 void usb_hs_init(void);
 bool usb_hs_ready(void);
-void usb_hs_send(uint8_t *data, uint32_t length);
-
-extern "C"
-{
-// Interrupt handlers
-void USBHS_IRQHandler(void);
-#ifdef USB_HS_DEDICATED_EP1_ENABLED
-/* this function handles EP1_IN IRQ Handler */
-void USBHS_EP1_In_IRQHandler(void);
-/* this function handles EP1_OUT IRQ Handler */
-void USBHS_EP1_Out_IRQHandler(void);
-#endif /* USB_HS_DEDICATED_EP1_ENABLED */
-}
+void usb_hs_send(uint8_t *data, uint32_t length);

+ 74 - 0
lib/ZuluSCSI_platform_GD32F450/usb_serial.cpp

@@ -0,0 +1,74 @@
+/** 
+ * ZuluSCSI™ - Copyright (c) 2023 Rabbit Hole Computing™
+ * 
+ * ZuluSCSI™ firmware is licensed under the GPL version 3 or any later version. 
+ * 
+ * https://www.gnu.org/licenses/gpl-3.0.html
+ * ----
+ * This program is free software: you can redistribute it and/or modify
+ * it 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. 
+ * 
+ * This program is distributed in the hope that it 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 program.  If not, see <https://www.gnu.org/licenses/>.
+**/
+
+
+#include "ZuluSCSI_platform.h"
+#include "usb_serial.h"
+
+extern "C" 
+{
+#include <gd32_cdc_acm_core.h>
+#include <drv_usb_hw.h>
+#include <usbd_core.h>
+#include <drv_usbd_int.h>
+
+}
+extern "C" usb_core_driver cdc_acm;
+
+void usb_serial_init(void)
+{
+    // set USB full speed prescaler and turn on USB clock
+#ifdef USE_USB_FS
+    rcu_pll48m_clock_config(RCU_PLL48MSRC_PLLQ);
+    rcu_ck48m_clock_config(RCU_CK48MSRC_PLL48M);
+    rcu_periph_clock_enable(RCU_USBFS);
+#elif defined(USE_USB_HS)
+    #ifdef USE_EMBEDDED_PHY
+        rcu_pll48m_clock_config(RCU_PLL48MSRC_PLLQ);
+        rcu_ck48m_clock_config(RCU_CK48MSRC_PLL48M);
+    #elif defined(USE_ULPI_PHY)
+        rcu_periph_clock_enable(RCU_USBHSULPI);
+    #endif /* USE_EMBEDDED_PHY */
+
+    rcu_periph_clock_enable(RCU_USBHS);
+#endif    
+    usbd_init(&cdc_acm, USB_CORE_ENUM_HS, &gd32_cdc_desc, &gd32_cdc_class);
+}
+
+
+bool usb_serial_ready(void)
+{
+    // check that (our) serial is the currently active class
+    if ((USBD_CONFIGURED == cdc_acm.dev.cur_status) && (cdc_acm.dev.desc == &gd32_cdc_desc)) 
+    {
+        if (1U == gd32_cdc_acm_check_ready(&cdc_acm)) 
+        {
+            return true;
+        }
+    }
+    return false;
+}
+
+void usb_serial_send(uint8_t *data, uint32_t length)
+{
+    gd32_cdc_acm_data_send(&cdc_acm, data, length);
+}
+

+ 35 - 0
lib/ZuluSCSI_platform_GD32F450/usb_serial.h

@@ -0,0 +1,35 @@
+/** 
+ * ZuluSCSI™ - Copyright (c) 2023 Rabbit Hole Computing™
+ * 
+ * ZuluSCSI™ firmware is licensed under the GPL version 3 or any later version. 
+ * 
+ * https://www.gnu.org/licenses/gpl-3.0.html
+ * ----
+ * This program is free software: you can redistribute it and/or modify
+ * it 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. 
+ * 
+ * This program is distributed in the hope that it 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 program.  If not, see <https://www.gnu.org/licenses/>.
+**/
+
+#pragma once
+
+// init USB full speed interface
+void usb_serial_init(void);
+// check if the USB serial interface is ready to send data
+bool usb_serial_ready(void);
+// Send data of the USB serial interface
+void usb_serial_send(uint8_t *data, uint32_t length);
+
+extern "C"
+{
+    // The USB full speed IRQ handler
+    void USBHS_IRQHandler(void);
+}

+ 18 - 0
lib/ZuluSCSI_platform_GD32F450/usbd_conf.h

@@ -43,6 +43,7 @@ OF SUCH DAMAGE.
 #define USBD_ITF_MAX_NUM                    1
 
 #define CDC_COM_INTERFACE                   0
+#define USBD_MSC_INTERFACE              0U
 
 #define USB_STR_DESC_MAX_SIZE               255
 
@@ -50,6 +51,9 @@ OF SUCH DAMAGE.
 #define CDC_DATA_OUT_EP                     EP3_OUT /* EP3 for data OUT */
 #define CDC_CMD_EP                          EP2_IN  /* EP2 for CDC commands */
 
+#define MSC_IN_EP                       EP1_IN
+#define MSC_OUT_EP                      EP1_OUT
+
 #define USB_STRING_COUNT                    4
 
 #define USB_CDC_CMD_PACKET_SIZE             8    /* Control Endpoint Packet size */
@@ -57,6 +61,20 @@ OF SUCH DAMAGE.
 #define APP_RX_DATA_SIZE                    2048 /* Total size of IN buffer: 
                                                     APP_RX_DATA_SIZE*8 / MAX_BAUDARATE * 1000 should be > CDC_IN_FRAME_INTERVAL*8 */
 
+#ifdef USE_USB_HS
+    #ifdef USE_ULPI_PHY
+        #define MSC_DATA_PACKET_SIZE    512U
+    #else
+        #define MSC_DATA_PACKET_SIZE    64U
+    #endif
+#else /*USE_USB_FS*/
+    #define MSC_DATA_PACKET_SIZE        64U
+#endif
+
+#define MSC_MEDIA_PACKET_SIZE           4096U
+
+#define MEM_LUN_NUM                     1U
+
 /* CDC endpoints parameters: you can fine tune these values depending on the needed baud rate and performance */
 #ifdef USE_USB_HS
     #ifdef USE_ULPI_PHY

+ 289 - 0
lib/ZuluSCSI_platform_GD32F450/usbd_msc_bbb.c

@@ -0,0 +1,289 @@
+/*!
+    \file    usbd_msc_bbb.c
+    \brief   USB BBB(Bulk/Bulk/Bulk) protocol core functions
+    \note    BBB means Bulk-only transport protocol for USB MSC
+
+    \version 2020-08-01, V3.0.0, firmware for GD32F4xx
+    \version 2022-03-09, V3.1.0, firmware for GD32F4xx
+    \version 2022-06-30, V3.2.0, firmware for GD32F4xx
+*/
+
+/*
+    Copyright (c) 2022, GigaDevice Semiconductor Inc.
+
+    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. Neither the name of the copyright holder nor the names of its contributors 
+       may be used to endorse or promote products derived from this software without 
+       specific prior written permission.
+
+    THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 
+WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. 
+IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, 
+INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT 
+NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR 
+PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, 
+WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY 
+OF SUCH DAMAGE.
+*/
+
+#include "usbd_enum.h"
+#include "usbd_msc_bbb.h"
+
+/* local function prototypes ('static') */
+static void msc_bbb_cbw_decode (usb_core_driver *udev);
+static void msc_bbb_data_send  (usb_core_driver *udev, uint8_t *pbuf, uint32_t Len);
+static void msc_bbb_abort      (usb_core_driver *udev);
+
+/*!
+    \brief      initialize the BBB process
+    \param[in]  udev: pointer to USB device instance
+    \param[out] none
+    \retval     none
+*/
+void msc_bbb_init (usb_core_driver *udev)
+{
+    uint8_t lun_num;
+
+    usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE];
+
+    msc->bbb_state = BBB_IDLE;
+    msc->bbb_status = BBB_STATUS_NORMAL;
+
+    /* initializes the storage logic unit */
+    for(lun_num = 0U; lun_num < MEM_LUN_NUM; lun_num++) {
+        usbd_mem_fops->mem_init(lun_num);
+    }
+
+    /* flush the Rx FIFO */
+    usbd_fifo_flush (udev, MSC_OUT_EP);
+
+    /* flush the Tx FIFO */
+    usbd_fifo_flush (udev, MSC_IN_EP);
+
+    /* prepare endpoint to receive the first BBB CBW */
+    usbd_ep_recev (udev, MSC_OUT_EP, (uint8_t *)&msc->bbb_cbw, BBB_CBW_LENGTH);
+}
+
+/*!
+    \brief      reset the BBB machine
+    \param[in]  udev: pointer to USB device instance
+    \param[out] none
+    \retval     none
+*/
+void msc_bbb_reset (usb_core_driver *udev)
+{
+    usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE];
+
+    msc->bbb_state = BBB_IDLE;
+    msc->bbb_status = BBB_STATUS_RECOVERY;
+
+    /* prepare endpoint to receive the first BBB command */
+    usbd_ep_recev (udev, MSC_OUT_EP, (uint8_t *)&msc->bbb_cbw, BBB_CBW_LENGTH);
+}
+
+/*!
+    \brief      deinitialize the BBB machine
+    \param[in]  udev: pointer to USB device instance
+    \param[out] none
+    \retval     none
+*/
+void msc_bbb_deinit (usb_core_driver *udev)
+{
+    usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE];
+
+    msc->bbb_state = BBB_IDLE;
+}
+
+/*!
+    \brief      handle BBB data IN stage
+    \param[in]  udev: pointer to USB device instance
+    \param[in]  ep_num: endpoint number
+    \param[out] none
+    \retval     none
+*/
+void msc_bbb_data_in (usb_core_driver *udev, uint8_t ep_num)
+{
+    usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE];
+
+    switch (msc->bbb_state) {
+    case BBB_DATA_IN:
+        if (scsi_process_cmd (udev, msc->bbb_cbw.bCBWLUN, &msc->bbb_cbw.CBWCB[0]) < 0) {
+            msc_bbb_csw_send (udev, CSW_CMD_FAILED);
+        }
+        break;
+
+    case BBB_SEND_DATA:
+    case BBB_LAST_DATA_IN:
+        msc_bbb_csw_send (udev, CSW_CMD_PASSED);
+        break;
+
+    default:
+        break;
+    }
+}
+
+/*!
+    \brief      handle BBB data OUT stage
+    \param[in]  udev: pointer to USB device instance
+    \param[in]  ep_num: endpoint number
+    \param[out] none
+    \retval     none
+*/
+void msc_bbb_data_out (usb_core_driver *udev, uint8_t ep_num)
+{
+    usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE];
+
+    switch (msc->bbb_state) {
+    case BBB_IDLE:
+        msc_bbb_cbw_decode (udev);
+        break;
+
+    case BBB_DATA_OUT:
+        if (scsi_process_cmd (udev, msc->bbb_cbw.bCBWLUN, &msc->bbb_cbw.CBWCB[0]) < 0) {
+            msc_bbb_csw_send (udev, CSW_CMD_FAILED);
+        }
+        break;
+
+    default:
+        break;
+    }
+}
+
+/*!
+    \brief      send the CSW(command status wrapper)
+    \param[in]  udev: pointer to USB device instance
+    \param[in]  csw_status: CSW status
+    \param[out] none
+    \retval     none
+*/
+void msc_bbb_csw_send (usb_core_driver *udev, uint8_t csw_status)
+{
+    usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE];
+
+    msc->bbb_csw.dCSWSignature = BBB_CSW_SIGNATURE;
+    msc->bbb_csw.bCSWStatus = csw_status;
+    msc->bbb_state = BBB_IDLE;
+
+    usbd_ep_send (udev, MSC_IN_EP, (uint8_t *)&msc->bbb_csw, BBB_CSW_LENGTH);
+
+    /* prepare endpoint to receive next command */
+    usbd_ep_recev (udev, MSC_OUT_EP, (uint8_t *)&msc->bbb_cbw, BBB_CBW_LENGTH);
+}
+
+/*!
+    \brief      complete the clear feature request
+    \param[in]  udev: pointer to USB device instance
+    \param[in]  ep_num: endpoint number
+    \param[out] none
+    \retval     none
+*/
+void msc_bbb_clrfeature (usb_core_driver *udev, uint8_t ep_num)
+{
+    usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE];
+
+    if (msc->bbb_status == BBB_STATUS_ERROR) { /* bad CBW signature */ 
+        usbd_ep_stall(udev, MSC_IN_EP);
+
+        msc->bbb_status = BBB_STATUS_NORMAL;
+    } else if(((ep_num & 0x80U) == 0x80U) && (msc->bbb_status != BBB_STATUS_RECOVERY)) {
+        msc_bbb_csw_send (udev, CSW_CMD_FAILED);
+    } else {
+
+    }
+}
+
+/*!
+    \brief      decode the CBW command and set the BBB state machine accordingly
+    \param[in]  udev: pointer to USB device instance
+    \param[out] none
+    \retval     none
+*/
+static void msc_bbb_cbw_decode (usb_core_driver *udev)
+{
+    usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE];
+
+    msc->bbb_csw.dCSWTag = msc->bbb_cbw.dCBWTag;
+    msc->bbb_csw.dCSWDataResidue = msc->bbb_cbw.dCBWDataTransferLength;
+
+    if((BBB_CBW_LENGTH != usbd_rxcount_get(udev, MSC_OUT_EP)) ||
+            (BBB_CBW_SIGNATURE != msc->bbb_cbw.dCBWSignature) ||
+            (msc->bbb_cbw.bCBWLUN > 1U) ||
+            (msc->bbb_cbw.bCBWCBLength < 1U) ||
+            (msc->bbb_cbw.bCBWCBLength > 16U)) {
+        /* illegal command handler */
+        scsi_sense_code (udev, msc->bbb_cbw.bCBWLUN, ILLEGAL_REQUEST, INVALID_CDB);
+
+        msc->bbb_status = BBB_STATUS_ERROR;
+
+        msc_bbb_abort (udev);
+    } else {
+        if (scsi_process_cmd (udev, msc->bbb_cbw.bCBWLUN, &msc->bbb_cbw.CBWCB[0]) < 0) {
+            msc_bbb_abort (udev);
+        } else if ((BBB_DATA_IN != msc->bbb_state) && 
+                    (BBB_DATA_OUT != msc->bbb_state) &&
+                      (BBB_LAST_DATA_IN != msc->bbb_state)) { /* burst xfer handled internally */
+            if (msc->bbb_datalen > 0U) {
+                msc_bbb_data_send (udev, msc->bbb_data, msc->bbb_datalen);
+            } else if (0U == msc->bbb_datalen) {
+                msc_bbb_csw_send (udev, CSW_CMD_PASSED);
+            } else {
+
+            }
+        } else {
+
+        }
+    }
+}
+
+/*!
+    \brief      send the requested data
+    \param[in]  udev: pointer to USB device instance
+    \param[in]  buf: pointer to data buffer
+    \param[in]  len: data length
+    \param[out] none
+    \retval     none
+*/
+static void msc_bbb_data_send (usb_core_driver *udev, uint8_t *buf, uint32_t len)
+{
+    usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE];
+
+    len = USB_MIN (msc->bbb_cbw.dCBWDataTransferLength, len);
+
+    msc->bbb_csw.dCSWDataResidue -= len;
+    msc->bbb_csw.bCSWStatus = CSW_CMD_PASSED;
+    msc->bbb_state = BBB_SEND_DATA;
+
+    usbd_ep_send (udev, MSC_IN_EP, buf, len);
+}
+
+/*!
+    \brief      abort the current transfer
+    \param[in]  udev: pointer to USB device instance
+    \param[out] none
+    \retval     none
+*/
+static void msc_bbb_abort (usb_core_driver *udev)
+{
+    usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE];
+
+    if ((0U == msc->bbb_cbw.bmCBWFlags) && 
+        (0U != msc->bbb_cbw.dCBWDataTransferLength) &&
+        (BBB_STATUS_NORMAL == msc->bbb_status)) {
+        usbd_ep_stall(udev, MSC_OUT_EP);
+    }
+
+    usbd_ep_stall(udev, MSC_IN_EP);
+
+    if (msc->bbb_status == BBB_STATUS_ERROR) {
+        usbd_ep_recev (udev, MSC_OUT_EP, (uint8_t *)&msc->bbb_cbw, BBB_CBW_LENGTH);
+    }
+}

+ 103 - 0
lib/ZuluSCSI_platform_GD32F450/usbd_msc_bbb.h

@@ -0,0 +1,103 @@
+/*!
+    \file    usbd_msc_bbb.h
+    \brief   the header file of the usbd_msc_bbb.c file
+
+    \version 2020-08-01, V3.0.0, firmware for GD32F4xx
+    \version 2022-03-09, V3.1.0, firmware for GD32F4xx
+    \version 2022-06-30, V3.2.0, firmware for GD32F4xx
+*/
+
+/*
+    Copyright (c) 2022, GigaDevice Semiconductor Inc.
+
+    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. Neither the name of the copyright holder nor the names of its contributors 
+       may be used to endorse or promote products derived from this software without 
+       specific prior written permission.
+
+    THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 
+WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. 
+IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, 
+INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT 
+NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR 
+PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, 
+WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY 
+OF SUCH DAMAGE.
+*/
+
+#ifndef __USBD_MSC_BBB_H
+#define __USBD_MSC_BBB_H
+
+#include "usbd_core.h"
+#include "msc_bbb.h"
+#include "usbd_msc_mem.h"
+#include "usbd_msc_scsi.h"
+
+/* MSC BBB state */
+enum msc_bbb_state {
+    BBB_IDLE = 0U,          /*!< idle state  */
+    BBB_DATA_OUT,           /*!< data OUT state */
+    BBB_DATA_IN,            /*!< data IN state */
+    BBB_LAST_DATA_IN,       /*!< last data IN state */
+    BBB_SEND_DATA           /*!< send immediate data state */
+};
+
+/* MSC BBB status */
+enum msc_bbb_status {
+    BBB_STATUS_NORMAL = 0U, /*!< normal status */
+    BBB_STATUS_RECOVERY,    /*!< recovery status*/
+    BBB_STATUS_ERROR        /*!< error status */
+};
+
+typedef struct
+{
+    uint8_t bbb_data[MSC_MEDIA_PACKET_SIZE];
+
+    uint8_t max_lun;
+    uint8_t bbb_state;
+    uint8_t bbb_status;
+
+    uint32_t bbb_datalen;
+
+    msc_bbb_cbw bbb_cbw;
+    msc_bbb_csw bbb_csw;
+
+    uint8_t scsi_sense_head;
+    uint8_t scsi_sense_tail;
+
+    uint32_t scsi_blk_size[MEM_LUN_NUM];
+    uint32_t scsi_blk_nbr[MEM_LUN_NUM];
+
+    uint32_t scsi_blk_addr;
+    uint32_t scsi_blk_len;
+    uint32_t scsi_disk_pop;
+
+    msc_scsi_sense scsi_sense[SENSE_LIST_DEEPTH];
+} usbd_msc_handler;
+
+/* function declarations */
+/* initialize the BBB process */
+void msc_bbb_init (usb_core_driver *udev);
+/* reset the BBB machine */
+void msc_bbb_reset (usb_core_driver *udev);
+/* deinitialize the BBB machine */
+void msc_bbb_deinit (usb_core_driver *udev);
+/* handle BBB data IN stage */
+void msc_bbb_data_in (usb_core_driver *udev, uint8_t ep_num);
+/* handle BBB data OUT stage */
+void msc_bbb_data_out (usb_core_driver *udev, uint8_t ep_num);
+/* send the CSW(command status wrapper) */
+void msc_bbb_csw_send (usb_core_driver *udev, uint8_t csw_status);
+/* complete the clear feature request */
+void msc_bbb_clrfeature (usb_core_driver *udev, uint8_t ep_num);
+
+#endif /* __USBD_MSC_BBB_H */

+ 406 - 0
lib/ZuluSCSI_platform_GD32F450/usbd_msc_core.c

@@ -0,0 +1,406 @@
+/*!
+    \file    usbd_msc_core.c
+    \brief   USB MSC device class core functions
+
+    \version 2020-08-01, V3.0.0, firmware for GD32F4xx
+    \version 2022-03-09, V3.1.0, firmware for GD32F4xx
+    \version 2022-06-30, V3.2.0, firmware for GD32F4xx
+*/
+
+/*
+    Copyright (c) 2022, GigaDevice Semiconductor Inc.
+
+    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. Neither the name of the copyright holder nor the names of its contributors 
+       may be used to endorse or promote products derived from this software without 
+       specific prior written permission.
+
+    THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 
+WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. 
+IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, 
+INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT 
+NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR 
+PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, 
+WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY 
+OF SUCH DAMAGE.
+*/
+
+#include "usbd_enum.h"
+#include "usbd_msc_bbb.h"
+#include "usbd_msc_core.h"
+#include <string.h>
+
+#define USBD_VID                    0x28E9U
+#define USBD_PID                    0x028FU
+
+/* local function prototypes ('static') */
+static uint8_t msc_core_init   (usb_dev *udev, uint8_t config_index);
+static uint8_t msc_core_deinit (usb_dev *udev, uint8_t config_index);
+static uint8_t msc_core_req    (usb_dev *udev, usb_req *req);
+static uint8_t msc_core_in     (usb_dev *udev, uint8_t ep_num);
+static uint8_t msc_core_out    (usb_dev *udev, uint8_t ep_num);
+
+usb_class_core msc_class = 
+{
+    .init     = msc_core_init,
+    .deinit   = msc_core_deinit,
+
+    .req_proc = msc_core_req,
+
+    .data_in  = msc_core_in,
+    .data_out = msc_core_out
+};
+
+/* note: it should use the C99 standard when compiling the below codes */
+/* USB standard device descriptor */
+__ALIGN_BEGIN const usb_desc_dev msc_dev_desc __ALIGN_END =
+{
+    .header = 
+    {
+        .bLength           = USB_DEV_DESC_LEN, 
+        .bDescriptorType   = USB_DESCTYPE_DEV
+    },
+    .bcdUSB                = 0x0200U,
+    .bDeviceClass          = 0x00U,
+    .bDeviceSubClass       = 0x00U,
+    .bDeviceProtocol       = 0x00U,
+    .bMaxPacketSize0       = USB_FS_EP0_MAX_LEN,
+    .idVendor              = USBD_VID,
+    .idProduct             = USBD_PID,
+    .bcdDevice             = 0x0100U,
+    .iManufacturer         = STR_IDX_MFC,
+    .iProduct              = STR_IDX_PRODUCT,
+    .iSerialNumber         = STR_IDX_SERIAL,
+    .bNumberConfigurations = USBD_CFG_MAX_NUM
+};
+
+/* USB device configuration descriptor */
+__ALIGN_BEGIN const usb_desc_config_set msc_config_desc __ALIGN_END = 
+{
+    .config = 
+    {
+        .header = 
+        {
+            .bLength         = sizeof(usb_desc_config), 
+            .bDescriptorType = USB_DESCTYPE_CONFIG
+        },
+        .wTotalLength        = USB_MSC_CONFIG_DESC_SIZE,
+        .bNumInterfaces      = 0x01U,
+        .bConfigurationValue = 0x01U,
+        .iConfiguration      = 0x00U,
+        .bmAttributes        = 0xC0U,
+        .bMaxPower           = 0x32U
+    },
+
+    .msc_itf = 
+    {
+        .header = 
+        {
+            .bLength         = sizeof(usb_desc_itf), 
+            .bDescriptorType = USB_DESCTYPE_ITF
+        },
+        .bInterfaceNumber    = 0x00U,
+        .bAlternateSetting   = 0x00U,
+        .bNumEndpoints       = 0x02U,
+        .bInterfaceClass     = USB_CLASS_MSC,
+        .bInterfaceSubClass  = USB_MSC_SUBCLASS_SCSI,
+        .bInterfaceProtocol  = USB_MSC_PROTOCOL_BBB,
+        .iInterface          = 0x00U
+    },
+
+    .msc_epin = 
+    {
+        .header = 
+        {
+            .bLength         = sizeof(usb_desc_ep), 
+            .bDescriptorType = USB_DESCTYPE_EP
+        },
+        .bEndpointAddress    = MSC_IN_EP,
+        .bmAttributes        = USB_EP_ATTR_BULK,
+        .wMaxPacketSize      = MSC_EPIN_SIZE,
+        .bInterval           = 0x00U
+    },
+
+    .msc_epout = 
+    {
+        .header = 
+        {
+            .bLength         = sizeof(usb_desc_ep), 
+            .bDescriptorType = USB_DESCTYPE_EP
+        },
+        .bEndpointAddress    = MSC_OUT_EP,
+        .bmAttributes        = USB_EP_ATTR_BULK,
+        .wMaxPacketSize      = MSC_EPOUT_SIZE,
+        .bInterval           = 0x00U
+    }
+};
+
+/* USB device configuration descriptor */
+__ALIGN_BEGIN const usb_desc_config_set other_speed_msc_config_desc __ALIGN_END = 
+{
+    .config = 
+    {
+        .header = 
+        {
+            .bLength         = sizeof(usb_desc_config), 
+            .bDescriptorType = USB_DESCTYPE_OTHER_SPD_CONFIG
+        },
+        .wTotalLength        = USB_MSC_CONFIG_DESC_SIZE,
+        .bNumInterfaces      = 0x01U,
+        .bConfigurationValue = 0x01U,
+        .iConfiguration      = 0x00U,
+        .bmAttributes        = 0xC0U,
+        .bMaxPower           = 0x32U
+    },
+
+    .msc_itf = 
+    {
+        .header = 
+        {
+            .bLength         = sizeof(usb_desc_itf), 
+            .bDescriptorType = USB_DESCTYPE_ITF
+        },
+        .bInterfaceNumber    = 0x00U,
+        .bAlternateSetting   = 0x00U,
+        .bNumEndpoints       = 0x02U,
+        .bInterfaceClass     = USB_CLASS_MSC,
+        .bInterfaceSubClass  = USB_MSC_SUBCLASS_SCSI,
+        .bInterfaceProtocol  = USB_MSC_PROTOCOL_BBB,
+        .iInterface          = 0x00U
+    },
+
+    .msc_epin = 
+    {
+        .header = 
+        {
+            .bLength         = sizeof(usb_desc_ep), 
+            .bDescriptorType = USB_DESCTYPE_EP
+        },
+        .bEndpointAddress    = MSC_IN_EP,
+        .bmAttributes        = USB_EP_ATTR_BULK,
+        .wMaxPacketSize      = 64U,
+        .bInterval           = 0x00U
+    },
+
+    .msc_epout = 
+    {
+        .header = 
+        {
+            .bLength         = sizeof(usb_desc_ep), 
+            .bDescriptorType = USB_DESCTYPE_EP
+        },
+        .bEndpointAddress    = MSC_OUT_EP,
+        .bmAttributes        = USB_EP_ATTR_BULK,
+        .wMaxPacketSize      = 64U,
+        .bInterval           = 0x00U
+    }
+};
+
+__ALIGN_BEGIN const uint8_t usbd_qualifier_desc[10] __ALIGN_END = 
+{
+    0x0A, 
+    0x06,
+    0x00, 
+    0x02,
+    0x00, 
+    0x00,
+    0x00, 
+    0x40,
+    0x01, 
+    0x00
+};
+
+/* USB language ID descriptor */
+static __ALIGN_BEGIN const usb_desc_LANGID usbd_language_id_desc __ALIGN_END = 
+{
+    .header = 
+    {
+        .bLength            = sizeof(usb_desc_LANGID), 
+        .bDescriptorType    = USB_DESCTYPE_STR
+    },
+    .wLANGID                 = ENG_LANGID
+};
+
+/* USB manufacture string */
+static __ALIGN_BEGIN const usb_desc_str manufacturer_string __ALIGN_END = 
+{
+    .header =
+    {
+        .bLength         = USB_STRING_LEN(10U),
+        .bDescriptorType = USB_DESCTYPE_STR,
+    },
+    .unicode_string = {'G', 'i', 'g', 'a', 'D', 'e', 'v', 'i', 'c', 'e'}
+};
+
+/* USB product string */
+static __ALIGN_BEGIN const usb_desc_str product_string __ALIGN_END = 
+{
+    .header =
+    {
+        .bLength         = USB_STRING_LEN(12U),
+        .bDescriptorType = USB_DESCTYPE_STR,
+    },
+    .unicode_string = {'G', 'D', '3', '2', '-', 'U', 'S', 'B', '_', 'M', 'S', 'C'}
+};
+
+/* USBD serial string */
+static __ALIGN_BEGIN usb_desc_str serial_string __ALIGN_END = 
+{
+    .header =
+    {
+        .bLength         = USB_STRING_LEN(12U),
+        .bDescriptorType = USB_DESCTYPE_STR,
+    }
+};
+
+/* USB string descriptor */
+static void *const usbd_msc_strings[] = 
+{
+    [STR_IDX_LANGID]  = (uint8_t *)&usbd_language_id_desc,
+    [STR_IDX_MFC]     = (uint8_t *)&manufacturer_string,
+    [STR_IDX_PRODUCT] = (uint8_t *)&product_string,
+    [STR_IDX_SERIAL]  = (uint8_t *)&serial_string
+};
+
+usb_desc msc_desc = {
+    .dev_desc    = (uint8_t *)&msc_dev_desc,
+    .config_desc = (uint8_t *)&msc_config_desc,
+
+#if defined(USE_USB_HS) && defined(USE_ULPI_PHY)
+    .other_speed_config_desc = (uint8_t *)&other_speed_msc_config_desc,
+    .qualifier_desc = (uint8_t *)&usbd_qualifier_desc,
+#endif /* USE_USB_HS && USE_ULPI_PHY */
+
+    .strings     = usbd_msc_strings
+};
+
+static __ALIGN_BEGIN uint8_t usbd_msc_maxlun = 0U __ALIGN_END;
+
+/*!
+    \brief      initialize the MSC device
+    \param[in]  udev: pointer to USB device instance
+    \param[in]  config_index: configuration index
+    \param[out] none
+    \retval     USB device operation status
+*/
+static uint8_t msc_core_init (usb_dev *udev, uint8_t config_index)
+{
+    static __ALIGN_BEGIN usbd_msc_handler msc_handler __ALIGN_END;
+
+    memset((void *)&msc_handler, 0U, sizeof(usbd_msc_handler));
+
+    udev->dev.class_data[USBD_MSC_INTERFACE] = (void *)&msc_handler;
+
+    /* configure MSC Tx endpoint */
+    usbd_ep_setup (udev, &(msc_config_desc.msc_epin));
+
+    /* configure MSC Rx endpoint */
+    usbd_ep_setup (udev, &(msc_config_desc.msc_epout));
+
+    /* initialize the BBB layer */
+    msc_bbb_init(udev);
+
+    return USBD_OK;
+}
+
+/*!
+    \brief      deinitialize the MSC device
+    \param[in]  udev: pointer to USB device instance
+    \param[in]  config_index: configuration index
+    \param[out] none
+    \retval     USB device operation status
+*/
+static uint8_t msc_core_deinit (usb_dev *udev, uint8_t config_index)
+{
+    /* clear MSC endpoints */
+    usbd_ep_clear (udev, MSC_IN_EP);
+    usbd_ep_clear (udev, MSC_OUT_EP);
+
+    /* deinitialize the BBB layer */
+    msc_bbb_deinit(udev);
+
+    return USBD_OK;
+}
+
+/*!
+    \brief      handle the MSC class-specific and standard requests
+    \param[in]  udev: pointer to USB device instance
+    \param[in]  req: device class-specific request
+    \param[out] none
+    \retval     USB device operation status
+*/
+static uint8_t msc_core_req (usb_dev *udev, usb_req *req)
+{
+    usb_transc *transc = &udev->dev.transc_in[0];
+
+    switch (req->bRequest) {
+    case BBB_GET_MAX_LUN :
+        if((0U == req->wValue) && 
+            (1U == req->wLength) &&
+            (0x80U == (req->bmRequestType & 0x80U))) {
+            usbd_msc_maxlun = (uint8_t)usbd_mem_fops->mem_maxlun();
+
+            transc->xfer_buf = &usbd_msc_maxlun;
+            transc->remain_len = 1U;
+        } else {
+            return USBD_FAIL;
+        }
+        break;
+
+    case BBB_RESET :
+        if((0U == req->wValue) && 
+            (0U == req->wLength) &&
+             (0x80U != (req->bmRequestType & 0x80U))) {
+            msc_bbb_reset(udev);
+        } else {
+            return USBD_FAIL;
+        }
+        break;
+
+    case USB_CLEAR_FEATURE:
+        msc_bbb_clrfeature (udev, (uint8_t)req->wIndex);
+        break;
+
+    default:
+        return USBD_FAIL;
+    }
+
+    return USBD_OK;
+}
+
+/*!
+    \brief      handle data in stage
+    \param[in]  udev: pointer to USB device instance
+    \param[in]  ep_num: the endpoint number
+    \param[out] none
+    \retval     none
+*/
+static uint8_t msc_core_in (usb_dev *udev, uint8_t ep_num)
+{
+    msc_bbb_data_in (udev, ep_num);
+
+    return USBD_OK;
+}
+
+/*!
+    \brief      handle data out stage
+    \param[in]  udev: pointer to USB device instance
+    \param[in]  ep_num: the endpoint number
+    \param[out] none
+    \retval     none
+*/
+static uint8_t msc_core_out (usb_dev *udev, uint8_t ep_num)
+{
+    msc_bbb_data_out (udev, ep_num);
+
+    return USBD_OK;
+}

+ 61 - 0
lib/ZuluSCSI_platform_GD32F450/usbd_msc_core.h

@@ -0,0 +1,61 @@
+/*!
+    \file    usbd_msc_core.h
+    \brief   the header file of USB MSC device class core functions
+
+    \version 2020-08-01, V3.0.0, firmware for GD32F4xx
+    \version 2022-03-09, V3.1.0, firmware for GD32F4xx
+    \version 2022-06-30, V3.2.0, firmware for GD32F4xx
+*/
+
+/*
+    Copyright (c) 2022, GigaDevice Semiconductor Inc.
+
+    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. Neither the name of the copyright holder nor the names of its contributors 
+       may be used to endorse or promote products derived from this software without 
+       specific prior written permission.
+
+    THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 
+WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. 
+IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, 
+INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT 
+NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR 
+PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, 
+WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY 
+OF SUCH DAMAGE.
+*/
+
+#ifndef __USBD_MSC_CORE_H
+#define __USBD_MSC_CORE_H
+
+#include "usbd_core.h"
+#include "usb_msc.h"
+
+#define USB_MSC_CONFIG_DESC_SIZE          32U
+
+#define MSC_EPIN_SIZE                     MSC_DATA_PACKET_SIZE
+#define MSC_EPOUT_SIZE                    MSC_DATA_PACKET_SIZE
+
+/* USB configuration descriptor structure */
+typedef struct
+{
+    usb_desc_config         config;
+
+    usb_desc_itf            msc_itf;
+    usb_desc_ep             msc_epin;
+    usb_desc_ep             msc_epout;
+} usb_desc_config_set;
+
+extern usb_desc msc_desc;
+extern usb_class_core msc_class;
+
+#endif /* __USBD_MSC_CORE_H */

+ 61 - 0
lib/ZuluSCSI_platform_GD32F450/usbd_msc_mem.h

@@ -0,0 +1,61 @@
+/*!
+    \file    usbd_msc_mem.h
+    \brief   header file for storage memory
+
+    \version 2020-08-01, V3.0.0, firmware for GD32F4xx
+    \version 2022-03-09, V3.1.0, firmware for GD32F4xx
+    \version 2022-06-30, V3.2.0, firmware for GD32F4xx
+*/
+
+/*
+    Copyright (c) 2022, GigaDevice Semiconductor Inc.
+
+    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. Neither the name of the copyright holder nor the names of its contributors 
+       may be used to endorse or promote products derived from this software without 
+       specific prior written permission.
+
+    THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 
+WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. 
+IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, 
+INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT 
+NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR 
+PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, 
+WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY 
+OF SUCH DAMAGE.
+*/
+
+#ifndef __USBD_MSC_MEM_H
+#define __USBD_MSC_MEM_H
+
+#include "usbd_conf.h"
+
+#define USBD_STD_INQUIRY_LENGTH     36U
+
+typedef struct
+{
+    int8_t (*mem_init)         (uint8_t lun);
+    int8_t (*mem_ready)        (uint8_t lun);
+    int8_t (*mem_protected)    (uint8_t lun);
+    int8_t (*mem_read)         (uint8_t lun, uint8_t *buf, uint32_t block_addr, uint16_t block_len);
+    int8_t (*mem_write)        (uint8_t lun, uint8_t *buf, uint32_t block_addr, uint16_t block_len);
+    int8_t (*mem_maxlun)       (void);
+
+    uint8_t *mem_toc_data;
+    uint8_t *mem_inquiry_data[MEM_LUN_NUM];
+    uint32_t mem_block_size[MEM_LUN_NUM];
+    uint32_t mem_block_len[MEM_LUN_NUM];
+} usbd_mem_cb;
+
+extern usbd_mem_cb *usbd_mem_fops;
+
+#endif /* __USBD_MSC_MEM_H */

+ 781 - 0
lib/ZuluSCSI_platform_GD32F450/usbd_msc_scsi.c

@@ -0,0 +1,781 @@
+/*!
+    \file    usbd_msc_scsi.c
+    \brief   USB SCSI layer functions
+
+    \version 2020-08-01, V3.0.0, firmware for GD32F4xx
+    \version 2022-03-09, V3.1.0, firmware for GD32F4xx
+    \version 2022-06-30, V3.2.0, firmware for GD32F4xx
+*/
+
+/*
+    Copyright (c) 2022, GigaDevice Semiconductor Inc.
+
+    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. Neither the name of the copyright holder nor the names of its contributors 
+       may be used to endorse or promote products derived from this software without 
+       specific prior written permission.
+
+    THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 
+WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. 
+IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, 
+INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT 
+NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR 
+PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, 
+WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY 
+OF SUCH DAMAGE.
+*/
+
+#include "usbd_enum.h"
+#include "usbd_msc_bbb.h"
+#include "usbd_msc_scsi.h"
+
+/* USB mass storage page 0 inquiry data */
+const uint8_t msc_page00_inquiry_data[] = 
+{
+    0x00U,
+    0x00U,
+    0x00U,
+    0x00U,
+    (INQUIRY_PAGE00_LENGTH - 4U),
+    0x80U,
+    0x83U,
+};
+
+/* USB mass storage sense 6 data */
+const uint8_t msc_mode_sense6_data[] = 
+{
+    0x00U,
+    0x00U,
+    0x00U,
+    0x00U,
+    0x00U,
+    0x00U,
+    0x00U,
+    0x00U
+};
+
+/* USB mass storage sense 10 data */
+const uint8_t msc_mode_sense10_data[] = 
+{
+    0x00U,
+    0x06U,
+    0x00U,
+    0x00U,
+    0x00U,
+    0x00U,
+    0x00U,
+    0x00U
+};
+
+/* local function prototypes ('static') */
+static int8_t scsi_test_unit_ready      (usb_core_driver *udev, uint8_t lun, uint8_t *params);
+static int8_t scsi_mode_select6         (usb_core_driver *udev, uint8_t lun, uint8_t *params);
+static int8_t scsi_mode_select10        (usb_core_driver *udev, uint8_t lun, uint8_t *params);
+static int8_t scsi_inquiry              (usb_core_driver *udev, uint8_t lun, uint8_t *params);
+static int8_t scsi_read_format_capacity (usb_core_driver *udev, uint8_t lun, uint8_t *params);
+static int8_t scsi_read_capacity10      (usb_core_driver *udev, uint8_t lun, uint8_t *params);
+static int8_t scsi_request_sense        (usb_core_driver *udev, uint8_t lun, uint8_t *params);
+static int8_t scsi_mode_sense6          (usb_core_driver *udev, uint8_t lun, uint8_t *params);
+static int8_t scsi_toc_cmd_read         (usb_core_driver *udev, uint8_t lun, uint8_t *params);
+static int8_t scsi_mode_sense10         (usb_core_driver *udev, uint8_t lun, uint8_t *params);
+static int8_t scsi_write10              (usb_core_driver *udev, uint8_t lun, uint8_t *params);
+static int8_t scsi_read10               (usb_core_driver *udev, uint8_t lun, uint8_t *params);
+static int8_t scsi_verify10             (usb_core_driver *udev, uint8_t lun, uint8_t *params);
+
+static int8_t scsi_process_read         (usb_core_driver *udev, uint8_t lun);
+static int8_t scsi_process_write        (usb_core_driver *udev, uint8_t lun);
+
+static inline int8_t scsi_check_address_range  (usb_core_driver *udev, uint8_t lun, uint32_t blk_offset, uint16_t blk_nbr);
+static inline int8_t scsi_format_cmd           (usb_core_driver *udev, uint8_t lun);
+static inline int8_t scsi_start_stop_unit      (usb_core_driver *udev, uint8_t lun, uint8_t *params);
+static inline int8_t scsi_allow_medium_removal (usb_core_driver *udev, uint8_t lun, uint8_t *params);
+
+/*!
+    \brief      process SCSI commands
+    \param[in]  udev: pointer to USB device instance
+    \param[in]  lun: logical unit number
+    \param[in]  params: command parameters
+    \param[out] none
+    \retval     status
+*/
+int8_t scsi_process_cmd(usb_core_driver *udev, uint8_t lun, uint8_t *params)
+{
+    switch (params[0]) {
+    case SCSI_TEST_UNIT_READY:
+        return scsi_test_unit_ready (udev, lun, params);
+
+    case SCSI_REQUEST_SENSE:
+        return scsi_request_sense (udev, lun, params);
+
+    case SCSI_INQUIRY:
+        return scsi_inquiry (udev, lun, params);
+
+    case SCSI_START_STOP_UNIT:
+        return scsi_start_stop_unit (udev, lun, params);
+
+    case SCSI_ALLOW_MEDIUM_REMOVAL:
+        return scsi_allow_medium_removal (udev, lun, params);
+
+    case SCSI_MODE_SENSE6:
+        return scsi_mode_sense6 (udev, lun, params);
+
+    case SCSI_MODE_SENSE10:
+        return scsi_mode_sense10 (udev, lun, params);
+
+    case SCSI_READ_FORMAT_CAPACITIES:
+        return scsi_read_format_capacity (udev, lun, params);
+
+    case SCSI_READ_CAPACITY10:
+        return scsi_read_capacity10 (udev, lun, params);
+
+    case SCSI_READ10:
+        return scsi_read10 (udev, lun, params); 
+
+    case SCSI_WRITE10:
+        return scsi_write10 (udev, lun, params);
+
+    case SCSI_VERIFY10:
+        return scsi_verify10 (udev, lun, params);
+
+    case SCSI_FORMAT_UNIT:
+        return scsi_format_cmd (udev, lun);
+
+    case SCSI_READ_TOC_DATA:
+        return scsi_toc_cmd_read (udev, lun, params);
+
+    case SCSI_MODE_SELECT6:
+        return scsi_mode_select6 (udev, lun, params);
+
+    case SCSI_MODE_SELECT10:
+        return scsi_mode_select10 (udev, lun, params);
+
+    default:
+        scsi_sense_code (udev, lun, ILLEGAL_REQUEST, INVALID_CDB);
+        return -1;
+    }
+}
+
+/*!
+    \brief      load the last error code in the error list
+    \param[in]  udev: pointer to USB device instance
+    \param[in]  lun: logical unit number
+    \param[in]  skey: sense key
+    \param[in]  asc: additional sense key
+    \param[out] none
+    \retval     none
+*/
+void scsi_sense_code (usb_core_driver *udev, uint8_t lun, uint8_t skey, uint8_t asc)
+{
+    usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE];
+
+    msc->scsi_sense[msc->scsi_sense_tail].SenseKey = skey;
+    msc->scsi_sense[msc->scsi_sense_tail].ASC = asc;
+    msc->scsi_sense_tail++;
+
+    if (SENSE_LIST_DEEPTH == msc->scsi_sense_tail) {
+        msc->scsi_sense_tail = 0U;
+    }
+}
+
+/*!
+    \brief      process SCSI Test Unit Ready command
+    \param[in]  udev: pointer to USB device instance
+    \param[in]  lun: logical unit number
+    \param[in]  params: command parameters
+    \param[out] none
+    \retval     status
+*/
+static int8_t scsi_test_unit_ready (usb_core_driver *udev, uint8_t lun, uint8_t *params)
+{
+    usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE];
+
+    /* case 9 : Hi > D0 */
+    if (0U != msc->bbb_cbw.dCBWDataTransferLength) {
+        scsi_sense_code (udev, msc->bbb_cbw.bCBWLUN, ILLEGAL_REQUEST, INVALID_CDB);
+
+        return -1;
+    }
+
+    if (0 != usbd_mem_fops->mem_ready(lun)) {
+        scsi_sense_code(udev, lun, NOT_READY, MEDIUM_NOT_PRESENT);
+
+        return -1;
+    }
+
+    msc->bbb_datalen = 0U;
+
+    return 0;
+}
+
+/*!
+    \brief      process Inquiry command
+    \param[in]  udev: pointer to USB device instance
+    \param[in]  lun: logical unit number
+    \param[in]  params: command parameters
+    \param[out] none
+    \retval     status
+*/
+static int8_t scsi_mode_select6 (usb_core_driver *udev, uint8_t lun, uint8_t *params)
+{
+    usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE];
+
+    msc->bbb_datalen = 0U;
+
+    return 0;
+}
+
+/*!
+    \brief      process Inquiry command
+    \param[in]  udev: pointer to USB device instance
+    \param[in]  lun: logical unit number
+    \param[in]  params: command parameters
+    \param[out] none
+    \retval     status
+*/
+static int8_t scsi_mode_select10 (usb_core_driver *udev, uint8_t lun, uint8_t *params)
+{
+    usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE];
+
+    msc->bbb_datalen = 0U;
+
+    return 0;
+}
+
+/*!
+    \brief      process Inquiry command
+    \param[in]  udev: pointer to USB device instance
+    \param[in]  lun: logical unit number
+    \param[in]  params: command parameters
+    \param[out] none
+    \retval     status
+*/
+static int8_t scsi_inquiry (usb_core_driver *udev, uint8_t lun, uint8_t *params)
+{
+    uint8_t *page = NULL;
+    uint16_t len = 0U;
+
+    usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE];
+
+    if (params[1] & 0x01U) {
+        page = (uint8_t *)msc_page00_inquiry_data;
+
+        len = INQUIRY_PAGE00_LENGTH;
+    } else {
+        page = (uint8_t *)usbd_mem_fops->mem_inquiry_data[lun];
+
+        len = (uint16_t)(page[4] + 5U);
+
+        if (params[4] <= len) {
+            len = params[4];
+        }
+    }
+
+    msc->bbb_datalen = len;
+
+    while (len) {
+        len--;
+        msc->bbb_data[len] = page[len];
+    }
+
+    return 0;
+}
+
+/*!
+    \brief      process Read Capacity 10 command
+    \param[in]  udev: pointer to USB device instance
+    \param[in]  lun: logical unit number
+    \param[in]  params: command parameters
+    \param[out] none
+    \retval     status
+*/
+static int8_t scsi_read_capacity10 (usb_core_driver *udev, uint8_t lun, uint8_t *params)
+{
+    uint32_t blk_num = usbd_mem_fops->mem_block_len[lun] - 1U;
+    usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE];
+
+    msc->scsi_blk_nbr[lun] = usbd_mem_fops->mem_block_len[lun];
+    msc->scsi_blk_size[lun] = usbd_mem_fops->mem_block_size[lun];
+
+    msc->bbb_data[0] = (uint8_t)(blk_num >> 24U);
+    msc->bbb_data[1] = (uint8_t)(blk_num >> 16U);
+    msc->bbb_data[2] = (uint8_t)(blk_num >> 8U);
+    msc->bbb_data[3] = (uint8_t)(blk_num);
+
+    msc->bbb_data[4] = (uint8_t)(msc->scsi_blk_size[lun] >> 24U);
+    msc->bbb_data[5] = (uint8_t)(msc->scsi_blk_size[lun] >> 16U);
+    msc->bbb_data[6] = (uint8_t)(msc->scsi_blk_size[lun] >> 8U);
+    msc->bbb_data[7] = (uint8_t)(msc->scsi_blk_size[lun]);
+
+    msc->bbb_datalen = 8U;
+
+    return 0;
+}
+
+/*!
+    \brief      process Read Format Capacity command
+    \param[in]  udev: pointer to USB device instance
+    \param[in]  lun: logical unit number
+    \param[in]  params: command parameters
+    \param[out] none
+    \retval     status
+*/
+static int8_t scsi_read_format_capacity (usb_core_driver *udev, uint8_t lun, uint8_t *params)
+{
+    uint16_t i = 0U;
+    uint32_t blk_size = usbd_mem_fops->mem_block_size[lun];
+    uint32_t blk_num = usbd_mem_fops->mem_block_len[lun];
+    uint32_t blk_nbr = blk_num - 1U;
+
+    usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE];
+
+    for (i = 0U; i < 12U; i++) {
+        msc->bbb_data[i] = 0U;
+    }
+
+    msc->bbb_data[3] = 0x08U;
+    msc->bbb_data[4] = (uint8_t)(blk_nbr >> 24U);
+    msc->bbb_data[5] = (uint8_t)(blk_nbr >> 16U);
+    msc->bbb_data[6] = (uint8_t)(blk_nbr >>  8U);
+    msc->bbb_data[7] = (uint8_t)(blk_nbr);
+
+    msc->bbb_data[8] = 0x02U;
+    msc->bbb_data[9] = (uint8_t)(blk_size >> 16U);
+    msc->bbb_data[10] = (uint8_t)(blk_size >> 8U);
+    msc->bbb_data[11] = (uint8_t)(blk_size);
+
+    msc->bbb_datalen = 12U;
+
+    return 0;
+}
+
+/*!
+    \brief      process Mode Sense6 command
+    \param[in]  udev: pointer to USB device instance
+    \param[in]  lun: logical unit number
+    \param[in]  params: command parameters
+    \param[out] none
+    \retval     status
+*/
+static int8_t scsi_mode_sense6 (usb_core_driver *udev, uint8_t lun, uint8_t *params)
+{
+    uint16_t len = 8U;
+    usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE];
+
+    msc->bbb_datalen = len;
+
+    while (len) {
+        len--;
+        msc->bbb_data[len] = msc_mode_sense6_data[len];
+    }
+
+    return 0;
+}
+
+/*!
+    \brief      process Mode Sense10 command
+    \param[in]  udev: pointer to USB device instance
+    \param[in]  lun: logical unit number
+    \param[in]  params: command parameters
+    \param[out] none
+    \retval     status
+*/
+static int8_t scsi_mode_sense10 (usb_core_driver *udev, uint8_t lun, uint8_t *params)
+{
+    uint16_t len = 8U;
+    usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE];
+
+    msc->bbb_datalen = len;
+
+    while (len) {
+        len--;
+        msc->bbb_data[len] = msc_mode_sense10_data[len];
+    }
+
+    return 0;
+}
+
+/*!
+    \brief      process Request Sense command
+    \param[in]  udev: pointer to USB device instance
+    \param[in]  lun: logical unit number
+    \param[in]  params: command parameters
+    \param[out] none
+    \retval     status
+*/
+static int8_t scsi_request_sense (usb_core_driver *udev, uint8_t lun, uint8_t *params)
+{
+    uint8_t i = 0U;
+    usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE];
+
+    for (i = 0U; i < REQUEST_SENSE_DATA_LEN; i++) {
+        msc->bbb_data[i] = 0U;
+    }
+
+    msc->bbb_data[0] = 0x70U;
+    msc->bbb_data[7] = REQUEST_SENSE_DATA_LEN - 6U;
+
+    if ((msc->scsi_sense_head != msc->scsi_sense_tail)) {
+        msc->bbb_data[2] = msc->scsi_sense[msc->scsi_sense_head].SenseKey;
+        msc->bbb_data[12] = msc->scsi_sense[msc->scsi_sense_head].ASC;
+        msc->bbb_data[13] = msc->scsi_sense[msc->scsi_sense_head].ASCQ;
+        msc->scsi_sense_head++;
+
+        if (msc->scsi_sense_head == SENSE_LIST_DEEPTH) {
+            msc->scsi_sense_head = 0U;
+        }
+    }
+
+    msc->bbb_datalen = USB_MIN(REQUEST_SENSE_DATA_LEN, params[4]);
+
+    return 0;
+}
+
+
+/*
+byte 5 (index 4) of start stop unit 
+7  6  5  4  3  2  1  0
+[ PWRCON ]  R  F  E  S
+S = start
+E = loadeject
+*/
+
+#define STARTSTOPUNIT_START (1)
+#define STARTSTOPUNIT_LOADEJECT (2)
+
+
+/*!
+    \brief      process Start Stop Unit command
+    \param[in]  udev: pointer to USB device instance
+    \param[in]  lun: logical unit number
+    \param[in]  params: command parameters
+    \param[out] none
+    \retval     status
+*/
+static inline int8_t scsi_start_stop_unit (usb_core_driver *udev, uint8_t lun, uint8_t *params)
+{
+    usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE];
+
+    msc->bbb_datalen = 0U;
+    /* not part of GDS class! make sure to bring this over if updating USB class */
+    // if start = 0, load eject = 1,  host is advising of media eject (usually a device removal too)
+    if ((params[4] & STARTSTOPUNIT_LOADEJECT)) {
+        if (!(params[4] & STARTSTOPUNIT_START))
+            msc->scsi_disk_pop = 1U;
+    }
+
+    return 0;
+}
+
+/*!
+    \brief      process Allow Medium Removal command
+    \param[in]  udev: pointer to USB device instance
+    \param[in]  lun: logical unit number
+    \param[in]  params: command parameters
+    \param[out] none
+    \retval     status
+*/
+static inline int8_t scsi_allow_medium_removal (usb_core_driver *udev, uint8_t lun, uint8_t *params)
+{
+    usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE];
+
+    msc->bbb_datalen = 0U;
+
+    return 0;
+}
+
+/*!
+    \brief      process Read10 command
+    \param[in]  udev: pointer to USB device instance
+    \param[in]  lun: logical unit number
+    \param[in]  params: command parameters
+    \param[out] none
+    \retval     status
+*/
+static int8_t scsi_read10 (usb_core_driver *udev, uint8_t lun, uint8_t *params)
+{
+    usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE];
+
+    if (msc->bbb_state == BBB_IDLE) {
+        /* direction is from device to host */
+        if (0x80U != (msc->bbb_cbw.bmCBWFlags & 0x80U)) {
+            scsi_sense_code (udev, msc->bbb_cbw.bCBWLUN, ILLEGAL_REQUEST, INVALID_CDB);
+
+            return -1;
+        }
+
+        if (0 != usbd_mem_fops->mem_ready(lun)) {
+            scsi_sense_code (udev, lun, NOT_READY, MEDIUM_NOT_PRESENT);
+
+            return -1;
+        }
+
+        msc->scsi_blk_addr = (params[2] << 24U) | (params[3] << 16U) | \
+                             (params[4] << 8U) |  params[5];
+
+        msc->scsi_blk_len = (params[7] << 8U) | params[8];
+
+        if (scsi_check_address_range (udev, lun, msc->scsi_blk_addr, (uint16_t)msc->scsi_blk_len) < 0) {
+            return -1; /* error */
+        }
+
+        msc->bbb_state = BBB_DATA_IN;
+
+        msc->scsi_blk_addr *= msc->scsi_blk_size[lun];
+        msc->scsi_blk_len  *= msc->scsi_blk_size[lun];
+
+        /* cases 4,5 : Hi <> Dn */
+        if (msc->bbb_cbw.dCBWDataTransferLength != msc->scsi_blk_len) {
+            scsi_sense_code (udev, msc->bbb_cbw.bCBWLUN, ILLEGAL_REQUEST, INVALID_CDB);
+
+            return -1;
+        }
+    }
+
+    msc->bbb_datalen = MSC_MEDIA_PACKET_SIZE;
+
+    return scsi_process_read (udev, lun);
+}
+
+/*!
+    \brief      process Write10 command
+    \param[in]  udev: pointer to USB device instance
+    \param[in]  lun: logical unit number
+    \param[in]  params: command parameters
+    \param[out] none
+    \retval     status
+*/
+static int8_t scsi_write10 (usb_core_driver *udev, uint8_t lun, uint8_t *params)
+{
+    usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE];
+
+    if (BBB_IDLE == msc->bbb_state) {
+        /* case 8 : Hi <> Do */
+        if (0x80U == (msc->bbb_cbw.bmCBWFlags & 0x80U)) {
+            scsi_sense_code (udev, msc->bbb_cbw.bCBWLUN, ILLEGAL_REQUEST, INVALID_CDB);
+
+            return -1;
+        }
+
+        /* check whether media is ready */
+        if (0 != usbd_mem_fops->mem_ready(lun)) {
+            scsi_sense_code (udev, lun, NOT_READY, MEDIUM_NOT_PRESENT);
+
+            return -1;
+        }
+
+        /* check if media is write-protected */
+        if (0 != usbd_mem_fops->mem_protected(lun)) {
+            scsi_sense_code (udev, lun, NOT_READY, WRITE_PROTECTED);
+
+            return -1;
+        }
+
+        msc->scsi_blk_addr = (params[2] << 24U) | (params[3] << 16U) | \
+                             (params[4] << 8U) |  params[5];
+
+        msc->scsi_blk_len = (params[7] << 8U) | params[8];
+
+        /* check if LBA address is in the right range */
+        if (scsi_check_address_range (udev, lun, msc->scsi_blk_addr, (uint16_t)msc->scsi_blk_len) < 0) {
+            return -1; /* error */
+        }
+
+        msc->scsi_blk_addr *= msc->scsi_blk_size[lun];
+        msc->scsi_blk_len  *= msc->scsi_blk_size[lun];
+
+        /* cases 3,11,13 : Hn,Ho <> D0 */
+        if (msc->bbb_cbw.dCBWDataTransferLength != msc->scsi_blk_len) {
+            scsi_sense_code (udev, msc->bbb_cbw.bCBWLUN, ILLEGAL_REQUEST, INVALID_CDB);
+
+            return -1;
+        }
+
+        /* prepare endpoint to receive first data packet */
+        msc->bbb_state = BBB_DATA_OUT;
+
+        usbd_ep_recev (udev, 
+                       MSC_OUT_EP, 
+                       msc->bbb_data, 
+                       USB_MIN (msc->scsi_blk_len, MSC_MEDIA_PACKET_SIZE));
+    } else { /* write process ongoing */
+        return scsi_process_write (udev, lun);
+    }
+
+    return 0;
+}
+
+/*!
+    \brief      process Verify10 command
+    \param[in]  udev: pointer to USB device instance
+    \param[in]  lun: logical unit number
+    \param[in]  params: command parameters
+    \param[out] none
+    \retval     status
+*/
+static int8_t scsi_verify10 (usb_core_driver *udev, uint8_t lun, uint8_t *params)
+{
+    usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE];
+
+    if (0x02U == (params[1] & 0x02U)) {
+        scsi_sense_code (udev, lun, ILLEGAL_REQUEST, INVALID_FIELED_IN_COMMAND);
+
+        return -1; /* error, verify mode not supported*/
+    }
+
+    if (scsi_check_address_range (udev, lun, msc->scsi_blk_addr, (uint16_t)msc->scsi_blk_len) < 0) {
+        return -1; /* error */
+    }
+
+    msc->bbb_datalen = 0U;
+
+    return 0;
+}
+
+/*!
+    \brief      check address range
+    \param[in]  udev: pointer to USB device instance
+    \param[in]  lun: logical unit number
+    \param[in]  blk_offset: block offset
+    \param[in]  blk_nbr: number of block to be processed
+    \param[out] none
+    \retval     status
+*/
+static inline int8_t scsi_check_address_range (usb_core_driver *udev, uint8_t lun, uint32_t blk_offset, uint16_t blk_nbr)
+{
+    usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE];
+
+    if ((blk_offset + blk_nbr) > msc->scsi_blk_nbr[lun]) {
+        scsi_sense_code (udev, lun, ILLEGAL_REQUEST, ADDRESS_OUT_OF_RANGE);
+
+        return -1;
+    }
+
+    return 0;
+}
+
+/*!
+    \brief      handle read process
+    \param[in]  udev: pointer to USB device instance
+    \param[in]  lun: logical unit number
+    \param[out] none
+    \retval     status
+*/
+static int8_t scsi_process_read (usb_core_driver *udev, uint8_t lun)
+{
+    usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE];
+
+    uint32_t len = USB_MIN(msc->scsi_blk_len, MSC_MEDIA_PACKET_SIZE);
+
+    if (usbd_mem_fops->mem_read(lun,
+                                msc->bbb_data, 
+                                msc->scsi_blk_addr, 
+                                (uint16_t)(len / msc->scsi_blk_size[lun])) < 0) {
+        scsi_sense_code(udev, lun, HARDWARE_ERROR, UNRECOVERED_READ_ERROR);
+
+        return -1; 
+    }
+
+    usbd_ep_send (udev, MSC_IN_EP, msc->bbb_data, len);
+
+    msc->scsi_blk_addr += len;
+    msc->scsi_blk_len  -= len;
+
+    /* case 6 : Hi = Di */
+    msc->bbb_csw.dCSWDataResidue -= len;
+
+    if (0U == msc->scsi_blk_len) {
+        msc->bbb_state = BBB_LAST_DATA_IN;
+    }
+
+    return 0;
+}
+
+/*!
+    \brief      handle write process
+    \param[in]  udev: pointer to USB device instance
+    \param[in]  lun: logical unit number
+    \param[out] none
+    \retval     status
+*/
+static int8_t scsi_process_write (usb_core_driver *udev, uint8_t lun)
+{
+    usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE];
+
+    uint32_t len = USB_MIN(msc->scsi_blk_len, MSC_MEDIA_PACKET_SIZE);
+
+    if (usbd_mem_fops->mem_write (lun,
+                                  msc->bbb_data, 
+                                  msc->scsi_blk_addr, 
+                                  (uint16_t)(len / msc->scsi_blk_size[lun])) < 0) {
+        scsi_sense_code(udev, lun, HARDWARE_ERROR, WRITE_FAULT);
+
+        return -1;
+    }
+
+    msc->scsi_blk_addr += len;
+    msc->scsi_blk_len  -= len;
+
+    /* case 12 : Ho = Do */
+    msc->bbb_csw.dCSWDataResidue -= len;
+
+    if (0U == msc->scsi_blk_len) {
+        msc_bbb_csw_send (udev, CSW_CMD_PASSED);
+    } else {
+        /* prepare endpoint to receive next packet */
+        usbd_ep_recev (udev, 
+                       MSC_OUT_EP, 
+                       msc->bbb_data, 
+                       USB_MIN (msc->scsi_blk_len, MSC_MEDIA_PACKET_SIZE));
+    }
+
+    return 0;
+}
+
+/*!
+    \brief      process Format Unit command
+    \param[in]  udev: pointer to USB device instance
+    \param[in]  lun: logical unit number
+    \param[out] none
+    \retval     status
+*/
+static inline int8_t scsi_format_cmd (usb_core_driver *udev, uint8_t lun)
+{
+    return 0;
+}
+
+/*!
+    \brief      process Read_Toc command
+    \param[in]  udev: pointer to USB device instance
+    \param[in]  lun: logical unit number
+    \param[in]  params: command parameters
+    \param[out] none
+    \retval     status
+*/
+static int8_t scsi_toc_cmd_read (usb_core_driver *udev, uint8_t lun, uint8_t *params)
+{
+    uint8_t* pPage;
+    uint16_t len;
+
+    usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE];
+
+    pPage = (uint8_t *)&usbd_mem_fops->mem_toc_data[lun * READ_TOC_CMD_LEN];
+    len = (uint16_t)pPage[1] + 2U;
+
+    msc->bbb_datalen = len;
+
+    while (len) {
+        len--;
+        msc->bbb_data[len] = pPage[len];
+    }
+
+    return 0;
+}

+ 60 - 0
lib/ZuluSCSI_platform_GD32F450/usbd_msc_scsi.h

@@ -0,0 +1,60 @@
+/*!
+    \file    usbd_msc_scsi.h
+    \brief   the header file of the usbd_msc_scsi.c file
+
+    \version 2020-08-01, V3.0.0, firmware for GD32F4xx
+    \version 2022-03-09, V3.1.0, firmware for GD32F4xx
+    \version 2022-06-30, V3.2.0, firmware for GD32F4xx
+*/
+
+/*
+    Copyright (c) 2022, GigaDevice Semiconductor Inc.
+
+    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. Neither the name of the copyright holder nor the names of its contributors 
+       may be used to endorse or promote products derived from this software without 
+       specific prior written permission.
+
+    THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 
+WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. 
+IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, 
+INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT 
+NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR 
+PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, 
+WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY 
+OF SUCH DAMAGE.
+*/
+
+#ifndef __USBD_MSC_SCSI_H
+#define __USBD_MSC_SCSI_H
+
+#include "usbd_msc_bbb.h"
+#include "msc_scsi.h"
+
+#define SENSE_LIST_DEEPTH                           4U
+
+#define MODE_SENSE6_LENGTH                          8U
+#define MODE_SENSE10_LENGTH                         8U
+#define INQUIRY_PAGE00_LENGTH                       96U
+#define FORMAT_CAPACITIES_LENGTH                    20U
+
+extern const uint8_t msc_page00_inquiry_data[];
+extern const uint8_t msc_mode_sense6_data[];
+extern const uint8_t msc_mode_sense10_data[];
+
+/* function declarations */
+/* process SCSI commands */
+int8_t scsi_process_cmd (usb_core_driver *udev, uint8_t lun, uint8_t *cmd);
+/* load the last error code in the error list */
+void scsi_sense_code (usb_core_driver *udev, uint8_t lun, uint8_t skey, uint8_t asc);
+
+#endif /* __USBD_MSC_SCSI_H */

+ 2 - 0
platformio.ini

@@ -284,3 +284,5 @@ build_flags =
      -DHAS_SDIO_CLASS
      -DPIO_USBFS_DEVICE_CDC
      -DZULUSCSI_V1_4
+;     -DPIO_USBFS_DEVICE_MSC
+     -DPLATFORM_MASS_STORAGE

+ 1 - 1
src/ZuluSCSI_msc.h

@@ -29,7 +29,7 @@
 #define CR_ENUM_TIMEOUT 1000
 
 enum  MSC_LEDState { LED_SOLIDON = 0, LED_BLINK_FAST, LED_BLINK_SLOW };
-extern volatile MSC_LEDState MSC_LEDMode;
+extern volatile enum MSC_LEDState MSC_LEDMode;
 
 // run cardreader main loop (blocking)
 void zuluscsi_msc_loop();