Merge remote-tracking branch 'origin/main'

This commit is contained in:
Hosted Weblate 2022-03-18 01:02:37 +01:00
commit 73d78b3d29
No known key found for this signature in database
GPG Key ID: A3FAAA06E6569B4C
43 changed files with 251 additions and 286 deletions

View File

@ -25,7 +25,7 @@ msgstr ""
#: main.c
msgid ""
"\n"
"Code stopped by auto-reload.\n"
"Code stopped by auto-reload. Reloading soon.\n"
msgstr ""
#: supervisor/shared/safe_mode.c
@ -584,10 +584,6 @@ msgstr ""
msgid "Brightness must be 0-1.0"
msgstr ""
#: shared-bindings/supervisor/__init__.c
msgid "Brightness must be between 0 and 255"
msgstr ""
#: shared-bindings/displayio/Display.c
#: shared-bindings/framebufferio/FramebufferDisplay.c
msgid "Brightness not adjustable"
@ -688,6 +684,7 @@ msgstr ""
msgid "Can only alarm on two low pins from deep sleep."
msgstr ""
#: ports/espressif/common-hal/_bleio/Characteristic.c
#: ports/nrf/common-hal/_bleio/Characteristic.c
msgid "Can't set CCCD on local Characteristic"
msgstr ""
@ -1429,7 +1426,8 @@ msgstr ""
#: ports/espressif/common-hal/canio/CAN.c
#: ports/espressif/common-hal/i2cperipheral/I2CPeripheral.c
#: ports/mimxrt10xx/common-hal/busio/I2C.c
#: ports/mimxrt10xx/common-hal/busio/SPI.c ports/nrf/common-hal/busio/I2C.c
#: ports/mimxrt10xx/common-hal/busio/SPI.c
#: ports/mimxrt10xx/common-hal/usb_host/Port.c ports/nrf/common-hal/busio/I2C.c
#: ports/raspberrypi/common-hal/busio/I2C.c
#: ports/raspberrypi/common-hal/busio/SPI.c
#: ports/raspberrypi/common-hal/busio/UART.c shared-bindings/busio/SPI.c
@ -1605,6 +1603,7 @@ msgstr ""
msgid "Nimble out of memory"
msgstr ""
#: ports/espressif/common-hal/_bleio/Characteristic.c
#: ports/nrf/common-hal/_bleio/Characteristic.c
msgid "No CCCD for this Characteristic"
msgstr ""
@ -2158,7 +2157,6 @@ msgstr ""
msgid "Size not supported"
msgstr ""
#: ports/atmel-samd/common-hal/alarm/SleepMemory.c
#: ports/raspberrypi/common-hal/alarm/SleepMemory.c
msgid "Sleep Memory not available"
msgstr ""
@ -2447,6 +2445,7 @@ msgstr ""
msgid "Unknown gatt error: 0x%04x"
msgstr ""
#: ports/atmel-samd/common-hal/alarm/pin/PinAlarm.c
#: supervisor/shared/safe_mode.c
msgid "Unknown reason."
msgstr ""
@ -4065,6 +4064,7 @@ msgstr ""
#: ports/espressif/boards/adafruit_metro_esp32s2/mpconfigboard.h
#: ports/espressif/boards/adafruit_qtpy_esp32s2/mpconfigboard.h
#: ports/espressif/boards/adafruit_qtpy_esp32s3_nopsram/mpconfigboard.h
#: ports/espressif/boards/ai_thinker_esp32-c3s-2m/mpconfigboard.h
#: ports/espressif/boards/ai_thinker_esp32-c3s/mpconfigboard.h
#: ports/espressif/boards/ai_thinker_esp_12k_nodemcu/mpconfigboard.h
#: ports/espressif/boards/artisense_rd00/mpconfigboard.h
@ -4077,6 +4077,7 @@ msgstr ""
#: ports/espressif/boards/espressif_esp32s3_devkitc_1_n8/mpconfigboard.h
#: ports/espressif/boards/espressif_esp32s3_devkitc_1_n8r2/mpconfigboard.h
#: ports/espressif/boards/espressif_esp32s3_devkitc_1_n8r8/mpconfigboard.h
#: ports/espressif/boards/espressif_esp32s3_devkitm_1_n8/mpconfigboard.h
#: ports/espressif/boards/espressif_hmi_devkit_1/mpconfigboard.h
#: ports/espressif/boards/espressif_kaluga_1.3/mpconfigboard.h
#: ports/espressif/boards/espressif_kaluga_1/mpconfigboard.h
@ -4088,6 +4089,10 @@ msgstr ""
#: ports/espressif/boards/gravitech_cucumber_ms/mpconfigboard.h
#: ports/espressif/boards/gravitech_cucumber_r/mpconfigboard.h
#: ports/espressif/boards/gravitech_cucumber_rs/mpconfigboard.h
#: ports/espressif/boards/hexky_s2/mpconfigboard.h
#: ports/espressif/boards/hiibot_iots2/mpconfigboard.h
#: ports/espressif/boards/lilygo_ttgo_t8_esp32_s2_wroom/mpconfigboard.h
#: ports/espressif/boards/lilygo_ttgo_t8_s2/mpconfigboard.h
#: ports/espressif/boards/lilygo_ttgo_t8_s2_st7789/mpconfigboard.h
#: ports/espressif/boards/lolin_s2_mini/mpconfigboard.h
#: ports/espressif/boards/lolin_s2_pico/mpconfigboard.h

50
main.c
View File

