Explorar el Código

Merge pull request #209 from BlueSCSI/eric/pico1-sdk2

SDK updates & timeout fixes
Eric Helgeson hace 1 año
padre
commit
cc8f787a2f

+ 27 - 23
lib/BlueSCSI_platform_RP2040/BlueSCSI_platform.cpp

@@ -22,7 +22,7 @@
 #endif
 
 #ifndef __MBED__
-# include <SerialUSB.h>
+#include <Adafruit_TinyUSB.h>
 # include <class/cdc/cdc_device.h>
 #else
 # include <platform/mbed_error.h>
@@ -34,7 +34,6 @@
 #include "hardware/i2c.h"
 
 extern "C" {
-#include <pico/cyw43_arch.h>
 
 const char *g_platform_name = PLATFORM_NAME;
 static bool g_scsi_initiator = false;
@@ -73,7 +72,7 @@ void mbed_error_hook(const mbed_error_ctx * error_context);
 /***************/
 
 // Helper function to configure whole GPIO in one line
-static void gpio_conf(uint gpio, enum gpio_function fn, bool pullup, bool pulldown, bool output, bool initial_state, bool fast_slew)
+static void gpio_conf(uint gpio, gpio_function_t fn, bool pullup, bool pulldown, bool output, bool initial_state, bool fast_slew)
 {
     gpio_put(gpio, initial_state);
     gpio_set_dir(gpio, output);
@@ -82,7 +81,7 @@ static void gpio_conf(uint gpio, enum gpio_function fn, bool pullup, bool pulldo
 
     if (fast_slew)
     {
-        padsbank0_hw->io[gpio] |= PADS_BANK0_GPIO0_SLEWFAST_BITS;
+        pads_bank0_hw->io[gpio] |= PADS_BANK0_GPIO0_SLEWFAST_BITS;
     }
 }
 
@@ -127,6 +126,9 @@ void platform_init()
 {
     // Make sure second core is stopped
     multicore_reset_core1();
+#ifndef __MBED__
+    Serial.begin(115200);
+#endif // __MBED__
 
     // Default debug logging to disabled
     g_log_debug = false;
@@ -134,6 +136,7 @@ void platform_init()
     // Report platform and firmware version
     log("Platform: ", g_platform_name);
     log("FW Version: ", g_log_firmwareversion);
+    debuglog("PicoSDK: ", PICO_SDK_VERSION_STRING);
 
     /* First configure the pins that affect external buffer directions.
      * RP2040 defaults to pulldowns, while these pins have external pull-ups.
@@ -173,8 +176,8 @@ void platform_init()
         gpio_conf(scsi_pins.IN_ATN,    GPIO_FUNC_SIO, false, false, false, false, false);
         delay(10); /// Settle time
         // Check option switches
-        bool optionS1 = !gpio_get(scsi_pins.IN_ATN);
-        bool optionS2 = !gpio_get(scsi_pins.IN_ACK);
+        [[maybe_unused]] bool optionS1 = !gpio_get(scsi_pins.IN_ATN);
+        [[maybe_unused]] bool optionS2 = !gpio_get(scsi_pins.IN_ACK);
 
         // Reset REQ to appropriate pin for older hardware
         scsi_pins.OUT_REQ = SCSI_OUT_REQ_BEFORE_2023_09a;
@@ -201,9 +204,9 @@ void platform_init()
     // Get flash chip size
     uint8_t cmd_read_jedec_id[4] = {0x9f, 0, 0, 0};
     uint8_t response_jedec[4] = {0};
-    __disable_irq();
+    uint32_t status = save_and_disable_interrupts();
     flash_do_cmd(cmd_read_jedec_id, response_jedec, 4);
-    __enable_irq();
+    restore_interrupts_from_disabled(status);
     g_flash_chip_size = (1 << response_jedec[3]);
     log("Flash chip size: ", (int)(g_flash_chip_size / 1024), " kB");
 
@@ -290,9 +293,6 @@ void platform_late_init()
         gpio_conf(scsi_pins.IN_RST,    GPIO_FUNC_SIO, true, false, false, true, false);
 
 
-#ifndef __MBED__
-    Serial.begin();
-#endif // __MBED__
 
 #ifdef ENABLE_AUDIO_OUTPUT
         // one-time control setup for DMA channels and second core
@@ -495,7 +495,7 @@ static void adc_poll()
     * If ADC sample reads are done, either via direct reading, FIFO, or DMA,
     * at the same time a SPI DMA write begins, it appears that the first
     * 16-bit word of the DMA data is lost. This causes the bitstream to glitch
-    * and audio to 'pop' noticably. For now, just disable ADC reads when audio
+    * and audio to 'pop' noticeably. For now, just disable ADC reads when audio
     * is playing.
     */
    if (audio_is_active()) return;
@@ -570,7 +570,9 @@ static void watchdog_callback(unsigned alarm_num)
 #ifdef __MBED__
             uint32_t *p =  (uint32_t*)__get_PSP();
 #else
-            uint32_t *p =  (uint32_t*)__get_MSP();
+            uint32_t msp;
+            asm volatile ("MRS %0, msp" : "=r" (msp) );
+            uint32_t *p = (uint32_t*)msp;
 #endif
             for (int i = 0; i < 8; i++)
             {
@@ -597,7 +599,9 @@ static void watchdog_callback(unsigned alarm_num)
 #ifdef __MBED__
             uint32_t *p =  (uint32_t*)__get_PSP();
 #else
-            uint32_t *p =  (uint32_t*)__get_MSP();
+            uint32_t msp;
+            asm volatile ("MRS %0, msp" : "=r" (msp) );
+            uint32_t *p = (uint32_t*)msp;
 #endif
             for (int i = 0; i < 8; i++)
             {
@@ -627,7 +631,7 @@ void platform_reset_watchdog()
     if (!g_watchdog_initialized)
     {
         int alarm_num = -1;
-        for (int i = 0; i < NUM_TIMERS; i++)
+        for (int i = 0; i < NUM_GENERIC_TIMERS; i++)
         {
             if (!hardware_alarm_is_claimed(i))
             {
@@ -736,7 +740,7 @@ bool platform_rewrite_flash_page(uint32_t offset, uint8_t buffer[PLATFORM_FLASH_
     assert(offset >= PLATFORM_BOOTLOADER_SIZE);
 
     // Avoid any mbed timer interrupts triggering during the flashing.
-    __disable_irq();
+    uint32_t status = save_and_disable_interrupts();
 
     // For some reason any code executed after flashing crashes
     // unless we disable the XIP cache.
@@ -754,17 +758,17 @@ bool platform_rewrite_flash_page(uint32_t offset, uint8_t buffer[PLATFORM_FLASH_
     for (int i = 0; i < num_words; i++)
     {
         uint32_t expected = buf32[i];
-        uint32_t actual = *(volatile uint32_t*)(XIP_NOCACHE_BASE + offset + i * 4);
+        uint32_t actual = *(volatile uint32_t*)(XIP_SRAM_BASE + offset + i * 4);
 
         if (actual != expected)
         {
             log("Flash verify failed at offset ", offset + i * 4, " got ", actual, " expected ", expected);
-            __enable_irq();
+            restore_interrupts_from_disabled(status);
             return false;
         }
     }
 
-    __enable_irq();
+    restore_interrupts_from_disabled(status);
 
     return true;
 }
@@ -774,7 +778,7 @@ void platform_boot_to_main_firmware()
     // To ensure that the system state is reset properly, we perform
     // a SYSRESETREQ and jump straight from the reset vector to main application.
     g_bootloader_exit_req = &g_bootloader_exit_req;
-    SCB->AIRCR = 0x05FA0004;
+    scb_hw->aircr = 0x05FA0004;
     while(1);
 }
 
@@ -787,7 +791,7 @@ void btldr_reset_handler()
         application_base = (uint32_t*)(XIP_BASE + PLATFORM_BOOTLOADER_SIZE);
     }
 
-    SCB->VTOR = (uint32_t)application_base;
+    scb_hw->aircr = (uint32_t)application_base;
     __asm__(
         "msr msp, %0\n\t"
         "bx %1" : : "r" (application_base[0]),
@@ -859,10 +863,10 @@ bool platform_write_romdrive(const uint8_t *data, uint32_t start, uint32_t count
     assert(start < platform_get_romdrive_maxsize());
     assert((count % PLATFORM_ROMDRIVE_PAGE_SIZE) == 0);
 
-    __disable_irq();
+    uint32_t status = save_and_disable_interrupts();
     flash_range_erase(start + ROMDRIVE_OFFSET, count);
     flash_range_program(start + ROMDRIVE_OFFSET, data, count);
-    __enable_irq();
+    restore_interrupts_from_disabled(status);
     return true;
 }
 

+ 9 - 2
lib/BlueSCSI_platform_RP2040/BlueSCSI_platform_gpio.h

@@ -3,7 +3,9 @@
 #pragma once
 
 #include <hardware/gpio.h>
+#ifdef BLUESCSI_NETWORK
 #include <pico/cyw43_arch.h>
+#endif
 
 // SCSI data input/output port.
 // The data bus uses external bidirectional buffer, with
@@ -56,8 +58,13 @@
 
 // Status LED pins
 #define LED_PIN      25
-#define LED_ON()     platform_network_supported() ? cyw43_gpio_set(&cyw43_state, 0, true) : sio_hw->gpio_set = 1 << LED_PIN
-#define LED_OFF()    platform_network_supported() ? cyw43_gpio_set(&cyw43_state, 0, false) : sio_hw->gpio_clr = 1 << LED_PIN
+#ifdef BLUESCSI_NETWORK
+    #define LED_ON()     platform_network_supported() ? cyw43_gpio_set(&cyw43_state, 0, true) : sio_hw->gpio_set = 1 << LED_PIN
+    #define LED_OFF()    platform_network_supported() ? cyw43_gpio_set(&cyw43_state, 0, false) : sio_hw->gpio_clr = 1 << LED_PIN
+#else
+    #define LED_ON()     sio_hw->gpio_set = 1 << LED_PIN
+    #define LED_OFF()    sio_hw->gpio_clr = 1 << LED_PIN
+#endif
 
 // SDIO and SPI block
 #define SD_SPI_SCK   10

+ 6 - 9
lib/BlueSCSI_platform_RP2040/BlueSCSI_platform_network.cpp

@@ -21,9 +21,10 @@
 #include <network.h>
 
 extern "C" {
-
+#ifdef BLUESCSI_NETWORK
 #include <cyw43.h>
 #include <pico/cyw43_arch.h>
+#endif
 
 #ifndef CYW43_IOCTL_GET_RSSI
 #define CYW43_IOCTL_GET_RSSI (0xfe)
@@ -34,17 +35,12 @@ static const char defaultMAC[] = { 0x00, 0x80, 0x19, 0xc0, 0xff, 0xee };
 
 static bool network_in_use = false;
 
-bool platform_network_supported()
+bool __not_in_flash_func(platform_network_supported)()
 {
-	/* from cores/rp2040/RP2040Support.h */
-#if !defined(ARDUINO_RASPBERRY_PI_PICO_W)
-	return false;
-#else
-	extern bool __isPicoW;
-	return __isPicoW;
-#endif
+	return rp2040.isPicoW();
 }
 
+#ifdef BLUESCSI_NETWORK
 int platform_network_init(char *mac)
 {
 	pico_unique_board_id_t board_id;
@@ -311,4 +307,5 @@ void cyw43_cb_tcpip_set_link_up(cyw43_t *self, int itf)
 		log_f("Successfully connected to Wi-Fi SSID \"%s\"", ssid);
 }
 
+#endif
 }

+ 3 - 3
lib/BlueSCSI_platform_RP2040/audio.cpp

@@ -63,7 +63,7 @@ const uint8_t snd_parity[256] __attribute__((aligned(256), section(".scratch_y.s
  * receiver.
  * 
  * To facilitate fast lookups this table should be put in SRAM with low
- * contention, aligned to an apppropriate boundry.
+ * contention, aligned to an appropriate boundary.
  */
 const uint16_t biphase[256] __attribute__((aligned(512), section(".scratch_y.biphase"))) = {
     0xCCCC, 0xB333, 0xD333, 0xACCC, 0xCB33, 0xB4CC, 0xD4CC, 0xAB33,
@@ -306,7 +306,7 @@ static void snd_process_b() {
 }
 
 // Allows execution on Core1 via function pointers. Each function can take
-// no parameters and should return nothing, operating via side-effects only.
+// no parameters and should return nothing, operating via side effects only.
 static void core1_handler() {
     while (1) {
         void (*function)() = (void (*)()) multicore_fifo_pop_blocking();
@@ -497,7 +497,7 @@ bool audio_play(uint8_t owner, ImageBackingStore* img, uint64_t start, uint64_t
     sfcnt = 0;
     invert = 0;
 
-    // setup the two DMA units to hand-off to each other
+    // setup the two DMA units to hand off to each other
     // to maintain a stable bitstream these need to run without interruption
 	snd_dma_a_cfg = dma_channel_get_default_config(SOUND_DMA_CHA);
 	channel_config_set_transfer_data_size(&snd_dma_a_cfg, DMA_SIZE_16);

+ 1 - 1
lib/BlueSCSI_platform_RP2040/rp2040.ld

@@ -1,7 +1,7 @@
 MEMORY
 {
     FLASH(rx) : ORIGIN = 0x10000000, LENGTH = 352k
-    RAM(rwx) : ORIGIN = 0x20000000, LENGTH = 256k  /* Leave space for pico-debug */
+    RAM(rwx) : ORIGIN = 0x20000000, LENGTH = 240k  /* Leave space for pico-debug */
     SCRATCH_X(rwx) : ORIGIN = 0x20040000, LENGTH = 4k
     SCRATCH_Y(rwx) : ORIGIN = 0x20041000, LENGTH = 4k
 }

+ 1 - 1
lib/BlueSCSI_platform_RP2040/rp2040_btldr.ld

@@ -11,7 +11,7 @@
      * which comes as part of the main firmware.elf and is never overwritten.
      */
     FLASH(rx) : ORIGIN = 0x10000100, LENGTH = 128k-256
-    RAM(rwx) : ORIGIN = 0x20000000, LENGTH = 240k  /* Leave space for pico-debug */
+    RAM(rwx) : ORIGIN = 0x20000000, LENGTH = 256k  /* Leave space for pico-debug */
     SCRATCH_X(rwx) : ORIGIN = 0x20040000, LENGTH = 4k
     SCRATCH_Y(rwx) : ORIGIN = 0x20041000, LENGTH = 4k
 }

+ 22 - 22
lib/BlueSCSI_platform_RP2040/rp2040_sdio.cpp

@@ -120,7 +120,7 @@ static const uint8_t crc7_table[256] = {
 // is applied to each line separately and generates total of
 // 4 x 16 = 64 bits of checksum.
 __attribute__((optimize("O3")))
-uint64_t sdio_crc16_4bit_checksum(uint32_t *data, uint32_t num_words)
+uint64_t __not_in_flash_func(sdio_crc16_4bit_checksum)(uint32_t *data, uint32_t num_words)
 {
     uint64_t crc = 0;
     uint32_t *end = data + num_words;
@@ -157,7 +157,7 @@ uint64_t sdio_crc16_4bit_checksum(uint32_t *data, uint32_t num_words)
 /*******************************************************
  * Clock Runner
  *******************************************************/
-void cycleSdClock() {
+void __not_in_flash_func(cycleSdClock)() {
     pio_sm_exec(SDIO_PIO, SDIO_CMD_SM, pio_encode_nop() | pio_encode_sideset_opt(1, 1) | pio_encode_delay(1));
     pio_sm_exec(SDIO_PIO, SDIO_CMD_SM, pio_encode_nop() | pio_encode_sideset_opt(1, 0) | pio_encode_delay(1));
 }
@@ -165,7 +165,7 @@ void cycleSdClock() {
 /*******************************************************
  * Status Register Receiver
  *******************************************************/
-sdio_status_t receive_status_register(uint8_t* sds) {
+sdio_status_t __not_in_flash_func(receive_status_register)(uint8_t* sds) {
     rp2040_sdio_rx_start(sds, 1, 64);
 
     // Wait for the DMA operation to complete, or fail if it took too long
@@ -199,7 +199,7 @@ waitagain:
  * Basic SDIO command execution
  *******************************************************/
 
-static void sdio_send_command(uint8_t command, uint32_t arg, uint8_t response_bits)
+static void __not_in_flash_func(sdio_send_command)(uint8_t command, uint32_t arg, uint8_t response_bits)
 {
     // if (command != 41 && command != 55) {
     //     log("C: ", (int)command, " A: ", arg);
@@ -249,7 +249,7 @@ static void sdio_send_command(uint8_t command, uint32_t arg, uint8_t response_bi
     dma_channel_configure(SDIO_DMA_CH, &dmacfg, &SDIO_PIO->txf[SDIO_CMD_SM], &g_sdio.cmdBuf, 6, true);
 }
 
-sdio_status_t rp2040_sdio_command_R1(uint8_t command, uint32_t arg, uint32_t *response)
+sdio_status_t __not_in_flash_func(rp2040_sdio_command_R1)(uint8_t command, uint32_t arg, uint32_t *response)
 {
     uint32_t resp[2];
     if (response) {
@@ -343,7 +343,7 @@ sdio_status_t rp2040_sdio_command_R1(uint8_t command, uint32_t arg, uint32_t *re
     return SDIO_OK;
 }
 
-sdio_status_t rp2040_sdio_command_R2(uint8_t command, uint32_t arg, uint8_t response[16])
+sdio_status_t __not_in_flash_func(rp2040_sdio_command_R2)(uint8_t command, uint32_t arg, uint8_t response[16])
 {
     // The response is too long to fit in the PIO FIFO, so use DMA to receive it.
     uint32_t response_buf[5];
@@ -428,7 +428,7 @@ sdio_status_t rp2040_sdio_command_R2(uint8_t command, uint32_t arg, uint8_t resp
 }
 
 
-sdio_status_t rp2040_sdio_command_R3(uint8_t command, uint32_t arg, uint32_t *response)
+sdio_status_t __not_in_flash_func(rp2040_sdio_command_R3)(uint8_t command, uint32_t arg, uint32_t *response)
 {
     uint32_t resp[2];
     dma_channel_config dmacfg = dma_channel_get_default_config(SDIO_DMA_CHB);
@@ -476,7 +476,7 @@ sdio_status_t rp2040_sdio_command_R3(uint8_t command, uint32_t arg, uint32_t *re
  * Data reception from SD card
  *******************************************************/
 
-sdio_status_t rp2040_sdio_rx_start(uint8_t *buffer, uint32_t num_blocks, uint32_t block_size)
+sdio_status_t __not_in_flash_func(rp2040_sdio_rx_start)(uint8_t *buffer, uint32_t num_blocks, uint32_t block_size)
 {
     // Buffer must be aligned
     assert(((uint32_t)buffer & 3) == 0 && num_blocks <= SDIO_MAX_BLOCKS);
@@ -542,7 +542,7 @@ sdio_status_t rp2040_sdio_rx_start(uint8_t *buffer, uint32_t num_blocks, uint32_
 }
 
 // Check checksums for received blocks
-static void sdio_verify_rx_checksums(uint32_t maxcount)
+static void __not_in_flash_func(sdio_verify_rx_checksums)(uint32_t maxcount)
 {
     while (g_sdio.blocks_checksumed < g_sdio.blocks_done && maxcount-- > 0)
     {
@@ -568,7 +568,7 @@ static void sdio_verify_rx_checksums(uint32_t maxcount)
     }
 }
 
-sdio_status_t rp2040_sdio_rx_poll(uint32_t *bytes_complete)
+sdio_status_t __not_in_flash_func(rp2040_sdio_rx_poll)(uint32_t *bytes_complete)
 {
     // Was everything done when the previous rx_poll() finished?
     if (g_sdio.blocks_done >= g_sdio.total_blocks)
@@ -630,7 +630,7 @@ sdio_status_t rp2040_sdio_rx_poll(uint32_t *bytes_complete)
  * Data transmission to SD card
  *******************************************************/
 
-static void sdio_start_next_block_tx()
+static void __not_in_flash_func(sdio_start_next_block_tx)()
 {
     // Initialize PIOs
     pio_sm_init(SDIO_PIO, SDIO_CMD_SM, g_sdio.pio_data_tx_offset, &g_sdio.pio_cfg_data_tx);
@@ -685,7 +685,7 @@ static void sdio_start_next_block_tx()
     pio_set_sm_mask_enabled(SDIO_PIO, (1ul << SDIO_CMD_SM)/* | (1ul << SDIO_DATA_SM)*/, true);
 }
 
-static void sdio_compute_next_tx_checksum()
+static void __not_in_flash_func(sdio_compute_next_tx_checksum)()
 {
     assert (g_sdio.blocks_done < g_sdio.total_blocks && g_sdio.blocks_checksumed < g_sdio.total_blocks);
     int blockidx = g_sdio.blocks_checksumed++;
@@ -694,7 +694,7 @@ static void sdio_compute_next_tx_checksum()
 }
 
 // Start transferring data from memory to SD card
-sdio_status_t rp2040_sdio_tx_start(const uint8_t *buffer, uint32_t num_blocks)
+sdio_status_t __not_in_flash_func(rp2040_sdio_tx_start)(const uint8_t *buffer, uint32_t num_blocks)
 {
     // Buffer must be aligned
     assert(((uint32_t)buffer & 3) == 0 && num_blocks <= SDIO_MAX_BLOCKS);
@@ -722,7 +722,7 @@ sdio_status_t rp2040_sdio_tx_start(const uint8_t *buffer, uint32_t num_blocks)
     return SDIO_OK;
 }
 
-sdio_status_t check_sdio_write_response(uint32_t card_response)
+sdio_status_t __not_in_flash_func(check_sdio_write_response)(uint32_t card_response)
 {
     uint8_t wr_status = card_response & 0x1F;
     //  5 = 0b0101 = data accepted  (11100101)
@@ -751,7 +751,7 @@ sdio_status_t check_sdio_write_response(uint32_t card_response)
 }
 
 // When a block finishes, this IRQ handler starts the next one
-static void rp2040_sdio_tx_irq()
+static void __not_in_flash_func(rp2040_sdio_tx_irq)()
 {
     dma_hw->ints1 = 1 << SDIO_DMA_CHB;
 
@@ -815,9 +815,9 @@ static void rp2040_sdio_tx_irq()
 }
 
 // Check if transmission is complete
-sdio_status_t rp2040_sdio_tx_poll(uint32_t *bytes_complete)
+sdio_status_t __not_in_flash_func(rp2040_sdio_tx_poll)(uint32_t *bytes_complete)
 {
-    if (SCB->ICSR & SCB_ICSR_VECTACTIVE_Msk)
+    if (scb_hw->icsr & (0x1FFUL))
     {
         // Verify that IRQ handler gets called even if we are in hardfault handler
         rp2040_sdio_tx_irq();
@@ -849,7 +849,7 @@ sdio_status_t rp2040_sdio_tx_poll(uint32_t *bytes_complete)
 }
 
 // Force everything to idle state
-sdio_status_t rp2040_sdio_stop()
+sdio_status_t __not_in_flash_func(rp2040_sdio_stop)()
 {
     dma_channel_abort(SDIO_DMA_CH);
     dma_channel_abort(SDIO_DMA_CHB);
@@ -859,7 +859,7 @@ sdio_status_t rp2040_sdio_stop()
     return SDIO_OK;
 }
 
-void rp2040_sdio_init(int clock_divider)
+void __not_in_flash_func(rp2040_sdio_init)(int clock_divider)
 {
     // Mark resources as being in use, unless it has been done already.
     static bool resources_claimed = false;
@@ -881,7 +881,7 @@ void rp2040_sdio_init(int clock_divider)
 
     // Load PIO programs
     pio_clear_instruction_memory(SDIO_PIO);
-    
+
     // Set pull resistors for all SD data lines
     gpio_set_pulls(SDIO_CLK, true, false);
     gpio_set_pulls(SDIO_CMD, true, false);
@@ -938,7 +938,7 @@ void rp2040_sdio_init(int clock_divider)
 #endif
 }
 
-void rp2040_sdio_update_delays(pio_program program, uint32_t offset, uint16_t additional_delay) {
+void __not_in_flash_func(rp2040_sdio_update_delays)(pio_program program, uint32_t offset, uint16_t additional_delay) {
     //log("Offset:", offset);
     uint16_t instr_to_rewrite;
     uint16_t existing_delay;
@@ -963,7 +963,7 @@ void rp2040_sdio_update_delays(pio_program program, uint32_t offset, uint16_t ad
     }
 }
 
-void rp2040_sdio_delay_increment(uint16_t additional_delay) {
+void __not_in_flash_func(rp2040_sdio_delay_increment)(uint16_t additional_delay) {
     /*
     Rewrite in-place every SDIO instruction for all the SDIO programs.
     These additional delay cycles effectively decrease the SDIO clock rate, which can be helpful in electrically noisy environments.

+ 8 - 8
lib/BlueSCSI_platform_RP2040/scsi_accel_rp2040.cpp

@@ -204,7 +204,7 @@ void scsi_accel_rp2040_startWrite(const uint8_t* data, uint32_t count, volatile
     // Any read requests should be matched with a stopRead()
     assert(g_scsi_dma_state != SCSIDMA_READ && g_scsi_dma_state != SCSIDMA_READ_DONE);
 
-    __disable_irq();
+    uint32_t status = save_and_disable_interrupts();
     if (g_scsi_dma_state == SCSIDMA_WRITE)
     {
         if (!g_scsi_dma.next_app_buf && data == g_scsi_dma.app_buf + g_scsi_dma.app_bytes)
@@ -227,7 +227,7 @@ void scsi_accel_rp2040_startWrite(const uint8_t* data, uint32_t count, volatile
             count = 0;
         }
     }
-    __enable_irq();
+    restore_interrupts_from_disabled(status);
 
     // Check if the request was combined
     if (count == 0) return;
@@ -326,7 +326,7 @@ bool scsi_accel_rp2040_isWriteFinished(const uint8_t* data)
 
     // Check if this data item is still in queue.
     bool finished = true;
-    __disable_irq();
+    uint32_t status = save_and_disable_interrupts();
     if (data >= g_scsi_dma.app_buf &&
         data < g_scsi_dma.app_buf + g_scsi_dma.app_bytes &&
         (uint32_t)data >= dma_hw->ch[SCSI_DMA_CH_A].al1_read_addr)
@@ -338,7 +338,7 @@ bool scsi_accel_rp2040_isWriteFinished(const uint8_t* data)
     {
         finished = false; // In queued transfer
     }
-    __enable_irq();
+    restore_interrupts_from_disabled(status);
 
     return finished;
 }
@@ -589,7 +589,7 @@ void scsi_accel_rp2040_startRead(uint8_t *data, uint32_t count, int *parityError
     // Any write requests should be matched with a stopWrite()
     assert(g_scsi_dma_state != SCSIDMA_WRITE && g_scsi_dma_state != SCSIDMA_WRITE_DONE);
 
-    __disable_irq();
+    uint32_t status = save_and_disable_interrupts();
     if (g_scsi_dma_state == SCSIDMA_READ)
     {
         if (!g_scsi_dma.next_app_buf && data == g_scsi_dma.app_buf + g_scsi_dma.app_bytes)
@@ -612,7 +612,7 @@ void scsi_accel_rp2040_startRead(uint8_t *data, uint32_t count, int *parityError
             count = 0;
         }
     }
-    __enable_irq();
+    restore_interrupts_from_disabled(status);
 
     // Check if the request was combined
     if (count == 0) return;
@@ -658,7 +658,7 @@ bool scsi_accel_rp2040_isReadFinished(const uint8_t* data)
 
     // Check if this data item is still in queue.
     bool finished = true;
-    __disable_irq();
+    uint32_t status = save_and_disable_interrupts();
     if (data >= g_scsi_dma.app_buf &&
         data < g_scsi_dma.app_buf + g_scsi_dma.app_bytes &&
         (uint32_t)data >= dma_hw->ch[SCSI_DMA_CH_A].write_addr)
@@ -670,7 +670,7 @@ bool scsi_accel_rp2040_isReadFinished(const uint8_t* data)
     {
         finished = false; // In queued transfer
     }
-    __enable_irq();
+    restore_interrupts_from_disabled(status);
 
     return finished;
 }

+ 1 - 1
lib/SCSI2SD/src/firmware/mode.c

@@ -261,7 +261,7 @@ static const uint8_t IomegaZip100VendorPage[] =
 0x5c, 0xf, 0xff, 0xf
 };
 
-static const uint8_t IomegaZip250VendorPage[] =
+__attribute__((unused)) static const uint8_t IomegaZip250VendorPage[] =
 {
 0x2f, // Page Code
 4, // Page Length

+ 2 - 1
lib/SCSI2SD/src/firmware/network.c

@@ -13,7 +13,7 @@
  * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
  * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
  */
-
+#ifdef BLUESCSI_NETWORK
 #include <string.h>
 
 #include "scsi.h"
@@ -528,3 +528,4 @@ int scsiNetworkPurge(void)
 
 	return sent;
 }
+#endif

+ 6 - 2
lib/SCSI2SD/src/firmware/scsi.c

@@ -623,8 +623,12 @@ static void process_Command()
 	// write commands. Will fall-through to generic disk handling.
 	else if (((cfg->deviceType == S2S_CFG_OPTICAL) && scsiCDRomCommand()) ||
 		((cfg->deviceType == S2S_CFG_SEQUENTIAL) && scsiTapeCommand()) ||
-		((cfg->deviceType == S2S_CFG_MO) && scsiMOCommand()) ||
-		((cfg->deviceType == S2S_CFG_NETWORK && scsiNetworkCommand())))
+		((cfg->deviceType == S2S_CFG_MO) && scsiMOCommand())
+#ifdef BLUESCSI_NETWORK
+               || ((cfg->deviceType == S2S_CFG_NETWORK && scsiNetworkCommand()))
+#endif
+        )
+
 	{
 		// Already handled.
 	}

+ 10 - 6
platformio.ini

@@ -12,9 +12,9 @@ default_envs = BlueSCSI_Pico
 
 ; BlueSCSI RP2040 hardware platform, based on the Raspberry Pi foundation RP2040 microcontroller
 [env:BlueSCSI_Pico]
-platform = https://github.com/maxgerhardt/platform-raspberrypi.git#196d31bbafaf60b84751b1a415d8dca2365debdf
-platform_packages = platformio/toolchain-gccarmnoneeabi@1.120301.0
-    framework-arduinopico@https://github.com/BlueSCSI/arduino-pico-internal.git#e139b9c7816602597f473b3231032cca5d71a48a
+platform = https://github.com/maxgerhardt/platform-raspberrypi.git#2d445020acf8b792768a5fa5ba1870ac9607c11c
+platform_packages =
+    framework-arduinopico@https://github.com/BlueSCSI/arduino-pico-internal.git#v4.1.1-DaynaPORT
 framework = arduino
 board = rpipicow
 board_build.core = earlephilhower
@@ -44,9 +44,13 @@ build_flags =
     -DUSE_ARDUINO=1
     -DPICO_DEFAULT_I2C_SDA_PIN=16
     -DPICO_DEFAULT_I2C_SCL_PIN=17
-    ; -DLOGBUFSIZE=8192
-    ; -DPREFETCH_BUFFER_SIZE=6144
-    ; -DSCSI2SD_BUFFER_SIZE=57344
+    -DBLUESCSI_NETWORK=1
+; Arduino's default USB task/irq is conflicting with WiFi somehow
+    -DUSE_TINYUSB
+; build flags mirroring the framework-arduinopico#v4.1.1-DaynaPORT static library build
+    -DPICO_CYW43_ARCH_POLL=1
+    -DCYW43_LWIP=0
+    -DCYW43_USE_OTP_MAC=0
 
 ; Experimental Audio build
 ; Requires separate hardware and overclock.

+ 4 - 1
src/BlueSCSI.cpp

@@ -547,12 +547,13 @@ static void reinitSCSI()
   scsiPhyReset();
   scsiDiskInit();
   scsiInit();
-
+#ifdef BLUESCSI_NETWORK
   if (scsiDiskCheckAnyNetworkDevicesConfigured())
   {
     platform_network_init(scsiDev.boardCfg.wifiMACAddress);
     platform_network_wifi_join(scsiDev.boardCfg.wifiSSID, scsiDev.boardCfg.wifiPassword);
   }
+#endif
 }
 
 void check_and_apply_sdio_delay() {
@@ -714,7 +715,9 @@ extern "C" void bluescsi_main_loop(void)
   platform_reset_watchdog();
   platform_poll();
   diskEjectButtonUpdate(true);
+#ifdef BLUESCSI_NETWORK
   platform_network_poll();
+#endif
   
 #ifdef PLATFORM_HAS_INITIATOR_MODE
   if (unlikely(platform_is_initiator_mode_enabled()))

+ 6 - 0
src/BlueSCSI_cdrom.cpp

@@ -1663,6 +1663,12 @@ static void doReadCD(uint32_t lba, uint32_t length, uint8_t sector_type,
 
         assert(buf == bufstart + result_length);
         scsiStartWrite(bufstart, result_length);
+
+        // Reset the watchdog while the transfer is progressing.
+        // If the host stops transferring, the watchdog will eventually expire.
+        // This is needed to avoid hitting the watchdog if the host performs
+        // a large transfer compared to its transfer speed.
+        platform_reset_watchdog();
     }
 
     scsiFinishWrite();

+ 12 - 0
src/BlueSCSI_disk.cpp

@@ -1695,6 +1695,12 @@ void diskDataOut()
             }
             platform_set_sd_callback(NULL, NULL);
             g_disk_transfer.bytes_sd += len;
+
+            // Reset the watchdog while the transfer is progressing.
+            // If the host stops transferring, the watchdog will eventually expire.
+            // This is needed to avoid hitting the watchdog if the host performs
+            // a large transfer compared to its transfer speed.
+            platform_reset_watchdog();
         }
     }
 
@@ -1868,6 +1874,12 @@ static void start_dataInTransfer(uint8_t *buffer, uint32_t count)
 
     platform_poll();
     diskEjectButtonUpdate(false);
+
+    // Reset the watchdog while the transfer is progressing.
+    // If the host stops transferring, the watchdog will eventually expire.
+    // This is needed to avoid hitting the watchdog if the host performs
+    // a large transfer compared to its transfer speed.
+    platform_reset_watchdog();
 }
 
 static void diskDataIn()