diff --git a/.gitmodules b/.gitmodules index 01e80110518f..dba13ad3dcdf 100644 --- a/.gitmodules +++ b/.gitmodules @@ -406,3 +406,6 @@ [submodule "frozen/Adafruit_CircuitPython_Wiznet5k"] path = frozen/Adafruit_CircuitPython_Wiznet5k url = https://github.com/adafruit/Adafruit_CircuitPython_Wiznet5k +[submodule "ports/analog/msdk"] + path = ports/analog/msdk + url = https://github.com/analogdevicesinc/msdk.git diff --git a/docs/shared_bindings_matrix.py b/docs/shared_bindings_matrix.py index 33dfad01e986..2ddc43912aeb 100644 --- a/docs/shared_bindings_matrix.py +++ b/docs/shared_bindings_matrix.py @@ -31,6 +31,7 @@ from concurrent.futures import ThreadPoolExecutor SUPPORTED_PORTS = [ + "analog", "atmel-samd", "broadcom", "cxd56", diff --git a/docs/supported_ports.rst b/docs/supported_ports.rst index 69eaa5ef1489..41f872864791 100644 --- a/docs/supported_ports.rst +++ b/docs/supported_ports.rst @@ -12,6 +12,7 @@ Additional testing is limited. .. toctree:: :maxdepth: 2 + ../ports/analog/README ../ports/atmel-samd/README ../ports/broadcom/README ../ports/cxd56/README diff --git a/locale/circuitpython.pot b/locale/circuitpython.pot index 25d4a2831228..106bca3d1f0b 100644 --- a/locale/circuitpython.pot +++ b/locale/circuitpython.pot @@ -1179,6 +1179,7 @@ msgstr "" msgid "Interrupted by output function" msgstr "" +#: ports/espressif/common-hal/_bleio/Service.c #: ports/espressif/common-hal/espulp/ULP.c #: ports/espressif/common-hal/microcontroller/Processor.c #: ports/mimxrt10xx/common-hal/audiobusio/__init__.c @@ -1303,6 +1304,7 @@ msgid "MAC address was invalid" msgstr "" #: ports/espressif/common-hal/_bleio/Characteristic.c +#: ports/espressif/common-hal/_bleio/Descriptor.c msgid "MITM security not supported" msgstr "" @@ -2238,14 +2240,12 @@ msgid "Update failed" msgstr "" #: ports/espressif/common-hal/_bleio/Characteristic.c -#: ports/espressif/common-hal/_bleio/Descriptor.c #: ports/nordic/common-hal/_bleio/Characteristic.c #: ports/nordic/common-hal/_bleio/Descriptor.c msgid "Value length != required fixed length" msgstr "" #: ports/espressif/common-hal/_bleio/Characteristic.c -#: ports/espressif/common-hal/_bleio/Descriptor.c #: ports/nordic/common-hal/_bleio/Characteristic.c #: ports/nordic/common-hal/_bleio/Descriptor.c msgid "Value length > max_length" @@ -3090,7 +3090,8 @@ msgstr "" msgid "function missing required positional argument #%d" msgstr "" -#: py/argcheck.c py/bc.c py/objnamedtuple.c shared-bindings/time/__init__.c +#: py/argcheck.c py/bc.c py/objnamedtuple.c shared-bindings/_eve/__init__.c +#: shared-bindings/time/__init__.c #, c-format msgid "function takes %d positional arguments but %d were given" msgstr "" @@ -3242,7 +3243,7 @@ msgstr "" msgid "input must be a dense ndarray" msgstr "" -#: extmod/ulab/code/user/user.c +#: extmod/ulab/code/user/user.c shared-bindings/_eve/__init__.c msgid "input must be an ndarray" msgstr "" diff --git a/ports/analog/Makefile b/ports/analog/Makefile new file mode 100644 index 000000000000..79eb7a49052d --- /dev/null +++ b/ports/analog/Makefile @@ -0,0 +1,301 @@ +# This file is part of the CircuitPython project: https://circuitpython.org +# +# SPDX-FileCopyrightText: Copyright (c) 2020 Scott Shawcroft for Adafruit Industries +# SPDX-FileCopyrightText: Copyright (c) 2024 Brandon Hurst, Analog Devices, Inc. +# +# SPDX-License-Identifier: MIT + +# Includes mpconfigboard.mk & mpconfigport.mk, +# along with numerous other shared environment makefiles. +include ../../py/circuitpy_mkenv.mk + +CROSS_COMPILE = arm-none-eabi- + +# MCU_SERIES e.g. "max32" +# MCU_VARIANT e.g. "max32690" +# defined in mpconfigboard.mk +MCU_SERIES_LOWER := $(shell echo $(MCU_SERIES) | tr '[:upper:]' '[:lower:]') +MCU_SERIES_UPPER := $(shell echo $(MCU_SERIES) | tr '[:lower:]' '[:upper:]') +MCU_VARIANT_LOWER := $(shell echo $(MCU_VARIANT) | tr '[:upper:]' '[:lower:]') +MCU_VARIANT_UPPER := $(shell echo $(MCU_VARIANT) | tr '[:lower:]' '[:upper:]') + +# ******************************************************************************* +#### MSDK INCLUDES #### +# Necessary for msdk makefiles +TARGET := $(MCU_VARIANT_UPPER) +TARGET_UC := $(MCU_VARIANT_UPPER) +TARGET_LC := $(MCU_VARIANT_LOWER) + +MSDK_ROOT = ./msdk +MSDK_LIBS = $(MSDK_ROOT)/Libraries +CMSIS_ROOT = $(MSDK_LIBS)/CMSIS +ADI_PERIPH = $(MSDK_ROOT)/Libraries/PeriphDrivers +ADI_MISC_DRIVERS_DIR ?= $(MSDK_LIBS)/MiscDrivers +ADI_BOARD_DIR = $(MSDK_LIBS)/Boards/$(MCU_VARIANT_UPPER)/$(BOARD) + +# For debugging the build +ifneq ($(BUILD_VERBOSE),"") +$(info MSDK_ROOT is $(MSDK_ROOT)) +$(info MSDK_LIBS is $(MSDK_LIBS)) +$(info CMSIS_ROOT is $(CMSIS_ROOT)) +$(info ADI_PERIPH is $(ADI_PERIPH)) +$(info ADI_MISC_DRIVERS_DIR is $(ADI_MISC_DRIVERS_DIR)) +$(info ADI_BOARD_DIR is $(ADI_BOARD_DIR)) +$(info MAXIM_PATH is $(MAXIM_PATH)) +endif + +# ----------------- +# Sources & Include +# ----------------- +# Define max32 die type for PeriphDriver Includes +# default to me18 for max32690 +# more info: +# https://analogdevicesinc.github.io/msdk//USERGUIDE/#die-types-to-part-numbers +ifeq ($(MCU_VARIANT_LOWER), "max32690") +DIE_TYPE=me18 +else +DIE_TYPE=me18 +endif + +PERIPH_SRC = $(ADI_PERIPH)/Source + +INC += -I. +INC += -I../.. +INC += -I$(BUILD) +INC += -I$(BUILD)/genhdr +INC += -I./../../lib/cmsis/inc +INC += -I./boards/ +INC += -I./boards/$(BOARD) +INC += -I./peripherals/ +INC += -I../../lib/mp-readline + +INC += \ + -I$(TOP)/$(BOARD_PATH) \ + -I$(TOP)/lib/cmsis/inc \ + -I$(CMSIS_ROOT)/Include \ + -I$(CMSIS_ROOT)/Device/Maxim/$(MCU_VARIANT_UPPER)/Include \ + -I$(ADI_PERIPH)/Include/$(MCU_VARIANT_UPPER) \ + -I$(PERIPH_SRC)/SYS \ + -I$(PERIPH_SRC)/CTB \ + -I$(PERIPH_SRC)/DMA \ + -I$(PERIPH_SRC)/FLC \ + -I$(PERIPH_SRC)/GPIO \ + -I$(PERIPH_SRC)/ICC \ + -I$(PERIPH_SRC)/TMR \ + -I$(PERIPH_SRC)/RTC \ + -I$(PERIPH_SRC)/UART + +INC += -I$(CMSIS_ROOT)/Device/Maxim/$(MCU_VARIANT_UPPER)/Source/GCC + +SRC_MAX32 += \ + $(CMSIS_ROOT)/Device/Maxim/$(MCU_VARIANT_UPPER)/Source/heap.c \ + $(CMSIS_ROOT)/Device/Maxim/$(MCU_VARIANT_UPPER)/Source/system_$(MCU_VARIANT_LOWER).c \ + $(PERIPH_SRC)/SYS/mxc_assert.c \ + $(PERIPH_SRC)/SYS/mxc_delay.c \ + $(PERIPH_SRC)/SYS/mxc_lock.c \ + $(PERIPH_SRC)/SYS/nvic_table.c \ + $(PERIPH_SRC)/SYS/pins_$(DIE_TYPE).c \ + $(PERIPH_SRC)/SYS/sys_$(DIE_TYPE).c \ + $(PERIPH_SRC)/CTB/ctb_$(DIE_TYPE).c \ + $(PERIPH_SRC)/CTB/ctb_reva.c \ + $(PERIPH_SRC)/CTB/ctb_common.c \ + $(PERIPH_SRC)/DMA/dma_reva.c \ + $(PERIPH_SRC)/DMA/dma_revb.c \ + $(PERIPH_SRC)/DMA/dma_$(DIE_TYPE).c \ + $(PERIPH_SRC)/FLC/flc_common.c \ + $(PERIPH_SRC)/FLC/flc_$(DIE_TYPE).c \ + $(PERIPH_SRC)/FLC/flc_reva.c \ + $(PERIPH_SRC)/GPIO/gpio_common.c \ + $(PERIPH_SRC)/GPIO/gpio_$(DIE_TYPE).c \ + $(PERIPH_SRC)/GPIO/gpio_reva.c \ + $(PERIPH_SRC)/ICC/icc_$(DIE_TYPE).c \ + $(PERIPH_SRC)/ICC/icc_reva.c \ + $(PERIPH_SRC)/RTC/rtc_$(DIE_TYPE).c \ + $(PERIPH_SRC)/RTC/rtc_reva.c \ + $(PERIPH_SRC)/TMR/tmr_common.c \ + $(PERIPH_SRC)/TMR/tmr_revb.c \ + $(PERIPH_SRC)/TMR/tmr_$(DIE_TYPE).c \ + $(PERIPH_SRC)/UART/uart_common.c \ + $(PERIPH_SRC)/UART/uart_$(DIE_TYPE).c \ + $(PERIPH_SRC)/UART/uart_revb.c + +SRC_C += $(SRC_MAX32) \ + boards/$(BOARD)/board.c \ + boards/$(BOARD)/pins.c \ + peripherals/$(MCU_VARIANT_LOWER)/pins.c + +# ******************************************************************************* +### Compiler & Linker Flags ### +COMPILER ?= GCC + +ifeq ($(COMPILER), GCC) + +STARTUPFILE = $(CMSIS_ROOT)/Device/Maxim/$(MCU_VARIANT_UPPER)/Source/GCC/startup_$(MCU_VARIANT_LOWER).s +# STARTUPFILE = $(ADI_BOARD_DIR)/Source/startup_$(MCU_VARIANT_LOWER).s + +# CircuitPython custom linkerfile (necessary for build steps & filesystems) +LINKERFILE = linking/$(MCU_VARIANT_LOWER)_cktpy.ld +LDFLAGS += -nostartfiles -specs=nano.specs +endif + +SRC_S += supervisor/cpu.s \ + $(STARTUPFILE) + +# Needed to compile some MAX32 headers +CFLAGS += -D$(MCU_VARIANT_UPPER) \ + -DTARGET_REV=0x4131 \ + -DTARGET=$(MCU_VARIANT_UPPER) \ + -DIAR_PRAGMAS=0 \ + -DRISCV_LOAD=0 + +# todo: add these for linkerfiles later on so that it's easier to add new boards +# -DFLASH_ORIGIN=0x10000000 \ +# -DFLASH_SIZE=0x340000 \ +# -DSRAM_ORIGIN=0x20000000 \ +# -DSRAM_SIZE=0x100000 + +CPU_CORE=cortex-m4 +CFLAGS += -mthumb -mcpu=$(CPU_CORE) -mfloat-abi=softfp -mfpu=fpv4-sp-d16 + +# NOTE: Start with DEBUG ONLY settings for now +ifeq ($(DEBUG),) +DEBUG ?= 1 +endif + +ifeq ($(DEBUG),1) +CFLAGS += -ggdb3 +COPT = -Og +else +COPT += -O0 #opt completely off to start +endif + +# TinyUSB CFLAGS +CFLAGS += \ + -DCFG_TUSB_MCU=OPT_MCU_$(MCU_VARIANT_UPPER) \ + -DBOARD_TUD_MAX_SPEED=OPT_MODE_HIGH_SPEED \ + -DCFG_TUSB_OS=OPT_OS_NONE \ + -DCFG_TUD_CDC_TX_BUFSIZE=1024 \ + -DCFG_TUD_CDC_RX_BUFSIZE=1024 \ + -DCFG_TUD_MSC_BUFSIZE=4096 \ + -DCFG_TUD_MIDI_RX_BUFSIZE=128 \ + -DCFG_TUD_MIDI_TX_BUFSIZE=128 \ + -DCFG_TUD_VENDOR_RX_BUFSIZE=1024 \ + -DCFG_TUD_VENDOR_TX_BUFSIZE=1024 + +# Add TinyUSB sources +INC += -I../../lib/tinyusb/src +INC += -I../../supervisor/shared/usb +SRC_C += lib/tinyusb/src/portable/mentor/musb/dcd_musb.c + +# Add port sources incl. any board functions +SRC_C += \ + boards/$(BOARD)/board.c \ + background.c \ + mphalport.c \ + +CFLAGS += $(INC) -Werror -Wall -std=gnu11 -nostartfiles $(BASE_CFLAGS) $(COPT) + +# Suppress some errors for MSDK +# cast-align warning will be suppressed; +# it gets generated by CircuitPy's TLSF memory allocator lib +CFLAGS += -Wno-error=unused-parameter \ + -Wno-error=old-style-declaration \ + -Wno-error=sign-compare \ + -Wno-error=strict-prototypes \ + -Wno-error=cast-qual \ + -Wno-error=unused-variable \ + -Wno-error=lto-type-mismatch \ + -Wno-error=cast-align \ + -Wno-error=nested-externs \ + -Wno-error=sign-compare \ + -Wno-cast-align \ + +ENTRY = Reset_Handler +LDFLAGS += $(CFLAGS) --entry $(ENTRY) -Wl,-nostdlib -Wl,-T,$(LINKERFILE) -Wl,-Map=$@.map -Wl,-cref -Wl,-gc-sections +LIBS := -lgcc -lc + +# If not using CKTPY mathlib, use toolchain mathlib +ifndef INTERNAL_LIBM +LIBS += -lm +endif + +# ******************************************************************************* +### PORT-DEFINED BUILD RULES ### +# This section attempts to build the Python core, the supervisor, and any +# port-provided source code. +# +# QSTR sources are provided for the initial build step, which generates +# Python constants to represent C data which gets passed into the GC. + +SRC_COMMON_HAL_EXPANDED = $(addprefix shared-bindings/, $(SRC_COMMON_HAL)) \ + $(addprefix shared-bindings/, $(SRC_BINDINGS_ENUMS)) \ + $(addprefix common-hal/, $(SRC_COMMON_HAL)) + +SRC_SHARED_MODULE_EXPANDED = $(addprefix shared-bindings/, $(SRC_SHARED_MODULE)) \ + $(addprefix shared-module/, $(SRC_SHARED_MODULE)) \ + $(addprefix shared-module/, $(SRC_SHARED_MODULE_INTERNAL)) + +# There are duplicates between SRC_COMMON_HAL_EXPANDED and SRC_SHARED_MODULE_EXPANDED, +# because a few modules have files both in common-hal/ and shared-module/. +# Doing a $(sort ...) removes duplicates as part of sorting. +SRC_COMMON_HAL_SHARED_MODULE_EXPANDED = $(sort $(SRC_COMMON_HAL_EXPANDED) $(SRC_SHARED_MODULE_EXPANDED)) + +# OBJ includes +OBJ += $(PY_O) $(SUPERVISOR_O) $(addprefix $(BUILD)/, $(SRC_C:.c=.o)) +OBJ += $(addprefix $(BUILD)/, $(SRC_COMMON_HAL_SHARED_MODULE_EXPANDED:.c=.o)) +ifeq ($(INTERNAL_LIBM),1) +OBJ += $(addprefix $(BUILD)/, $(SRC_LIBM:.c=.o)) +endif +OBJ += $(addprefix $(BUILD)/, $(SRC_CIRCUITPY_COMMON:.c=.o)) +OBJ += $(addprefix $(BUILD)/, $(SRC_S:.s=.o)) +OBJ += $(addprefix $(BUILD)/, $(SRC_MOD:.c=.o)) + +# List of sources for qstr extraction +SRC_QSTR += $(SRC_C) $(SRC_SUPERVISOR) $(SRC_CIRCUITPY_COMMON) \ + $(SRC_COMMON_HAL_SHARED_MODULE_EXPANDED) $(SRC_MOD) +# Sources that only hold QSTRs after pre-processing. +SRC_QSTR_PREPROCESSOR += + +# Default build target +all: $(BUILD)/firmware.elf $(BUILD)/firmware.hex $(BUILD)/firmware.bin + +clean-all: + rm -rf build-* + +# Optional flash option when running within an installed MSDK to use OpenOCD +# Mainline OpenOCD does not yet have the MAX32's flash algorithm integrated. +# If the MSDK is installed, flash-msdk can be run to utilize the the modified +# openocd with the algorithms +MAXIM_PATH := $(subst \,/,$(MAXIM_PATH)) +flash-msdk: + $(MAXIM_PATH)/Tools/OpenOCD/openocd -s $(MAXIM_PATH)/Tools/OpenOCD/scripts \ + -f interface/cmsis-dap.cfg -f target/$(MCU_VARIANT_LOWER).cfg \ + -c "program $(BUILD)/firmware.elf verify; init; reset; exit" + +# flash target using JLink +JLINK_DEVICE = $(MCU_VARIANT_LOWER) + +JLINKEXE ?= JLink.exe +JLINKEXE += -if SWD -device ${JLINK_DEVICE} -speed 10000 +COMMAND_FILE := tools/flash_max32.jlink + +flash-jlink: $(BUILD)/firmware.bin + @$(JLINKEXE) -device $(MCU_VARIANT_UPPER) -NoGui 1 -CommandFile ${COMMAND_FILE} + +$(BUILD)/firmware.elf: $(OBJ) + $(STEPECHO) "LINK $@" + $(Q)echo $^ > $(BUILD)/firmware.objs + $(Q)$(CC) -o $@ $(LDFLAGS) @$(BUILD)/firmware.objs -Wl,--print-memory-usage -Wl,--start-group $(LIBS) -Wl,--end-group + $(Q)$(SIZE) $@ | $(PYTHON) $(TOP)/tools/build_memory_info.py $(LINKERFILE) $(BUILD) + +$(BUILD)/firmware.hex: $(BUILD)/firmware.elf + $(STEPECHO) "Create $@" + $(Q)$(OBJCOPY) -O ihex $^ $@ + +$(BUILD)/firmware.bin: $(BUILD)/firmware.elf + $(STEPECHO) "Create $@" + $(Q)$(OBJCOPY) -O binary $^ $@ + +# ******************************************************************************* +### CKTPY BUILD RULES ### +include $(TOP)/py/mkrules.mk diff --git a/ports/analog/README.md b/ports/analog/README.md new file mode 100644 index 000000000000..39d8db098dd0 --- /dev/null +++ b/ports/analog/README.md @@ -0,0 +1,59 @@ +# Analog Devices "MAX32" MCUs + +This port brings CircuitPython to ADI's "MAX32" series of microcontrollers. These devices are mostly ARM Cortex-M4-based and focus on delivering performance at low-power levels. Currently this port only supports MAX32690. + +## Structure of this port + +- **`boards/:`** Board-specific definitions including pins, board initialization, etc. +- **`common-hal/:`** Port-specific implementations of CircuitPython common-hal APIs. When a new module is enabled, this is often where the implementation is found. Expected functions for modules in `common-hal` are usually found in `shared-bindings/` or `shared-module/` in the CircuitPy root directory. +- **`linking/:`** Linkerfiles customized for CircuitPython. These are distinct from the linkerfiles used in MSDK as they adopt the structure required by CircuitPython. They may also omit unused features and memory sections, e.g. Mailboxes, RISC-V Flash, & Hyperbus RAM for MAX32690. +- **`msdk:/`** SDK for MAX32 devices. More info on our GitHub: [Analog Devices MSDK GitHub](https://github.com/analogdevicesinc/msdk) +- **`peripherals:/`** Helper files for peripherals such as clocks, gpio, etc. These files tend to be specific to vendor SDKs and provide some useful functions for the common-hal interfaces. +- **`supervisor/:`** Implementation files for the CircuitPython supervisor. This includes port setup, usb, and a filesystem on a storage medium such as SD Card/eMMC, QSPI Flash, or internal flash memory. Currently the internal flash is used. This folder is the most important part of a port's core functionality for CircuitPython. +- **`supervisor/port.c:`** Port-specific startup code including clock initialization, console startup, etc. + +- `. :` Build system and high-level interface to the CircuitPython core for the ADI port. + +## Building for MAX32 devices + +Ensure CircuitPython dependencies are up-to-date by following the CircuitPython introduction on Adafruit's Website: [Building CircuitPython - Introduction](https://learn.adafruit.com/building-circuitpython/introduction). In particular, it is necessary to fetch all submodules (including the ARM Toolchain inside MSDK) and build the `mpy-cross` compiler. + +Ensure the MSDK's ARM toolchain is contained on your PATH. This can be done in MinGW or WSL by exporting a prefix to the PATH variable: + + $ export MSDK_GNU_PATH=/ports/analog/msdk/Tools/GNUTools/10.3/bin + $ export PATH=$MSDK_GNU_PATH:$PATH + +This needs to be done each time you open a command environment to build CircuitPython. + +Once you have built `mpy-cross` and set up your build system for CircuitPython, you can build for MAX32 devices using the following commands: + + $ cd ports/analog + $ make BOARD= + +Be aware the build may take a long time without parallelizing via the `-jN` flag, where N is the # of cores on your machine. + +## Flashing the board + +Universal instructions on flashing MAX32 devices this project can be found in the **[MSDK User Guide](https://analogdevicesinc.github.io/msdk/USERGUIDE/)**. + +In addition, a user may flash the device by calling `make` with the `flash-msdk` target from within the `ports/analog` directory, as below: + +``` +$ make BOARD= flash-msdk +``` + +This requires the following: +- A MAX32625PICO is connected to the PC via USB +- The PICO board shows up as a "DAPLINK" drive which implements the CMSIS-DAP interface. +- The PICO board is connected to the target board via a 10-pin SWD ribbon cable. + - If SWD connectors are not keyed, the P1 indicator (red line) on the SWD ribbon cable should match the P1 indicator on the board silkscreen near the 10-pin SWD connector. + +## Using the REPL + +Once the device is plugged in, it will enumerate via USB as both a USB Serial Device (CDC) and a Mass Storage Device (MSC). You can connect to the Python REPL with your favorite Serial Monitor program e.g. TeraTerm, VS Code, Putty, etc. Use any buadrate with 8-bit, No Parity, 1 Stop Bit (8N1) settings. From this point forward, you can run Python code on the MCU! If you want help with learning CircuitPython-specific code or learning Python in general, a good place to start is Adafruit's ["Welcome to CircuitPython"](https://learn.adafruit.com/welcome-to-circuitpython/) guide. + +## Editing code.py + +Python code may be executed from `code.py` the `CIRCUITPY:` drive. When editing this file, please be aware that some text editors will work better than others. A list of suggested text editors can be found at Adafruit's guide here: https://learn.adafruit.com/welcome-to-circuitpython/recommended-editors + +Once you save `code.py`, it gets written back to the device you are running Circuitpython on, and will automatically run and output it's result to the REPL. You can also automatically reload and run code.py any time from the REPL by pressing CTRL+D. diff --git a/ports/analog/background.c b/ports/analog/background.c new file mode 100644 index 000000000000..ffad007ffa51 --- /dev/null +++ b/ports/analog/background.c @@ -0,0 +1,49 @@ +// This file is part of the CircuitPython project: https://circuitpython.org +// +// SPDX-FileCopyrightText: Copyright (c) 2017 Scott Shawcroft for Adafruit Industries +// SPDX-FileCopyrightText: Copyright (c) 2024 Brandon Hurst, Analog Devices, Inc. +// +// SPDX-License-Identifier: MIT + +#include "py/runtime.h" +#include "supervisor/filesystem.h" +#include "supervisor/usb.h" +#include "supervisor/shared/stack.h" + +#include "max32_port.h" + +// From boards/$(BOARD)/board.c +extern const mxc_gpio_cfg_t pb_pin[]; +extern const int num_pbs; +extern const mxc_gpio_cfg_t led_pin[]; +extern const int num_leds; + +/** NOTE: ALL "ticks" refer to a 1/1024 s period */ +static int status_led_ticks = 0; + +// This function is where port-specific background +// tasks should be performed +// Execute port specific actions during background tick. Only if ticks are enabled. +void port_background_tick(void) { + status_led_ticks++; + + // Set an LED approx. 1/s + if (status_led_ticks > 1024) { + MXC_GPIO_OutToggle(led_pin[2].port, led_pin[2].mask); + status_led_ticks = 0; + } +} + +// Execute port specific actions during background tasks. This is before the +// background callback system and happens *very* often. Use +// port_background_tick() when possible. +void port_background_task(void) { +} + +// Take port specific actions at the beginning and end of background ticks. +// This is used e.g., to set a monitoring pin for debug purposes. "Actual +// work" should be done in port_background_tick() instead. +void port_start_background_tick(void) { +} +void port_finish_background_tick(void) { +} diff --git a/ports/analog/background.h b/ports/analog/background.h new file mode 100644 index 000000000000..d32f2b0dc2c3 --- /dev/null +++ b/ports/analog/background.h @@ -0,0 +1,11 @@ +// This file is part of the CircuitPython project: https://circuitpython.org +// +// SPDX-FileCopyrightText: Copyright (c) 2019 Dan Halbert for Adafruit Industries +// SPDX-FileCopyrightText: Copyright (c) 2024 Brandon Hurst, Analog Devices, Inc. +// +// SPDX-License-Identifier: MIT + +#ifndef MICROPY_INCLUDED_BACKGROUND_H +#define MICROPY_INCLUDED_BACKGROUND_H + +#endif // MICROPY_INCLUDED_BACKGROUND_H diff --git a/ports/analog/boards/apard32690/README.md b/ports/analog/boards/apard32690/README.md new file mode 100644 index 000000000000..960a26a007f2 --- /dev/null +++ b/ports/analog/boards/apard32690/README.md @@ -0,0 +1,36 @@ +# AD-APARD32690-SL + +This board features the MAX32690, a dual-core ARM Cortex-M4/RISC-V MCU with 3MiB Flash, 1MiB SRAM. The board also has support for 10BASE-T1L Ethernet, Wifi, Bluetooth, USB, and Security via MAXQ1065. However, most of these features are not yet available for this CircuitPython port (USB will be added soon; others are currently unplanned). + +## Onboard connectors & peripherals + +This board comes in a form-factor similar to an Arduino Mega, enabling Arduino-style shield boards to be plugged in and evaluated with the MAX32690. This vastly opens up the options for easily plugging peripherals into the board, especially when combined with the two Pmod:tm: connectors, P8 (SPI) and P13 (I2C). + +## Product Resources + +For more info about AD-APARD32690-SL, visit our product webpages for datasheets, User Guides, Software, and Design Documents: + +[AD-APARD32690-SL Product Webpage](https://www.analog.com/en/resources/evaluation-hardware-and-software/evaluation-boards-kits/ad-apard32690-sl.html) +[AD-APARD32690-SL User Guide](https://wiki.analog.com/resources/eval/user-guides/ad-apard32690-sl) + +### Building for this board + +To build for this board, ensure you are in the `ports/analog` directory and run the following command. Note that passing in the `-jN` flag, where N is the # of cores on your machine, can speed up compile times. + +``` +make BOARD=apard32690 +``` + +### Flashing this board + +To flash the board, run the following command if using the MAX32625PICO: + +``` +make BOARD=APARD flash-msdk +``` + +If using Segger JLink, please run the following command instead: + +``` +make BOARD=APARD flash-jlink +``` diff --git a/ports/analog/boards/apard32690/board.c b/ports/analog/boards/apard32690/board.c new file mode 100644 index 000000000000..cfef4bfcf61a --- /dev/null +++ b/ports/analog/boards/apard32690/board.c @@ -0,0 +1,60 @@ +// This file is part of the CircuitPython project: https://circuitpython.org +// +// SPDX-FileCopyrightText: Copyright (c) 2024 Brandon Hurst, Analog Devices, Inc +// +// SPDX-License-Identifier: MIT + +#include "supervisor/board.h" +#include "supervisor/port.h" +#include "mpconfigboard.h" +#include "max32_port.h" + +// Board-level setup for MAX32690 +mxc_gpio_regs_t *gpio_ports[NUM_GPIO_PORTS] = +{MXC_GPIO0, MXC_GPIO1, MXC_GPIO2, MXC_GPIO3, MXC_GPIO4}; + +// clang-format off +const mxc_gpio_cfg_t pb_pin[] = { + { MXC_GPIO1, MXC_GPIO_PIN_27, MXC_GPIO_FUNC_IN, MXC_GPIO_PAD_NONE, MXC_GPIO_VSSEL_VDDIOH, MXC_GPIO_DRVSTR_0}, +}; +const int num_pbs = (sizeof(pb_pin) / sizeof(mxc_gpio_cfg_t)); + +const mxc_gpio_cfg_t led_pin[] = { + { MXC_GPIO2, MXC_GPIO_PIN_1, MXC_GPIO_FUNC_OUT, MXC_GPIO_PAD_NONE, MXC_GPIO_VSSEL_VDDIO, MXC_GPIO_DRVSTR_0 }, + { MXC_GPIO0, MXC_GPIO_PIN_11, MXC_GPIO_FUNC_OUT, MXC_GPIO_PAD_NONE, MXC_GPIO_VSSEL_VDDIO, MXC_GPIO_DRVSTR_0 }, + { MXC_GPIO0, MXC_GPIO_PIN_12, MXC_GPIO_FUNC_OUT, MXC_GPIO_PAD_NONE, MXC_GPIO_VSSEL_VDDIO, MXC_GPIO_DRVSTR_0 }, +}; +const int num_leds = (sizeof(led_pin) / sizeof(mxc_gpio_cfg_t)); +// clang-format on + +// DEFAULT: Using the weak-defined supervisor/shared/board.c functions + +/***** OPTIONAL BOARD-SPECIFIC FUNCTIONS from supervisor/board.h *****/ +// Returns true if the user initiates safe mode in a board specific way. +// Also add BOARD_USER_SAFE_MODE in mpconfigboard.h to explain the board specific +// way. +// bool board_requests_safe_mode(void); + +volatile uint32_t system_ticks = 0; + +void SysTick_Handler(void) { + system_ticks++; +} + +uint32_t board_millis(void) { + return system_ticks; +} + +// Initializes board related state once on start up. +void board_init(void) { +} + +// Reset the state of off MCU components such as neopixels. +// void reset_board(void); + +// Deinit the board. This should put the board in deep sleep durable, low power +// state. It should not prevent the user access method from working (such as +// disabling USB, BLE or flash) because CircuitPython may continue to run. +// void board_deinit(void); + +/*******************************************************************/ diff --git a/ports/analog/boards/apard32690/mpconfigboard.h b/ports/analog/boards/apard32690/mpconfigboard.h new file mode 100644 index 000000000000..19b75a79d810 --- /dev/null +++ b/ports/analog/boards/apard32690/mpconfigboard.h @@ -0,0 +1,40 @@ +// This file is part of the CircuitPython project: https://circuitpython.org +// +// SPDX-FileCopyrightText: Copyright (c) 2017 Scott Shawcroft for Adafruit Industries +// SPDX-FileCopyrightText: Copyright (c) 2024 Brandon Hurst, Analog Devices Inc. +// +// SPDX-License-Identifier: MIT + +// Use the MP_WEAK supervisor/shared/board.c versions of routines not defined here. +// This file is part of the CircuitPython project: https://circuitpython.org +// +// SPDX-FileCopyrightText: Copyright (c) 2016 Glenn Ruben Bakke +// SPDX-FileCopyrightText: Copyright (c) 2018 Dan Halbert for Adafruit Industries +// +// SPDX-License-Identifier: MIT + +#pragma once + +#define MICROPY_HW_BOARD_NAME "APARD32690" +#define MICROPY_HW_MCU_NAME "max32690" + +#define FLASH_SIZE (0x300000) // 3MiB +#define FLASH_PAGE_SIZE (0x4000) // 16384 byte pages (16 KiB) + +#define BOARD_HAS_CRYSTAL 1 +#define NUM_GPIO_PORTS 5 +#define CONSOLE_UART MXC_UART0 + +// #if INTERNAL_FLASH_FILESYSTEM +#define CIRCUITPY_INTERNAL_FLASH_FILESYSTEM_START_ADDR (0x102E0000) // for MAX32690 +#define CIRCUITPY_INTERNAL_FLASH_FILESYSTEM_SIZE (128 * 1024) // 64K + +#define MAX32_FLASH_SIZE 0x300000 // 3 MiB +#define INTERNAL_FLASH_FILESYSTEM_SIZE CIRCUITPY_INTERNAL_FLASH_FILESYSTEM_SIZE +#define INTERNAL_FLASH_FILESYSTEM_START_ADDR 0x102E0000 // Load into the last MiB of code/data storage + +// #else +// #define CIRCUITPY_INTERNAL_FLASH_FILESYSTEM_SIZE (0) +// #endif + + #define MICROPY_HW_LED_STATUS (&pin_P2_01) diff --git a/ports/analog/boards/apard32690/mpconfigboard.mk b/ports/analog/boards/apard32690/mpconfigboard.mk new file mode 100644 index 000000000000..7cc54ccfc6dd --- /dev/null +++ b/ports/analog/boards/apard32690/mpconfigboard.mk @@ -0,0 +1,32 @@ +# This file is part of the CircuitPython project: https://circuitpython.org +# +# SPDX-FileCopyrightText: Copyright (c) 2020 Scott Shawcroft for Adafruit Industries +# SPDX-FileCopyrightText: Copyright (c) 2024 Brandon Hurst, Analog Devices, Inc +# +# SPDX-License-Identifier: MIT + +MCU_SERIES=max32 +MCU_VARIANT=max32690 + +INTERNAL_FLASH_FILESYSTEM=1 +# FLASH: 0x10000000 to 0x10300000 (ARM) +# SRAM: 0x20000000 to 0x20100000 + +#### USB CONFIGURATION +# Use 0x0456 for Analog Devices, Inc.; 0B6A for Maxim +USB_VID=0x0456 +# USB_VID=0x0B6A +USB_PID=0x003C +USB_MANUFACTURER="Analog Devices, Inc." +USB_PRODUCT="MAX32690 APARD" +USB_HIGHSPEED=1 + +# NOTE: MAX32 devices do not support IN/OUT pairs on the same EP +USB_NUM_ENDPOINT_PAIRS=12 +### + +# define UID len for memory safety (buffer gets passed as a raw ptr) +COMMON_HAL_MCU_PROCESSOR_UID_LENGTH=30 + +# NOTE: Not implementing external flash for now +# CFLAGS+=-DEXT_FLASH_MX25 diff --git a/ports/analog/boards/apard32690/pins.c b/ports/analog/boards/apard32690/pins.c new file mode 100644 index 000000000000..f4970aff7aeb --- /dev/null +++ b/ports/analog/boards/apard32690/pins.c @@ -0,0 +1,133 @@ +// This file is part of the CircuitPython project: https://circuitpython.org +// +// SPDX-FileCopyrightText: Copyright (c) 2017 Scott Shawcroft for Adafruit Industries +// SPDX-FileCopyrightText: Copyright (c) 2024 Brandon Hurst, Analog Devices, Inc. +// +// SPDX-License-Identifier: MIT + +#include "shared-bindings/board/__init__.h" + +static const mp_rom_map_elem_t board_module_globals_table[] = { + CIRCUITPYTHON_BOARD_DICT_STANDARD_ITEMS + // P0 + { MP_ROM_QSTR(MP_QSTR_P0_0), MP_ROM_PTR(&pin_P0_00) }, + { MP_ROM_QSTR(MP_QSTR_P0_1), MP_ROM_PTR(&pin_P0_01) }, + { MP_ROM_QSTR(MP_QSTR_P0_2), MP_ROM_PTR(&pin_P0_02) }, + { MP_ROM_QSTR(MP_QSTR_P0_3), MP_ROM_PTR(&pin_P0_03) }, + { MP_ROM_QSTR(MP_QSTR_P0_4), MP_ROM_PTR(&pin_P0_04) }, + { MP_ROM_QSTR(MP_QSTR_P0_5), MP_ROM_PTR(&pin_P0_05) }, + { MP_ROM_QSTR(MP_QSTR_P0_6), MP_ROM_PTR(&pin_P0_06) }, + { MP_ROM_QSTR(MP_QSTR_P0_7), MP_ROM_PTR(&pin_P0_07) }, + { MP_ROM_QSTR(MP_QSTR_P0_8), MP_ROM_PTR(&pin_P0_08) }, + { MP_ROM_QSTR(MP_QSTR_P0_9), MP_ROM_PTR(&pin_P0_09) }, + { MP_ROM_QSTR(MP_QSTR_P0_10), MP_ROM_PTR(&pin_P0_10) }, + { MP_ROM_QSTR(MP_QSTR_P0_11), MP_ROM_PTR(&pin_P0_11) }, + { MP_ROM_QSTR(MP_QSTR_P0_12), MP_ROM_PTR(&pin_P0_12) }, + { MP_ROM_QSTR(MP_QSTR_P0_13), MP_ROM_PTR(&pin_P0_13) }, + { MP_ROM_QSTR(MP_QSTR_P0_14), MP_ROM_PTR(&pin_P0_14) }, + { MP_ROM_QSTR(MP_QSTR_P0_15), MP_ROM_PTR(&pin_P0_15) }, + { MP_ROM_QSTR(MP_QSTR_P0_16), MP_ROM_PTR(&pin_P0_16) }, + { MP_ROM_QSTR(MP_QSTR_P0_17), MP_ROM_PTR(&pin_P0_17) }, + { MP_ROM_QSTR(MP_QSTR_P0_18), MP_ROM_PTR(&pin_P0_18) }, + { MP_ROM_QSTR(MP_QSTR_P0_19), MP_ROM_PTR(&pin_P0_19) }, + { MP_ROM_QSTR(MP_QSTR_P0_20), MP_ROM_PTR(&pin_P0_20) }, + { MP_ROM_QSTR(MP_QSTR_P0_21), MP_ROM_PTR(&pin_P0_21) }, + { MP_ROM_QSTR(MP_QSTR_P0_22), MP_ROM_PTR(&pin_P0_22) }, + { MP_ROM_QSTR(MP_QSTR_P0_23), MP_ROM_PTR(&pin_P0_23) }, + { MP_ROM_QSTR(MP_QSTR_P0_24), MP_ROM_PTR(&pin_P0_24) }, + { MP_ROM_QSTR(MP_QSTR_P0_25), MP_ROM_PTR(&pin_P0_25) }, + { MP_ROM_QSTR(MP_QSTR_P0_26), MP_ROM_PTR(&pin_P0_26) }, + { MP_ROM_QSTR(MP_QSTR_P0_27), MP_ROM_PTR(&pin_P0_27) }, + { MP_ROM_QSTR(MP_QSTR_P0_28), MP_ROM_PTR(&pin_P0_28) }, + { MP_ROM_QSTR(MP_QSTR_P0_29), MP_ROM_PTR(&pin_P0_29) }, + { MP_ROM_QSTR(MP_QSTR_P0_30), MP_ROM_PTR(&pin_P0_30) }, + { MP_ROM_QSTR(MP_QSTR_P0_31), MP_ROM_PTR(&pin_P0_31) }, + // P1 + { MP_ROM_QSTR(MP_QSTR_P1_0), MP_ROM_PTR(&pin_P1_00) }, + { MP_ROM_QSTR(MP_QSTR_P1_1), MP_ROM_PTR(&pin_P1_01) }, + { MP_ROM_QSTR(MP_QSTR_P1_2), MP_ROM_PTR(&pin_P1_02) }, + { MP_ROM_QSTR(MP_QSTR_P1_3), MP_ROM_PTR(&pin_P1_03) }, + { MP_ROM_QSTR(MP_QSTR_P1_4), MP_ROM_PTR(&pin_P1_04) }, + { MP_ROM_QSTR(MP_QSTR_P1_5), MP_ROM_PTR(&pin_P1_05) }, + { MP_ROM_QSTR(MP_QSTR_P1_6), MP_ROM_PTR(&pin_P1_06) }, + { MP_ROM_QSTR(MP_QSTR_P1_7), MP_ROM_PTR(&pin_P1_07) }, + { MP_ROM_QSTR(MP_QSTR_P1_8), MP_ROM_PTR(&pin_P1_08) }, + { MP_ROM_QSTR(MP_QSTR_P1_9), MP_ROM_PTR(&pin_P1_09) }, + { MP_ROM_QSTR(MP_QSTR_P1_10), MP_ROM_PTR(&pin_P1_10) }, + { MP_ROM_QSTR(MP_QSTR_P1_11), MP_ROM_PTR(&pin_P1_11) }, + { MP_ROM_QSTR(MP_QSTR_P1_12), MP_ROM_PTR(&pin_P1_12) }, + { MP_ROM_QSTR(MP_QSTR_P1_13), MP_ROM_PTR(&pin_P1_13) }, + { MP_ROM_QSTR(MP_QSTR_P1_14), MP_ROM_PTR(&pin_P1_14) }, + { MP_ROM_QSTR(MP_QSTR_P1_15), MP_ROM_PTR(&pin_P1_15) }, + { MP_ROM_QSTR(MP_QSTR_P1_16), MP_ROM_PTR(&pin_P1_16) }, + { MP_ROM_QSTR(MP_QSTR_P1_17), MP_ROM_PTR(&pin_P1_17) }, + { MP_ROM_QSTR(MP_QSTR_P1_18), MP_ROM_PTR(&pin_P1_18) }, + { MP_ROM_QSTR(MP_QSTR_P1_19), MP_ROM_PTR(&pin_P1_19) }, + { MP_ROM_QSTR(MP_QSTR_P1_20), MP_ROM_PTR(&pin_P1_20) }, + { MP_ROM_QSTR(MP_QSTR_P1_21), MP_ROM_PTR(&pin_P1_21) }, + { MP_ROM_QSTR(MP_QSTR_P1_22), MP_ROM_PTR(&pin_P1_22) }, + { MP_ROM_QSTR(MP_QSTR_P1_23), MP_ROM_PTR(&pin_P1_23) }, + { MP_ROM_QSTR(MP_QSTR_P1_24), MP_ROM_PTR(&pin_P1_24) }, + { MP_ROM_QSTR(MP_QSTR_P1_25), MP_ROM_PTR(&pin_P1_25) }, + { MP_ROM_QSTR(MP_QSTR_P1_26), MP_ROM_PTR(&pin_P1_26) }, + { MP_ROM_QSTR(MP_QSTR_P1_27), MP_ROM_PTR(&pin_P1_27) }, + { MP_ROM_QSTR(MP_QSTR_P1_28), MP_ROM_PTR(&pin_P1_28) }, + { MP_ROM_QSTR(MP_QSTR_P1_29), MP_ROM_PTR(&pin_P1_29) }, + { MP_ROM_QSTR(MP_QSTR_P1_30), MP_ROM_PTR(&pin_P1_30) }, + { MP_ROM_QSTR(MP_QSTR_P1_31), MP_ROM_PTR(&pin_P1_31) }, + // P2 + { MP_ROM_QSTR(MP_QSTR_P2_0), MP_ROM_PTR(&pin_P2_00) }, + { MP_ROM_QSTR(MP_QSTR_P2_1), MP_ROM_PTR(&pin_P2_01) }, + { MP_ROM_QSTR(MP_QSTR_P2_2), MP_ROM_PTR(&pin_P2_02) }, + { MP_ROM_QSTR(MP_QSTR_P2_3), MP_ROM_PTR(&pin_P2_03) }, + { MP_ROM_QSTR(MP_QSTR_P2_4), MP_ROM_PTR(&pin_P2_04) }, + { MP_ROM_QSTR(MP_QSTR_P2_5), MP_ROM_PTR(&pin_P2_05) }, + { MP_ROM_QSTR(MP_QSTR_P2_6), MP_ROM_PTR(&pin_P2_06) }, + { MP_ROM_QSTR(MP_QSTR_P2_7), MP_ROM_PTR(&pin_P2_07) }, + { MP_ROM_QSTR(MP_QSTR_P2_8), MP_ROM_PTR(&pin_P2_08) }, + { MP_ROM_QSTR(MP_QSTR_P2_9), MP_ROM_PTR(&pin_P2_09) }, + { MP_ROM_QSTR(MP_QSTR_P2_10), MP_ROM_PTR(&pin_P2_10) }, + { MP_ROM_QSTR(MP_QSTR_P2_11), MP_ROM_PTR(&pin_P2_11) }, + { MP_ROM_QSTR(MP_QSTR_P2_12), MP_ROM_PTR(&pin_P2_12) }, + { MP_ROM_QSTR(MP_QSTR_P2_13), MP_ROM_PTR(&pin_P2_13) }, + { MP_ROM_QSTR(MP_QSTR_P2_14), MP_ROM_PTR(&pin_P2_14) }, + { MP_ROM_QSTR(MP_QSTR_P2_15), MP_ROM_PTR(&pin_P2_15) }, + { MP_ROM_QSTR(MP_QSTR_P2_16), MP_ROM_PTR(&pin_P2_16) }, + { MP_ROM_QSTR(MP_QSTR_P2_17), MP_ROM_PTR(&pin_P2_17) }, + { MP_ROM_QSTR(MP_QSTR_P2_18), MP_ROM_PTR(&pin_P2_18) }, + { MP_ROM_QSTR(MP_QSTR_P2_19), MP_ROM_PTR(&pin_P2_19) }, + { MP_ROM_QSTR(MP_QSTR_P2_20), MP_ROM_PTR(&pin_P2_20) }, + { MP_ROM_QSTR(MP_QSTR_P2_21), MP_ROM_PTR(&pin_P2_21) }, + { MP_ROM_QSTR(MP_QSTR_P2_22), MP_ROM_PTR(&pin_P2_22) }, + { MP_ROM_QSTR(MP_QSTR_P2_23), MP_ROM_PTR(&pin_P2_23) }, + { MP_ROM_QSTR(MP_QSTR_P2_24), MP_ROM_PTR(&pin_P2_24) }, + { MP_ROM_QSTR(MP_QSTR_P2_25), MP_ROM_PTR(&pin_P2_25) }, + { MP_ROM_QSTR(MP_QSTR_P2_26), MP_ROM_PTR(&pin_P2_26) }, + { MP_ROM_QSTR(MP_QSTR_P2_27), MP_ROM_PTR(&pin_P2_27) }, + { MP_ROM_QSTR(MP_QSTR_P2_28), MP_ROM_PTR(&pin_P2_28) }, + { MP_ROM_QSTR(MP_QSTR_P2_29), MP_ROM_PTR(&pin_P2_29) }, + { MP_ROM_QSTR(MP_QSTR_P2_30), MP_ROM_PTR(&pin_P2_30) }, + { MP_ROM_QSTR(MP_QSTR_P2_31), MP_ROM_PTR(&pin_P2_31) }, + // P3 + { MP_ROM_QSTR(MP_QSTR_P3_0), MP_ROM_PTR(&pin_P3_00) }, + { MP_ROM_QSTR(MP_QSTR_P3_1), MP_ROM_PTR(&pin_P3_01) }, + { MP_ROM_QSTR(MP_QSTR_P3_2), MP_ROM_PTR(&pin_P3_02) }, + { MP_ROM_QSTR(MP_QSTR_P3_3), MP_ROM_PTR(&pin_P3_03) }, + { MP_ROM_QSTR(MP_QSTR_P3_4), MP_ROM_PTR(&pin_P3_04) }, + { MP_ROM_QSTR(MP_QSTR_P3_5), MP_ROM_PTR(&pin_P3_05) }, + { MP_ROM_QSTR(MP_QSTR_P3_6), MP_ROM_PTR(&pin_P3_06) }, + { MP_ROM_QSTR(MP_QSTR_P3_7), MP_ROM_PTR(&pin_P3_07) }, + { MP_ROM_QSTR(MP_QSTR_P3_8), MP_ROM_PTR(&pin_P3_08) }, + { MP_ROM_QSTR(MP_QSTR_P3_9), MP_ROM_PTR(&pin_P3_09) }, + // P4 + { MP_ROM_QSTR(MP_QSTR_P4_0), MP_ROM_PTR(&pin_P4_00) }, + { MP_ROM_QSTR(MP_QSTR_P4_1), MP_ROM_PTR(&pin_P4_01) }, + + // Silkscreen aliases + { MP_ROM_QSTR(MP_QSTR_LED0), MP_ROM_PTR(&pin_P2_01) }, + { MP_ROM_QSTR(MP_QSTR_LED1), MP_ROM_PTR(&pin_P0_11) }, + { MP_ROM_QSTR(MP_QSTR_LED2), MP_ROM_PTR(&pin_P0_12) }, + { MP_ROM_QSTR(MP_QSTR_S2), MP_ROM_PTR(&pin_P1_27) }, + +}; +MP_DEFINE_CONST_DICT(board_module_globals, board_module_globals_table); diff --git a/ports/analog/boards/max32690evkit/board.c b/ports/analog/boards/max32690evkit/board.c new file mode 100644 index 000000000000..ebb8b2da35fc --- /dev/null +++ b/ports/analog/boards/max32690evkit/board.c @@ -0,0 +1,59 @@ +// This file is part of the CircuitPython project: https://circuitpython.org +// +// SPDX-FileCopyrightText: Copyright (c) 2024 Brandon Hurst, Analog Devices, Inc +// +// SPDX-License-Identifier: MIT + +#include "supervisor/board.h" +#include "supervisor/port.h" +#include "mpconfigboard.h" +#include "max32_port.h" + +// Board-level setup for MAX32690 +mxc_gpio_regs_t *gpio_ports[NUM_GPIO_PORTS] = +{MXC_GPIO0, MXC_GPIO1, MXC_GPIO2, MXC_GPIO3, MXC_GPIO4}; + +// clang-format off +const mxc_gpio_cfg_t pb_pin[] = { + { MXC_GPIO4, MXC_GPIO_PIN_0, MXC_GPIO_FUNC_IN, MXC_GPIO_PAD_NONE, MXC_GPIO_VSSEL_VDDIOH, MXC_GPIO_DRVSTR_0}, +}; +const int num_pbs = (sizeof(pb_pin) / sizeof(mxc_gpio_cfg_t)); + +const mxc_gpio_cfg_t led_pin[] = { + { MXC_GPIO0, MXC_GPIO_PIN_14, MXC_GPIO_FUNC_OUT, MXC_GPIO_PAD_NONE, MXC_GPIO_VSSEL_VDDIO, MXC_GPIO_DRVSTR_0 }, + { MXC_GPIO2, MXC_GPIO_PIN_12, MXC_GPIO_FUNC_OUT, MXC_GPIO_PAD_NONE, MXC_GPIO_VSSEL_VDDIO, MXC_GPIO_DRVSTR_0 }, +}; +const int num_leds = (sizeof(led_pin) / sizeof(mxc_gpio_cfg_t)); +// clang-format on + +// DEFAULT: Using the weak-defined supervisor/shared/board.c functions + +/***** OPTIONAL BOARD-SPECIFIC FUNCTIONS from supervisor/board.h *****/ +// Returns true if the user initiates safe mode in a board specific way. +// Also add BOARD_USER_SAFE_MODE in mpconfigboard.h to explain the board specific +// way. +// bool board_requests_safe_mode(void); + +volatile uint32_t system_ticks = 0; + +void SysTick_Handler(void) { + system_ticks++; +} + +uint32_t board_millis(void) { + return system_ticks; +} + +// Initializes board related state once on start up. +void board_init(void) { +} + +// Reset the state of off MCU components such as neopixels. +// void reset_board(void); + +// Deinit the board. This should put the board in deep sleep durable, low power +// state. It should not prevent the user access method from working (such as +// disabling USB, BLE or flash) because CircuitPython may continue to run. +// void board_deinit(void); + +/*******************************************************************/ diff --git a/ports/analog/boards/max32690evkit/mpconfigboard.h b/ports/analog/boards/max32690evkit/mpconfigboard.h new file mode 100644 index 000000000000..e4395e8a0ae7 --- /dev/null +++ b/ports/analog/boards/max32690evkit/mpconfigboard.h @@ -0,0 +1,41 @@ +// This file is part of the CircuitPython project: https://circuitpython.org +// +// SPDX-FileCopyrightText: Copyright (c) 2017 Scott Shawcroft for Adafruit Industries +// SPDX-FileCopyrightText: Copyright (c) 2024 Brandon Hurst, Analog Devices Inc. +// +// SPDX-License-Identifier: MIT + +// Use the MP_WEAK supervisor/shared/board.c versions of routines not defined here. +// This file is part of the CircuitPython project: https://circuitpython.org +// +// SPDX-FileCopyrightText: Copyright (c) 2016 Glenn Ruben Bakke +// SPDX-FileCopyrightText: Copyright (c) 2018 Dan Halbert for Adafruit Industries +// +// SPDX-License-Identifier: MIT + +#pragma once + +#define MICROPY_HW_BOARD_NAME "MAX32690 EvKit" +#define MICROPY_HW_MCU_NAME "max32690" + +#define FLASH_SIZE (0x300000) // 3MiB +#define FLASH_PAGE_SIZE (0x4000) // 16384 byte pages (16 KiB) + +#define BOARD_HAS_CRYSTAL 1 +#define NUM_GPIO_PORTS 5 +#define CONSOLE_UART MXC_UART2 + +// #if INTERNAL_FLASH_FILESYSTEM +#define CIRCUITPY_INTERNAL_FLASH_FILESYSTEM_START_ADDR (0x102E0000) // for MAX32690 +#define CIRCUITPY_INTERNAL_FLASH_FILESYSTEM_SIZE (128 * 1024) // 64K + +#define MAX32_FLASH_SIZE 0x300000 // 3 MiB +#define INTERNAL_FLASH_FILESYSTEM_SIZE CIRCUITPY_INTERNAL_FLASH_FILESYSTEM_SIZE +#define INTERNAL_FLASH_FILESYSTEM_START_ADDR 0x102E0000 // Load into the last MiB of code/data storage + +// #else +// #define CIRCUITPY_INTERNAL_FLASH_FILESYSTEM_SIZE (0) +// #endif + +#define MICROPY_HW_LED_STATUS (&pin_P2_12) +#define MICROPY_HW_LED_STATUS_INVERTED 1 diff --git a/ports/analog/boards/max32690evkit/mpconfigboard.mk b/ports/analog/boards/max32690evkit/mpconfigboard.mk new file mode 100644 index 000000000000..61413216d817 --- /dev/null +++ b/ports/analog/boards/max32690evkit/mpconfigboard.mk @@ -0,0 +1,32 @@ +# This file is part of the CircuitPython project: https://circuitpython.org +# +# SPDX-FileCopyrightText: Copyright (c) 2020 Scott Shawcroft for Adafruit Industries +# SPDX-FileCopyrightText: Copyright (c) 2024 Brandon Hurst, Analog Devices, Inc +# +# SPDX-License-Identifier: MIT + +MCU_SERIES=max32 +MCU_VARIANT=max32690 + +INTERNAL_FLASH_FILESYSTEM=1 +# FLASH: 0x10000000 to 0x10300000 (ARM) +# SRAM: 0x20000000 to 0x20100000 + +#### USB CONFIGURATION +# Use 0x0456 for Analog Devices, Inc.; 0B6A for Maxim +USB_VID=0x0456 +# USB_VID=0x0B6A +USB_PID=0x003D +USB_MANUFACTURER="Analog Devices, Inc." +USB_PRODUCT="MAX32690 EvKit" +USB_HIGHSPEED=1 + +# NOTE: MAX32 devices do not support IN/OUT pairs on the same EP +USB_NUM_ENDPOINT_PAIRS=12 +### + +# define UID len for memory safety (buffer gets passed as a raw ptr) +COMMON_HAL_MCU_PROCESSOR_UID_LENGTH=30 + +# NOTE: Not implementing external flash for now +# CFLAGS+=-DEXT_FLASH_MX25 diff --git a/ports/analog/boards/max32690evkit/pins.c b/ports/analog/boards/max32690evkit/pins.c new file mode 100644 index 000000000000..3270e4d62b2a --- /dev/null +++ b/ports/analog/boards/max32690evkit/pins.c @@ -0,0 +1,131 @@ +// This file is part of the CircuitPython project: https://circuitpython.org +// +// SPDX-FileCopyrightText: Copyright (c) 2017 Scott Shawcroft for Adafruit Industries +// SPDX-FileCopyrightText: Copyright (c) 2024 Brandon Hurst, Analog Devices, Inc. +// +// SPDX-License-Identifier: MIT + +#include "shared-bindings/board/__init__.h" + +static const mp_rom_map_elem_t board_module_globals_table[] = { + CIRCUITPYTHON_BOARD_DICT_STANDARD_ITEMS + // P0 + { MP_ROM_QSTR(MP_QSTR_P0_0), MP_ROM_PTR(&pin_P0_00) }, + { MP_ROM_QSTR(MP_QSTR_P0_1), MP_ROM_PTR(&pin_P0_01) }, + { MP_ROM_QSTR(MP_QSTR_P0_2), MP_ROM_PTR(&pin_P0_02) }, + { MP_ROM_QSTR(MP_QSTR_P0_3), MP_ROM_PTR(&pin_P0_03) }, + { MP_ROM_QSTR(MP_QSTR_P0_4), MP_ROM_PTR(&pin_P0_04) }, + { MP_ROM_QSTR(MP_QSTR_P0_5), MP_ROM_PTR(&pin_P0_05) }, + { MP_ROM_QSTR(MP_QSTR_P0_6), MP_ROM_PTR(&pin_P0_06) }, + { MP_ROM_QSTR(MP_QSTR_P0_7), MP_ROM_PTR(&pin_P0_07) }, + { MP_ROM_QSTR(MP_QSTR_P0_8), MP_ROM_PTR(&pin_P0_08) }, + { MP_ROM_QSTR(MP_QSTR_P0_9), MP_ROM_PTR(&pin_P0_09) }, + { MP_ROM_QSTR(MP_QSTR_P0_10), MP_ROM_PTR(&pin_P0_10) }, + { MP_ROM_QSTR(MP_QSTR_P0_11), MP_ROM_PTR(&pin_P0_11) }, + { MP_ROM_QSTR(MP_QSTR_P0_12), MP_ROM_PTR(&pin_P0_12) }, + { MP_ROM_QSTR(MP_QSTR_P0_13), MP_ROM_PTR(&pin_P0_13) }, + { MP_ROM_QSTR(MP_QSTR_P0_14), MP_ROM_PTR(&pin_P0_14) }, + { MP_ROM_QSTR(MP_QSTR_P0_15), MP_ROM_PTR(&pin_P0_15) }, + { MP_ROM_QSTR(MP_QSTR_P0_16), MP_ROM_PTR(&pin_P0_16) }, + { MP_ROM_QSTR(MP_QSTR_P0_17), MP_ROM_PTR(&pin_P0_17) }, + { MP_ROM_QSTR(MP_QSTR_P0_18), MP_ROM_PTR(&pin_P0_18) }, + { MP_ROM_QSTR(MP_QSTR_P0_19), MP_ROM_PTR(&pin_P0_19) }, + { MP_ROM_QSTR(MP_QSTR_P0_20), MP_ROM_PTR(&pin_P0_20) }, + { MP_ROM_QSTR(MP_QSTR_P0_21), MP_ROM_PTR(&pin_P0_21) }, + { MP_ROM_QSTR(MP_QSTR_P0_22), MP_ROM_PTR(&pin_P0_22) }, + { MP_ROM_QSTR(MP_QSTR_P0_23), MP_ROM_PTR(&pin_P0_23) }, + { MP_ROM_QSTR(MP_QSTR_P0_24), MP_ROM_PTR(&pin_P0_24) }, + { MP_ROM_QSTR(MP_QSTR_P0_25), MP_ROM_PTR(&pin_P0_25) }, + { MP_ROM_QSTR(MP_QSTR_P0_26), MP_ROM_PTR(&pin_P0_26) }, + { MP_ROM_QSTR(MP_QSTR_P0_27), MP_ROM_PTR(&pin_P0_27) }, + { MP_ROM_QSTR(MP_QSTR_P0_28), MP_ROM_PTR(&pin_P0_28) }, + { MP_ROM_QSTR(MP_QSTR_P0_29), MP_ROM_PTR(&pin_P0_29) }, + { MP_ROM_QSTR(MP_QSTR_P0_30), MP_ROM_PTR(&pin_P0_30) }, + { MP_ROM_QSTR(MP_QSTR_P0_31), MP_ROM_PTR(&pin_P0_31) }, + // P1 + { MP_ROM_QSTR(MP_QSTR_P1_0), MP_ROM_PTR(&pin_P1_00) }, + { MP_ROM_QSTR(MP_QSTR_P1_1), MP_ROM_PTR(&pin_P1_01) }, + { MP_ROM_QSTR(MP_QSTR_P1_2), MP_ROM_PTR(&pin_P1_02) }, + { MP_ROM_QSTR(MP_QSTR_P1_3), MP_ROM_PTR(&pin_P1_03) }, + { MP_ROM_QSTR(MP_QSTR_P1_4), MP_ROM_PTR(&pin_P1_04) }, + { MP_ROM_QSTR(MP_QSTR_P1_5), MP_ROM_PTR(&pin_P1_05) }, + { MP_ROM_QSTR(MP_QSTR_P1_6), MP_ROM_PTR(&pin_P1_06) }, + { MP_ROM_QSTR(MP_QSTR_P1_7), MP_ROM_PTR(&pin_P1_07) }, + { MP_ROM_QSTR(MP_QSTR_P1_8), MP_ROM_PTR(&pin_P1_08) }, + { MP_ROM_QSTR(MP_QSTR_P1_9), MP_ROM_PTR(&pin_P1_09) }, + { MP_ROM_QSTR(MP_QSTR_P1_10), MP_ROM_PTR(&pin_P1_10) }, + { MP_ROM_QSTR(MP_QSTR_P1_11), MP_ROM_PTR(&pin_P1_11) }, + { MP_ROM_QSTR(MP_QSTR_P1_12), MP_ROM_PTR(&pin_P1_12) }, + { MP_ROM_QSTR(MP_QSTR_P1_13), MP_ROM_PTR(&pin_P1_13) }, + { MP_ROM_QSTR(MP_QSTR_P1_14), MP_ROM_PTR(&pin_P1_14) }, + { MP_ROM_QSTR(MP_QSTR_P1_15), MP_ROM_PTR(&pin_P1_15) }, + { MP_ROM_QSTR(MP_QSTR_P1_16), MP_ROM_PTR(&pin_P1_16) }, + { MP_ROM_QSTR(MP_QSTR_P1_17), MP_ROM_PTR(&pin_P1_17) }, + { MP_ROM_QSTR(MP_QSTR_P1_18), MP_ROM_PTR(&pin_P1_18) }, + { MP_ROM_QSTR(MP_QSTR_P1_19), MP_ROM_PTR(&pin_P1_19) }, + { MP_ROM_QSTR(MP_QSTR_P1_20), MP_ROM_PTR(&pin_P1_20) }, + { MP_ROM_QSTR(MP_QSTR_P1_21), MP_ROM_PTR(&pin_P1_21) }, + { MP_ROM_QSTR(MP_QSTR_P1_22), MP_ROM_PTR(&pin_P1_22) }, + { MP_ROM_QSTR(MP_QSTR_P1_23), MP_ROM_PTR(&pin_P1_23) }, + { MP_ROM_QSTR(MP_QSTR_P1_24), MP_ROM_PTR(&pin_P1_24) }, + { MP_ROM_QSTR(MP_QSTR_P1_25), MP_ROM_PTR(&pin_P1_25) }, + { MP_ROM_QSTR(MP_QSTR_P1_26), MP_ROM_PTR(&pin_P1_26) }, + { MP_ROM_QSTR(MP_QSTR_P1_27), MP_ROM_PTR(&pin_P1_27) }, + { MP_ROM_QSTR(MP_QSTR_P1_28), MP_ROM_PTR(&pin_P1_28) }, + { MP_ROM_QSTR(MP_QSTR_P1_29), MP_ROM_PTR(&pin_P1_29) }, + { MP_ROM_QSTR(MP_QSTR_P1_30), MP_ROM_PTR(&pin_P1_30) }, + { MP_ROM_QSTR(MP_QSTR_P1_31), MP_ROM_PTR(&pin_P1_31) }, + // P2 + { MP_ROM_QSTR(MP_QSTR_P2_0), MP_ROM_PTR(&pin_P2_00) }, + { MP_ROM_QSTR(MP_QSTR_P2_1), MP_ROM_PTR(&pin_P2_01) }, + { MP_ROM_QSTR(MP_QSTR_P2_2), MP_ROM_PTR(&pin_P2_02) }, + { MP_ROM_QSTR(MP_QSTR_P2_3), MP_ROM_PTR(&pin_P2_03) }, + { MP_ROM_QSTR(MP_QSTR_P2_4), MP_ROM_PTR(&pin_P2_04) }, + { MP_ROM_QSTR(MP_QSTR_P2_5), MP_ROM_PTR(&pin_P2_05) }, + { MP_ROM_QSTR(MP_QSTR_P2_6), MP_ROM_PTR(&pin_P2_06) }, + { MP_ROM_QSTR(MP_QSTR_P2_7), MP_ROM_PTR(&pin_P2_07) }, + { MP_ROM_QSTR(MP_QSTR_P2_8), MP_ROM_PTR(&pin_P2_08) }, + { MP_ROM_QSTR(MP_QSTR_P2_9), MP_ROM_PTR(&pin_P2_09) }, + { MP_ROM_QSTR(MP_QSTR_P2_10), MP_ROM_PTR(&pin_P2_10) }, + { MP_ROM_QSTR(MP_QSTR_P2_11), MP_ROM_PTR(&pin_P2_11) }, + { MP_ROM_QSTR(MP_QSTR_P2_12), MP_ROM_PTR(&pin_P2_12) }, + { MP_ROM_QSTR(MP_QSTR_P2_13), MP_ROM_PTR(&pin_P2_13) }, + { MP_ROM_QSTR(MP_QSTR_P2_14), MP_ROM_PTR(&pin_P2_14) }, + { MP_ROM_QSTR(MP_QSTR_P2_15), MP_ROM_PTR(&pin_P2_15) }, + { MP_ROM_QSTR(MP_QSTR_P2_16), MP_ROM_PTR(&pin_P2_16) }, + { MP_ROM_QSTR(MP_QSTR_P2_17), MP_ROM_PTR(&pin_P2_17) }, + { MP_ROM_QSTR(MP_QSTR_P2_18), MP_ROM_PTR(&pin_P2_18) }, + { MP_ROM_QSTR(MP_QSTR_P2_19), MP_ROM_PTR(&pin_P2_19) }, + { MP_ROM_QSTR(MP_QSTR_P2_20), MP_ROM_PTR(&pin_P2_20) }, + { MP_ROM_QSTR(MP_QSTR_P2_21), MP_ROM_PTR(&pin_P2_21) }, + { MP_ROM_QSTR(MP_QSTR_P2_22), MP_ROM_PTR(&pin_P2_22) }, + { MP_ROM_QSTR(MP_QSTR_P2_23), MP_ROM_PTR(&pin_P2_23) }, + { MP_ROM_QSTR(MP_QSTR_P2_24), MP_ROM_PTR(&pin_P2_24) }, + { MP_ROM_QSTR(MP_QSTR_P2_25), MP_ROM_PTR(&pin_P2_25) }, + { MP_ROM_QSTR(MP_QSTR_P2_26), MP_ROM_PTR(&pin_P2_26) }, + { MP_ROM_QSTR(MP_QSTR_P2_27), MP_ROM_PTR(&pin_P2_27) }, + { MP_ROM_QSTR(MP_QSTR_P2_28), MP_ROM_PTR(&pin_P2_28) }, + { MP_ROM_QSTR(MP_QSTR_P2_29), MP_ROM_PTR(&pin_P2_29) }, + { MP_ROM_QSTR(MP_QSTR_P2_30), MP_ROM_PTR(&pin_P2_30) }, + { MP_ROM_QSTR(MP_QSTR_P2_31), MP_ROM_PTR(&pin_P2_31) }, + // P3 + { MP_ROM_QSTR(MP_QSTR_P3_0), MP_ROM_PTR(&pin_P3_00) }, + { MP_ROM_QSTR(MP_QSTR_P3_1), MP_ROM_PTR(&pin_P3_01) }, + { MP_ROM_QSTR(MP_QSTR_P3_2), MP_ROM_PTR(&pin_P3_02) }, + { MP_ROM_QSTR(MP_QSTR_P3_3), MP_ROM_PTR(&pin_P3_03) }, + { MP_ROM_QSTR(MP_QSTR_P3_4), MP_ROM_PTR(&pin_P3_04) }, + { MP_ROM_QSTR(MP_QSTR_P3_5), MP_ROM_PTR(&pin_P3_05) }, + { MP_ROM_QSTR(MP_QSTR_P3_6), MP_ROM_PTR(&pin_P3_06) }, + { MP_ROM_QSTR(MP_QSTR_P3_7), MP_ROM_PTR(&pin_P3_07) }, + { MP_ROM_QSTR(MP_QSTR_P3_8), MP_ROM_PTR(&pin_P3_08) }, + { MP_ROM_QSTR(MP_QSTR_P3_9), MP_ROM_PTR(&pin_P3_09) }, + // P4 + { MP_ROM_QSTR(MP_QSTR_P4_0), MP_ROM_PTR(&pin_P4_00) }, + { MP_ROM_QSTR(MP_QSTR_P4_1), MP_ROM_PTR(&pin_P4_01) }, + + // Board silkscreen Aliases + { MP_ROM_QSTR(MP_QSTR_LED0), MP_ROM_PTR(&pin_P0_14) }, + { MP_ROM_QSTR(MP_QSTR_LED1), MP_ROM_PTR(&pin_P2_12) }, + { MP_ROM_QSTR(MP_QSTR_PB0), MP_ROM_PTR(&pin_P4_00) }, +}; +MP_DEFINE_CONST_DICT(board_module_globals, board_module_globals_table); diff --git a/ports/analog/common-hal/board/__init__.c b/ports/analog/common-hal/board/__init__.c new file mode 100644 index 000000000000..bcae8371c18c --- /dev/null +++ b/ports/analog/common-hal/board/__init__.c @@ -0,0 +1,5 @@ +// This file is part of the CircuitPython project: https://circuitpython.org +// +// SPDX-FileCopyrightText: Copyright (c) 2018 Dan Halbert for Adafruit Industries +// +// SPDX-License-Identifier: MIT diff --git a/ports/analog/common-hal/digitalio/DigitalInOut.c b/ports/analog/common-hal/digitalio/DigitalInOut.c new file mode 100644 index 000000000000..3861900d81cd --- /dev/null +++ b/ports/analog/common-hal/digitalio/DigitalInOut.c @@ -0,0 +1,227 @@ +// This file is part of the CircuitPython project: https://circuitpython.org +// +// SPDX-FileCopyrightText: Copyright (c) 2024 Brandon Hurst, Analog Devices, Inc +// +// SPDX-License-Identifier: MIT + +#define CIRCUITPY_DIGITALIO_HAVE_INVALID_DRIVE_MODE 1 +#include "shared-bindings/digitalio/DigitalInOut.h" +#include "shared-bindings/microcontroller/Pin.h" + +#include "max32_port.h" +#include "gpio_reva.h" +#include "mxc_errors.h" + +extern mxc_gpio_regs_t *gpio_ports[NUM_GPIO_PORTS]; + +void common_hal_digitalio_digitalinout_never_reset( + digitalio_digitalinout_obj_t *self) { + common_hal_never_reset_pin(self->pin); +} + +bool common_hal_digitalio_digitalinout_deinited(digitalio_digitalinout_obj_t *self) { + return self->pin == NULL; +} + +digitalinout_result_t common_hal_digitalio_digitalinout_construct( + digitalio_digitalinout_obj_t *self, const mcu_pin_obj_t *pin) { + + common_hal_mcu_pin_claim(pin); + self->pin = pin; + + mxc_gpio_cfg_t new_gpio_cfg = { + .port = gpio_ports[self->pin->port], + .mask = (self->pin->mask), + .vssel = self->pin->level, + .func = MXC_GPIO_FUNC_IN, + .drvstr = MXC_GPIO_DRVSTR_0, + .pad = MXC_GPIO_PAD_NONE, + }; + MXC_GPIO_Config(&new_gpio_cfg); + + return DIGITALINOUT_OK; +} + +void common_hal_digitalio_digitalinout_deinit(digitalio_digitalinout_obj_t *self) { + if (common_hal_digitalio_digitalinout_deinited(self)) { + return; + } + + reset_pin_number(self->pin->port, self->pin->mask); + self->pin = NULL; +} + +digitalinout_result_t common_hal_digitalio_digitalinout_switch_to_input( + digitalio_digitalinout_obj_t *self, digitalio_pull_t pull) { + mxc_gpio_regs_t *port = gpio_ports[self->pin->port]; + uint32_t mask = self->pin->mask; + int err = E_NO_ERROR; + + if (self->pin->port == 4) { + // Set GPIO(s) to input mode + MXC_MCR->gpio4_ctrl &= ~GPIO4_OUTEN_MASK(mask); + MXC_MCR->outen &= ~GPIO4_AFEN_MASK(mask); + } else { + err = MXC_GPIO_RevA_SetAF((mxc_gpio_reva_regs_t *)port, MXC_GPIO_FUNC_IN, mask); + } + if (err != E_NO_ERROR) { + return DIGITALINOUT_PIN_BUSY; + } + return common_hal_digitalio_digitalinout_set_pull(self, pull); +} + +digitalinout_result_t common_hal_digitalio_digitalinout_switch_to_output( + digitalio_digitalinout_obj_t *self, bool value, + digitalio_drive_mode_t drive_mode) { + mxc_gpio_regs_t *port = gpio_ports[self->pin->port]; + uint32_t mask = self->pin->mask; + + if (self->pin->port == 4) { + // Set GPIO(s) to output mode + MXC_MCR->gpio4_ctrl |= GPIO4_OUTEN_MASK(mask); + MXC_MCR->outen &= ~GPIO4_AFEN_MASK(mask); + } else { + MXC_GPIO_RevA_SetAF((mxc_gpio_reva_regs_t *)port, MXC_GPIO_FUNC_OUT, mask); + } + common_hal_digitalio_digitalinout_set_value(self, value); + + // todo (low): MSDK Hardware does not support open-drain configuration except + // todo (low): when directly managed by a peripheral such as I2C. + // todo (low): find a way to signal this to any upstream code + if (drive_mode != DRIVE_MODE_PUSH_PULL) { + return DIGITALINOUT_INVALID_DRIVE_MODE; + } + return DIGITALINOUT_OK; +} + +digitalio_direction_t common_hal_digitalio_digitalinout_get_direction( + digitalio_digitalinout_obj_t *self) { + + mxc_gpio_regs_t *port = gpio_ports[self->pin->port]; + uint32_t mask = self->pin->mask; + + if (self->pin->port < 4) { + // Check that I/O mode is enabled and we don't have in AND out on at the same time + MP_STATIC_ASSERT(!((port->en0 & mask) && (port->inen & mask) && (port->outen & mask))); + + if ((port->en0 & mask) && (port->outen & mask)) { + return DIRECTION_OUTPUT; + } else if ((port->en0 & mask) && (port->inen & mask)) { + return DIRECTION_INPUT; + // do not try to drive a pin which has an odd configuration here + } else { + return DIRECTION_INPUT; + } + } else { + if (MXC_MCR->gpio4_ctrl & GPIO4_OUTEN_MASK(mask)) { + return DIRECTION_OUTPUT; + } else { + return DIRECTION_INPUT; + } + } +} + +void common_hal_digitalio_digitalinout_set_value( + digitalio_digitalinout_obj_t *self, bool value) { + digitalio_direction_t dir = + common_hal_digitalio_digitalinout_get_direction(self); + + mxc_gpio_regs_t *port = gpio_ports[self->pin->port]; + uint32_t mask = self->pin->mask; + + if (dir == DIRECTION_OUTPUT) { + if (value == true) { + MXC_GPIO_OutSet(port, mask); + } else { + MXC_GPIO_OutClr(port, mask); + } + } +} + +bool common_hal_digitalio_digitalinout_get_value(digitalio_digitalinout_obj_t *self) { + digitalio_direction_t dir = + common_hal_digitalio_digitalinout_get_direction(self); + + mxc_gpio_regs_t *port = gpio_ports[self->pin->port]; + uint32_t mask = self->pin->mask; + + if (dir == DIRECTION_INPUT) { + if (self->pin->port == 4) { + return (bool)(MXC_MCR->gpio4_ctrl & GPIO4_DATAIN_MASK(mask)); + } + return MXC_GPIO_InGet(port, mask) && mask; + } else { + return MXC_GPIO_OutGet(port, mask) && mask; + } +} + +/** FIXME: Implement open-drain by switching to input WITHOUT re-labeling the pin */ +digitalinout_result_t common_hal_digitalio_digitalinout_set_drive_mode( + digitalio_digitalinout_obj_t *self, digitalio_drive_mode_t drive_mode) { + + if (drive_mode == DRIVE_MODE_OPEN_DRAIN) { + common_hal_digitalio_digitalinout_switch_to_input(self, PULL_NONE); + } + // On MAX32, drive mode is not configurable + // and should always be push-pull unless managed by a peripheral like I2C + return DIGITALINOUT_OK; +} + +digitalio_drive_mode_t common_hal_digitalio_digitalinout_get_drive_mode( + digitalio_digitalinout_obj_t *self) { + return DRIVE_MODE_PUSH_PULL; +} + +digitalinout_result_t common_hal_digitalio_digitalinout_set_pull( + digitalio_digitalinout_obj_t *self, digitalio_pull_t pull) { + + mxc_gpio_regs_t *port = gpio_ports[self->pin->port]; + uint32_t mask = self->pin->mask; + + // padctrl registers only work in input mode + if (self->pin->port == 4) { + MXC_MCR->gpio4_ctrl &= ~(GPIO4_PULLDIS_MASK(mask)); + return DIGITALINOUT_OK; + } else { + if ((mask & port->en0) & (mask & ~(port->outen))) { + // PULL_NONE, PULL_UP, or PULL_DOWN + switch (pull) { + case PULL_NONE: + port->padctrl0 &= ~(mask); + port->padctrl1 &= ~(mask); + break; + case PULL_UP: + port->padctrl0 |= mask; + port->padctrl1 &= ~(mask); + break; + case PULL_DOWN: + port->padctrl0 &= ~(mask); + port->padctrl1 |= mask; + break; + default: + break; + } + return DIGITALINOUT_OK; + } else { + return DIGITALINOUT_PIN_BUSY; + } + } +} + +/** FIXME: Account for GPIO4 handling here */ +digitalio_pull_t common_hal_digitalio_digitalinout_get_pull( + digitalio_digitalinout_obj_t *self) { + + bool pin_padctrl0 = (gpio_ports[self->pin->port]->padctrl0) & (self->pin->mask); + bool pin_padctrl1 = (gpio_ports[self->pin->port]->padctrl1) & (self->pin->mask); + + if ((pin_padctrl0) && !(pin_padctrl1)) { + return PULL_UP; + } else if (!(pin_padctrl0) && pin_padctrl1) { + return PULL_DOWN; + } else if (!(pin_padctrl0) && !(pin_padctrl1)) { + return PULL_NONE; + } else { + return PULL_NONE; + } +} diff --git a/ports/analog/common-hal/digitalio/DigitalInOut.h b/ports/analog/common-hal/digitalio/DigitalInOut.h new file mode 100644 index 000000000000..f58b23832b19 --- /dev/null +++ b/ports/analog/common-hal/digitalio/DigitalInOut.h @@ -0,0 +1,15 @@ +// This file is part of the CircuitPython project: https://circuitpython.org +// +// SPDX-FileCopyrightText: Copyright (c) 2017 Scott Shawcroft for Adafruit Industries +// SPDX-FileCopyrightText: Copyright (c) 2019 Lucian Copeland for Adafruit Industries +// +// SPDX-License-Identifier: MIT + +#pragma once + +#include "common-hal/microcontroller/Pin.h" + +typedef struct { + mp_obj_base_t base; + const mcu_pin_obj_t *pin; +} digitalio_digitalinout_obj_t; diff --git a/ports/analog/common-hal/digitalio/__init__.c b/ports/analog/common-hal/digitalio/__init__.c new file mode 100644 index 000000000000..fa222ed01f03 --- /dev/null +++ b/ports/analog/common-hal/digitalio/__init__.c @@ -0,0 +1,7 @@ +// This file is part of the CircuitPython project: https://circuitpython.org +// +// SPDX-FileCopyrightText: Copyright (c) 2024 Adafruit Industries LLC +// +// SPDX-License-Identifier: MIT + +// No digitalio module functions. diff --git a/ports/analog/common-hal/microcontroller/Pin.c b/ports/analog/common-hal/microcontroller/Pin.c new file mode 100644 index 000000000000..4545aa039c2f --- /dev/null +++ b/ports/analog/common-hal/microcontroller/Pin.c @@ -0,0 +1,113 @@ +// This file is part of the CircuitPython project: https://circuitpython.org +// +// SPDX-FileCopyrightText: Copyright (c) 2024 Brandon Hurst, Analog Devices, Inc +// +// SPDX-License-Identifier: MIT + +#include + +#include "shared-bindings/microcontroller/Pin.h" +#include "mpconfigboard.h" +#include "pins.h" + +#include "max32_port.h" + +#include "common-hal/microcontroller/Pin.h" + +static uint32_t claimed_pins[NUM_GPIO_PORTS]; + +// defined in board.c +extern mxc_gpio_regs_t *gpio_ports[NUM_GPIO_PORTS]; + +static uint32_t never_reset_pins[NUM_GPIO_PORTS]; + +#define INVALID_PIN 0xFF // id for invalid pin + +void reset_all_pins(void) { + // reset all pins except for never_reset_pins + for (int i = 0; i < NUM_GPIO_PORTS; i++) { + for (int j = 0; j < 32; j++) { + if (!(never_reset_pins[i] & (1 << j))) { + reset_pin_number(i, j); + } + } + // set claimed pins to never_reset pins + claimed_pins[i] = never_reset_pins[i]; + } +} + +void reset_pin_number(uint8_t pin_port, uint8_t pin_pad) { + if (pin_port == INVALID_PIN || pin_port > NUM_GPIO_PORTS) { + return; + } + + uint32_t mask = 1 << (pin_pad); + + /** START: RESET LOGIC for GPIOs */ + // Switch to I/O mode first + gpio_ports[pin_port]->en0_set = mask; + + // set GPIO configuration enable bits to I/O + gpio_ports[pin_port]->en0_clr = mask; + gpio_ports[pin_port]->en1_clr = mask; + gpio_ports[pin_port]->en2_clr = mask; + + // enable input mode GPIOn_INEN.pin = 1 + gpio_ports[pin_port]->inen |= mask; + + // High Impedance mode enable (GPIOn_PADCTRL1 = 0, _PADCTRL0 = 0), pu/pd disable + gpio_ports[pin_port]->padctrl0 &= ~mask; + gpio_ports[pin_port]->padctrl1 &= ~mask; + + // Output mode disable GPIOn_OUTEN = 0 + gpio_ports[pin_port]->outen |= mask; + + // Interrupt disable GPIOn_INTEN = 0 + gpio_ports[pin_port]->inten &= ~mask; + /** END: RESET LOGIC for GPIOs */ +} + +uint8_t common_hal_mcu_pin_number(const mcu_pin_obj_t *pin) { + if (pin == NULL) { + return INVALID_PIN; + } + + // most max32 gpio ports have 32 pins + // todo (low prior.): encode # of pins for each port, since some GPIO ports differ + return pin->port * 32 + pin->mask; +} + +bool common_hal_mcu_pin_is_free(const mcu_pin_obj_t *pin) { + if (pin == NULL) { + return true; + } + return !(claimed_pins[pin->port] & (pin->mask)); +} + +void common_hal_never_reset_pin(const mcu_pin_obj_t *pin) { + if ((pin != NULL) && (pin->mask != INVALID_PIN)) { + never_reset_pins[pin->port] |= (1 << pin->mask); + + // any never reset pin must also be claimed + claimed_pins[pin->port] |= (1 << pin->mask); + } +} + +void common_hal_reset_pin(const mcu_pin_obj_t *pin) { + if (pin == NULL) { + return; + } + + reset_pin_number(pin->port, pin->mask); +} + +void common_hal_mcu_pin_claim(const mcu_pin_obj_t *pin) { + if (pin == NULL) { + return; + } + claimed_pins[pin->port] |= (1 << pin->mask); +} + +void common_hal_mcu_pin_reset_number(uint8_t pin_no) { + reset_pin_number(pin_no / 32, pin_no & 32); +} diff --git a/ports/analog/common-hal/microcontroller/Pin.h b/ports/analog/common-hal/microcontroller/Pin.h new file mode 100644 index 000000000000..169586e7e903 --- /dev/null +++ b/ports/analog/common-hal/microcontroller/Pin.h @@ -0,0 +1,16 @@ +// This file is part of the CircuitPython project: https://circuitpython.org +// +// SPDX-FileCopyrightText: Copyright (c) 2024 Brandon Hurst, Analog Devices, Inc +// +// SPDX-License-Identifier: MIT + +#pragma once + +#include "py/mphal.h" + +#include "peripherals/pins.h" + +void reset_all_pins(void); +// reset_pin_number takes the pin number instead of the pointer so that objects don't +// need to store a full pointer. +void reset_pin_number(uint8_t pin_port, uint8_t pin_pad); diff --git a/ports/analog/common-hal/microcontroller/Processor.c b/ports/analog/common-hal/microcontroller/Processor.c new file mode 100644 index 000000000000..87d8047ff2cb --- /dev/null +++ b/ports/analog/common-hal/microcontroller/Processor.c @@ -0,0 +1,46 @@ +// This file is part of the CircuitPython project: https://circuitpython.org +// +// SPDX-FileCopyrightText: Copyright (c) 2024 Brandon Hurst, Analog Devices, Inc +// +// SPDX-License-Identifier: MIT + +#include +#include "py/runtime.h" + +#if CIRCUITPY_ALARM +#include "common-hal/alarm/__init__.h" +#endif + +#include "common-hal/microcontroller/Processor.h" +#include "shared-bindings/microcontroller/ResetReason.h" + +#include "max32_port.h" + +// No means of getting core temperature for currently supported devices +float common_hal_mcu_processor_get_temperature(void) { + return NAN; +} + +// MAX32690 can measure VCORE +// TODO: (low prior.) Implement ADC API under "peripherals" and use API to measure VCORE +float common_hal_mcu_processor_get_voltage(void) { + return NAN; +} + +uint32_t common_hal_mcu_processor_get_frequency(void) { + return SystemCoreClock; +} + +// NOTE: COMMON_HAL_MCU_PROCESSOR_UID_LENGTH is defined in mpconfigboard.h +// Use this per device to make sure raw_id is an appropriate minimum number of bytes +void common_hal_mcu_processor_get_uid(uint8_t raw_id[]) { + MXC_SYS_GetUSN(raw_id, NULL); // NULL checksum will not be verified by AES + return; +} + +mcu_reset_reason_t common_hal_mcu_processor_get_reset_reason(void) { + #if CIRCUITPY_ALARM + // TODO: (low prior.) add reset reason in alarm / deepsleep cases (should require alarm peripheral API in "peripherals") + #endif + return RESET_REASON_UNKNOWN; +} diff --git a/ports/analog/common-hal/microcontroller/Processor.h b/ports/analog/common-hal/microcontroller/Processor.h new file mode 100644 index 000000000000..aab7727550a9 --- /dev/null +++ b/ports/analog/common-hal/microcontroller/Processor.h @@ -0,0 +1,16 @@ +// This file is part of the CircuitPython project: https://circuitpython.org +// +// SPDX-FileCopyrightText: Copyright (c) 2017 Dan Halbert for Adafruit Industries +// +// SPDX-License-Identifier: MIT + +#pragma once + +#define COMMON_HAL_MCU_PROCESSOR_UID_LENGTH 12 + +#include "py/obj.h" + +typedef struct { + mp_obj_base_t base; + // Stores no state currently. +} mcu_processor_obj_t; diff --git a/ports/analog/common-hal/microcontroller/__init__.c b/ports/analog/common-hal/microcontroller/__init__.c new file mode 100644 index 000000000000..207ddbe52f37 --- /dev/null +++ b/ports/analog/common-hal/microcontroller/__init__.c @@ -0,0 +1,408 @@ +// This file is part of the CircuitPython project: https://circuitpython.org +// +// SP3_X-FileCopyrightText: Copyright (c) 2016 Scott Shawcroft for Adafruit Industries +// SP3_X-FileCopyrightText: Copyright (c) 2019 Lucian Copeland for Adafruit Industries +// SP3_X-FileCopyrightText: Copyright (c) 2024 Brandon Hurst, Analog Devices, Inc +// +// SP3_X-License-Identifier: MIT + +#include "py/mphal.h" +#include "py/obj.h" +#include "py/runtime.h" + +#include "common-hal/microcontroller/Pin.h" +#include "common-hal/microcontroller/Processor.h" + +// #include "shared-bindings/nvm/ByteArray.h" +#include "shared-bindings/microcontroller/__init__.h" +#include "shared-bindings/microcontroller/Pin.h" +#include "shared-bindings/microcontroller/Processor.h" +#include "supervisor/port.h" +#include "supervisor/filesystem.h" +#include "supervisor/shared/safe_mode.h" + + +#include "max32690.h" +#include "mxc_delay.h" + +/** NOTE: It is not advised to directly include the below! + * These are includes taken care of by the core cmsis file. + * e.g. "max32690.h". Since CMSIS is compiled as lib, these are + * included there as for example. +*/ +// #include // For enable/disable interrupts +// #include // For NVIC_SystemReset +// #include // For __DMB Data Memory Barrier (flush DBUS activity) + +void common_hal_mcu_delay_us(uint32_t delay) { + + MXC_Delay(MXC_DELAY_USEC(delay)); +} + +volatile uint32_t nesting_count = 0; + +void common_hal_mcu_disable_interrupts(void) { + __disable_irq(); + __DMB(); + nesting_count++; +} + +void common_hal_mcu_enable_interrupts(void) { + if (nesting_count == 0) { + // This is very very bad because it means there was mismatched disable/enables. + reset_into_safe_mode(SAFE_MODE_INTERRUPT_ERROR); + } + nesting_count--; + if (nesting_count > 0) { + return; + } + __DMB(); // flush internal DBUS before proceeding + __enable_irq(); +} + +static bool next_reset_to_bootloader = false; + +void common_hal_mcu_on_next_reset(mcu_runmode_t runmode) { + if (runmode == RUNMODE_SAFE_MODE) { + safe_mode_on_next_reset(SAFE_MODE_PROGRAMMATIC); + } + if (runmode == RUNMODE_BOOTLOADER) { + next_reset_to_bootloader = true; + } +} + +void common_hal_mcu_reset(void) { + if (next_reset_to_bootloader) { + reset_to_bootloader(); + } else { + NVIC_SystemReset(); + } +} + +// The singleton microcontroller.Processor object, bound to microcontroller.cpu +// It currently only has properties, and no state. +const mcu_processor_obj_t common_hal_mcu_processor_obj = { + .base = { + .type = &mcu_processor_type, + }, +}; + +// This maps MCU pin names to pin objects. +static const mp_rom_map_elem_t mcu_pin_global_dict_table[] = { + #if defined(PIN_P0_01) && !defined(IGNORE_PIN_P0_01) + { MP_ROM_QSTR(MP_QSTR_P0_01), MP_ROM_PTR(&pin_P0_01) }, + #endif + #if defined(PIN_P0_02) && !defined(IGNORE_PIN_P0_02) + { MP_ROM_QSTR(MP_QSTR_P0_02), MP_ROM_PTR(&pin_P0_02) }, + #endif + #if defined(PIN_P0_03) && !defined(IGNORE_PIN_P0_03) + { MP_ROM_QSTR(MP_QSTR_P0_03), MP_ROM_PTR(&pin_P0_03) }, + #endif + #if defined(PIN_P0_04) && !defined(IGNORE_PIN_P0_04) + { MP_ROM_QSTR(MP_QSTR_P0_04), MP_ROM_PTR(&pin_P0_04) }, + #endif + #if defined(PIN_P0_05) && !defined(IGNORE_PIN_P0_05) + { MP_ROM_QSTR(MP_QSTR_P0_05), MP_ROM_PTR(&pin_P0_05) }, + #endif + #if defined(PIN_P0_06) && !defined(IGNORE_PIN_P0_06) + { MP_ROM_QSTR(MP_QSTR_P0_06), MP_ROM_PTR(&pin_P0_06) }, + #endif + #if defined(PIN_P0_07) && !defined(IGNORE_PIN_P0_07) + { MP_ROM_QSTR(MP_QSTR_P0_07), MP_ROM_PTR(&pin_P0_07) }, + #endif + #if defined(PIN_P0_08) && !defined(IGNORE_PIN_P0_08) + { MP_ROM_QSTR(MP_QSTR_P0_08), MP_ROM_PTR(&pin_P0_08) }, + #endif + #if defined(PIN_P0_09) && !defined(IGNORE_PIN_P0_09) + { MP_ROM_QSTR(MP_QSTR_P0_09), MP_ROM_PTR(&pin_P0_09) }, + #endif + #if defined(PIN_P0_10) && !defined(IGNORE_PIN_P0_10) + { MP_ROM_QSTR(MP_QSTR_P0_10), MP_ROM_PTR(&pin_P0_10) }, + #endif + #if defined(PIN_P0_11) && !defined(IGNORE_PIN_P0_11) + { MP_ROM_QSTR(MP_QSTR_P0_11), MP_ROM_PTR(&pin_P0_11) }, + #endif + #if defined(PIN_P0_12) && !defined(IGNORE_PIN_P0_12) + { MP_ROM_QSTR(MP_QSTR_P0_12), MP_ROM_PTR(&pin_P0_12) }, + #endif + #if defined(PIN_P0_13) && !defined(IGNORE_PIN_P0_13) + { MP_ROM_QSTR(MP_QSTR_P0_13), MP_ROM_PTR(&pin_P0_13) }, + #endif + #if defined(PIN_P0_14) && !defined(IGNORE_PIN_P0_14) + { MP_ROM_QSTR(MP_QSTR_P0_14), MP_ROM_PTR(&pin_P0_14) }, + #endif + #if defined(PIN_P0_15) && !defined(IGNORE_PIN_P0_15) + { MP_ROM_QSTR(MP_QSTR_P0_15), MP_ROM_PTR(&pin_P0_15) }, + #endif + #if defined(PIN_P0_16) && !defined(IGNORE_PIN_P0_16) + { MP_ROM_QSTR(MP_QSTR_P0_16), MP_ROM_PTR(&pin_P0_16) }, + #endif + #if defined(PIN_P0_17) && !defined(IGNORE_PIN_P0_17) + { MP_ROM_QSTR(MP_QSTR_P0_17), MP_ROM_PTR(&pin_P0_17) }, + #endif + #if defined(PIN_P0_18) && !defined(IGNORE_PIN_P0_18) + { MP_ROM_QSTR(MP_QSTR_P0_18), MP_ROM_PTR(&pin_P0_18) }, + #endif + #if defined(PIN_P0_19) && !defined(IGNORE_PIN_P0_19) + { MP_ROM_QSTR(MP_QSTR_P0_19), MP_ROM_PTR(&pin_P0_19) }, + #endif + #if defined(PIN_P0_20) && !defined(IGNORE_PIN_P0_20) + { MP_ROM_QSTR(MP_QSTR_P0_20), MP_ROM_PTR(&pin_P0_20) }, + #endif + #if defined(PIN_P0_21) && !defined(IGNORE_PIN_P0_21) + { MP_ROM_QSTR(MP_QSTR_P0_21), MP_ROM_PTR(&pin_P0_21) }, + #endif + #if defined(PIN_P0_22) && !defined(IGNORE_PIN_P0_22) + { MP_ROM_QSTR(MP_QSTR_P0_22), MP_ROM_PTR(&pin_P0_22) }, + #endif + #if defined(PIN_P0_23) && !defined(IGNORE_PIN_P0_23) + { MP_ROM_QSTR(MP_QSTR_P0_23), MP_ROM_PTR(&pin_P0_23) }, + #endif + #if defined(PIN_P0_24) && !defined(IGNORE_PIN_P0_24) + { MP_ROM_QSTR(MP_QSTR_P0_24), MP_ROM_PTR(&pin_P0_24) }, + #endif + #if defined(PIN_P0_25) && !defined(IGNORE_PIN_P0_25) + { MP_ROM_QSTR(MP_QSTR_P0_25), MP_ROM_PTR(&pin_P0_25) }, + #endif + #if defined(PIN_P0_27) && !defined(IGNORE_PIN_P0_27) + { MP_ROM_QSTR(MP_QSTR_P0_27), MP_ROM_PTR(&pin_P0_27) }, + #endif + #if defined(PIN_P0_28) && !defined(IGNORE_PIN_P0_28) + { MP_ROM_QSTR(MP_QSTR_P0_28), MP_ROM_PTR(&pin_P0_28) }, + #endif + #if defined(PIN_P0_30) && !defined(IGNORE_PIN_P0_30) + { MP_ROM_QSTR(MP_QSTR_P0_30), MP_ROM_PTR(&pin_P0_30) }, + #endif + #if defined(PIN_P0_31) && !defined(IGNORE_PIN_P0_31) + { MP_ROM_QSTR(MP_QSTR_P0_31), MP_ROM_PTR(&pin_P0_31) }, + #endif + + #if defined(PIN_P1_01) && !defined(IGNORE_PIN_P1_01) + { MP_ROM_QSTR(MP_QSTR_P1_01), MP_ROM_PTR(&pin_P1_01) }, + #endif + #if defined(PIN_P1_02) && !defined(IGNORE_PIN_P1_02) + { MP_ROM_QSTR(MP_QSTR_P1_02), MP_ROM_PTR(&pin_P1_02) }, + #endif + #if defined(PIN_P1_03) && !defined(IGNORE_PIN_P1_03) + { MP_ROM_QSTR(MP_QSTR_P1_03), MP_ROM_PTR(&pin_P1_03) }, + #endif + #if defined(PIN_P1_04) && !defined(IGNORE_PIN_P1_04) + { MP_ROM_QSTR(MP_QSTR_P1_04), MP_ROM_PTR(&pin_P1_04) }, + #endif + #if defined(PIN_P1_05) && !defined(IGNORE_PIN_P1_05) + { MP_ROM_QSTR(MP_QSTR_P1_05), MP_ROM_PTR(&pin_P1_05) }, + #endif + #if defined(PIN_P1_06) && !defined(IGNORE_PIN_P1_06) + { MP_ROM_QSTR(MP_QSTR_P1_06), MP_ROM_PTR(&pin_P1_06) }, + #endif + #if defined(PIN_P1_07) && !defined(IGNORE_PIN_P1_07) + { MP_ROM_QSTR(MP_QSTR_P1_07), MP_ROM_PTR(&pin_P1_07) }, + #endif + #if defined(PIN_P1_08) && !defined(IGNORE_PIN_P1_08) + { MP_ROM_QSTR(MP_QSTR_P1_08), MP_ROM_PTR(&pin_P1_08) }, + #endif + #if defined(PIN_P1_09) && !defined(IGNORE_PIN_P1_09) + { MP_ROM_QSTR(MP_QSTR_P1_09), MP_ROM_PTR(&pin_P1_09) }, + #endif + #if defined(PIN_P1_10) && !defined(IGNORE_PIN_P1_10) + { MP_ROM_QSTR(MP_QSTR_P1_10), MP_ROM_PTR(&pin_P1_10) }, + #endif + #if defined(PIN_P1_11) && !defined(IGNORE_PIN_P1_11) + { MP_ROM_QSTR(MP_QSTR_P1_11), MP_ROM_PTR(&pin_P1_11) }, + #endif + #if defined(PIN_P1_12) && !defined(IGNORE_PIN_P1_12) + { MP_ROM_QSTR(MP_QSTR_P1_12), MP_ROM_PTR(&pin_P1_12) }, + #endif + #if defined(PIN_P1_13) && !defined(IGNORE_PIN_P1_13) + { MP_ROM_QSTR(MP_QSTR_P1_13), MP_ROM_PTR(&pin_P1_13) }, + #endif + #if defined(PIN_P1_14) && !defined(IGNORE_PIN_P1_14) + { MP_ROM_QSTR(MP_QSTR_P1_14), MP_ROM_PTR(&pin_P1_14) }, + #endif + #if defined(PIN_P1_15) && !defined(IGNORE_PIN_P1_15) + { MP_ROM_QSTR(MP_QSTR_P1_15), MP_ROM_PTR(&pin_P1_15) }, + #endif + #if defined(PIN_P1_16) && !defined(IGNORE_PIN_P1_16) + { MP_ROM_QSTR(MP_QSTR_P1_16), MP_ROM_PTR(&pin_P1_16) }, + #endif + #if defined(PIN_P1_17) && !defined(IGNORE_PIN_P1_17) + { MP_ROM_QSTR(MP_QSTR_P1_17), MP_ROM_PTR(&pin_P1_17) }, + #endif + #if defined(PIN_P1_18) && !defined(IGNORE_PIN_P1_18) + { MP_ROM_QSTR(MP_QSTR_P1_18), MP_ROM_PTR(&pin_P1_18) }, + #endif + #if defined(PIN_P1_19) && !defined(IGNORE_PIN_P1_19) + { MP_ROM_QSTR(MP_QSTR_P1_19), MP_ROM_PTR(&pin_P1_19) }, + #endif + #if defined(PIN_P1_20) && !defined(IGNORE_PIN_P1_20) + { MP_ROM_QSTR(MP_QSTR_P1_20), MP_ROM_PTR(&pin_P1_20) }, + #endif + #if defined(PIN_P1_21) && !defined(IGNORE_PIN_P1_21) + { MP_ROM_QSTR(MP_QSTR_P1_21), MP_ROM_PTR(&pin_P1_21) }, + #endif + #if defined(PIN_P1_22) && !defined(IGNORE_PIN_P1_22) + { MP_ROM_QSTR(MP_QSTR_P1_22), MP_ROM_PTR(&pin_P1_22) }, + #endif + #if defined(PIN_P1_23) && !defined(IGNORE_PIN_P1_23) + { MP_ROM_QSTR(MP_QSTR_P1_23), MP_ROM_PTR(&pin_P1_23) }, + #endif + #if defined(PIN_P1_24) && !defined(IGNORE_PIN_P1_24) + { MP_ROM_QSTR(MP_QSTR_P1_24), MP_ROM_PTR(&pin_P1_24) }, + #endif + #if defined(PIN_P1_25) && !defined(IGNORE_PIN_P1_25) + { MP_ROM_QSTR(MP_QSTR_P1_25), MP_ROM_PTR(&pin_P1_25) }, + #endif + #if defined(PIN_P1_26) && !defined(IGNORE_PIN_P1_26) + { MP_ROM_QSTR(MP_QSTR_P1_26), MP_ROM_PTR(&pin_P1_26) }, + #endif + #if defined(PIN_P1_27) && !defined(IGNORE_PIN_P1_27) + { MP_ROM_QSTR(MP_QSTR_P1_27), MP_ROM_PTR(&pin_P1_27) }, + #endif + #if defined(PIN_P1_28) && !defined(IGNORE_PIN_P1_28) + { MP_ROM_QSTR(MP_QSTR_P1_28), MP_ROM_PTR(&pin_P1_28) }, + #endif + #if defined(PIN_P1_29) && !defined(IGNORE_PIN_P1_29) + { MP_ROM_QSTR(MP_QSTR_P1_29), MP_ROM_PTR(&pin_P1_29) }, + #endif + #if defined(PIN_P1_30) && !defined(IGNORE_PIN_P1_30) + { MP_ROM_QSTR(MP_QSTR_P1_30), MP_ROM_PTR(&pin_P1_30) }, + #endif + #if defined(PIN_P1_31) && !defined(IGNORE_PIN_P1_31) + { MP_ROM_QSTR(MP_QSTR_P1_31), MP_ROM_PTR(&pin_P1_31) }, + #endif + + #if defined(PIN_P2_01) && !defined(IGNORE_PIN_P2_01) + { MP_ROM_QSTR(MP_QSTR_P2_01), MP_ROM_PTR(&pin_P2_01) }, + #endif + #if defined(PIN_P2_02) && !defined(IGNORE_PIN_P2_02) + { MP_ROM_QSTR(MP_QSTR_P2_02), MP_ROM_PTR(&pin_P2_02) }, + #endif + #if defined(PIN_P2_03) && !defined(IGNORE_PIN_P2_03) + { MP_ROM_QSTR(MP_QSTR_P2_03), MP_ROM_PTR(&pin_P2_03) }, + #endif + #if defined(PIN_P2_04) && !defined(IGNORE_PIN_P2_04) + { MP_ROM_QSTR(MP_QSTR_P2_04), MP_ROM_PTR(&pin_P2_04) }, + #endif + #if defined(PIN_P2_05) && !defined(IGNORE_PIN_P2_05) + { MP_ROM_QSTR(MP_QSTR_P2_05), MP_ROM_PTR(&pin_P2_05) }, + #endif + #if defined(PIN_P2_06) && !defined(IGNORE_PIN_P2_06) + { MP_ROM_QSTR(MP_QSTR_P2_06), MP_ROM_PTR(&pin_P2_06) }, + #endif + #if defined(PIN_P2_07) && !defined(IGNORE_PIN_P2_07) + { MP_ROM_QSTR(MP_QSTR_P2_07), MP_ROM_PTR(&pin_P2_07) }, + #endif + #if defined(PIN_P2_10) && !defined(IGNORE_PIN_P2_10) + { MP_ROM_QSTR(MP_QSTR_P2_10), MP_ROM_PTR(&pin_P2_10) }, + #endif + #if defined(PIN_P2_11) && !defined(IGNORE_PIN_P2_11) + { MP_ROM_QSTR(MP_QSTR_P2_11), MP_ROM_PTR(&pin_P2_11) }, + #endif + #if defined(PIN_P2_12) && !defined(IGNORE_PIN_P2_12) + { MP_ROM_QSTR(MP_QSTR_P2_12), MP_ROM_PTR(&pin_P2_12) }, + #endif + #if defined(PIN_P2_13) && !defined(IGNORE_PIN_P2_13) + { MP_ROM_QSTR(MP_QSTR_P2_13), MP_ROM_PTR(&pin_P2_13) }, + #endif + #if defined(PIN_P2_14) && !defined(IGNORE_PIN_P2_14) + { MP_ROM_QSTR(MP_QSTR_P2_14), MP_ROM_PTR(&pin_P2_14) }, + #endif + #if defined(PIN_P2_15) && !defined(IGNORE_PIN_P2_15) + { MP_ROM_QSTR(MP_QSTR_P2_15), MP_ROM_PTR(&pin_P2_15) }, + #endif + #if defined(PIN_P2_16) && !defined(IGNORE_PIN_P2_16) + { MP_ROM_QSTR(MP_QSTR_P2_16), MP_ROM_PTR(&pin_P2_16) }, + #endif + #if defined(PIN_P2_17) && !defined(IGNORE_PIN_P2_17) + { MP_ROM_QSTR(MP_QSTR_P2_17), MP_ROM_PTR(&pin_P2_17) }, + #endif + #if defined(PIN_P2_18) && !defined(IGNORE_PIN_P2_18) + { MP_ROM_QSTR(MP_QSTR_P2_18), MP_ROM_PTR(&pin_P2_18) }, + #endif + #if defined(PIN_P2_19) && !defined(IGNORE_PIN_P2_19) + { MP_ROM_QSTR(MP_QSTR_P2_19), MP_ROM_PTR(&pin_P2_19) }, + #endif + #if defined(PIN_P2_20) && !defined(IGNORE_PIN_P2_20) + { MP_ROM_QSTR(MP_QSTR_P2_20), MP_ROM_PTR(&pin_P2_20) }, + #endif + #if defined(PIN_P2_21) && !defined(IGNORE_PIN_P2_21) + { MP_ROM_QSTR(MP_QSTR_P2_21), MP_ROM_PTR(&pin_P2_21) }, + #endif + #if defined(PIN_P2_22) && !defined(IGNORE_PIN_P2_22) + { MP_ROM_QSTR(MP_QSTR_P2_22), MP_ROM_PTR(&pin_P2_22) }, + #endif + #if defined(PIN_P2_23) && !defined(IGNORE_PIN_P2_23) + { MP_ROM_QSTR(MP_QSTR_P2_23), MP_ROM_PTR(&pin_P2_23) }, + #endif + #if defined(PIN_P2_24) && !defined(IGNORE_PIN_P2_24) + { MP_ROM_QSTR(MP_QSTR_P2_24), MP_ROM_PTR(&pin_P2_24) }, + #endif + #if defined(PIN_P2_25) && !defined(IGNORE_PIN_P2_25) + { MP_ROM_QSTR(MP_QSTR_P2_25), MP_ROM_PTR(&pin_P2_25) }, + #endif + #if defined(PIN_P2_26) && !defined(IGNORE_PIN_P2_26) + { MP_ROM_QSTR(MP_QSTR_P2_26), MP_ROM_PTR(&pin_P2_26) }, + #endif + #if defined(PIN_P2_27) && !defined(IGNORE_PIN_P2_27) + { MP_ROM_QSTR(MP_QSTR_P2_27), MP_ROM_PTR(&pin_P2_27) }, + #endif + #if defined(PIN_P2_28) && !defined(IGNORE_PIN_P2_28) + { MP_ROM_QSTR(MP_QSTR_P2_28), MP_ROM_PTR(&pin_P2_28) }, + #endif + #if defined(PIN_P2_30) && !defined(IGNORE_PIN_P2_30) + { MP_ROM_QSTR(MP_QSTR_P2_30), MP_ROM_PTR(&pin_P2_30) }, + #endif + #if defined(PIN_P2_31) && !defined(IGNORE_PIN_P2_31) + { MP_ROM_QSTR(MP_QSTR_P2_31), MP_ROM_PTR(&pin_P2_31) }, + #endif + + #if defined(PIN_P3_01) && !defined(IGNORE_PIN_P3_01) + { MP_ROM_QSTR(MP_QSTR_P3_01), MP_ROM_PTR(&pin_P3_01) }, + #endif + #if defined(PIN_P3_02) && !defined(IGNORE_PIN_P3_02) + { MP_ROM_QSTR(MP_QSTR_P3_02), MP_ROM_PTR(&pin_P3_02) }, + #endif + #if defined(PIN_P3_03) && !defined(IGNORE_PIN_P3_03) + { MP_ROM_QSTR(MP_QSTR_P3_03), MP_ROM_PTR(&pin_P3_03) }, + #endif + #if defined(PIN_P3_04) && !defined(IGNORE_PIN_P3_04) + { MP_ROM_QSTR(MP_QSTR_P3_04), MP_ROM_PTR(&pin_P3_04) }, + #endif + #if defined(PIN_P3_05) && !defined(IGNORE_PIN_P3_05) + { MP_ROM_QSTR(MP_QSTR_P3_05), MP_ROM_PTR(&pin_P3_05) }, + #endif + #if defined(PIN_P3_06) && !defined(IGNORE_PIN_P3_06) + { MP_ROM_QSTR(MP_QSTR_P3_06), MP_ROM_PTR(&pin_P3_06) }, + #endif + #if defined(PIN_P3_07) && !defined(IGNORE_PIN_P3_07) + { MP_ROM_QSTR(MP_QSTR_P3_07), MP_ROM_PTR(&pin_P3_07) }, + #endif + #if defined(PIN_P3_08) && !defined(IGNORE_PIN_P3_08) + { MP_ROM_QSTR(MP_QSTR_P3_08), MP_ROM_PTR(&pin_P3_08) }, + #endif + #if defined(PIN_P3_09) && !defined(IGNORE_PIN_P3_09) + { MP_ROM_QSTR(MP_QSTR_P3_09), MP_ROM_PTR(&pin_P3_09) }, + #endif + + #if defined(PIN_P4_01) && !defined(IGNORE_PIN_P4_01) + { MP_ROM_QSTR(MP_QSTR_P4_01), MP_ROM_PTR(&pin_P4_02) }, + #endif + #if defined(PIN_P4_02) && !defined(IGNORE_PIN_P4_02) + { MP_ROM_QSTR(MP_QSTR_P4_01), MP_ROM_PTR(&pin_P4_02) }, + #endif + +}; +MP_DEFINE_CONST_DICT(mcu_pin_globals, mcu_pin_global_dict_table); + + +/** NOTE: Not implemented yet */ +// #if CIRCUITPY_INTERNAL_NVM_SIZE > 0 +// // The singleton nvm.ByteArray object. +// const nvm_bytearray_obj_t common_hal_mcu_nvm_obj = { +// .base = { +// .type = &nvm_bytearray_type, +// }, +// .len = NVM_BYTEARRAY_BUFFER_SIZE, +// .start_address = (uint8_t *)(CIRCUITPY_INTERNAL_NVM_START_ADDR) +// }; +// #endif diff --git a/ports/analog/common-hal/os/__init__.c b/ports/analog/common-hal/os/__init__.c new file mode 100644 index 000000000000..1f89300c4c18 --- /dev/null +++ b/ports/analog/common-hal/os/__init__.c @@ -0,0 +1,50 @@ +// This file is part of the CircuitPython project: https://circuitpython.org +// +// SPDX-FileCopyrightText: Copyright (c) 2017 Scott Shawcroft for Adafruit Industries +// SPDX-FileCopyrightText: Copyright (c) 2019 Lucian Copeland for Adafruit Industries +// +// SPDX-License-Identifier: MIT + +#include "genhdr/mpversion.h" +#include "py/mpconfig.h" +#include "py/objstr.h" +#include "py/objtuple.h" + +#include "py/mperrno.h" +#include "py/runtime.h" + +// #include "peripherals/periph.h" + +static const qstr os_uname_info_fields[] = { + MP_QSTR_sysname, MP_QSTR_nodename, + MP_QSTR_release, MP_QSTR_version, MP_QSTR_machine +}; +static const MP_DEFINE_STR_OBJ(os_uname_info_sysname_obj, "max32"); +static const MP_DEFINE_STR_OBJ(os_uname_info_nodename_obj, "max32"); + +static const MP_DEFINE_STR_OBJ(os_uname_info_release_obj, MICROPY_VERSION_STRING); +static const MP_DEFINE_STR_OBJ(os_uname_info_version_obj, MICROPY_GIT_TAG " on " MICROPY_BUILD_DATE); +static const MP_DEFINE_STR_OBJ(os_uname_info_machine_obj, MICROPY_HW_BOARD_NAME " with " MICROPY_HW_MCU_NAME); + +static MP_DEFINE_ATTRTUPLE( + os_uname_info_obj, + os_uname_info_fields, + 5, + (mp_obj_t)&os_uname_info_sysname_obj, + (mp_obj_t)&os_uname_info_nodename_obj, + (mp_obj_t)&os_uname_info_release_obj, + (mp_obj_t)&os_uname_info_version_obj, + (mp_obj_t)&os_uname_info_machine_obj + ); + +mp_obj_t common_hal_os_uname(void) { + return (mp_obj_t)&os_uname_info_obj; +} + +bool common_hal_os_urandom(uint8_t *buffer, uint32_t length) { + #if (HAS_TRNG) + // todo (low prior): implement + #else + #endif + return false; +} diff --git a/ports/analog/linking/max32690_cktpy.ld b/ports/analog/linking/max32690_cktpy.ld new file mode 100644 index 000000000000..9b32121a135a --- /dev/null +++ b/ports/analog/linking/max32690_cktpy.ld @@ -0,0 +1,186 @@ +/** This file is part of the CircuitPython project: https://circuitpython.org +* +* SPDX-FileCopyrightText: Copyright (c) 2024 Brandon Hurst, Analog Devices Inc. +* +* SPDX-License-Identifier: MIT +*/ + +MEMORY { + ROM (rx) : ORIGIN = 0x00000000, LENGTH = 128K + FLASH (rx) : ORIGIN = 0x10000000, LENGTH = 3M + FLASH_FIRMWARE (rx) : ORIGIN = 0x10000000, LENGTH = 2992K + FLASH_FS (rx) : ORIGIN = 0x102E0000, LENGTH = 128K + RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 1M +} +/* Minimum flash page is 16K */ +/* FLASH FIRMWARE: 3072K [3MB] - 16K - 64K = 2992K */ + +SECTIONS { + .rom : + { + KEEP(*(.rom_vector*)) + KEEP(*(.rom_handlers*)) + } > ROM + + + /** FIXME: can't place this in its own section for some reason + * system doesn't exit ROM code unless *(.isr_vector) + * is placed in the beginning of .text, + * even if .text is moved upward and *(.isr_vector) is + * placed at 0x10000000. + **/ + + /* Place ISR vector in a separate flash section */ + /* .isr_vector : */ + /* { */ + /* ISR Vector beginning of .text */ + /* KEEP(*(.isr_vector)) */ + /* KEEP(*(.isr_vector*)) */ + /* } > FLASH_ISR */ + + .text : + { + . = ALIGN(4); + _text = .; + + /* ISR Vector beginning of .text */ + /** fixme: may want to move this to FLASH_ISR long-term */ + KEEP(*(.isr_vector)) + KEEP(*(.isr_vector*)) + + . = ALIGN(4); + + /* program code; exclude RISCV code */ + EXCLUDE_FILE (*riscv.o) *(.text*) + *(.rodata*) /* read-only data: "const" */ + + KEEP(*(.init)) + KEEP(*(.fini)) + + /* .ctors */ + *crtbegin.o(.ctors) + *crtbegin?.o(.ctors) + *(EXCLUDE_FILE(*crtend?.o *crtend.o) .ctors) + *(SORT(.ctors.*)) + *(.ctors) + + /* .dtors */ + *crtbegin.o(.dtors) + *crtbegin?.o(.dtors) + *(EXCLUDE_FILE(*crtend?.o *crtend.o) .dtors) + *(SORT(.dtors.*)) + *(.dtors) + + /* C++ Exception handling */ + KEEP(*(.eh_frame*)) + . = ALIGN(4); + _etext = .; + } > FLASH_FIRMWARE + + .ARM.extab : + { + *(.ARM.extab* .gnu.linkonce.armextab.*) + } > FLASH_FIRMWARE + + /* Binary import */ + .bin_storage : + { + FILL(0xFF) + _bin_start_ = .; + KEEP(*(.bin_storage_img)) + _bin_end_ = .; + . = ALIGN(4); + } > FLASH_FIRMWARE + + /* it's used for C++ exception handling */ + /* we need to keep this to avoid overlapping */ + .ARM.exidx : + { + __exidx_start = .; + *(.ARM.exidx* .gnu.linkonce.armexidx.*) + __exidx_end = .; + } > FLASH_FIRMWARE + + .data : + { + . = ALIGN(4); + _data = .; + _sdata = .; + + *(vtable) + *(.data*) /*read-write initialized data: initialized global variable*/ + + /* These array sections are used by __libc_init_array to call static C++ constructors */ + . = ALIGN(4); + /* preinit data */ + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP(*(.preinit_array)) + PROVIDE_HIDDEN (__preinit_array_end = .); + + . = ALIGN(4); + /* init data */ + PROVIDE_HIDDEN (__init_array_start = .); + KEEP(*(SORT(.init_array.*))) + KEEP(*(.init_array)) + PROVIDE_HIDDEN (__init_array_end = .); + + . = ALIGN(4); + /* finit data */ + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP(*(SORT(.fini_array.*))) + KEEP(*(.fini_array)) + PROVIDE_HIDDEN (__fini_array_end = .); + + /* Run the flash programming functions from SRAM */ + *(.flashprog) + + . = ALIGN(4); + _edata = .; + } > RAM AT>FLASH_FIRMWARE + __load_data = LOADADDR(.data); + + .bss : + { + . = ALIGN(4); + _sbss = .; /* Provide _sbss for Cktpy */ + _bss = .; + + *(.bss*) /*read-write zero initialized data: uninitialized global variable*/ + *(COMMON) + + . = ALIGN(4); + _ebss = .; + _ezero = .; /* Provide _ezero /_ebss for CktPython (same as ebss) */ + } > RAM + + /* .stack_dummy section doesn't contains any symbols. It is only + * used for linker to calculate size of stack sections, and assign + * values to stack symbols later */ + .stack_dummy (COPY): + { + *(.stack*) + } > RAM + + /* Set stack top to end of RAM, and stack limit move down by + * size of stack_dummy section */ + __StackTop = ORIGIN(RAM) + LENGTH(RAM); + __StackLimit = __StackTop - SIZEOF(.stack_dummy); + + _stack = __StackTop; + _estack = __StackLimit; /* Provide _estack for CktPython */ + + .heap (COPY): + { + . = ALIGN(4); + _heap = .; + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + *(.heap*) + __HeapLimit = ABSOLUTE(__StackLimit); + } > RAM + + _eheap = __HeapLimit; + + /* Check if data + heap + stack exceeds RAM limit */ + ASSERT(__StackLimit >= _ebss, "region RAM overflowed with stack") +} diff --git a/ports/analog/max32_port.h b/ports/analog/max32_port.h new file mode 100644 index 000000000000..5d92fcfe6d3e --- /dev/null +++ b/ports/analog/max32_port.h @@ -0,0 +1,74 @@ +// This file is part of the CircuitPython project: https://circuitpython.org +// +// SPDX-FileCopyrightText: Copyright (c) 2024 Brandon Hurst, Analog Devices, Inc. +// +// SPDX-License-Identifier: MIT + +#ifndef MAX32_PORT_H +#define MAX32_PORT_H + +#include + +#include "mxc_assert.h" +#include "mxc_delay.h" +#include "mxc_device.h" +#include "mxc_pins.h" +#include "mxc_sys.h" +#include "mcr_regs.h" + +#include "gpio.h" + +#ifdef MAX32690 +#include "system_max32690.h" +#include "max32690.h" + +/** START: GPIO4 Handling specific to MAX32690 */ +#define GPIO4_PIN_MASK 0x00000003 +#define GPIO4_RESET_MASK 0xFFFFFF77 +#define GPIO4_OUTEN_MASK(mask) \ + (((mask & (1 << 0)) << MXC_F_MCR_GPIO4_CTRL_P40_OE_POS) | \ + ((mask & (1 << 1)) << (MXC_F_MCR_GPIO4_CTRL_P41_OE_POS - 1))) +#define GPIO4_PULLDIS_MASK(mask) \ + (((mask & (1 << 0)) << MXC_F_MCR_GPIO4_CTRL_P40_PE_POS) | \ + ((mask & (1 << 1)) << (MXC_F_MCR_GPIO4_CTRL_P41_PE_POS - 1))) +#define GPIO4_DATAOUT_MASK(mask) \ + (((mask & (1 << 0)) << MXC_F_MCR_GPIO4_CTRL_P40_DO_POS) | \ + ((mask & (1 << 1)) << (MXC_F_MCR_GPIO4_CTRL_P41_DO_POS - 1))) +#define GPIO4_DATAOUT_GET_MASK(mask) \ + ((((MXC_MCR->gpio4_ctrl & MXC_F_MCR_GPIO4_CTRL_P40_DO) >> MXC_F_MCR_GPIO4_CTRL_P40_DO_POS) | \ + ((MXC_MCR->gpio4_ctrl & MXC_F_MCR_GPIO4_CTRL_P41_DO) >> \ + (MXC_F_MCR_GPIO4_CTRL_P41_DO_POS - 1))) & \ + mask) +#define GPIO4_DATAIN_MASK(mask) \ + ((((MXC_MCR->gpio4_ctrl & MXC_F_MCR_GPIO4_CTRL_P40_IN) >> MXC_F_MCR_GPIO4_CTRL_P40_IN_POS) | \ + ((MXC_MCR->gpio4_ctrl & MXC_F_MCR_GPIO4_CTRL_P41_IN) >> \ + (MXC_F_MCR_GPIO4_CTRL_P41_IN_POS - 1))) & \ + mask) +#define GPIO4_AFEN_MASK(mask) \ + (((mask & (1 << 0)) << MXC_F_MCR_OUTEN_PDOWN_OUT_EN_POS) | \ + ((mask & (1 << 1)) >> (MXC_F_MCR_OUTEN_SQWOUT_EN_POS + 1))) +/** END: GPIO4 Handling specific to MAX32690 */ + +#endif + +/** Linker variables defined.... + * _estack: end of the stack + * _ebss: end of BSS section + * _ezero: same as ebss (acc. to main.c) + */ +extern uint32_t _ezero; +extern uint32_t _estack; +extern uint32_t _ebss; // Stored at the end of the bss section (which includes the heap). +extern uint32_t __stack, __heap; + +extern uint32_t SystemCoreClock; + +// Tick timer should be 1/1024 s. RTC Oscillator is usually 32.768 kHz ERTCO. +#define TICKS_PER_SEC 1024 + +#ifdef MAX32690 +// 12-bit ssec register, ticks @ 4096 Hz +#define SUBSEC_PER_TICK 4 +#endif + +#endif // MAX32_PORT_H diff --git a/ports/analog/mpconfigport.h b/ports/analog/mpconfigport.h new file mode 100644 index 000000000000..cadfbddbc55b --- /dev/null +++ b/ports/analog/mpconfigport.h @@ -0,0 +1,33 @@ +// This file is part of the CircuitPython project: https://circuitpython.org +// +// SPDX-FileCopyrightText: Copyright (c) 2015 Glenn Ruben Bakke +// SPDX-FileCopyrightText: Copyright (c) 2019 Dan Halbert for Adafruit Industries +// +// SPDX-License-Identifier: MIT + +#pragma once + +#include + +#define MICROPY_PY_FUNCTION_ATTRS (1) +#define MICROPY_PY_REVERSE_SPECIAL_METHODS (1) + +// 24KiB stack +#define CIRCUITPY_DEFAULT_STACK_SIZE 0x6000 + +// Also includes mpconfigboard.h +#include "py/circuitpy_mpconfig.h" + +// Board flags: +#ifndef BOARD_OVERWRITE_SWD +#define BOARD_OVERWRITE_SWD (0) +#endif +#ifndef BOARD_VTOR_DEFER +#define BOARD_VTOR_DEFER (0) +#endif +#ifndef BOARD_NO_VBUS_SENSE +#define BOARD_NO_VBUS_SENSE (0) +#endif +#ifndef BOARD_NO_USB_OTG_ID_SENSE +#define BOARD_NO_USB_OTG_ID_SENSE (0) +#endif diff --git a/ports/analog/mpconfigport.mk b/ports/analog/mpconfigport.mk new file mode 100644 index 000000000000..1b9655c7f33c --- /dev/null +++ b/ports/analog/mpconfigport.mk @@ -0,0 +1,72 @@ +# This file is part of the CircuitPython project: https://circuitpython.org +# +# SPDX-FileCopyrightText: Copyright (c) 2020 Scott Shawcroft for Adafruit Industries +# SPDX-FileCopyrightText: Copyright (c) 2024 Brandon Hurst, Analog Devices, Inc. +# +# SPDX-License-Identifier: MIT + +CHIP_FAMILY ?= max32 + +# Necessary to build CircuitPython +LONGINT_IMPL ?= MPZ +INTERNAL_LIBM ?= 1 + +# Req'd for OS; all max32 have TRNG +CFLAGS += -DHAS_TRNG=1 + +INTERNAL_FLASH_FILESYSTEM = 1 + +#################################################################################### +# Suggested config for first-time porting +#################################################################################### +# These modules are implemented in ports//common-hal: + +# Plan to implement +CIRCUITPY_BUSIO ?= 0 +CIRCUITPY_RTC ?= 0 + +# Other modules (may or may not implement): +CIRCUITPY_ANALOGIO ?= 0 +CIRCUITPY_AUDIOBUSIO ?= 0 +CIRCUITPY_AUDIOIO ?= 0 +CIRCUITPY_COUNTIO ?= 0 +CIRCUITPY_NEOPIXEL_WRITE ?= 0 +CIRCUITPY_FREQUENCYIO ?= 0 +CIRCUITPY_I2CTARGET ?= 0 +CIRCUITPY_PULSEIO ?= 0 +CIRCUITPY_PWMIO ?= 0 +CIRCUITPY_NVM ?= 0 +CIRCUITPY_ROTARYIO ?= 0 +CIRCUITPY_SDCARDIO ?= 0 +CIRCUITPY_FRAMEBUFFERIO ?= 0 +# Requires SPI, PulseIO (stub ok): +CIRCUITPY_DISPLAYIO ?= 0 + +# These modules are implemented in shared-module/ - they can be included in +# any port once their prerequisites in common-hal are complete. +# No requirements, but takes extra flash +CIRCUITPY_ULAB = 1 +# Requires DigitalIO: +CIRCUITPY_BITBANGIO ?= 1 +# Requires Microcontroller +CIRCUITPY_TOUCHIO ?= 1 +# Requires OS +CIRCUITPY_RANDOM ?= 0 +# Requires busio.UART +CIRCUITPY_CONSOLE_UART ?= 0 +# Does nothing without I2C +CIRCUITPY_REQUIRE_I2C_PULLUPS = 0 +# Requires neopixel_write or SPI (dotstar) +CIRCUITPY_PIXELBUF ?= 0 + +#################################################################################### +# Required for clean building (additional CircuitPython Defaults) +#################################################################################### + +# Depends on BUSIO +CIRCUITPY_BLEIO_HCI = 0 +CIRCUITPY_KEYPAD = 0 +CIRCUITPY_BUSDEVICE = 0 + +# For CircuitPython CI +CIRCUITPY_BUILD_EXTENSIONS ?= elf diff --git a/ports/analog/mphalport.c b/ports/analog/mphalport.c new file mode 100644 index 000000000000..8f305d6325e5 --- /dev/null +++ b/ports/analog/mphalport.c @@ -0,0 +1,25 @@ +// This file is part of the CircuitPython project: https://circuitpython.org +// +// SPDX-FileCopyrightText: Copyright (c) 2024 Brandon Hurst, Analog Devices, Inc +// +// SPDX-License-Identifier: MIT + +#include "mphalport.h" +#include "py/mphal.h" + +// includes __enable/__disable interrupts +#include "mxc_sys.h" + +#include "shared-bindings/microcontroller/__init__.h" + +void mp_hal_delay_us(mp_uint_t delay) { + common_hal_mcu_delay_us(delay); +} + +void mp_hal_disable_all_interrupts(void) { + __disable_irq(); +} + +void mp_hal_enable_all_interrupts(void) { + __enable_irq(); +} diff --git a/ports/analog/mphalport.h b/ports/analog/mphalport.h new file mode 100644 index 000000000000..3cd3e00c6e18 --- /dev/null +++ b/ports/analog/mphalport.h @@ -0,0 +1,21 @@ +// This file is part of the CircuitPython project: https://circuitpython.org +// +// SPDX-FileCopyrightText: Copyright (c) 2024 Brandon Hurst, Analog Devices, Inc +// +// SPDX-License-Identifier: MIT + +#pragma once + +#include "py/obj.h" +#include "lib/oofatfs/ff.h" +#include "supervisor/shared/tick.h" + +// Global millisecond tick count +static inline mp_uint_t mp_hal_ticks_ms(void) { + return supervisor_ticks_ms32(); +} + +void mp_hal_set_interrupt_char(int c); + +void mp_hal_disable_all_interrupts(void); +void mp_hal_enable_all_interrupts(void); diff --git a/ports/analog/msdk b/ports/analog/msdk new file mode 160000 index 000000000000..608acf33e95a --- /dev/null +++ b/ports/analog/msdk @@ -0,0 +1 @@ +Subproject commit 608acf33e95a994d548b8223955952c4749acaac diff --git a/ports/analog/peripherals/max32690/pins.c b/ports/analog/peripherals/max32690/pins.c new file mode 100644 index 000000000000..7550dc549efa --- /dev/null +++ b/ports/analog/peripherals/max32690/pins.c @@ -0,0 +1,123 @@ +// This file is part of the CircuitPython project: https://circuitpython.org +// +// SPDX-FileCopyrightText: Copyright (c) 2024 Brandon Hurst, Analog Devices, Inc. +// +// SPDX-License-Identifier: MIT + +#include "py/obj.h" +#include "py/mphal.h" +#include "peripherals/pins.h" +#include "max32690.h" + +const mcu_pin_obj_t pin_P0_00 = PIN(0, 0); +const mcu_pin_obj_t pin_P0_01 = PIN(0, 1); +const mcu_pin_obj_t pin_P0_02 = PIN(0, 2); +const mcu_pin_obj_t pin_P0_03 = PIN(0, 3); +const mcu_pin_obj_t pin_P0_04 = PIN(0, 4); +const mcu_pin_obj_t pin_P0_05 = PIN(0, 5); +const mcu_pin_obj_t pin_P0_06 = PIN(0, 6); +const mcu_pin_obj_t pin_P0_07 = PIN(0, 7); +const mcu_pin_obj_t pin_P0_08 = PIN(0, 8); +const mcu_pin_obj_t pin_P0_09 = PIN(0, 9); +const mcu_pin_obj_t pin_P0_10 = PIN(0, 10); +const mcu_pin_obj_t pin_P0_11 = PIN(0, 11); +const mcu_pin_obj_t pin_P0_12 = PIN(0, 12); +const mcu_pin_obj_t pin_P0_13 = PIN(0, 13); +const mcu_pin_obj_t pin_P0_14 = PIN(0, 14); +const mcu_pin_obj_t pin_P0_15 = PIN(0, 15); +const mcu_pin_obj_t pin_P0_16 = PIN(0, 16); +const mcu_pin_obj_t pin_P0_17 = PIN(0, 17); +const mcu_pin_obj_t pin_P0_18 = PIN(0, 18); +const mcu_pin_obj_t pin_P0_19 = PIN(0, 19); +const mcu_pin_obj_t pin_P0_20 = PIN(0, 20); +const mcu_pin_obj_t pin_P0_21 = PIN(0, 21); +const mcu_pin_obj_t pin_P0_22 = PIN(0, 22); +const mcu_pin_obj_t pin_P0_23 = PIN(0, 23); +const mcu_pin_obj_t pin_P0_24 = PIN(0, 24); +const mcu_pin_obj_t pin_P0_25 = PIN(0, 25); +const mcu_pin_obj_t pin_P0_26 = PIN(0, 26); +const mcu_pin_obj_t pin_P0_27 = PIN(0, 27); +const mcu_pin_obj_t pin_P0_28 = PIN(0, 28); +const mcu_pin_obj_t pin_P0_29 = PIN(0, 29); +const mcu_pin_obj_t pin_P0_30 = PIN(0, 30); +const mcu_pin_obj_t pin_P0_31 = PIN(0, 31); + +const mcu_pin_obj_t pin_P1_00 = PIN(1, 0); +const mcu_pin_obj_t pin_P1_01 = PIN(1, 1); +const mcu_pin_obj_t pin_P1_02 = PIN(1, 2); +const mcu_pin_obj_t pin_P1_03 = PIN(1, 3); +const mcu_pin_obj_t pin_P1_04 = PIN(1, 4); +const mcu_pin_obj_t pin_P1_05 = PIN(1, 5); +const mcu_pin_obj_t pin_P1_06 = PIN(1, 6); +const mcu_pin_obj_t pin_P1_07 = PIN(1, 7); +const mcu_pin_obj_t pin_P1_08 = PIN(1, 8); +const mcu_pin_obj_t pin_P1_09 = PIN(1, 9); +const mcu_pin_obj_t pin_P1_10 = PIN(1, 10); +const mcu_pin_obj_t pin_P1_11 = PIN(1, 11); +const mcu_pin_obj_t pin_P1_12 = PIN(1, 12); +const mcu_pin_obj_t pin_P1_13 = PIN(1, 13); +const mcu_pin_obj_t pin_P1_14 = PIN(1, 14); +const mcu_pin_obj_t pin_P1_15 = PIN(1, 15); +const mcu_pin_obj_t pin_P1_16 = PIN(1, 16); +const mcu_pin_obj_t pin_P1_17 = PIN(1, 17); +const mcu_pin_obj_t pin_P1_18 = PIN(1, 18); +const mcu_pin_obj_t pin_P1_19 = PIN(1, 19); +const mcu_pin_obj_t pin_P1_20 = PIN(1, 20); +const mcu_pin_obj_t pin_P1_21 = PIN(1, 21); +const mcu_pin_obj_t pin_P1_22 = PIN(1, 22); +const mcu_pin_obj_t pin_P1_23 = PIN(1, 23); +const mcu_pin_obj_t pin_P1_24 = PIN(1, 24); +const mcu_pin_obj_t pin_P1_25 = PIN(1, 25); +const mcu_pin_obj_t pin_P1_26 = PIN(1, 26); +const mcu_pin_obj_t pin_P1_27 = PIN(1, 27); +const mcu_pin_obj_t pin_P1_28 = PIN(1, 28); +const mcu_pin_obj_t pin_P1_29 = PIN(1, 29); +const mcu_pin_obj_t pin_P1_30 = PIN(1, 30); +const mcu_pin_obj_t pin_P1_31 = PIN(1, 31); + +const mcu_pin_obj_t pin_P2_00 = PIN(2, 0); +const mcu_pin_obj_t pin_P2_01 = PIN(2, 1); +const mcu_pin_obj_t pin_P2_02 = PIN(2, 2); +const mcu_pin_obj_t pin_P2_03 = PIN(2, 3); +const mcu_pin_obj_t pin_P2_04 = PIN(2, 4); +const mcu_pin_obj_t pin_P2_05 = PIN(2, 5); +const mcu_pin_obj_t pin_P2_06 = PIN(2, 6); +const mcu_pin_obj_t pin_P2_07 = PIN(2, 7); +const mcu_pin_obj_t pin_P2_08 = PIN(2, 8); +const mcu_pin_obj_t pin_P2_09 = PIN(2, 9); +const mcu_pin_obj_t pin_P2_10 = PIN(2, 10); +const mcu_pin_obj_t pin_P2_11 = PIN(2, 11); +const mcu_pin_obj_t pin_P2_12 = PIN(2, 12); +const mcu_pin_obj_t pin_P2_13 = PIN(2, 13); +const mcu_pin_obj_t pin_P2_14 = PIN(2, 14); +const mcu_pin_obj_t pin_P2_15 = PIN(2, 15); +const mcu_pin_obj_t pin_P2_16 = PIN(2, 16); +const mcu_pin_obj_t pin_P2_17 = PIN(2, 17); +const mcu_pin_obj_t pin_P2_18 = PIN(2, 18); +const mcu_pin_obj_t pin_P2_19 = PIN(2, 19); +const mcu_pin_obj_t pin_P2_20 = PIN(2, 20); +const mcu_pin_obj_t pin_P2_21 = PIN(2, 21); +const mcu_pin_obj_t pin_P2_22 = PIN(2, 22); +const mcu_pin_obj_t pin_P2_23 = PIN(2, 23); +const mcu_pin_obj_t pin_P2_24 = PIN(2, 24); +const mcu_pin_obj_t pin_P2_25 = PIN(2, 25); +const mcu_pin_obj_t pin_P2_26 = PIN(2, 26); +const mcu_pin_obj_t pin_P2_27 = PIN(2, 27); +const mcu_pin_obj_t pin_P2_28 = PIN(2, 28); +const mcu_pin_obj_t pin_P2_29 = PIN(2, 29); +const mcu_pin_obj_t pin_P2_30 = PIN(2, 30); +const mcu_pin_obj_t pin_P2_31 = PIN(2, 31); + +const mcu_pin_obj_t pin_P3_00 = PIN(3, 0); +const mcu_pin_obj_t pin_P3_01 = PIN(3, 1); +const mcu_pin_obj_t pin_P3_02 = PIN(3, 2); +const mcu_pin_obj_t pin_P3_03 = PIN(3, 3); +const mcu_pin_obj_t pin_P3_04 = PIN(3, 4); +const mcu_pin_obj_t pin_P3_05 = PIN(3, 5); +const mcu_pin_obj_t pin_P3_06 = PIN(3, 6); +const mcu_pin_obj_t pin_P3_07 = PIN(3, 7); +const mcu_pin_obj_t pin_P3_08 = PIN(3, 8); +const mcu_pin_obj_t pin_P3_09 = PIN(3, 9); + +const mcu_pin_obj_t pin_P4_00 = PIN(4, 0); +const mcu_pin_obj_t pin_P4_01 = PIN(4, 1); diff --git a/ports/analog/peripherals/max32690/pins.h b/ports/analog/peripherals/max32690/pins.h new file mode 100644 index 000000000000..44022decdf71 --- /dev/null +++ b/ports/analog/peripherals/max32690/pins.h @@ -0,0 +1,120 @@ +// This file is part of the CircuitPython project: https://circuitpython.org +// +// SPDX-FileCopyrightText: Copyright (c) 2024 Brandon Hurst, Analog Devices, Inc. +// +// SPDX-License-Identifier: MIT + +#pragma once + +extern const mcu_pin_obj_t pin_P0_00; +extern const mcu_pin_obj_t pin_P0_01; +extern const mcu_pin_obj_t pin_P0_02; +extern const mcu_pin_obj_t pin_P0_03; +extern const mcu_pin_obj_t pin_P0_04; +extern const mcu_pin_obj_t pin_P0_05; +extern const mcu_pin_obj_t pin_P0_06; +extern const mcu_pin_obj_t pin_P0_07; +extern const mcu_pin_obj_t pin_P0_08; +extern const mcu_pin_obj_t pin_P0_09; +extern const mcu_pin_obj_t pin_P0_10; +extern const mcu_pin_obj_t pin_P0_11; +extern const mcu_pin_obj_t pin_P0_12; +extern const mcu_pin_obj_t pin_P0_13; +extern const mcu_pin_obj_t pin_P0_14; +extern const mcu_pin_obj_t pin_P0_15; +extern const mcu_pin_obj_t pin_P0_16; +extern const mcu_pin_obj_t pin_P0_17; +extern const mcu_pin_obj_t pin_P0_18; +extern const mcu_pin_obj_t pin_P0_19; +extern const mcu_pin_obj_t pin_P0_20; +extern const mcu_pin_obj_t pin_P0_21; +extern const mcu_pin_obj_t pin_P0_22; +extern const mcu_pin_obj_t pin_P0_23; +extern const mcu_pin_obj_t pin_P0_24; +extern const mcu_pin_obj_t pin_P0_25; +extern const mcu_pin_obj_t pin_P0_26; +extern const mcu_pin_obj_t pin_P0_27; +extern const mcu_pin_obj_t pin_P0_28; +extern const mcu_pin_obj_t pin_P0_29; +extern const mcu_pin_obj_t pin_P0_30; +extern const mcu_pin_obj_t pin_P0_31; + +extern const mcu_pin_obj_t pin_P1_00; +extern const mcu_pin_obj_t pin_P1_01; +extern const mcu_pin_obj_t pin_P1_02; +extern const mcu_pin_obj_t pin_P1_03; +extern const mcu_pin_obj_t pin_P1_04; +extern const mcu_pin_obj_t pin_P1_05; +extern const mcu_pin_obj_t pin_P1_06; +extern const mcu_pin_obj_t pin_P1_07; +extern const mcu_pin_obj_t pin_P1_08; +extern const mcu_pin_obj_t pin_P1_09; +extern const mcu_pin_obj_t pin_P1_10; +extern const mcu_pin_obj_t pin_P1_11; +extern const mcu_pin_obj_t pin_P1_12; +extern const mcu_pin_obj_t pin_P1_13; +extern const mcu_pin_obj_t pin_P1_14; +extern const mcu_pin_obj_t pin_P1_15; +extern const mcu_pin_obj_t pin_P1_16; +extern const mcu_pin_obj_t pin_P1_17; +extern const mcu_pin_obj_t pin_P1_18; +extern const mcu_pin_obj_t pin_P1_19; +extern const mcu_pin_obj_t pin_P1_20; +extern const mcu_pin_obj_t pin_P1_21; +extern const mcu_pin_obj_t pin_P1_22; +extern const mcu_pin_obj_t pin_P1_23; +extern const mcu_pin_obj_t pin_P1_24; +extern const mcu_pin_obj_t pin_P1_25; +extern const mcu_pin_obj_t pin_P1_26; +extern const mcu_pin_obj_t pin_P1_27; +extern const mcu_pin_obj_t pin_P1_28; +extern const mcu_pin_obj_t pin_P1_29; +extern const mcu_pin_obj_t pin_P1_30; +extern const mcu_pin_obj_t pin_P1_31; + +extern const mcu_pin_obj_t pin_P2_00; +extern const mcu_pin_obj_t pin_P2_01; +extern const mcu_pin_obj_t pin_P2_02; +extern const mcu_pin_obj_t pin_P2_03; +extern const mcu_pin_obj_t pin_P2_04; +extern const mcu_pin_obj_t pin_P2_05; +extern const mcu_pin_obj_t pin_P2_06; +extern const mcu_pin_obj_t pin_P2_07; +extern const mcu_pin_obj_t pin_P2_08; +extern const mcu_pin_obj_t pin_P2_09; +extern const mcu_pin_obj_t pin_P2_10; +extern const mcu_pin_obj_t pin_P2_11; +extern const mcu_pin_obj_t pin_P2_12; +extern const mcu_pin_obj_t pin_P2_13; +extern const mcu_pin_obj_t pin_P2_14; +extern const mcu_pin_obj_t pin_P2_15; +extern const mcu_pin_obj_t pin_P2_16; +extern const mcu_pin_obj_t pin_P2_17; +extern const mcu_pin_obj_t pin_P2_18; +extern const mcu_pin_obj_t pin_P2_19; +extern const mcu_pin_obj_t pin_P2_20; +extern const mcu_pin_obj_t pin_P2_21; +extern const mcu_pin_obj_t pin_P2_22; +extern const mcu_pin_obj_t pin_P2_23; +extern const mcu_pin_obj_t pin_P2_24; +extern const mcu_pin_obj_t pin_P2_25; +extern const mcu_pin_obj_t pin_P2_26; +extern const mcu_pin_obj_t pin_P2_27; +extern const mcu_pin_obj_t pin_P2_28; +extern const mcu_pin_obj_t pin_P2_29; +extern const mcu_pin_obj_t pin_P2_30; +extern const mcu_pin_obj_t pin_P2_31; + +extern const mcu_pin_obj_t pin_P3_00; +extern const mcu_pin_obj_t pin_P3_01; +extern const mcu_pin_obj_t pin_P3_02; +extern const mcu_pin_obj_t pin_P3_03; +extern const mcu_pin_obj_t pin_P3_04; +extern const mcu_pin_obj_t pin_P3_05; +extern const mcu_pin_obj_t pin_P3_06; +extern const mcu_pin_obj_t pin_P3_07; +extern const mcu_pin_obj_t pin_P3_08; +extern const mcu_pin_obj_t pin_P3_09; + +extern const mcu_pin_obj_t pin_P4_00; // BTLDR Stimulus +extern const mcu_pin_obj_t pin_P4_01; diff --git a/ports/analog/peripherals/pins.h b/ports/analog/peripherals/pins.h new file mode 100644 index 000000000000..3bd7d02bf46d --- /dev/null +++ b/ports/analog/peripherals/pins.h @@ -0,0 +1,36 @@ +// This file is part of the CircuitPython project: https://circuitpython.org +// +// SPDX-FileCopyrightText: Copyright (c) 2024 Brandon Hurst, Analog Devices, Inc. +// +// SPDX-License-Identifier: MIT + +#pragma once + +// STD includes +#include +#include + +// CktPy includes +#include "py/obj.h" + +// HAL includes +#include "gpio.h" +#include "gpio_regs.h" + +typedef struct { + mp_obj_base_t base; + uint8_t port; + uint32_t mask; // the pad # target e.g. P0.01 is Port=0, Mask=1 + mxc_gpio_vssel_t level; +} mcu_pin_obj_t; + +extern const mp_obj_type_t mcu_pin_type; + +#define PIN(pin_port, pin_mask) { {&mcu_pin_type}, .port = pin_port, .mask = 1UL << pin_mask, .level = MXC_GPIO_VSSEL_VDDIO } + +// for non-connected pins +#define NO_PIN 0xFF + +#ifdef MAX32690 +#include "max32690/pins.h" +#endif diff --git a/ports/analog/qstrdefsport.h b/ports/analog/qstrdefsport.h new file mode 100644 index 000000000000..2d2c26092348 --- /dev/null +++ b/ports/analog/qstrdefsport.h @@ -0,0 +1,10 @@ +// This file is part of the CircuitPython project: https://circuitpython.org +// +// SPDX-FileCopyrightText: Copyright (c) 2024 Adafruit Industries LLC +// +// SPDX-License-Identifier: MIT + +// Do not use #pragma once in this file; it will cause a warning during qstr generation. + +// qstrs specific to this port +// *FORMAT-OFF* diff --git a/ports/analog/supervisor/cpu.s b/ports/analog/supervisor/cpu.s new file mode 100644 index 000000000000..7cb8291045f1 --- /dev/null +++ b/ports/analog/supervisor/cpu.s @@ -0,0 +1,34 @@ +// This file is part of the CircuitPython project: https://circuitpython.org +// +// SPDX-FileCopyrightText: Copyright (c) 2017 Scott Shawcroft for Adafruit Industries +// SPDX-FileCopyrightText: Copyright (c) 2024 Brandon Hurst, Analog Devices, Inc +// +// SPDX-License-Identifier: MIT + +.syntax unified +.cpu cortex-m4 +.thumb +.text +.align 2 + +@ uint cpu_get_regs_and_sp(r0=uint regs[10]) +.global cpu_get_regs_and_sp +.thumb +.thumb_func +.type cpu_get_regs_and_sp, %function +cpu_get_regs_and_sp: +@ store registers into given array +str r4, [r0], #4 +str r5, [r0], #4 +str r6, [r0], #4 +str r7, [r0], #4 +str r8, [r0], #4 +str r9, [r0], #4 +str r10, [r0], #4 +str r11, [r0], #4 +str r12, [r0], #4 +str r13, [r0], #4 + +@ return the sp +mov r0, sp +bx lr diff --git a/ports/analog/supervisor/internal_flash.c b/ports/analog/supervisor/internal_flash.c new file mode 100644 index 000000000000..8518b235566c --- /dev/null +++ b/ports/analog/supervisor/internal_flash.c @@ -0,0 +1,246 @@ +// This file is part of the CircuitPython project: https://circuitpython.org +// +// SPDX-FileCopyrightText: Copyright (c) 2013, 2014 Damien P. George +// SPDX-FileCopyrightText: Copyright (c) 2020 Lucian Copeland for Adafruit Industries +// SPDX-FileCopyrightText: Copyright (c) 2024 Brandon Hurst, Analog Devices, Inc. +// +// SPDX-License-Identifier: MIT + +#include "supervisor/internal_flash.h" + +#include +#include +#include + +#include "extmod/vfs.h" +#include "extmod/vfs_fat.h" + +#include "py/obj.h" +#include "py/mphal.h" +#include "py/runtime.h" + +#include "supervisor/filesystem.h" +#include "supervisor/flash.h" +#include "supervisor/shared/safe_mode.h" +#if CIRCUITPY_USB_DEVICE +#include "supervisor/usb.h" +#endif + +#include "mpconfigboard.h" + +// MAX32 HAL Includes +#include "flc.h" +#include "flc_reva.h" +#include "icc.h" // includes icc_.c for MSDK die type +#include "mxc_device.h" + +/** + * NOTE: + * ANY function which modifies flash contents must execute from a crit section. + * This is because FLC functions are loc'd in RAM, and an ISR executing + * from Flash will trigger a HardFault. + * + * An alternative would be to initialize with NVIC_SetRAM(), + * which makes ISRs execute from RAM. + * + * NOTE: + * Additionally, any code that modifies flash contents must disable the + * cache. Turn off ICC0 any time flash is to be modified. Remember to re-enable if using. + * + * For Maxim devices which include an additional RISC-V processor, this shall be ignored. + * Therefore only ICC0 need be used for the purpose of these functions. + */ + +typedef struct { + const uint32_t base_addr; + const uint32_t sector_size; + const uint32_t num_sectors; +} flash_layout_t; + +#ifdef MAX32690 +// struct layout is the actual layout of flash +// FS Code will use INTERNAL_FLASH_FILESYSTEM_START_ADDR +// and won't conflict with ISR vector in first 16 KiB of flash +static const flash_layout_t flash_layout[] = { + { 0x10000000, FLASH_PAGE_SIZE, 192}, + // { 0x10300000, 0x2000, 32 }, // RISC-V flash +}; +// must be able to hold a full page (for re-writing upon erase) +static uint32_t page_buffer[FLASH_PAGE_SIZE / 4] = {0x0}; + +#else +#error "Invalid BOARD. Please set BOARD equal to any board under 'boards/'." +#endif + +static inline int32_t block2addr(uint32_t block) { + if (block >= 0 && block < INTERNAL_FLASH_FILESYSTEM_NUM_BLOCKS) { + return CIRCUITPY_INTERNAL_FLASH_FILESYSTEM_START_ADDR + block * FILESYSTEM_BLOCK_SIZE; + } else { + return -1; + } +} + +// Get index, start addr, & size of the flash sector where addr lies +int flash_get_sector_info(uint32_t addr, uint32_t *start_addr, uint32_t *size) { + // This function should return -1 in the event of errors. + if (addr >= flash_layout[0].base_addr) { + uint32_t sector_index = 0; + if (MP_ARRAY_SIZE(flash_layout) == 1) { + sector_index = (addr - flash_layout[0].base_addr) / flash_layout[0].sector_size; + if (sector_index >= flash_layout[0].num_sectors) { + return -1; // addr is not in flash + } + if (start_addr) { + *start_addr = flash_layout[0].base_addr + (sector_index * flash_layout[0].sector_size); + } else { + return -1; // start_addr is NULL + } + if (size) { + *size = flash_layout[0].sector_size; + } else { + return -1; // size is NULL + } + return sector_index; + } + + // algorithm for multiple flash sections + for (uint8_t i = 0; i < MP_ARRAY_SIZE(flash_layout); ++i) { + for (uint8_t j = 0; j < flash_layout[i].num_sectors; ++j) { + uint32_t sector_start_next = flash_layout[i].base_addr + + (j + 1) * flash_layout[i].sector_size; + if (addr < sector_start_next) { + if (start_addr) { + *start_addr = flash_layout[i].base_addr + + j * flash_layout[i].sector_size; + } + if (size) { + *size = flash_layout[i].sector_size; + } + return sector_index; + } + ++sector_index; + } + } + } + return -1; +} + +void supervisor_flash_init(void) { + // No initialization needed. + // Pay attention to the note at the top of this file! +} + +uint32_t supervisor_flash_get_block_size(void) { + return FILESYSTEM_BLOCK_SIZE; +} + +uint32_t supervisor_flash_get_block_count(void) { + return INTERNAL_FLASH_FILESYSTEM_NUM_BLOCKS; +} + +void port_internal_flash_flush(void) { + + // Flush all instruction cache + // ME18 has bug where top-level sysctrl flush bit only works one. + // Have to use low-level flush bits for each ICC instance. + MXC_ICC_Flush(MXC_ICC0); + MXC_ICC_Flush(MXC_ICC1); + + // Clear the line fill buffer by reading 2 pages from flash + volatile uint32_t *line_addr; + volatile uint32_t line; + line_addr = (uint32_t *)(MXC_FLASH_MEM_BASE); + line = *line_addr; + line_addr = (uint32_t *)(MXC_FLASH_MEM_BASE + MXC_FLASH_PAGE_SIZE); + line = *line_addr; + (void)line; // Silence build warnings that this variable is not used. +} + +// Read flash blocks, using cache if it contains the right data +// return 0 on success, non-zero on error +mp_uint_t supervisor_flash_read_blocks(uint8_t *dest, uint32_t block, uint32_t num_blocks) { + // Find the address of the block we want to read + int src_addr = block2addr(block); + if (src_addr == -1) { + // bad block num + return 1; + } + + uint32_t sector_size, sector_start; + if (flash_get_sector_info(src_addr, §or_start, §or_size) == -1) { + // bad sector idx + return 2; + } + + /** NOTE: The MXC_FLC_Read function executes from SRAM and does some more error checking + * than memcpy does. Will use it for now. + */ + MXC_FLC_Read(src_addr, dest, FILESYSTEM_BLOCK_SIZE * num_blocks); + + return 0; // success +} + +// Write to flash blocks +// return 0 on success, non-zero on error +mp_uint_t supervisor_flash_write_blocks(const uint8_t *src, uint32_t block_num, uint32_t num_blocks) { + uint32_t error, blocks_left, count, page_start, page_size = 0; + + while (num_blocks > 0) { + int dest_addr = block2addr(block_num); + // bad block number passed in + if (dest_addr == -1) { + return 1; + } + + if (flash_get_sector_info(dest_addr, &page_start, &page_size) == -1) { + reset_into_safe_mode(SAFE_MODE_FLASH_WRITE_FAIL); + } + + // Find the number of blocks left within this sector + // BLOCKS_LEFT = (SECTOR_SIZE - BLOCK_OFFSET within sector)) / BLOCK_SIZE + blocks_left = (page_size - (dest_addr - page_start)) / FILESYSTEM_BLOCK_SIZE; + count = MIN(num_blocks, blocks_left); + + MXC_ICC_Disable(MXC_ICC0); + + // Buffer the page of flash to erase + MXC_FLC_Read(page_start, page_buffer, page_size); + + // Erase flash page + MXC_CRITICAL( + error = MXC_FLC_PageErase(dest_addr); + ); + if (error != E_NO_ERROR) { + // lock flash & reset + MXC_FLC0->ctrl = (MXC_FLC0->ctrl & ~MXC_F_FLC_REVA_CTRL_UNLOCK) | MXC_S_FLC_REVA_CTRL_UNLOCK_LOCKED; + reset_into_safe_mode(SAFE_MODE_FLASH_WRITE_FAIL); + } + + // Copy new src data into the page buffer + // fill the new data in at the offset dest_addr - page_start + // account for uint32_t page_buffer vs uint8_t src + memcpy((page_buffer + (dest_addr - page_start) / 4), src, count * FILESYSTEM_BLOCK_SIZE); + + // Write new page buffer back into flash + MXC_CRITICAL( + error = MXC_FLC_Write(page_start, page_size, page_buffer); + ); + if (error != E_NO_ERROR) { + // lock flash & reset + MXC_FLC0->ctrl = (MXC_FLC0->ctrl & ~MXC_F_FLC_REVA_CTRL_UNLOCK) | MXC_S_FLC_REVA_CTRL_UNLOCK_LOCKED; + reset_into_safe_mode(SAFE_MODE_FLASH_WRITE_FAIL); + } + + MXC_ICC_Enable(MXC_ICC0); + + block_num += count; + src += count * FILESYSTEM_BLOCK_SIZE; + num_blocks -= count; + } + return 0; // success +} + +// Empty the fs cache +void supervisor_flash_release_cache(void) { + supervisor_flash_flush(); +} diff --git a/ports/analog/supervisor/internal_flash.h b/ports/analog/supervisor/internal_flash.h new file mode 100644 index 000000000000..cc25f80be770 --- /dev/null +++ b/ports/analog/supervisor/internal_flash.h @@ -0,0 +1,15 @@ +// This file is part of the CircuitPython project: https://circuitpython.org +// +// SPDX-FileCopyrightText: Copyright (c) 2013, 2014 Damien P. George +// SPDX-FileCopyrightText: Copyright (c) 2024 Brandon Hurst, Analog Devices, Inc. +// +// SPDX-License-Identifier: MIT + +#pragma once + +#include +#include + +#include "py/mpconfig.h" + +#define INTERNAL_FLASH_FILESYSTEM_NUM_BLOCKS (INTERNAL_FLASH_FILESYSTEM_SIZE / FILESYSTEM_BLOCK_SIZE) diff --git a/ports/analog/supervisor/port.c b/ports/analog/supervisor/port.c new file mode 100644 index 000000000000..cdbf88d2528d --- /dev/null +++ b/ports/analog/supervisor/port.c @@ -0,0 +1,318 @@ +/****************************************************************************** + * + * Copyright (C) 2022-2023 Maxim Integrated Products, Inc. All Rights Reserved. + * (now owned by Analog Devices, Inc.), + * Copyright (C) 2023 Analog Devices, Inc. All Rights Reserved. This software + * is proprietary to Analog Devices, Inc. and its licensors. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ******************************************************************************/ + +/** + * @file port.c + * @author Brandon Hurst @ Analog Devices, Inc. + * @brief Functions required for a basic CircuitPython port + * @date 2024-07-30 + * + * @copyright Copyright (c) 2024 + */ + +#include +#include +#include "supervisor/background_callback.h" +#include "supervisor/board.h" +#include "supervisor/port.h" + +#include "common-hal/microcontroller/Pin.h" +#include "shared-bindings/microcontroller/__init__.h" + +// Sys includes +#include "max32_port.h" + +// Timers +#include "mxc_delay.h" +#include "rtc.h" + +// msec to RTC subsec ticks (4 kHz) +/* Converts a time in milleseconds to equivalent RSSA register value */ +#define MSEC_TO_SS_ALARM(x) (0 - ((x * 4096) / 1000)) + +// Externs defined by linker .ld file +extern uint32_t _stack, _heap, _estack, _eheap; +extern uint32_t _ebss; + +// From boards/$(BOARD)/board.c +extern const mxc_gpio_cfg_t pb_pin[]; +extern const int num_pbs; +extern const mxc_gpio_cfg_t led_pin[]; +extern const int num_leds; + +// For saving rtc data for ticks +static uint32_t subsec, sec = 0; +static uint32_t tick_flag = 0; + +// defined by cmsis core files +extern void NVIC_SystemReset(void) NORETURN; + +safe_mode_t port_init(void) { + int err = E_NO_ERROR; + + // 1ms tick timer + SysTick_Config(SystemCoreClock / 1000); + + // Enable GPIO (enables clocks + common init for ports) + for (int i = 0; i < MXC_CFG_GPIO_INSTANCES; i++) { + err = MXC_GPIO_Init(0x1 << i); + if (err) { + return SAFE_MODE_PROGRAMMATIC; + } + } + + // Init Board LEDs + /* setup GPIO for the LED */ + for (int i = 0; i < num_leds; i++) { + // Set the output value + MXC_GPIO_OutClr(led_pin[i].port, led_pin[i].mask); + + if (MXC_GPIO_Config(&led_pin[i]) != E_NO_ERROR) { + return SAFE_MODE_PROGRAMMATIC; + } + } + + // Turn on one LED to indicate Sign of Life + MXC_GPIO_OutSet(led_pin[2].port, led_pin[2].mask); + + // Enable clock to RTC peripheral + MXC_GCR->clkctrl |= MXC_F_GCR_CLKCTRL_ERTCO_EN; + while (!(MXC_GCR->clkctrl & MXC_F_GCR_CLKCTRL_ERTCO_RDY)) { + ; + } + + NVIC_EnableIRQ(RTC_IRQn); + NVIC_EnableIRQ(USB_IRQn); + + // Init RTC w/ 0sec, 0subsec + // Driven by 32.768 kHz ERTCO, with ssec= 1/4096 s + while (MXC_RTC_Init(0, 0) != E_SUCCESS) { + } + ; + + // enable 1 sec RTC SSEC alarm + MXC_RTC_DisableInt(MXC_F_RTC_CTRL_SSEC_ALARM_IE); + MXC_RTC_SetSubsecondAlarm(MSEC_TO_SS_ALARM(1000)); + MXC_RTC_EnableInt(MXC_F_RTC_CTRL_SSEC_ALARM_IE); + + // Enable RTC + while (MXC_RTC_Start() != E_SUCCESS) { + } + ; + + return SAFE_MODE_NONE; +} + +void RTC_IRQHandler(void) { + // Read flags to clear + int flags = MXC_RTC_GetFlags(); + + switch (flags) { + case MXC_F_RTC_CTRL_SSEC_ALARM: + MXC_RTC_ClearFlags(MXC_F_RTC_CTRL_SSEC_ALARM); + break; + case MXC_F_RTC_CTRL_TOD_ALARM: + MXC_RTC_ClearFlags(MXC_F_RTC_CTRL_TOD_ALARM); + break; + case MXC_F_RTC_CTRL_RDY: + MXC_RTC_ClearFlags(MXC_F_RTC_CTRL_RDY); + break; + default: + break; + } + + tick_flag = 1; +} + +// Reset the MCU completely +void reset_cpu(void) { + // includes MCU reset request + awaits on memory bus + NVIC_SystemReset(); +} + +// Reset MCU state +void reset_port(void) { + reset_all_pins(); +} + +// Reset to the bootloader +// note: not implemented since max32 requires external signals to +// activate bootloaders +void reset_to_bootloader(void) { + NVIC_SystemReset(); + while (true) { + __NOP(); + } +} + +/** Acquire values of stack & heap starts & limits + * Return variables defined by linkerscript. + */ +uint32_t *port_stack_get_limit(void) { + // ignore array bounds GCC warnings + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Warray-bounds" + + // NOTE: Only return how much stack we have allotted for CircuitPython + return port_stack_get_top() - (CIRCUITPY_DEFAULT_STACK_SIZE + CIRCUITPY_EXCEPTION_STACK_SIZE) / sizeof(uint32_t); + #pragma GCC diagnostic pop +} +uint32_t *port_stack_get_top(void) { + return &_stack; +} +uint32_t *port_heap_get_bottom(void) { + return &_heap; +} +uint32_t *port_heap_get_top(void) { + return port_stack_get_limit(); +} + +/** Save & retrieve a word from memory over a reset cycle. + * Used for safe mode + */ +void port_set_saved_word(uint32_t value) { + _ebss = value; +} +uint32_t port_get_saved_word(void) { + return _ebss; +} + +// Raw monotonic tick count since startup. +// NOTE (rollover): +// seconds reg is 32 bits, can hold up to 2^32-1 +// theref. rolls over after ~136 years +uint64_t port_get_raw_ticks(uint8_t *subticks) { + // Ensure we can read from ssec register as soon as we can + // MXC function does cross-tick / busy checking of RTC controller + if (MXC_RTC->ctrl & MXC_F_RTC_CTRL_EN) { + // NOTE: RTC_GetTime always returns BUSY if RTC is not running + while ((MXC_RTC_GetTime(&sec, &subsec)) != E_NO_ERROR) { + ; + } + } else { + sec = MXC_RTC->sec; + subsec = MXC_RTC->ssec; + } + + // Return ticks given total subseconds + // ticks = TICKS/s * s + subsec/ subs/tick + uint64_t raw_ticks = ((uint64_t)TICKS_PER_SEC) * sec + (subsec / SUBSEC_PER_TICK); + + if (subticks) { + // subticks may only be filled to a resn of 1/4096 in some cases + // e.g. multiply by 32 / 8 = 4 to get true 1/32768 subticks + *subticks = (32 / (SUBSEC_PER_TICK)) * (subsec - (subsec / SUBSEC_PER_TICK)); + } + + return raw_ticks; +} + +// Enable 1/1024 second tick. +void port_enable_tick(void) { + while (MXC_RTC_Start() == E_BUSY) { + ; + } +} + +// Disable 1/1024 second tick. +void port_disable_tick(void) { + while (MXC_RTC_Stop() == E_BUSY) { + ; + } +} + +// Wake the CPU after a given # of ticks or sooner +void port_interrupt_after_ticks(uint32_t ticks) { + uint32_t ticks_msec = 0; + + ticks_msec = (ticks / TICKS_PER_SEC) * 1000; + + // Disable RTC interrupts + MXC_RTC_DisableInt(MXC_F_RTC_CTRL_SSEC_ALARM_IE | + MXC_F_RTC_CTRL_TOD_ALARM_IE | MXC_F_RTC_CTRL_RDY_IE); + + // Stop RTC & store current time & ticks + port_get_raw_ticks(NULL); + + // Clear the flag to be set by the RTC Handler + tick_flag = 0; + + // Subsec alarm is the starting/reload value of the SSEC counter. + // ISR triggered when SSEC rolls over from 0xFFFF_FFFF to 0x0 + while (MXC_RTC_SetSubsecondAlarm(MSEC_TO_SS_ALARM(ticks_msec)) != E_SUCCESS) { + } + + MXC_RTC_EnableInt(MXC_F_RTC_CTRL_SSEC_ALARM_IE); + +} + +void port_idle_until_interrupt(void) { + #if CIRCUITPY_RTC + // Check if alarm triggers before we even got here + if (MXC_RTC_GetFlags() == (MXC_F_RTC_CTRL_TOD_ALARM | MXC_F_RTC_CTRL_SSEC_ALARM)) { + return; + } + #endif + + // Interrupts should be disabled to ensure the ISR queue is flushed + // WFI still returns as long as the interrupt flag toggles; + // only when we re-enable interrupts will the ISR function trigger + common_hal_mcu_disable_interrupts(); + if (!background_callback_pending()) { + __DSB(); + /** DEBUG: may comment out WFI for debugging port functions */ + // __WFI(); + } + common_hal_mcu_enable_interrupts(); +} + +__attribute__((used)) void MemManage_Handler(void) { + reset_into_safe_mode(SAFE_MODE_HARD_FAULT); + while (true) { + asm ("nop;"); + } +} + +__attribute__((used)) void BusFault_Handler(void) { + reset_into_safe_mode(SAFE_MODE_HARD_FAULT); + while (true) { + asm ("nop;"); + } +} + +__attribute__((used)) void UsageFault_Handler(void) { + reset_into_safe_mode(SAFE_MODE_HARD_FAULT); + while (true) { + asm ("nop;"); + } +} + +__attribute__((used)) void HardFault_Handler(void) { + reset_into_safe_mode(SAFE_MODE_HARD_FAULT); + while (true) { + asm ("nop;"); + } +} + +// Required by libc _init_array loops in startup code +// if we are compiling using "-nostdlib/-nostartfiles" +void _init(void) { +} diff --git a/ports/analog/supervisor/serial.c b/ports/analog/supervisor/serial.c new file mode 100644 index 000000000000..536355e38f60 --- /dev/null +++ b/ports/analog/supervisor/serial.c @@ -0,0 +1,84 @@ +// This file is part of the CircuitPython project: https://circuitpython.org +// +// SPDX-FileCopyrightText: Copyright (c) 2017, 2018 Scott Shawcroft for Adafruit Industries +// SPDX-FileCopyrightText: Copyright (c) 2019 Lucian Copeland for Adafruit Industries +// SPDX-FileCopyrightText: Copyright (c) Brandon Hurst, Analog Devices, Inc. +// +// SPDX-License-Identifier: MIT + +#include "py/mphal.h" +#include +#include "supervisor/shared/serial.h" + +#include "uart.h" +#include "uart_regs.h" + +#ifndef MAX32_SERIAL +#define MAX32_SERIAL 0 +#endif + +#if MAX32_SERIAL +#ifdef MAX32690 +#define CONSOLE_UART MXC_UART0 +#endif +#endif + +void port_serial_init(void) { + #if MAX32_SERIAL + MXC_GCR->clkctrl |= MXC_F_GCR_CLKCTRL_IBRO_EN; + while (!(MXC_GCR->clkctrl & MXC_F_GCR_CLKCTRL_IBRO_RDY)) { + ; + } + MXC_UART_Init(CONSOLE_UART, 115200, MXC_UART_IBRO_CLK); + #endif +} + +bool port_serial_connected(void) { + return true; +} + +char port_serial_read(void) { + #if MAX32_SERIAL + // uint8_t data; + // HAL_UART_Receive(&huart2, &data, 1, 500); + // return data; + uint8_t rData; + + mxc_uart_req_t uart_req = { + .uart = CONSOLE_UART, + .rxCnt = 0, + .txCnt = 0, + .txData = NULL, + .rxData = &rData, + .txLen = 0, + .rxLen = 1 + }; + MXC_UART_Transaction(&uart_req); + return rData; + #else + return -1; + #endif +} + +uint32_t port_serial_bytes_available(void) { + #if MAX32_SERIAL + return MXC_UART_GetRXFIFOAvailable(CONSOLE_UART); + #else + return 0; + #endif +} + +void port_serial_write_substring(const char *text, uint32_t len) { + #if MAX32_SERIAL + mxc_uart_req_t uart_req = { + .uart = CONSOLE_UART, + .rxCnt = 0, + .txCnt = 0, + .txData = (const unsigned char *)text, + .rxData = NULL, + .txLen = len, + .rxLen = 0 + }; + MXC_UART_Transaction(&uart_req); + #endif +} diff --git a/ports/analog/supervisor/usb.c b/ports/analog/supervisor/usb.c new file mode 100644 index 000000000000..1624359ab51f --- /dev/null +++ b/ports/analog/supervisor/usb.c @@ -0,0 +1,43 @@ +// This file is part of the CircuitPython project: https://circuitpython.org +// +// SPDX-FileCopyrightText: Copyright (c) 2018 hathach for Adafruit Industries +// SPDX-FileCopyrightText: Copyright (c) 2024 Brandon Hurst, Analog Devices, Inc +// +// SPDX-License-Identifier: MIT + +#include "supervisor/usb.h" +#include "common-hal/microcontroller/Pin.h" + +#include "py/mpconfig.h" + +#include "lib/tinyusb/src/device/usbd.h" + +// max32 includes +#include "mxc_sys.h" +#include "gcr_regs.h" +#include "mcr_regs.h" + +void init_usb_hardware(void) { + // USB GPIOs are non-configurable on MAX32 devices + // No need to add them to the never_reset list for mcu/Pin API. + + // 1 ms SysTick initialized in board.c + + // Enable requisite clocks & power for USB + MXC_SYS_ClockSourceEnable(MXC_SYS_CLOCK_IPO); + MXC_MCR->ldoctrl |= MXC_F_MCR_LDOCTRL_0P9EN; + MXC_SYS_ClockEnable(MXC_SYS_PERIPH_CLOCK_USB); + MXC_SYS_Reset_Periph(MXC_SYS_RESET0_USB); + + // Supervisor calls TinyUSB's dcd_init, + // which initializes the USB PHY. + // Depending on CIRCUITPY_TINYUSB and CIRCUITPY_USB_DEVICE + + // Interrupt enables are left to TUSB depending on the device class +} + +void USB_IRQHandler(void) { + // Schedules USB background callback + // appropriate to a given device class via TinyUSB lib + usb_irq_handler(0); +} diff --git a/ports/analog/tools/flash_max32.jlink b/ports/analog/tools/flash_max32.jlink new file mode 100644 index 000000000000..4c9cbacb96fe --- /dev/null +++ b/ports/analog/tools/flash_max32.jlink @@ -0,0 +1,6 @@ +si 1 +erase +loadbin build-APARD/firmware.bin 0x10000000 +r +g +exit diff --git a/shared-module/storage/__init__.c b/shared-module/storage/__init__.c index 12486aff752f..850b7a33fc90 100644 --- a/shared-module/storage/__init__.c +++ b/shared-module/storage/__init__.c @@ -92,6 +92,11 @@ size_t storage_usb_add_descriptor(uint8_t *descriptor_buf, descriptor_counts_t * descriptor_buf[MSC_IN_ENDPOINT_INDEX] = 0x80 | (USB_MSC_EP_NUM_IN ? USB_MSC_EP_NUM_IN : descriptor_counts->current_endpoint); descriptor_counts->num_in_endpoints++; + // Some TinyUSB devices have issues with bi-directional endpoints + #ifdef TUD_ENDPOINT_ONE_DIRECTION_ONLY + descriptor_counts->current_endpoint++; + #endif + descriptor_buf[MSC_OUT_ENDPOINT_INDEX] = USB_MSC_EP_NUM_OUT ? USB_MSC_EP_NUM_OUT : descriptor_counts->current_endpoint; descriptor_counts->num_out_endpoints++; diff --git a/shared-module/usb_cdc/__init__.c b/shared-module/usb_cdc/__init__.c index 502d8fa620e0..0248c0f180fd 100644 --- a/shared-module/usb_cdc/__init__.c +++ b/shared-module/usb_cdc/__init__.c @@ -192,6 +192,11 @@ size_t usb_cdc_add_descriptor(uint8_t *descriptor_buf, descriptor_counts_t *desc ? (USB_CDC_EP_NUM_DATA_IN ? USB_CDC_EP_NUM_DATA_IN : descriptor_counts->current_endpoint) : (USB_CDC2_EP_NUM_DATA_IN ? USB_CDC2_EP_NUM_DATA_IN : descriptor_counts->current_endpoint)); descriptor_counts->num_in_endpoints++; + // Some TinyUSB devices have issues with bi-directional endpoints + #ifdef TUD_ENDPOINT_ONE_DIRECTION_ONLY + descriptor_counts->current_endpoint++; + #endif + descriptor_buf[CDC_DATA_OUT_ENDPOINT_INDEX] = console ? (USB_CDC_EP_NUM_DATA_OUT ? USB_CDC_EP_NUM_DATA_OUT : descriptor_counts->current_endpoint) diff --git a/shared-module/usb_hid/__init__.c b/shared-module/usb_hid/__init__.c index b007bc3ac2d4..4d0d5fc2e3d5 100644 --- a/shared-module/usb_hid/__init__.c +++ b/shared-module/usb_hid/__init__.c @@ -172,6 +172,12 @@ size_t usb_hid_add_descriptor(uint8_t *descriptor_buf, descriptor_counts_t *desc descriptor_buf[HID_IN_ENDPOINT_INDEX] = 0x80 | (USB_HID_EP_NUM_IN ? USB_HID_EP_NUM_IN : descriptor_counts->current_endpoint); descriptor_counts->num_in_endpoints++; + + // Some TinyUSB devices have issues with bi-directional endpoints + #ifdef TUD_ENDPOINT_ONE_DIRECTION_ONLY + descriptor_counts->current_endpoint++; + #endif + descriptor_buf[HID_OUT_ENDPOINT_INDEX] = USB_HID_EP_NUM_OUT ? USB_HID_EP_NUM_OUT : descriptor_counts->current_endpoint; descriptor_counts->num_out_endpoints++; diff --git a/shared-module/usb_midi/__init__.c b/shared-module/usb_midi/__init__.c index e0853e4e2a7a..3808801ff7e1 100644 --- a/shared-module/usb_midi/__init__.c +++ b/shared-module/usb_midi/__init__.c @@ -176,6 +176,12 @@ size_t usb_midi_add_descriptor(uint8_t *descriptor_buf, descriptor_counts_t *des descriptor_buf[MIDI_STREAMING_IN_ENDPOINT_INDEX] = 0x80 | (USB_MIDI_EP_NUM_IN ? USB_MIDI_EP_NUM_IN : descriptor_counts->current_endpoint); descriptor_counts->num_in_endpoints++; + + // Some TinyUSB devices have issues with bi-directional endpoints + #ifdef TUD_ENDPOINT_ONE_DIRECTION_ONLY + descriptor_counts->current_endpoint++; + #endif + descriptor_buf[MIDI_STREAMING_OUT_ENDPOINT_INDEX] = USB_MIDI_EP_NUM_OUT ? USB_MIDI_EP_NUM_OUT : descriptor_counts->current_endpoint; descriptor_counts->num_out_endpoints++; diff --git a/tests/pyboard.py b/tests/pyboard.py index 616773a313a1..582a1f894f8b 120000 --- a/tests/pyboard.py +++ b/tests/pyboard.py @@ -1 +1 @@ -../tools/cpboard.py \ No newline at end of file +../tools/cpboard.py diff --git a/tools/ci_fetch_deps.py b/tools/ci_fetch_deps.py index cbae4b3ff5e0..a06631bb307e 100644 --- a/tools/ci_fetch_deps.py +++ b/tools/ci_fetch_deps.py @@ -46,6 +46,12 @@ def matching_submodules(s): # Submodules needed by port builds outside of their ports directory. # Should we try and detect these? PORT_DEPS = { + "analog": [ + "extmod/ulab/", + "lib/tlsf/", + "lib/tinyusb/", + "lib/protomatter", + ], "atmel-samd": [ "extmod/ulab/", "lib/adafruit_floppy/",