@ -52,7 +52,7 @@
#include "supervisor/memory.h"
#include "supervisor/port.h"
#include "supervisor/serial.h"
#include "supervisor/shared/autoreload.h"
#include "supervisor/shared/reload.h"
#include "supervisor/shared/safe_mode.h"
#include "supervisor/shared/stack.h"
#include "supervisor/shared/status_leds.h"
@ -124,7 +124,6 @@ static void reset_devices(void) {
}
STATIC void start_mp(supervisor_allocation *heap, bool first_run) {
autoreload_stop();
supervisor_workflow_reset();
// Stack limit should be less than real stack size, so we have a chance
@ -329,14 +328,20 @@ STATIC bool run_code_py(safe_mode_t safe_mode, bool first_run, bool *simulate_re
result.exception = MP_OBJ_NULL;
result.exception_line = 0;
bool skip_repl;
bool skip_repl = false;
bool skip_wait = false;
bool found_main = false;
uint8_t next_code_options = 0;
// Collects stickiness bits that apply in the current situation.
uint8_t next_code_stickiness_situation = SUPERVISOR_NEXT_CODE_OPT_NEWLY_SET;
// Do the filesystem flush check before reload in case another write comes
// in while we're doing the flush.
if (safe_mode == NO_SAFE_MODE) {
stack_resize();
filesystem_flush();
}
if (safe_mode == NO_SAFE_MODE && !autoreload_pending()) {
static const char *const supported_filenames[] = STRING_LIST(
"code.txt", "code.py", "main.py", "main.txt");
#if CIRCUITPY_FULL_BUILD
@ -345,8 +350,6 @@ STATIC bool run_code_py(safe_mode_t safe_mode, bool first_run, bool *simulate_re
"main.txt.py", "main.py.txt", "main.txt.txt","main.py.py");
#endif
stack_resize();
filesystem_flush();
supervisor_allocation *heap = allocate_remaining_memory();
// Prepare the VM state. Includes an alarm check/reset for sleep.
@ -389,13 +392,14 @@ STATIC bool run_code_py(safe_mode_t safe_mode, bool first_run, bool *simulate_re
// Print done before resetting everything so that we get the message over
// BLE before it is reset and we have a delay before reconnect.
if (reload_requested && result.return_code == PYEXEC_EXCEPTION) {
serial_write_compressed(translate("\nCode stopped by auto-reload.\n"));
if ((result.return_code & PYEXEC_RELOAD) && supervisor_get_run_reason() == RUN_REASON_AUTO_RELOAD) {
serial_write_compressed(translate("\nCode stopped by auto-reload. Reloading soon.\n"));
} else {
serial_write_compressed(translate("\nCode done running.\n"));
}
// Finished executing python code. Cleanup includes a board reset.
// Finished executing python code. Cleanup includes filesystem flush and a board reset.
cleanup_after_vm(heap, result.exception);
// If a new next code file was set, that is a reason to keep it (obviously). Stuff this into
@ -407,8 +411,14 @@ STATIC bool run_code_py(safe_mode_t safe_mode, bool first_run, bool *simulate_re
next_code_options |= SUPERVISOR_NEXT_CODE_OPT_NEWLY_SET;
}
if (reload_requested) {
if (result.return_code & PYEXEC_RELOAD) {
next_code_stickiness_situation |= SUPERVISOR_NEXT_CODE_OPT_STICKY_ON_RELOAD;
// Reload immediately unless the reload is due to autoreload. In that
// case, we wait below to see if any other writes occur.
if (supervisor_get_run_reason() != RUN_REASON_AUTO_RELOAD) {
skip_repl = true;
skip_wait = true;
}
} else if (result.return_code == 0) {
next_code_stickiness_situation |= SUPERVISOR_NEXT_CODE_OPT_STICKY_ON_SUCCESS;
if (next_code_options & SUPERVISOR_NEXT_CODE_OPT_RELOAD_ON_SUCCESS) {
@ -426,7 +436,7 @@ STATIC bool run_code_py(safe_mode_t safe_mode, bool first_run, bool *simulate_re
}
}
if (result.return_code & PYEXEC_FORCED_EXIT) {
skip_repl = reload_requested;
skip_repl = false;
skip_wait = true;
}
}
@ -466,22 +476,27 @@ STATIC bool run_code_py(safe_mode_t safe_mode, bool first_run, bool *simulate_re
size_t total_time = blink_time + LED_SLEEP_TIME_MS;
#endif
// This loop is waits after code completes. It waits for fake sleeps to
// finish, user input or autoreloads.
#if CIRCUITPY_ALARM
bool fake_sleeping = false;
#endif
while (!skip_wait) {
RUN_BACKGROUND_TASKS;
// If a reload was requested by the supervisor or autoreload, return
if (reload_requested) {
// If a reload was requested by the supervisor or autoreload, return.
if (autoreload_ready()) {
next_code_stickiness_situation |= SUPERVISOR_NEXT_CODE_OPT_STICKY_ON_RELOAD;
// Should the STICKY_ON_SUCCESS and STICKY_ON_ERROR bits be cleared in
// next_code_stickiness_situation? I can see arguments either way, but I'm deciding
// "no" for now, mainly because it's a bit less code. At this point, we have both a
// success or error and a reload, so let's have both of the respective options take
// effect (in OR combination).
reload_requested = false;
skip_repl = true;
// We're kicking off the autoreload process so reset now. If any
// other reloads trigger after this, then we'll want another wait
// period.
autoreload_reset();
break;
}
@ -508,7 +523,7 @@ STATIC bool run_code_py(safe_mode_t safe_mode, bool first_run, bool *simulate_re
#endif
// If messages haven't been printed yet, print them
if (!printed_press_any_key && serial_connected()) {
if (!printed_press_any_key && serial_connected() && !autoreload_pending()) {
if (!serial_connected_at_start) {
print_code_py_status_message(safe_mode);
}
@ -627,13 +642,14 @@ STATIC bool run_code_py(safe_mode_t safe_mode, bool first_run, bool *simulate_re
}
}
// Done waiting, start the board back up.
// free code allocation if unused
if ((next_code_options & next_code_stickiness_situation) == 0) {
free_memory(next_code_allocation);
next_code_allocation = NULL;
}
// Done waiting, start the board back up.
#if CIRCUITPY_STATUS_LED
if (led_active) {
new_status_color(BLACK);
@ -757,7 +773,7 @@ STATIC int run_repl(bool first_run) {
usb_setup_with_vm();
#endif
autoreload_suspend(AUTORELOAD_LOCK_REPL);
autoreload_suspend(AUTORELOAD_SUSPEND_REPL);
// Set the status LED to the REPL color before running the REPL. For
// NeoPixels and DotStars this will be sticky but for PWM or single LED it
@ -787,7 +803,7 @@ STATIC int run_repl(bool first_run) {
status_led_deinit();
#endif
autoreload_resume(AUTORELOAD_LOCK_REPL);
autoreload_resume(AUTORELOAD_SUSPEND_REPL);
return exit_code;
}

View File

@ -9,3 +9,6 @@ CHIP_FAMILY = samd21
INTERNAL_FLASH_FILESYSTEM = 1
LONGINT_IMPL = NONE
CIRCUITPY_FULL_BUILD = 0
CIRCUITPY_ONEWIREIO = 0
CIRCUITPY_RAINBOWIO = 0

View File

@ -10,15 +10,14 @@ QSPI_FLASH_FILESYSTEM = 1
EXTERNAL_FLASH_DEVICES = "S25FL116K, S25FL216K, GD25Q16C"
LONGINT_IMPL = MPZ
CIRCUITPY_BLEIO = 0
CIRCUITPY_BLEIO_HCI = 0
CIRCUITPY_AESIO = 0
CIRCUITPY_ONEWIREIO = 0
CIRCUITPY_PARALLELDISPLAY = 0
CIRCUITPY_SDCARDIO = 0
CIRCUITPY_SHARPDISPLAY = 0
CIRCUITPY_TRACEBACK = 0
# Include these Python libraries in firmware.
FROZEN_MPY_DIRS += $(TOP)/frozen/Adafruit_CircuitPython_PortalBase
FROZEN_MPY_DIRS += $(TOP)/frozen/Adafruit_CircuitPython_Requests
FROZEN_MPY_DIRS += $(TOP)/frozen/Adafruit_CircuitPython_ESP32SPI
FROZEN_MPY_DIRS += $(TOP)/frozen/Adafruit_CircuitPython_NeoPixel

View File

@ -11,4 +11,6 @@ LONGINT_IMPL = NONE
CIRCUITPY_FULL_BUILD = 0
# There are many pin definitions on this board; it doesn't quite fit on very large translations.
CIRCUITPY_ONEWIREIO = 0
CIRCUITPY_RAINBOWIO = 0
CIRCUITPY_USB_MIDI = 0

View File

@ -34,7 +34,6 @@
#include "py/smallint.h"
#include "shared-bindings/microcontroller/__init__.h"
#include "shared-bindings/time/__init__.h"
#include "supervisor/shared/autoreload.h"
#include "hal/include/hal_atomic.h"
#include "hal/include/hal_delay.h"

View File

@ -129,8 +129,9 @@
#include "common-hal/_pew/PewPew.h"
#endif
static volatile bool sleep_ok = true;
#ifdef SAMD21
static uint8_t _tick_event_channel = 0;
uint8_t _tick_event_channel;
// Sleeping requires a register write that can stall interrupt handling. Turning
// off sleeps allows for more accurate interrupt timing. (Python still thinks
@ -142,7 +143,13 @@ void rtc_start_pulse(void) {
void rtc_end_pulse(void) {
sleep_ok = true;
}
#endif
#endif // SAMD21
static void reset_ticks(void) {
#ifdef SAMD21
_tick_event_channel = EVSYS_SYNCH_NUM;
#endif
}
extern volatile bool mp_msc_enabled;
@ -426,9 +433,7 @@ void reset_port(void) {
#endif
reset_event_system();
#ifdef SAMD21
_tick_event_channel = EVSYS_SYNCH_NUM;
#endif
reset_ticks();
reset_all_pins();
@ -498,7 +503,7 @@ uint32_t port_get_saved_word(void) {
static volatile uint64_t overflowed_ticks = 0;
static uint32_t _get_count(uint64_t *overflow_count) {
while(1) {
while (1) {
// Disable interrupts so we can grab the count and the overflow atomically.
common_hal_mcu_disable_interrupts();
@ -521,7 +526,7 @@ static uint32_t _get_count(uint64_t *overflow_count) {
return count;
}
// Try again if overflow hasn't been processed yet.
// Try again if overflow hasn't been processed yet.
}
}
@ -620,7 +625,7 @@ void port_enable_tick(void) {
RTC->MODE0.INTENSET.reg = RTC_MODE0_INTENSET_PER2;
#endif
#ifdef SAMD21
// SAMD21 ticks won't survive port_reset(). This *should* be ok since it'll
// SAMD21 ticks won't survive reset_port(). This *should* be ok since it'll
// be triggered by ticks and no Python will be running.
if (_tick_event_channel >= EVSYS_SYNCH_NUM) {
turn_on_event_system();
@ -653,6 +658,7 @@ void port_disable_tick(void) {
uint8_t value = 1 << _tick_event_channel;
EVSYS->INTENCLR.reg = EVSYS_INTENSET_EVD(value);
}
_tick_event_channel = EVSYS_SYNCH_NUM;
#endif
}

View File

@ -54,8 +54,6 @@
#define BOARD_USER_SAFE_MODE_ACTION translate("pressing the left button at start up\n")
#define CIRCUITPY_AUTORELOAD_DELAY_MS 500
#define CIRCUITPY_INTERNAL_NVM_SIZE (4096)
#define BOARD_FLASH_SIZE (FLASH_SIZE - 0x4000 - CIRCUITPY_INTERNAL_NVM_SIZE)

View File

@ -3,8 +3,6 @@
#define MICROPY_HW_BOARD_NAME "Arduino Nano 33 BLE"
#define MICROPY_HW_MCU_NAME "nRF52840"
#define CIRCUITPY_AUTORELOAD_DELAY_MS 500
#define DEFAULT_I2C_BUS_SCL (&pin_P0_02)
#define DEFAULT_I2C_BUS_SDA (&pin_P0_31)

View File

@ -3,8 +3,6 @@
#define MICROPY_HW_BOARD_NAME "BastBLE"
#define MICROPY_HW_MCU_NAME "nRF52840"
#define CIRCUITPY_AUTORELOAD_DELAY_MS 500
#if QSPI_FLASH_FILESYSTEM
#define MICROPY_QSPI_DATA0 NRF_GPIO_PIN_MAP(0, 30)
#define MICROPY_QSPI_DATA1 NRF_GPIO_PIN_MAP(0, 29)

View File

@ -36,6 +36,7 @@ CIRCUITPY_RE = 0
CIRCUITPY_RGBMATRIX = 0
CIRCUITPY_SDCARDIO = 0
CIRCUITPY_SYNTHIO = 0
CIRCUITPY_TRACEBACK = 0
CIRCUITPY_TOUCHIO = 0
CIRCUITPY_TRACEBACK = 0
CIRCUITPY_ULAB = 0

View File

@ -53,8 +53,6 @@
#define SPI_FLASH_CS_PIN &pin_P0_20
#endif
#define CIRCUITPY_AUTORELOAD_DELAY_MS 500
#define CIRCUITPY_INTERNAL_NVM_SIZE (4096)
#define BOARD_FLASH_SIZE (FLASH_SIZE - 0x4000 - CIRCUITPY_INTERNAL_NVM_SIZE)

View File

@ -5,8 +5,6 @@
#define MICROPY_HW_LED_STATUS (&pin_P0_27)
#define CIRCUITPY_AUTORELOAD_DELAY_MS 500
#define CIRCUITPY_INTERNAL_NVM_SIZE (4096)
#define BOARD_FLASH_SIZE (FLASH_SIZE - 0x4000 - CIRCUITPY_INTERNAL_NVM_SIZE)

View File

@ -24,8 +24,6 @@
#define SPI_FLASH_CS_PIN &pin_P0_23
#endif
#define CIRCUITPY_AUTORELOAD_DELAY_MS 500
#define CIRCUITPY_INTERNAL_NVM_SIZE (4096)
#define BOARD_FLASH_SIZE (FLASH_SIZE - 0x4000 - CIRCUITPY_INTERNAL_NVM_SIZE)

View File

@ -3,8 +3,6 @@
#define MICROPY_HW_BOARD_NAME "SSCI ISP1807 Dev Board"
#define MICROPY_HW_MCU_NAME "nRF52840"
#define CIRCUITPY_AUTORELOAD_DELAY_MS 500
#define DEFAULT_I2C_BUS_SCL (&pin_P0_23)
#define DEFAULT_I2C_BUS_SDA (&pin_P0_19)

View File

@ -3,8 +3,6 @@
#define MICROPY_HW_BOARD_NAME "SSCI ISP1807 Micro Board"
#define MICROPY_HW_MCU_NAME "nRF52840"
#define CIRCUITPY_AUTORELOAD_DELAY_MS 500
#define DEFAULT_I2C_BUS_SCL (&pin_P0_23)
#define DEFAULT_I2C_BUS_SDA (&pin_P0_29)

View File

@ -5,8 +5,6 @@
#define MICROPY_HW_LED_STATUS (&pin_P0_12)
#define CIRCUITPY_AUTORELOAD_DELAY_MS 500
#define CIRCUITPY_INTERNAL_NVM_SIZE (4096)
#define BOARD_FLASH_SIZE (FLASH_SIZE - 0x4000 - CIRCUITPY_INTERNAL_NVM_SIZE)

View File

@ -34,7 +34,6 @@
#include "py/smallint.h"
#include "shared-bindings/microcontroller/__init__.h"
#include "shared-bindings/time/__init__.h"
#include "supervisor/shared/autoreload.h"
#include "mpconfigboard.h"
#include "mphalport.h"

View File

@ -42,8 +42,6 @@
#define SPI_FLASH_SCK_PIN (&pin_PB13)
#define SPI_FLASH_CS_PIN (&pin_PB12)
#define CIRCUITPY_AUTORELOAD_DELAY_MS (500)
#define BOARD_FLASH_SIZE (FLASH_SIZE - 0x2000 - 0xC000)
#define AUTORESET_DELAY_MS (500)

View File

@ -45,8 +45,6 @@
#define DEFAULT_I2C_BUS_SCL (&pin_PB06)
#define DEFAULT_I2C_BUS_SDA (&pin_PB07)
#define CIRCUITPY_AUTORELOAD_DELAY_MS (500)
#define BOARD_FLASH_SIZE (FLASH_SIZE - 0x2000 - 0xC000)
#define AUTORESET_DELAY_MS (500)

View File

@ -45,10 +45,6 @@
#define DEFAULT_I2C_BUS_SCL (&pin_PB06)
#define DEFAULT_I2C_BUS_SDA (&pin_PB07)
#define CIRCUITPY_AUTORELOAD_DELAY_MS (500)
#define BOARD_FLASH_SIZE (FLASH_SIZE - 0x2000 - 0xC000)
#define AUTORESET_DELAY_MS (500)
#define MICROPY_FATFS_EXFAT 0

View File

@ -346,8 +346,6 @@ void port_enable_tick(void) {
stm32_peripherals_rtc_assign_wkup_callback(supervisor_tick);
stm32_peripherals_rtc_enable_wakeup_timer();
}
// TODO: what is this? can I get rid of it?
extern volatile uint32_t autoreload_delay_ms;
// Disable 1/1024 second tick.
void port_disable_tick(void) {

View File

@ -437,7 +437,7 @@ void supervisor_run_background_tasks_if_tick(void);
// CIRCUITPY_AUTORELOAD_DELAY_MS = 0 will completely disable autoreload.
#ifndef CIRCUITPY_AUTORELOAD_DELAY_MS
#define CIRCUITPY_AUTORELOAD_DELAY_MS 500
#define CIRCUITPY_AUTORELOAD_DELAY_MS 750
#endif
#ifndef CIRCUITPY_FILESYSTEM_FLUSH_INTERVAL_MS

View File

@ -159,7 +159,6 @@ PY_CORE_O_BASENAME = $(addprefix py/,\
objzip.o \
opmethods.o \
proto.o \
reload.o \
sequence.o \
stream.o \
binary.o \

View File

@ -1,32 +0,0 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2018 by Roy Hooper
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#include "reload.h"
#include "py/mpstate.h"
void mp_raise_reload_exception(void) {
MP_STATE_THREAD(mp_pending_exception) = MP_OBJ_FROM_PTR(&MP_STATE_VM(mp_reload_exception));
#if MICROPY_ENABLE_SCHEDULER
if (MP_STATE_VM(sched_state) == MP_SCHED_IDLE) {
MP_STATE_VM(sched_state) = MP_SCHED_PENDING;
}
#endif
}

View File

@ -1,26 +0,0 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2018 by Roy Hooper
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#ifndef CIRCUITPYTHON_RELOAD_H
#define CIRCUITPYTHON_RELOAD_H
void mp_raise_reload_exception(void);
#endif // CIRCUITPYTHON_RELOAD_H

View File

@ -25,7 +25,6 @@
*/
#include "py/obj.h"
#include "py/reload.h"
#include "py/runtime.h"
#include "shared-bindings/alarm/__init__.h"
@ -35,7 +34,6 @@
#include "shared-bindings/alarm/touch/TouchAlarm.h"
#include "shared-bindings/supervisor/Runtime.h"
#include "shared-bindings/time/__init__.h"
#include "supervisor/shared/autoreload.h"
#include "supervisor/shared/workflow.h"
//| """Alarms and sleep

View File

@ -108,6 +108,14 @@ const mp_obj_property_t supervisor_runtime_serial_bytes_available_obj = {
MP_ROM_NONE},
};
supervisor_run_reason_t supervisor_get_run_reason(void) {
return _run_reason;
}
void supervisor_set_run_reason(supervisor_run_reason_t run_reason) {
_run_reason = run_reason;
}
//| run_reason: RunReason
//| """Returns why CircuitPython started running this particular time."""
//|
@ -123,10 +131,6 @@ const mp_obj_property_t supervisor_runtime_run_reason_obj = {
MP_ROM_NONE},
};
void supervisor_set_run_reason(supervisor_run_reason_t run_reason) {
_run_reason = run_reason;
}
STATIC const mp_rom_map_elem_t supervisor_runtime_locals_dict_table[] = {
{ MP_ROM_QSTR(MP_QSTR_usb_connected), MP_ROM_PTR(&supervisor_runtime_usb_connected_obj) },
{ MP_ROM_QSTR(MP_QSTR_serial_connected), MP_ROM_PTR(&supervisor_runtime_serial_connected_obj) },

View File

@ -34,6 +34,7 @@
extern const mp_obj_type_t supervisor_runtime_type;
supervisor_run_reason_t supervisor_get_run_reason(void);
void supervisor_set_run_reason(supervisor_run_reason_t run_reason);
bool common_hal_supervisor_runtime_get_serial_connected(void);

View File

@ -27,14 +27,13 @@
#include "py/obj.h"
#include "py/runtime.h"
#include "py/reload.h"
#include "py/objstr.h"
#include "shared/runtime/interrupt_char.h"
#include "supervisor/shared/autoreload.h"
#include "supervisor/shared/bluetooth/bluetooth.h"
#include "supervisor/shared/display.h"
#include "supervisor/shared/status_leds.h"
#include "supervisor/shared/reload.h"
#include "supervisor/shared/stack.h"
#include "supervisor/shared/traceback.h"
#include "supervisor/shared/translate.h"
@ -95,9 +94,7 @@ MP_DEFINE_CONST_FUN_OBJ_1(supervisor_set_rgb_status_brightness_obj, supervisor_s
//| ...
//|
STATIC mp_obj_t supervisor_reload(void) {
reload_requested = true;
supervisor_set_run_reason(RUN_REASON_SUPERVISOR_RELOAD);
mp_raise_reload_exception();
reload_initiate(RUN_REASON_SUPERVISOR_RELOAD);
return mp_const_none;
}
MP_DEFINE_CONST_FUN_OBJ_0(supervisor_reload_obj, supervisor_reload);

View File

@ -29,7 +29,6 @@
#include "shared-module/displayio/__init__.h"
#include "shared/runtime/interrupt_char.h"
#include "py/reload.h"
#include "py/runtime.h"
#include "shared-bindings/board/__init__.h"
#include "shared-bindings/displayio/Bitmap.h"
@ -37,8 +36,8 @@
#include "shared-bindings/displayio/Group.h"
#include "shared-bindings/displayio/Palette.h"
#include "shared-module/displayio/area.h"
#include "supervisor/shared/autoreload.h"
#include "supervisor/shared/display.h"
#include "supervisor/shared/reload.h"
#include "supervisor/memory.h"
#include "supervisor/spi_flash_api.h"
@ -83,7 +82,7 @@ void displayio_background(void) {
if (mp_hal_is_interrupted()) {
return;
}
if (reload_requested) {
if (autoreload_ready()) {
// Reload is about to happen, so don't redisplay.
return;
}

View File

@ -175,12 +175,13 @@ STATIC int parse_compile_execute(const void *source, mp_parse_input_kind_t input
} else if (mp_obj_is_subclass_fast(MP_OBJ_FROM_PTR(mp_obj_get_type((mp_obj_t)nlr.ret_val)), &mp_type_DeepSleepRequest)) {
ret = PYEXEC_DEEP_SLEEP;
#endif
} else if ((mp_obj_t)nlr.ret_val == MP_OBJ_FROM_PTR(&MP_STATE_VM(mp_reload_exception))) {
ret = PYEXEC_RELOAD;
} else {
if ((mp_obj_t)nlr.ret_val != MP_OBJ_FROM_PTR(&MP_STATE_VM(mp_reload_exception))) {
mp_obj_print_exception(&mp_plat_print, MP_OBJ_FROM_PTR(nlr.ret_val));
}
mp_obj_print_exception(&mp_plat_print, MP_OBJ_FROM_PTR(nlr.ret_val));
ret = PYEXEC_EXCEPTION;
}
}
if (result != NULL) {
result->return_code = ret;

View File

@ -49,6 +49,7 @@ extern int pyexec_system_exit;
#define PYEXEC_FORCED_EXIT (0x100)
#define PYEXEC_EXCEPTION (0x200)
#define PYEXEC_DEEP_SLEEP (0x400)
#define PYEXEC_RELOAD (0x800)
int pyexec_raw_repl(void);
int pyexec_friendly_repl(void);

View File

@ -1,99 +0,0 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2016 Scott Shawcroft for Adafruit Industries
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#include "autoreload.h"
#include "py/mphal.h"
#include "py/reload.h"
#include "supervisor/shared/tick.h"
supervisor_allocation *next_code_allocation;
#include "shared-bindings/supervisor/Runtime.h"
static volatile uint32_t autoreload_delay_ms = 0;
static bool autoreload_enabled = false;
static size_t autoreload_suspended = 0;
volatile bool reload_requested = false;
inline void autoreload_tick() {
if (autoreload_delay_ms == 0) {
return;
}
if (autoreload_delay_ms == 1 && autoreload_enabled &&
autoreload_suspended == 0 && !reload_requested) {
mp_raise_reload_exception();
reload_requested = true;
supervisor_set_run_reason(RUN_REASON_AUTO_RELOAD);
supervisor_disable_tick();
}
autoreload_delay_ms--;
}
void autoreload_enable() {
autoreload_enabled = true;
reload_requested = false;
}
void autoreload_disable() {
autoreload_enabled = false;
}
void autoreload_suspend(size_t lock_mask) {
autoreload_suspended |= lock_mask;
}
void autoreload_resume(size_t lock_mask) {
autoreload_suspended &= ~lock_mask;
}
inline bool autoreload_is_enabled() {
return autoreload_enabled;
}
void autoreload_start() {
// Enable ticks if we haven't been tracking an autoreload delay. We check
// our current state so that we only turn ticks on once. Multiple starts
// can occur before we reload and then turn ticks off.
if (autoreload_delay_ms == 0) {
supervisor_enable_tick();
}
autoreload_delay_ms = CIRCUITPY_AUTORELOAD_DELAY_MS;
}
void autoreload_stop() {
autoreload_delay_ms = 0;
reload_requested = false;
}
void autoreload_now() {
if (!autoreload_enabled || autoreload_suspended || reload_requested) {
return;
}
mp_raise_reload_exception();
reload_requested = true;
supervisor_set_run_reason(RUN_REASON_AUTO_RELOAD);
}

View File

@ -43,7 +43,7 @@
#include "common-hal/_bleio/__init__.h"
#include "supervisor/fatfs_port.h"
#include "supervisor/shared/autoreload.h"
#include "supervisor/shared/reload.h"
#include "supervisor/shared/bluetooth/file_transfer.h"
#include "supervisor/shared/bluetooth/file_transfer_protocol.h"
#include "supervisor/shared/tick.h"
@ -325,8 +325,7 @@ STATIC uint8_t _process_write(const uint8_t *raw_buf, size_t command_len) {
if (chunk_size == 0) {
// Don't reload until everything is written out of the packet buffer.
common_hal_bleio_packet_buffer_flush(&_transfer_packet_buffer);
// Trigger an autoreload
autoreload_start();
autoreload_trigger();
return ANY_COMMAND;
}
@ -383,8 +382,7 @@ STATIC uint8_t _process_write_data(const uint8_t *raw_buf, size_t command_len) {
#endif
// Don't reload until everything is written out of the packet buffer.
common_hal_bleio_packet_buffer_flush(&_transfer_packet_buffer);
// Trigger an autoreload
autoreload_start();
autoreload_trigger();
return ANY_COMMAND;
}
return WRITE_DATA;
@ -465,8 +463,7 @@ STATIC uint8_t _process_delete(const uint8_t *raw_buf, size_t command_len) {
if (result == FR_OK) {
// Don't reload until everything is written out of the packet buffer.
common_hal_bleio_packet_buffer_flush(&_transfer_packet_buffer);
// Trigger an autoreload
autoreload_start();
autoreload_trigger();
}
return ANY_COMMAND;
}
@ -520,8 +517,7 @@ STATIC uint8_t _process_mkdir(const uint8_t *raw_buf, size_t command_len) {
if (result == FR_OK) {
// Don't reload until everything is written out of the packet buffer.
common_hal_bleio_packet_buffer_flush(&_transfer_packet_buffer);
// Trigger an autoreload
autoreload_start();
autoreload_trigger();
}
return ANY_COMMAND;
}
@ -668,8 +664,7 @@ STATIC uint8_t _process_move(const uint8_t *raw_buf, size_t command_len) {
if (result == FR_OK) {
// Don't reload until everything is written out of the packet buffer.
common_hal_bleio_packet_buffer_flush(&_transfer_packet_buffer);
// Trigger an autoreload
autoreload_start();
autoreload_trigger();
}
return ANY_COMMAND;
}
@ -692,7 +687,7 @@ void supervisor_bluetooth_file_transfer_background(void) {
if (size == 0) {
break;
}
autoreload_suspend(AUTORELOAD_LOCK_BLE);
autoreload_suspend(AUTORELOAD_SUSPEND_BLE);
// TODO: If size < 0 return an error.
current_offset += size;
#if CIRCUITPY_VERBOSE_BLE
@ -710,7 +705,7 @@ void supervisor_bluetooth_file_transfer_background(void) {
response[0] = next_command;
response[1] = STATUS_ERROR_PROTOCOL;
common_hal_bleio_packet_buffer_write(&_transfer_packet_buffer, response, 2, NULL, 0);
autoreload_resume(AUTORELOAD_LOCK_BLE);
autoreload_resume(AUTORELOAD_SUSPEND_BLE);
break;
}
switch (current_state) {
@ -744,7 +739,7 @@ void supervisor_bluetooth_file_transfer_background(void) {
current_offset = 0;
}
if (next_command == ANY_COMMAND) {
autoreload_resume(AUTORELOAD_LOCK_BLE);
autoreload_resume(AUTORELOAD_SUSPEND_BLE);
}
}
running = false;
@ -754,5 +749,5 @@ void supervisor_bluetooth_file_transfer_disconnected(void) {
next_command = ANY_COMMAND;
current_offset = 0;
f_close(&active_file);
autoreload_resume(AUTORELOAD_LOCK_BLE);
autoreload_resume(AUTORELOAD_SUSPEND_BLE);
}

View File

@ -113,7 +113,7 @@ static mp_uint_t flash_read_blocks(uint8_t *dest, uint32_t block_num, uint32_t n
return supervisor_flash_read_blocks(dest, block_num - PART1_START_BLOCK, num_blocks);
}
volatile bool filesystem_dirty = false;
static volatile bool filesystem_dirty = false;
static mp_uint_t flash_write_blocks(const uint8_t *src, uint32_t block_num, uint32_t num_blocks) {
if (block_num == 0) {

113
supervisor/shared/reload.c Normal file
View File

@ -0,0 +1,113 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2016 Scott Shawcroft for Adafruit Industries
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#include "reload.h"
#include "py/mphal.h"
#include "py/mpstate.h"
#include "supervisor/shared/reload.h"
#include "supervisor/shared/tick.h"
supervisor_allocation *next_code_allocation;
#include "shared-bindings/supervisor/Runtime.h"
// True if user has disabled autoreload.
static bool autoreload_enabled = false;
// Non-zero if autoreload is temporarily off, due to an AUTORELOAD_SUSPEND_... reason.
static uint32_t autoreload_suspended = 0;
volatile uint32_t last_autoreload_trigger = 0;
void reload_initiate(supervisor_run_reason_t run_reason) {
supervisor_set_run_reason(run_reason);
// Raise reload exception, in case code is running.
MP_STATE_THREAD(mp_pending_exception) = MP_OBJ_FROM_PTR(&MP_STATE_VM(mp_reload_exception));
#if MICROPY_ENABLE_SCHEDULER
if (MP_STATE_VM(sched_state) == MP_SCHED_IDLE) {
MP_STATE_VM(sched_state) = MP_SCHED_PENDING;
}
#endif
}
void autoreload_reset() {
last_autoreload_trigger = 0;
}
void autoreload_enable() {
autoreload_enabled = true;
last_autoreload_trigger = 0;
}
void autoreload_disable() {
autoreload_enabled = false;
}
void autoreload_suspend(uint32_t suspend_reason_mask) {
autoreload_suspended |= suspend_reason_mask;
}
void autoreload_resume(uint32_t suspend_reason_mask) {
autoreload_suspended &= ~suspend_reason_mask;
}
inline bool autoreload_is_enabled() {
return autoreload_enabled;
}
void autoreload_trigger() {
if (autoreload_enabled & !autoreload_suspended) {
last_autoreload_trigger = supervisor_ticks_ms32();
// Guard against the rare time that ticks is 0;
if (last_autoreload_trigger == 0) {
last_autoreload_trigger += 1;
}
// Initiate a reload of the VM immediately. Later code will pause to
// wait for the autoreload to become ready. Doing the VM exit
// immediately is clearer for the user.
reload_initiate(RUN_REASON_AUTO_RELOAD);
}
}
bool autoreload_ready() {
if (last_autoreload_trigger == 0 || autoreload_suspended != 0) {
return false;
}
// Wait for autoreload interval before reloading
uint32_t now = supervisor_ticks_ms32();
uint32_t diff;
if (now >= last_autoreload_trigger) {
diff = now - last_autoreload_trigger;
} else {
diff = now + (0xffffffff - last_autoreload_trigger);
}
return diff > CIRCUITPY_AUTORELOAD_DELAY_MS;
}
bool autoreload_pending(void) {
return last_autoreload_trigger != 0;
}

View File

@ -27,9 +27,9 @@
#ifndef MICROPY_INCLUDED_SUPERVISOR_AUTORELOAD_H
#define MICROPY_INCLUDED_SUPERVISOR_AUTORELOAD_H
#include <stdbool.h>
#include "supervisor/memory.h"
#include "py/obj.h"
#include "shared-bindings/supervisor/RunReason.h"
enum {
SUPERVISOR_NEXT_CODE_OPT_RELOAD_ON_SUCCESS = 0x1,
@ -41,8 +41,9 @@ enum {
};
enum {
AUTORELOAD_LOCK_REPL = 0x1,
AUTORELOAD_LOCK_BLE = 0x2
AUTORELOAD_SUSPEND_REPL = 0x1,
AUTORELOAD_SUSPEND_BLE = 0x2,
AUTORELOAD_SUSPEND_USB = 0x4
};
typedef struct {
@ -52,20 +53,32 @@ typedef struct {
extern supervisor_allocation *next_code_allocation;
extern volatile bool reload_requested;
// Helper for exiting the VM and reloading immediately.
void reload_initiate(supervisor_run_reason_t run_reason);
void autoreload_tick(void);
void autoreload_start(void);
void autoreload_stop(void);
// Enabled state is user controllable and very sticky. We don't reset it.
void autoreload_enable(void);
void autoreload_disable(void);
bool autoreload_is_enabled(void);
// Temporarily turn it off. Used during the REPL.
void autoreload_suspend(size_t lock_mask);
void autoreload_resume(size_t lock_mask);
// Start the autoreload process.
void autoreload_trigger(void);
// True when the autoreload should occur. (A trigger happened and the delay has
// passed.)
bool autoreload_ready(void);
// Reset the autoreload timer in preparation for another trigger. Call when the
// last trigger starts being executed.
void autoreload_reset(void);
// True when a trigger has occurred but we're still delaying in case another
// trigger occurs.
bool autoreload_pending(void);
void autoreload_now(void);
// Temporarily turn autoreload off, for the given reason(s). Autoreload triggers
// will still be tracked so resuming with autoreload ready with cause an
// immediate reload.
// Used during the REPL or during parts of BLE workflow.
void autoreload_suspend(uint32_t suspend_reason_mask);
// Allow autoreloads again, for the given reason(s).
void autoreload_resume(uint32_t suspend_reason_mask);
#endif // MICROPY_INCLUDED_SUPERVISOR_AUTORELOAD_H

View File

@ -34,7 +34,6 @@
#include "supervisor/filesystem.h"
#include "supervisor/background_callback.h"
#include "supervisor/port.h"
#include "supervisor/shared/autoreload.h"
#include "supervisor/shared/stack.h"
#if CIRCUITPY_BLEIO_HCI
@ -66,7 +65,9 @@ static volatile uint64_t PLACE_IN_DTCM_BSS(background_ticks);
static background_callback_t tick_callback;
volatile uint64_t last_finished_tick = 0;
static volatile uint64_t last_finished_tick = 0;
static volatile size_t tick_enable_count = 0;
static void supervisor_background_tasks(void *unused) {
port_start_background_task();
@ -101,10 +102,6 @@ void supervisor_tick(void) {
filesystem_tick();
#endif
#ifdef CIRCUITPY_AUTORELOAD_DELAY_MS
autoreload_tick();
#endif
#ifdef CIRCUITPY_GAMEPAD_TICKS
if (!(port_get_raw_ticks(NULL) & CIRCUITPY_GAMEPAD_TICKS)) {
#if CIRCUITPY_GAMEPADSHIFT
@ -160,8 +157,7 @@ void mp_hal_delay_ms(mp_uint_t delay_ms) {
}
}
volatile size_t tick_enable_count = 0;
extern void supervisor_enable_tick(void) {
void supervisor_enable_tick(void) {
common_hal_mcu_disable_interrupts();
if (tick_enable_count == 0) {
port_enable_tick();
@ -170,7 +166,7 @@ extern void supervisor_enable_tick(void) {
common_hal_mcu_enable_interrupts();
}
extern void supervisor_disable_tick(void) {
void supervisor_disable_tick(void) {
common_hal_mcu_disable_interrupts();
if (tick_enable_count > 0) {
tick_enable_count--;

View File

@ -37,20 +37,23 @@
* interrupt context.
*/
extern void supervisor_tick(void);
/** @brief Get the lower 32 bits of the time in milliseconds
*
* This can be more efficient than supervisor_ticks_ms64, for sites where a wraparound
* of ~49.5 days is not harmful.
*/
extern uint32_t supervisor_ticks_ms32(void);
/** @brief Get the full time in milliseconds
*
* Because common ARM mcus cannot atomically work with 64-bit quantities, this
* function must briefly disable interrupts in order to return the value. If
* only relative durations of less than about ~49.5 days need to be considered,
* then it may be possible to use supervisor_ticks_ms64 instead.
* then it may be possible to use supervisor_ticks_ms32() instead.
*/
extern uint64_t supervisor_ticks_ms64(void);
/** @brief Run background ticks, but only about every millisecond.
*
* Normally, this is not called directly. Instead use the RUN_BACKGROUND_TASKS

View File

@ -36,7 +36,7 @@
#include "shared-module/storage/__init__.h"
#include "supervisor/filesystem.h"
#include "supervisor/shared/autoreload.h"
#include "supervisor/shared/reload.h"
#define MSC_FLASH_BLOCK_SIZE 512
@ -170,7 +170,6 @@ bool tud_msc_is_writable_cb(uint8_t lun) {
// Callback invoked when received READ10 command.
// Copy disk's data to buffer (up to bufsize) and return number of copied bytes.
int32_t tud_msc_read10_cb(uint8_t lun, uint32_t lba, uint32_t offset, void *buffer, uint32_t bufsize) {
(void)lun;
(void)offset;
const uint32_t block_count = bufsize / MSC_FLASH_BLOCK_SIZE;
@ -186,6 +185,7 @@ int32_t tud_msc_read10_cb(uint8_t lun, uint32_t lba, uint32_t offset, void *buff
int32_t tud_msc_write10_cb(uint8_t lun, uint32_t lba, uint32_t offset, uint8_t *buffer, uint32_t bufsize) {
(void)lun;
(void)offset;
autoreload_suspend(AUTORELOAD_SUSPEND_USB);
const uint32_t block_count = bufsize / MSC_FLASH_BLOCK_SIZE;
@ -215,8 +215,9 @@ int32_t tud_msc_write10_cb(uint8_t lun, uint32_t lba, uint32_t offset, uint8_t *
void tud_msc_write10_complete_cb(uint8_t lun) {
(void)lun;
// This write is complete, start the autoreload clock.
autoreload_start();
// This write is complete; initiate an autoreload.
autoreload_resume(AUTORELOAD_SUSPEND_USB);
autoreload_trigger();
}
// Invoked when received SCSI_CMD_INQUIRY

View File

@ -1,7 +1,6 @@
SRC_SUPERVISOR = \
main.c \
supervisor/port.c \
supervisor/shared/autoreload.c \
supervisor/shared/background_callback.c \
supervisor/shared/board.c \
supervisor/shared/cpu.c \
@ -9,6 +8,7 @@ SRC_SUPERVISOR = \
supervisor/shared/lock.c \
supervisor/shared/memory.c \
supervisor/shared/micropython.c \
supervisor/shared/reload.c \
supervisor/shared/safe_mode.c \
supervisor/shared/stack.c \
supervisor/shared/status_leds.c \

View File

@ -20,7 +20,6 @@ import black
import circuitpython_typing
import circuitpython_typing.socket
PATHS_IGNORE = frozenset({"shared-bindings/__future__"})
TYPE_MODULE_IMPORTS_IGNORE = frozenset(