diff --git a/.gitmodules b/.gitmodules index 4861053fe9..fbb74f013e 100644 --- a/.gitmodules +++ b/.gitmodules @@ -40,3 +40,6 @@ [submodule "tools/usb_descriptor"] path = tools/usb_descriptor url = https://github.com/adafruit/usb_descriptor.git +[submodule "lib/nrfutil"] + path = lib/nrfutil + url = https://github.com/adafruit/nRF52_nrfutil diff --git a/.travis.yml b/.travis.yml index 330ace5f2e..aeadbc90b1 100644 --- a/.travis.yml +++ b/.travis.yml @@ -13,6 +13,7 @@ env: - TRAVIS_BOARD=metro_m4_express - TRAVIS_BOARD=trinket_m0 - TRAVIS_BOARD=gemma_m0 + - TRAVIS_BOARD=feather52 - TRAVIS_TEST=qemu - TRAVIS_TEST=unix @@ -47,8 +48,10 @@ before_script: # For teensy build - sudo apt-get install realpath + # For nrf builds + - ([[ $TRAVIS_BOARD != "feather52" ]] || sudo ports/nrf/drivers/bluetooth/download_ble_stack.sh) # For coverage testing (upgrade is used to get latest urllib3 version) - - sudo pip install --upgrade cpp-coveralls + - ([[ -z "$TRAVIS_TEST" ]] || sudo pip install --upgrade cpp-coveralls) - gcc --version - ([[ -z "$TRAVIS_BOARD" ]] || arm-none-eabi-gcc --version) - python3 --version diff --git a/lib/nrfutil b/lib/nrfutil new file mode 160000 index 0000000000..07b43832ee --- /dev/null +++ b/lib/nrfutil @@ -0,0 +1 @@ +Subproject commit 07b43832ee53a4a248c30f5a3014e2632d8aeb88 diff --git a/ports/nrf/Makefile b/ports/nrf/Makefile index 8db3508e47..aff03443dc 100644 --- a/ports/nrf/Makefile +++ b/ports/nrf/Makefile @@ -1,6 +1,6 @@ # Select the board to build for: if not given on the command line, -# then default to pca10040. -BOARD ?= pca10040 +# then default to feather52. +BOARD ?= feather52 ifeq ($(wildcard boards/$(BOARD)/.),) $(error Invalid BOARD specified) endif @@ -11,33 +11,38 @@ SD_LOWER = $(shell echo $(SD) | tr '[:upper:]' '[:lower:]') # TODO: Verify that it is a valid target. - ifeq ($(SD), ) # If the build directory is not given, make it reflect the board name. BUILD ?= build-$(BOARD) include ../../py/mkenv.mk include boards/$(BOARD)/mpconfigboard.mk + -include mpconfigport.mk + +INC += -Idrivers/bluetooth/s132_$(MCU_VARIANT)_$(SOFTDEV_VERSION)/s132_$(MCU_VARIANT)_$(SOFTDEV_VERSION)_API/include +INC += -Idrivers/bluetooth/s132_$(MCU_VARIANT)_$(SOFTDEV_VERSION)/s132_$(MCU_VARIANT)_$(SOFTDEV_VERSION)_API/include/$(MCU_VARIANT) + else # If the build directory is not given, make it reflect the board name. BUILD ?= build-$(BOARD)-$(SD_LOWER) include ../../py/mkenv.mk include boards/$(BOARD)/mpconfigboard_$(SD_LOWER).mk + -include mpconfigport.mk include drivers/bluetooth/bluetooth_common.mk endif + # qstr definitions (must come before including py.mk) -QSTR_DEFS = qstrdefsport.h $(BUILD)/pins_qstr.h +QSTR_DEFS = qstrdefsport.h FROZEN_MPY_DIR = freeze # include py core make definitions include ../../py/py.mk +include $(TOP)/supervisor/supervisor.mk FATFS_DIR = lib/oofatfs -MPY_CROSS = ../../mpy-cross/mpy-cross -MPY_TOOL = ../../tools/mpy-tool.py CROSS_COMPILE = arm-none-eabi- @@ -105,22 +110,12 @@ LIBS += -L $(dir $(LIBC_FILE_NAME)) -lc LIBS += -L $(dir $(LIBGCC_FILE_NAME)) -lgcc endif -SRC_LIB = $(addprefix lib/,\ - libc/string0.c \ - mp-readline/readline.c \ - utils/pyexec.c \ - timeutils/timeutils.c \ - oofatfs/ff.c \ - oofatfs/option/unicode.c \ - ) - SRC_HAL = $(addprefix hal/,\ hal_uart.c \ hal_uarte.c \ hal_spi.c \ hal_spie.c \ hal_time.c \ - hal_rtc.c \ hal_timer.c \ hal_twi.c \ hal_adc.c \ @@ -136,17 +131,32 @@ SRC_HAL += $(addprefix hal/,\ ) endif + SRC_C += \ - main.c \ mphalport.c \ help.c \ - gccollect.c \ pin_named_pins.c \ fatfs_port.c \ + fifo.c \ drivers/softpwm.c \ drivers/ticker.c \ drivers/bluetooth/ble_drv.c \ drivers/bluetooth/ble_uart.c \ + boards/$(BOARD)/board.c \ + boards/$(BOARD)/pins.c \ + device/$(MCU_VARIANT)/system_$(MCU_SUB_VARIANT).c \ + device/$(MCU_VARIANT)/startup_$(MCU_SUB_VARIANT).c \ + lib/oofatfs/ff.c \ + lib/oofatfs/option/ccsbcs.c \ + lib/timeutils/timeutils.c \ + lib/utils/buffer_helper.c \ + lib/utils/context_manager_helpers.c \ + lib/utils/interrupt_char.c \ + lib/utils/pyexec.c \ + lib/libc/string0.c \ + lib/mp-readline/readline.c \ + internal_flash.c \ + DRIVERS_SRC_C += $(addprefix modules/,\ machine/modmachine.c \ @@ -156,11 +166,9 @@ DRIVERS_SRC_C += $(addprefix modules/,\ machine/adc.c \ machine/pin.c \ machine/timer.c \ - machine/rtc.c \ machine/pwm.c \ machine/led.c \ machine/temp.c \ - uos/moduos.c \ utime/modutime.c \ pyb/modpyb.c \ ubluepy/modubluepy.c \ @@ -179,18 +187,72 @@ DRIVERS_SRC_C += $(addprefix modules/,\ random/modrandom.c \ ) -SRC_C += \ - device/$(MCU_VARIANT)/system_$(MCU_SUB_VARIANT).c \ - device/$(MCU_VARIANT)/startup_$(MCU_SUB_VARIANT).c \ + +SRC_COMMON_HAL += \ + board/__init__.c \ + digitalio/__init__.c \ + digitalio/DigitalInOut.c \ + microcontroller/__init__.c \ + microcontroller/Pin.c \ + microcontroller/Processor.c \ + os/__init__.c \ + time/__init__.c \ + analogio/__init__.c \ + analogio/AnalogIn.c \ + analogio/AnalogOut.c \ + busio/__init__.c\ + busio/I2C.c \ + busio/SPI.c \ + pulseio/__init__.c \ + pulseio/PulseIn.c \ + pulseio/PulseOut.c \ + pulseio/PWMOut.c \ + storage/__init__.c \ + +# These don't have corresponding files in each port but are still located in +# shared-bindings to make it clear what the contents of the modules are. +SRC_BINDINGS_ENUMS = \ + digitalio/Direction.c \ + digitalio/DriveMode.c \ + digitalio/Pull.c \ + help.c \ + math/__init__.c \ + supervisor/__init__.c \ + util.c + +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 = \ + os/__init__.c \ + random/__init__.c \ + storage/__init__.c \ + +# bitbangio/__init__.c \ + bitbangio/I2C.c \ + bitbangio/OneWire.c \ + bitbangio/SPI.c \ + busio/OneWire.c \ + gamepad/__init__.c \ + gamepad/GamePad.c \ + struct/__init__.c \ + uheap/__init__.c \ + ustack/__init__.c + +#SRC_SHARED_MODULE_EXPANDED = $(addprefix shared-bindings/, $(SRC_SHARED_MODULE)) \ + $(addprefix shared-module/, $(SRC_SHARED_MODULE)) + +SRC_SHARED_MODULE_EXPANDED = $(addprefix shared-module/, $(SRC_SHARED_MODULE)) FROZEN_MPY_PY_FILES := $(shell find -L $(FROZEN_MPY_DIR) -type f -name '*.py') FROZEN_MPY_MPY_FILES := $(addprefix $(BUILD)/,$(FROZEN_MPY_PY_FILES:.py=.mpy)) -OBJ += $(PY_O) $(addprefix $(BUILD)/, $(SRC_C:.c=.o)) -OBJ += $(addprefix $(BUILD)/, $(SRC_LIB:.c=.o)) +OBJ += $(PY_O) $(SUPERVISOR_O) $(addprefix $(BUILD)/, $(SRC_C:.c=.o)) OBJ += $(addprefix $(BUILD)/, $(SRC_HAL:.c=.o)) OBJ += $(addprefix $(BUILD)/, $(DRIVERS_SRC_C:.c=.o)) -OBJ += $(BUILD)/pins_gen.o +OBJ += $(addprefix $(BUILD)/, $(SRC_COMMON_HAL_EXPANDED:.c=.o)) +OBJ += $(addprefix $(BUILD)/, $(SRC_SHARED_MODULE_EXPANDED:.c=.o)) $(BUILD)/$(FATFS_DIR)/ff.o: COPT += -Os $(filter $(PY_BUILD)/../extmod/vfs_fat_%.o, $(PY_O)): COPT += -Os @@ -241,11 +303,11 @@ endif $(BUILD)/$(OUTPUT_FILENAME).elf: $(OBJ) $(ECHO) "LINK $@" - $(Q)$(CC) $(LDFLAGS) -o $@ $(OBJ) $(LIBS) + $(Q)$(CC) $(LDFLAGS) -o $@ $(OBJ) -Wl,--start-group $(LIBS) -Wl,--end-group $(Q)$(SIZE) $@ # List of sources for qstr extraction -SRC_QSTR += $(SRC_C) $(SRC_MOD) $(SRC_LIB) $(DRIVERS_SRC_C) +SRC_QSTR += $(SRC_C) $(SRC_SUPERVISOR) $(SRC_MOD) $(DRIVERS_SRC_C) $(SRC_COMMON_HAL_EXPANDED) $(SRC_SHARED_MODULE_EXPANDED) # Append any auto-generated sources that are needed by sources listed in # SRC_QSTR @@ -256,16 +318,16 @@ SRC_QSTR_AUTO_DEPS += # any of the objects. The normal dependency generation will deal with the # case when pins.h is modified. But when it doesn't exist, we don't know # which source files might need it. -$(OBJ): | $(HEADER_BUILD)/pins.h +#$(OBJ): | $(HEADER_BUILD)/pins.h # Use a pattern rule here so that make will only call make-pins.py once to make # both pins_$(BOARD).c and pins.h -$(BUILD)/%_$(BOARD).c $(HEADER_BUILD)/%.h $(HEADER_BUILD)/%_af_const.h $(BUILD)/%_qstr.h: boards/$(BOARD)/%.csv $(MAKE_PINS) $(AF_FILE) $(PREFIX_FILE) | $(HEADER_BUILD) - $(ECHO) "Create $@" - $(Q)$(PYTHON) $(MAKE_PINS) --board $(BOARD_PINS) --af $(AF_FILE) --prefix $(PREFIX_FILE) --hdr $(GEN_PINS_HDR) --qstr $(GEN_PINS_QSTR) --af-const $(GEN_PINS_AF_CONST) --af-py $(GEN_PINS_AF_PY) > $(GEN_PINS_SRC) +#$(BUILD)/%_$(BOARD).c $(HEADER_BUILD)/%.h $(HEADER_BUILD)/%_af_const.h $(BUILD)/%_qstr.h: boards/$(BOARD)/%.csv $(MAKE_PINS) $(AF_FILE) $(PREFIX_FILE) | $(HEADER_BUILD) +# $(ECHO) "Create $@" +# $(Q)$(PYTHON) $(MAKE_PINS) --board $(BOARD_PINS) --af $(AF_FILE) --prefix $(PREFIX_FILE) --hdr $(GEN_PINS_HDR) --qstr $(GEN_PINS_QSTR) --af-const $(GEN_PINS_AF_CONST) --af-py $(GEN_PINS_AF_PY) > $(GEN_PINS_SRC) -$(BUILD)/pins_gen.o: $(BUILD)/pins_gen.c - $(call compile_c) +#$(BUILD)/pins_gen.o: $(BUILD)/pins_gen.c +# $(call compile_c) MAKE_PINS = boards/make-pins.py BOARD_PINS = boards/$(BOARD)/pins.csv @@ -290,4 +352,4 @@ CFLAGS += -DMICROPY_QSTR_EXTRA_POOL=mp_qstr_frozen_const_pool CFLAGS += -DMICROPY_MODULE_FROZEN_MPY endif -include ../../py/mkrules.mk +include $(TOP)/py/mkrules.mk diff --git a/ports/nrf/boards/board.h b/ports/nrf/boards/board.h new file mode 100644 index 0000000000..fecc0fb576 --- /dev/null +++ b/ports/nrf/boards/board.h @@ -0,0 +1,47 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2017 Scott Shawcroft for Adafruit Industries + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +// This file defines board specific functions. + +#ifndef MICROPY_INCLUDED_NRF_BOARDS_BOARD_H +#define MICROPY_INCLUDED_NRF_BOARDS_BOARD_H + +#include + +extern volatile uint32_t ticks_ms; + +// Initializes board related state once on start up. +void board_init(void); + +// 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); + +// Reset the state of off MCU components such as neopixels. +void reset_board(void); + +#endif // MICROPY_INCLUDED_NRF_BOARDS_BOARD_H diff --git a/ports/nrf/boards/common.ld b/ports/nrf/boards/common.ld index c6e4952b45..df81aae583 100644 --- a/ports/nrf/boards/common.ld +++ b/ports/nrf/boards/common.ld @@ -1,3 +1,7 @@ +/* Flash region for File System */ +__fatfs_flash_start_addr = ORIGIN(FLASH_FATFS); +__fatfs_flash_length = LENGTH(FLASH_FATFS); + /* define output sections */ SECTIONS { @@ -75,8 +79,8 @@ SECTIONS .heap : { . = ALIGN(4); - PROVIDE ( end = . ); - PROVIDE ( _end = . ); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); _heap_start = .; /* define a global symbol at heap start */ . = . + _minimum_heap_size; } >RAM @@ -101,3 +105,4 @@ SECTIONS .ARM.attributes 0 : { *(.ARM.attributes) } } + diff --git a/ports/nrf/boards/feather52/README.md b/ports/nrf/boards/feather52/README.md index e05d899533..d5e0026225 100644 --- a/ports/nrf/boards/feather52/README.md +++ b/ports/nrf/boards/feather52/README.md @@ -1,6 +1,10 @@ # Setup -Before you can build, you will need to run the following commands once: +## Installing CircuitPython submodules + +Before you can build, you will need to run the following commands once, which +will install the submodules that are part of the CircuitPython ecosystem, and +build the `mpy-cross` tool: ``` $ cd circuitpython @@ -8,7 +12,7 @@ $ git submodule update --init $ make -C mpy-cross ``` -You then need to download the SD and Nordic SDK files: +You then need to download the SD and Nordic SDK files via: > This script relies on `wget`, which must be available from the command line. @@ -17,47 +21,41 @@ $ cd ports/nrf $ ./drivers/bluetooth/download_ble_stack.sh ``` +## Installing `nrfutil` + +The Adafruit Bluefruit nRF52 Feather ships with a serial and OTA BLE bootloader +that can be used to flash firmware images over a simple serial connection, +using the on-board USB serial converter. + +If you haven't installed this command-line tool yet, go to the `/libs/nrfutil` +folder (where nrfutil 0.5.2 is installed as a sub-module) and run the following +commands: + +> If you get a 'sudo: pip: command not found' error running 'sudo pip install', +you can install pip via 'sudo easy_install pip' + +``` +$ cd ../../lib/nrfutil +$ sudo pip install -r requirements.txt +$ sudo python setup.py install +``` + # Building and flashing firmware images -## Building CircuitPython +## Building CircuitPython binaries #### REPL over UART (default settings) To build a CircuitPython binary with default settings for the `feather52` target enter: +> **NOTE:** `BOARD=feather52` is the default option and isn't stricly required. + ``` $ make BOARD=feather52 V=1 ``` -#### REPL over BLE UART (AKA `NUS`) - -To build a CircuitPython binary with REPL over BLE UART, edit -`bluetooth_conf.h` with the following values (under -`#elif (BLUETOOTH_SD == 132)`): - -``` -#define MICROPY_PY_BLE (1) -#define MICROPY_PY_BLE_NUS (1) -#define BLUETOOTH_WEBBLUETOOTH_REPL (1) -``` - -Then build the CircuitPython binary, including `SD=s132` -to enable BLE support in the build process: - -``` -$ make BOARD=feather52 V=1 SD=s132 -``` - -## Flashing with `nrfutil` - -The Adafruit Bluefruit nRF52 Feather ships with a serial and OTA BLE bootloader -that can be used to flash firmware images over a simple serial connection, -using the on-board USB serial converter. - -These commands assume that you have already installed `nrfutil`, as described -in the [learning guide](https://learn.adafruit.com/bluefruit-nrf52-feather-learning-guide/arduino-bsp-setup) -for the Arduino variant of the board. +## Flashing binaries with `nrfutil` ### 1. **Update bootloader** to single-bank version @@ -88,7 +86,7 @@ To enable BLE5 support and the latest S132 release, flash the v5.0.0 bootloader $ make BOARD=feather52 SERIAL=/dev/tty.SLAB_USBtoUART SOFTDEV_VERSION=5.0.0 boot-flash ``` -### 2. Generate a CircuitPython DFU .zip package and flash it over serial +### 2. Generate and flash a CircuitPython DFU .zip package over serial The following command will package and flash the CircuitPython binary using the appropriate bootloader mentionned above. @@ -102,9 +100,76 @@ image, as described earlier in this readme. $ make BOARD=feather52 SERIAL=/dev/tty.SLAB_USBtoUART dfu-gen dfu-flash ``` -If you built your CircuitPython binary with **BLE UART** support you will -need to add the `SD=s132` flag as shown below: +If you built your CircuitPython binary with **BLE** support you will need to +add the `SD=s132` flag as shown below: ``` $ make BOARD=feather52 SERIAL=/dev/tty.SLAB_USBtoUART SD=s132 dfu-gen dfu-flash ``` + +## Working with CircuitPython + +### Running local files with `ampy` + +[ampy](https://learn.adafruit.com/micropython-basics-load-files-and-run-code/install-ampy) +is a command-line tool that can be used with the nRF52 Feather to transfer +local python files to the nRF52 for execution, rather than having to enter +the REPL manually, enter paste mode, and paste the code yourself. + +> **IMPORTANT**: You must have `ampy` version **1.0.3** or higher to use `ampy` + with the nRF52. The bootloader on the nRF52 requires a delay between the + HW reset, and the moment when the command sequance is sent to enter raw + mode. This required `-d/--delay` flag was added in release 1.0.3. + + +Save the following file as `test.py`: + +``` +import board +import digitalio +import time + +led = digitalio.DigitalInOut(board.LED2) +led.direction = digitalio.Direction.OUTPUT + +while True: + led.value = True + time.sleep(0.5) + led.value = False + time.sleep(0.5) +``` + +Then run the saved file via ampy, updating the serial port as required: + +``` +$ ampy -p /dev/tty.SLAB_USBtoUART -d 1.5 run test.py +``` + +This should give you blinky at 1 Hz on LED2 (the blue LED on the nRF52 Feather). + +### Uploading files and libraries with `ampy` + +To upload Python files or pre-compiled CircuitPython libraries to the `lib` folder, +run the following commands: + +> In this example **i2c_device.py** is used, which is part of + [Adafruit_CircuitPython_BusDevice](https://github.com/adafruit/Adafruit_CircuitPython_BusDevice) + +``` +$ ampy -p /dev/tty.SLAB_USBtoUART -d 1.5 put i2c_device.py lib/i2c_device.py +``` + +To verify that the file was uploaded correctly, you can check the contents of +the `lib` folder with: + +``` +$ ampy -p /dev/tty.SLAB_USBtoUART -d 1.5 ls /lib +i2c_device.py +``` + +### Suggested libraries + +The following libraries should be installed as a minimum on most new boards: + +- [Adafruit_CircuitPython_BusDevice](https://github.com/adafruit/Adafruit_CircuitPython_BusDevice) +- [Adafruit_CircuitPython_Register](https://github.com/adafruit/Adafruit_CircuitPython_Register/tree/master) diff --git a/ports/nrf/boards/feather52/board.c b/ports/nrf/boards/feather52/board.c new file mode 100644 index 0000000000..c550e90614 --- /dev/null +++ b/ports/nrf/boards/feather52/board.c @@ -0,0 +1,114 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2017 Scott Shawcroft for Adafruit Industries + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#include +#include + +#include "nrf.h" + +#include "boards/board.h" + +// Must match temp register in bootloader +#define BOOTLOADER_VERSION_REGISTER NRF_TIMER2->CC[0] +uint32_t bootloaderVersion = 0; + +volatile uint32_t ticks_ms = 0; + +#define HAL_LFCLK_FREQ (32768UL) +#define HAL_RTC_FREQ (1024UL) +#define HAL_RTC_COUNTER_PRESCALER ((HAL_LFCLK_FREQ/HAL_RTC_FREQ)-1) + +/* Maximum RTC ticks */ +#define portNRF_RTC_MAXTICKS ((1U<<24)-1U) + +void board_init(void) +{ + // Retrieve bootloader version + bootloaderVersion = BOOTLOADER_VERSION_REGISTER; + + // 32Khz XTAL + NRF_CLOCK->LFCLKSRC = (uint32_t)((CLOCK_LFCLKSRC_SRC_Xtal << CLOCK_LFCLKSRC_SRC_Pos) & CLOCK_LFCLKSRC_SRC_Msk); + NRF_CLOCK->TASKS_LFCLKSTART = 1UL; + + // Set up RTC1 as tick timer + NVIC_DisableIRQ(RTC1_IRQn); + NRF_RTC1->EVTENCLR = RTC_EVTEN_COMPARE0_Msk; + NRF_RTC1->INTENCLR = RTC_INTENSET_COMPARE0_Msk; + NRF_RTC1->TASKS_STOP = 1; + NRF_RTC1->TASKS_CLEAR = 1; + + ticks_ms = 0; + + NRF_RTC1->PRESCALER = HAL_RTC_COUNTER_PRESCALER; + NRF_RTC1->INTENSET = RTC_INTENSET_TICK_Msk; + NRF_RTC1->TASKS_START = 1; + NRF_RTC1->EVTENSET = RTC_EVTEN_OVRFLW_Msk; + NVIC_SetPriority(RTC1_IRQn, 0xf); // lowest priority + NVIC_EnableIRQ(RTC1_IRQn); +} + +void RTC1_IRQHandler(void) +{ + // Clear event + NRF_RTC1->EVENTS_TICK = 0; + volatile uint32_t dummy = NRF_RTC1->EVENTS_TICK; + (void) dummy; + + // Tick correction + uint32_t systick_counter = NRF_RTC1->COUNTER; + uint32_t diff = (systick_counter - ticks_ms) & portNRF_RTC_MAXTICKS; + ticks_ms += diff; +} + +// Check the status of the two buttons on CircuitPlayground Express. If both are +// pressed, then boot into user safe mode. +bool board_requests_safe_mode(void) { +// gpio_set_pin_function(PIN_PA14, GPIO_PIN_FUNCTION_OFF); +// gpio_set_pin_direction(PIN_PA14, GPIO_DIRECTION_IN); +// gpio_set_pin_pull_mode(PIN_PA14, GPIO_PULL_DOWN); +// +// gpio_set_pin_function(PIN_PA28, GPIO_PIN_FUNCTION_OFF); +// gpio_set_pin_direction(PIN_PA28, GPIO_DIRECTION_IN); +// gpio_set_pin_pull_mode(PIN_PA28, GPIO_PULL_DOWN); +// bool safe_mode = gpio_get_pin_level(PIN_PA14) && +// gpio_get_pin_level(PIN_PA28); +// reset_pin(PIN_PA14); +// reset_pin(PIN_PA28); +// return safe_mode; + + return false; +} + +void reset_board(void) { +// uint8_t empty[30]; +// memset(empty, 0, 30); +// digitalio_digitalinout_obj_t neopixel_pin; +// common_hal_digitalio_digitalinout_construct(&neopixel_pin, &pin_PB23); +// common_hal_digitalio_digitalinout_switch_to_output(&neopixel_pin, false, +// DRIVE_MODE_PUSH_PULL); +// common_hal_neopixel_write(&neopixel_pin, empty, 30); +// common_hal_digitalio_digitalinout_deinit(&neopixel_pin); +} diff --git a/ports/nrf/boards/feather52/bootloader/.gitattributes b/ports/nrf/boards/feather52/bootloader/.gitattributes new file mode 100644 index 0000000000..608f8c345c --- /dev/null +++ b/ports/nrf/boards/feather52/bootloader/.gitattributes @@ -0,0 +1,2 @@ +# Inform git that .zip files should be treated as binary +*.zip binary diff --git a/ports/nrf/boards/feather52/bootloader/README.md b/ports/nrf/boards/feather52/bootloader/README.md new file mode 100644 index 0000000000..4348590859 --- /dev/null +++ b/ports/nrf/boards/feather52/bootloader/README.md @@ -0,0 +1,9 @@ +# Adafruit nRF52 Feather Single-Bank Bootloader + +These files contain an implementation of a single-bank bootloader, +which doubles the amount of flash memory available to applications +at the expense of safe over the air updates. + +Two versions are present, based on release **2.0.1** and **5.0.0** +of the Nordic S132 SoftDevice. The SoftDevice is included as poart +of the bootloader binary. diff --git a/ports/nrf/boards/feather52/bootloader/feather52_bootloader_2.0.1_s132_single.zip b/ports/nrf/boards/feather52/bootloader/feather52_bootloader_2.0.1_s132_single.zip index 14e3bf7d68..42a83bb907 100644 Binary files a/ports/nrf/boards/feather52/bootloader/feather52_bootloader_2.0.1_s132_single.zip and b/ports/nrf/boards/feather52/bootloader/feather52_bootloader_2.0.1_s132_single.zip differ diff --git a/ports/nrf/boards/feather52/custom_nrf52832_dfu_app_2.0.1.ld b/ports/nrf/boards/feather52/custom_nrf52832_dfu_app_2.0.1.ld index 824b6becfe..183822f92a 100644 --- a/ports/nrf/boards/feather52/custom_nrf52832_dfu_app_2.0.1.ld +++ b/ports/nrf/boards/feather52/custom_nrf52832_dfu_app_2.0.1.ld @@ -5,10 +5,15 @@ ------------------------------------------------------------------------ START ADDR END ADDR SIZE DESCRIPTION ---------- ---------- ------- ----------------------------------------- - 0x00074000..0x00080000 ( 48KB) Serial + OTA Bootloader - 0x0006D000..0x00073FFF ( 28KB) Private Config Data (Bonding, Keys, etc.) - 0x00055000..0x0006CFFF ( 96KB) User Filesystem - 0x0001C000..0x00054FFF (228KB) Application Code + 0x0007F000..0x0007FFFF ( 4KB) Bootloader Settings + 0x0007E000..0x0007EFFF ( 4KB) Master Boot Record Params + 0x00074000..0x0007DFFF ( 40KB) Serial + OTA Bootloader + + 0x00073000..0x00073FFF ( 4KB ) Private Config Data (Bonding, Keys, etc.) + 0x00072000..0x00072FFF ( 4KB ) User NVM data + 0x00059000..0x00071FFF (100KB) User Filesystem + + 0x0001C000..0x00058FFF (244KB) Application Code 0x00001000..0x0001BFFF (108KB) SoftDevice 0x00000000..0x00000FFF (4KB) Master Boot Record */ @@ -16,15 +21,16 @@ /* Specify the memory areas (S132 2.0.1) */ MEMORY { - FLASH (rx) : ORIGIN = 0x00000000, LENGTH = 0x080000 /* entire flash, 512 KiB */ - FLASH_ISR (rx) : ORIGIN = 0x0001c000, LENGTH = 0x001000 /* sector 0, 4 KiB */ - FLASH_TEXT (rx) : ORIGIN = 0x0001d000, LENGTH = 0x038000 /* APP - ISR, 224 KiB */ - RAM (xrw) : ORIGIN = 0x200039c0, LENGTH = 0x0c640 /* 49.5 KiB, give 8KiB headroom for softdevice */ + FLASH (rx) : ORIGIN = 0x00000000, LENGTH = 0x080000 /* entire flash, 512 KiB */ + FLASH_ISR (rx) : ORIGIN = 0x0001c000, LENGTH = 0x001000 /* sector 0, 4 KiB */ + FLASH_TEXT (rx) : ORIGIN = 0x0001d000, LENGTH = 0x03C000 /* APP - ISR, 240 KiB */ + FLASH_FATFS (r) : ORIGIN = 0x00059000, LENGTH = 0x019000 /* File system 100KB KB */ + RAM (xrw) : ORIGIN = 0x200039c0, LENGTH = 0x0c640 /* 49.5 KiB, give 8KiB headroom for softdevice */ } /* produce a link error if there is not this amount of RAM for these sections */ _minimum_stack_size = 2K; -_minimum_heap_size = 16K; +_minimum_heap_size = 0 /*16K Circuit Python use static variable for HEAP */; /* top end of the stack */ @@ -35,4 +41,4 @@ _estack = ORIGIN(RAM) + LENGTH(RAM); _ram_end = ORIGIN(RAM) + LENGTH(RAM); _heap_end = 0x20007000; /* tunable */ -INCLUDE "boards/common.ld" \ No newline at end of file +INCLUDE "boards/common.ld" diff --git a/ports/nrf/boards/feather52/custom_nrf52832_dfu_app_5.0.0.ld b/ports/nrf/boards/feather52/custom_nrf52832_dfu_app_5.0.0.ld index e7a09303b9..f9209bf3d1 100644 --- a/ports/nrf/boards/feather52/custom_nrf52832_dfu_app_5.0.0.ld +++ b/ports/nrf/boards/feather52/custom_nrf52832_dfu_app_5.0.0.ld @@ -5,10 +5,15 @@ ------------------------------------------------------------------------ START ADDR END ADDR SIZE DESCRIPTION ---------- ---------- ------- ----------------------------------------- - 0x00074000..0x00080000 ( 48KB) Serial + OTA Bootloader - 0x0006D000..0x00073FFF ( 28KB) Private Config Data (Bonding, Keys, etc.) - 0x00055000..0x0006CFFF ( 96KB) User Filesystem - 0x00023000..0x00054FFF (200KB) Application Code + 0x0007F000..0x0007FFFF ( 4KB) Bootloader Settings + 0x0007E000..0x0007EFFF ( 4KB) Master Boot Record Params + 0x00074000..0x0007DFFF ( 40KB) Serial + OTA Bootloader + + 0x00073000..0x00073FFF ( 4KB ) Private Config Data (Bonding, Keys, etc.) + 0x00072000..0x00072FFF ( 4KB ) User NVM data + 0x00059000..0x00071FFF ( 100KB) User Filesystem + + 0x00023000..0x00058FFF (216KB) Application Code 0x00001000..0x00022FFF (136KB) SoftDevice 0x00000000..0x00000FFF (4KB) Master Boot Record */ @@ -18,13 +23,14 @@ MEMORY { FLASH (rx) : ORIGIN = 0x00000000, LENGTH = 0x080000 /* entire flash, 512 KiB */ FLASH_ISR (rx) : ORIGIN = 0x00023000, LENGTH = 0x001000 /* sector 0, 4 KiB */ - FLASH_TEXT (rx) : ORIGIN = 0x00024000, LENGTH = 0x030FFF /* APP - ISR, 200 KiB */ + FLASH_TEXT (rx) : ORIGIN = 0x00024000, LENGTH = 0x036000 /* APP - ISR, 216 KiB */ + FLASH_FATFS (r) : ORIGIN = 0x00059000, LENGTH = 0x019000 /* File system 100KB KB */ RAM (xrw) : ORIGIN = 0x200039c0, LENGTH = 0x0c640 /* 49.5 KiB, give 8KiB headroom for softdevice */ } /* produce a link error if there is not this amount of RAM for these sections */ _minimum_stack_size = 2K; -_minimum_heap_size = 16K; +_minimum_heap_size = 0 /*16K Circuit Python use static variable for HEAP */; /* top end of the stack */ diff --git a/ports/nrf/boards/feather52/examples/blinky.py b/ports/nrf/boards/feather52/examples/blinky.py new file mode 100644 index 0000000000..29cca26d04 --- /dev/null +++ b/ports/nrf/boards/feather52/examples/blinky.py @@ -0,0 +1,12 @@ +import board +import digitalio +import time + +led = digitalio.DigitalInOut(board.LED2) +led.direction = digitalio.Direction.OUTPUT + +while True: + led.value = True + time.sleep(0.5) + led.value = False + time.sleep(0.5) diff --git a/ports/nrf/boards/feather52/examples/i2c_scan.py b/ports/nrf/boards/feather52/examples/i2c_scan.py new file mode 100644 index 0000000000..8e3ef557d1 --- /dev/null +++ b/ports/nrf/boards/feather52/examples/i2c_scan.py @@ -0,0 +1,20 @@ +import board +import busio + +i2c = busio.I2C(board.SCL, board.SDA) +count = 0 + +# Wait for I2C lock +while not i2c.try_lock(): + pass + +# Scan for devices on the I2C bus +print("Scanning I2C bus") +for x in i2c.scan(): + print(hex(x)) + count += 1 + +print("%d device(s) found on I2C bus" % count) + +# Release the I2C bus +i2c.unlock() diff --git a/ports/nrf/boards/feather52/examples/pulseio.py b/ports/nrf/boards/feather52/examples/pulseio.py new file mode 100644 index 0000000000..cdbe16addd --- /dev/null +++ b/ports/nrf/boards/feather52/examples/pulseio.py @@ -0,0 +1,25 @@ +import time +from board import * +from pulseio import * + +# Setup BLUE and RED LEDs as PWM output (default frequency is 500 Hz) +ledb = PWMOut(LED2) +ledr = PWMOut(LED1) + +# Set the BLUE LED to have a duty cycle of 5000 (out of 65535, so ~7.5%) +ledb.duty_cycle = 5000 + +# Setup pin A0 as a standard PWM out @ 50% to test on the oscilloscope. +# You should see a 50% duty cycle waveform at ~500Hz on the scope when you +# connect a probe to pin A0 +a0 = PWMOut(A0) +a0.duty_cycle = int(65535/2) + +# Constantly pulse the RED LED +while True: + for i in range(100): + ledr.duty_cycle = int(i / 100 * 65535) + time.sleep(0.01) + for i in range(100, -1, -1): + ledr.duty_cycle = int(i / 100 * 65535) + time.sleep(0.01) diff --git a/ports/nrf/boards/feather52/mpconfigboard.h b/ports/nrf/boards/feather52/mpconfigboard.h index fca9274b79..555cffde41 100644 --- a/ports/nrf/boards/feather52/mpconfigboard.h +++ b/ports/nrf/boards/feather52/mpconfigboard.h @@ -24,8 +24,6 @@ * THE SOFTWARE. */ -#define PCA10040 - #define MICROPY_HW_BOARD_NAME "Bluefruit nRF52 Feather" #define MICROPY_HW_MCU_NAME "NRF52832" #define MICROPY_PY_SYS_PLATFORM "nrf52" @@ -33,7 +31,7 @@ #define MICROPY_PY_MACHINE_HW_PWM (1) #define MICROPY_PY_MACHINE_HW_SPI (1) #define MICROPY_PY_MACHINE_TIMER (1) -#define MICROPY_PY_MACHINE_RTC (1) +#define MICROPY_PY_MACHINE_RTC (0) #define MICROPY_PY_MACHINE_I2C (1) #define MICROPY_PY_MACHINE_ADC (1) #define MICROPY_PY_MACHINE_TEMP (1) @@ -59,18 +57,23 @@ #define MICROPY_HW_LED2 (19) // LED2 // UART config -#define MICROPY_HW_UART1_RX (pin_A8) -#define MICROPY_HW_UART1_TX (pin_A6) +#define MICROPY_HW_UART1_RX (pin_PA08) +#define MICROPY_HW_UART1_TX (pin_PA06) #define MICROPY_HW_UART1_HWFC (0) // SPI0 config #define MICROPY_HW_SPI0_NAME "SPI0" -#define MICROPY_HW_SPI0_SCK (pin_A12) // (Arduino D13) -#define MICROPY_HW_SPI0_MOSI (pin_A13) // (Arduino D11) -#define MICROPY_HW_SPI0_MISO (pin_A14) // (Arduino D12) +#define MICROPY_HW_SPI0_SCK (pin_PA12) // (Arduino D13) +#define MICROPY_HW_SPI0_MOSI (pin_PA13) // (Arduino D11) +#define MICROPY_HW_SPI0_MISO (pin_PA14) // (Arduino D12) #define MICROPY_HW_PWM0_NAME "PWM0" #define MICROPY_HW_PWM1_NAME "PWM1" #define MICROPY_HW_PWM2_NAME "PWM2" #define HELP_TEXT_BOARD_LED "1,2" + + + +#define PORT_HEAP_SIZE (32*1024) +#define CIRCUITPY_AUTORELOAD_DELAY_MS 500 diff --git a/ports/nrf/boards/feather52/mpconfigboard.mk b/ports/nrf/boards/feather52/mpconfigboard.mk index 30f64ca43c..089189e9f5 100644 --- a/ports/nrf/boards/feather52/mpconfigboard.mk +++ b/ports/nrf/boards/feather52/mpconfigboard.mk @@ -8,7 +8,7 @@ BOOTLOADER_PKG = boards/feather52/bootloader/feather52_bootloader_$(SOFTDEV_VERS NRF_DEFINES += -DNRF52832_XXAA - +CFLAGS += -DADAFRUIT_FEATHER52 check_defined = \ $(strip $(foreach 1,$1, \ diff --git a/ports/nrf/boards/feather52/pins.c b/ports/nrf/boards/feather52/pins.c new file mode 100644 index 0000000000..36ce2cc6f3 --- /dev/null +++ b/ports/nrf/boards/feather52/pins.c @@ -0,0 +1,126 @@ +// This file was automatically generated by make-pins.py +// +// --af nrf52_af.csv +// --board boards/feather52/pins.csv +// --prefix boards/nrf52_prefix.c + +// nrf52_prefix.c becomes the initial portion of the generated pins file. + +#include + +#include "py/obj.h" +#include "py/mphal.h" +#include "pin.h" + +#define AF(af_idx, af_fn, af_unit, af_type, af_ptr) \ +{ \ + { &pin_af_type }, \ + .name = MP_QSTR_AF ## af_idx ## _ ## af_fn ## af_unit, \ + .idx = (af_idx), \ + .fn = AF_FN_ ## af_fn, \ + .unit = (af_unit), \ + .type = AF_PIN_TYPE_ ## af_fn ## _ ## af_type, \ + .af_fn = (af_ptr) \ +} + +#define PIN(p_port, p_pin, p_af, p_adc_channel) \ +{ \ + { &mcu_pin_type }, \ + .name = MP_QSTR_ ## p_port ## p_pin, \ + .port = PORT_ ## p_port, \ + .pin = (p_pin), \ + .num_af = (sizeof(p_af) / sizeof(pin_af_obj_t)), \ + /*.pin_mask = (1 << p_pin), */\ + .af = p_af, \ + .adc_channel = p_adc_channel,\ +} + +#define NO_ADC 0 + +const pin_obj_t pin_PA02 = PIN(A, 2, NULL, SAADC_CH_PSELP_PSELP_AnalogInput0); +const pin_obj_t pin_PA03 = PIN(A, 3, NULL, SAADC_CH_PSELP_PSELP_AnalogInput1); +const pin_obj_t pin_PA04 = PIN(A, 4, NULL, SAADC_CH_PSELP_PSELP_AnalogInput2); +const pin_obj_t pin_PA05 = PIN(A, 5, NULL, SAADC_CH_PSELP_PSELP_AnalogInput3); +const pin_obj_t pin_PA06 = PIN(A, 6, NULL, NO_ADC); +const pin_obj_t pin_PA07 = PIN(A, 7, NULL, NO_ADC); +const pin_obj_t pin_PA08 = PIN(A, 8, NULL, NO_ADC); +const pin_obj_t pin_PA09 = PIN(A, 9, NULL, NO_ADC); +const pin_obj_t pin_PA10 = PIN(A, 10, NULL, NO_ADC); +const pin_obj_t pin_PA11 = PIN(A, 11, NULL, NO_ADC); +const pin_obj_t pin_PA12 = PIN(A, 12, NULL, NO_ADC); +const pin_obj_t pin_PA13 = PIN(A, 13, NULL, NO_ADC); +const pin_obj_t pin_PA14 = PIN(A, 14, NULL, NO_ADC); +const pin_obj_t pin_PA15 = PIN(A, 15, NULL, NO_ADC); +const pin_obj_t pin_PA16 = PIN(A, 16, NULL, NO_ADC); +const pin_obj_t pin_PA17 = PIN(A, 17, NULL, NO_ADC); + +const pin_obj_t pin_PA19 = PIN(A, 19, NULL, NO_ADC); +const pin_obj_t pin_PA20 = PIN(A, 20, NULL, NO_ADC); + +const pin_obj_t pin_PA25 = PIN(A, 25, NULL, NO_ADC); +const pin_obj_t pin_PA26 = PIN(A, 26, NULL, NO_ADC); +const pin_obj_t pin_PA27 = PIN(A, 27, NULL, NO_ADC); +const pin_obj_t pin_PA28 = PIN(A, 28, NULL, SAADC_CH_PSELP_PSELP_AnalogInput4); +const pin_obj_t pin_PA29 = PIN(A, 29, NULL, SAADC_CH_PSELP_PSELP_AnalogInput5); +const pin_obj_t pin_PA30 = PIN(A, 30, NULL, SAADC_CH_PSELP_PSELP_AnalogInput6); +const pin_obj_t pin_PA31 = PIN(A, 31, NULL, SAADC_CH_PSELP_PSELP_AnalogInput7); + +STATIC const mp_rom_map_elem_t mcu_pin_globals_table[] = { + { MP_ROM_QSTR(MP_QSTR_PA02), MP_ROM_PTR(&pin_PA02) }, + { MP_ROM_QSTR(MP_QSTR_PA03), MP_ROM_PTR(&pin_PA03) }, + { MP_ROM_QSTR(MP_QSTR_PA04), MP_ROM_PTR(&pin_PA04) }, + { MP_ROM_QSTR(MP_QSTR_PA05), MP_ROM_PTR(&pin_PA05) }, + { MP_ROM_QSTR(MP_QSTR_PA06), MP_ROM_PTR(&pin_PA06) }, + { MP_ROM_QSTR(MP_QSTR_PA07), MP_ROM_PTR(&pin_PA07) }, + { MP_ROM_QSTR(MP_QSTR_PA08), MP_ROM_PTR(&pin_PA08) }, + { MP_ROM_QSTR(MP_QSTR_PA09), MP_ROM_PTR(&pin_PA09) }, + { MP_ROM_QSTR(MP_QSTR_PA10), MP_ROM_PTR(&pin_PA10) }, + { MP_ROM_QSTR(MP_QSTR_PA11), MP_ROM_PTR(&pin_PA11) }, + { MP_ROM_QSTR(MP_QSTR_PA12), MP_ROM_PTR(&pin_PA12) }, + { MP_ROM_QSTR(MP_QSTR_PA13), MP_ROM_PTR(&pin_PA13) }, + { MP_ROM_QSTR(MP_QSTR_PA14), MP_ROM_PTR(&pin_PA14) }, + { MP_ROM_QSTR(MP_QSTR_PA15), MP_ROM_PTR(&pin_PA15) }, + { MP_ROM_QSTR(MP_QSTR_PA16), MP_ROM_PTR(&pin_PA16) }, + { MP_ROM_QSTR(MP_QSTR_PA17), MP_ROM_PTR(&pin_PA17) }, + { MP_ROM_QSTR(MP_QSTR_PA19), MP_ROM_PTR(&pin_PA19) }, + { MP_ROM_QSTR(MP_QSTR_PA20), MP_ROM_PTR(&pin_PA20) }, + { MP_ROM_QSTR(MP_QSTR_PA25), MP_ROM_PTR(&pin_PA25) }, + { MP_ROM_QSTR(MP_QSTR_PA26), MP_ROM_PTR(&pin_PA26) }, + { MP_ROM_QSTR(MP_QSTR_PA27), MP_ROM_PTR(&pin_PA27) }, + { MP_ROM_QSTR(MP_QSTR_PA28), MP_ROM_PTR(&pin_PA28) }, + { MP_ROM_QSTR(MP_QSTR_PA29), MP_ROM_PTR(&pin_PA29) }, + { MP_ROM_QSTR(MP_QSTR_PA30), MP_ROM_PTR(&pin_PA30) }, + { MP_ROM_QSTR(MP_QSTR_PA31), MP_ROM_PTR(&pin_PA31) }, +}; +MP_DEFINE_CONST_DICT(mcu_pin_globals, mcu_pin_globals_table); + +STATIC const mp_rom_map_elem_t board_module_globals_table[] = { + { MP_ROM_QSTR(MP_QSTR_A0 ), MP_ROM_PTR(&pin_PA02) }, + { MP_ROM_QSTR(MP_QSTR_A1 ), MP_ROM_PTR(&pin_PA03) }, + { MP_ROM_QSTR(MP_QSTR_A2 ), MP_ROM_PTR(&pin_PA04) }, + { MP_ROM_QSTR(MP_QSTR_A3 ), MP_ROM_PTR(&pin_PA05) }, + { MP_ROM_QSTR(MP_QSTR_TX ), MP_ROM_PTR(&pin_PA06) }, + { MP_ROM_QSTR(MP_QSTR_A7 ), MP_ROM_PTR(&pin_PA07) }, + { MP_ROM_QSTR(MP_QSTR_RX ), MP_ROM_PTR(&pin_PA08) }, + { MP_ROM_QSTR(MP_QSTR_NFC1 ), MP_ROM_PTR(&pin_PA09) }, + { MP_ROM_QSTR(MP_QSTR_NFC2 ), MP_ROM_PTR(&pin_PA10) }, + { MP_ROM_QSTR(MP_QSTR_D11 ), MP_ROM_PTR(&pin_PA11) }, + { MP_ROM_QSTR(MP_QSTR_SCK ), MP_ROM_PTR(&pin_PA12) }, + { MP_ROM_QSTR(MP_QSTR_MOSI ), MP_ROM_PTR(&pin_PA13) }, + { MP_ROM_QSTR(MP_QSTR_MISO ), MP_ROM_PTR(&pin_PA14) }, + { MP_ROM_QSTR(MP_QSTR_D15 ), MP_ROM_PTR(&pin_PA15) }, + { MP_ROM_QSTR(MP_QSTR_D16 ), MP_ROM_PTR(&pin_PA16) }, + { MP_ROM_QSTR(MP_QSTR_LED1 ), MP_ROM_PTR(&pin_PA17) }, + { MP_ROM_QSTR(MP_QSTR_LED2 ), MP_ROM_PTR(&pin_PA19) }, + { MP_ROM_QSTR(MP_QSTR_DFU ), MP_ROM_PTR(&pin_PA20) }, + { MP_ROM_QSTR(MP_QSTR_SDA ), MP_ROM_PTR(&pin_PA25) }, + { MP_ROM_QSTR(MP_QSTR_SCL ), MP_ROM_PTR(&pin_PA26) }, + { MP_ROM_QSTR(MP_QSTR_D27 ), MP_ROM_PTR(&pin_PA27) }, + { MP_ROM_QSTR(MP_QSTR_A4 ), MP_ROM_PTR(&pin_PA28) }, + { MP_ROM_QSTR(MP_QSTR_A5 ), MP_ROM_PTR(&pin_PA29) }, + { MP_ROM_QSTR(MP_QSTR_A6 ), MP_ROM_PTR(&pin_PA30) }, + { MP_ROM_QSTR(MP_QSTR_A7 ), MP_ROM_PTR(&pin_PA31) }, + // LED for standard examples + { MP_ROM_QSTR(MP_QSTR_D13 ), MP_ROM_PTR(&pin_PA17) }, +}; +MP_DEFINE_CONST_DICT(board_module_globals, board_module_globals_table); diff --git a/ports/nrf/boards/feather52/pins.csv b/ports/nrf/boards/feather52/pins.csv index b7017602a7..8997ec559a 100644 --- a/ports/nrf/boards/feather52/pins.csv +++ b/ports/nrf/boards/feather52/pins.csv @@ -1,25 +1,25 @@ -PA2,PA2,ADC0_IN0 -PA3,PA3,ADC0_IN1 -PA4,PA4,ADC0_IN2 -PA5,PA5,ADC0_IN3 -UART_TX,PA6 +A0,PA2,ADC0_IN0 +A1,PA3,ADC0_IN1 +A2,PA4,ADC0_IN2 +A3,PA5,ADC0_IN3 +TX,PA6 PA7,PA7 -UART_RX,PA8 +RX,PA8 NFC1,PA9 NFC2,PA10 -PA11,PA11 -SPI_SCK,PA12 -SPI_MOSI,PA13 -SPI_MISO,PA14 -PA15,PA15 -PA16,PA16 +D11,PA11 +SCK,PA12 +MOSI,PA13 +MISO,PA14 +D15,PA15 +D16,PA16 LED1,PA17 LED2,PA19 -PA20,PA20 -I2C_SDA,PA25 -I2C_SCL,PA26 -PA27,PA27 -PA28,PA28,ADC0_IN4 -PA29,PA29,ADC0_IN5 -PA30,PA30,ADC0_IN6 -PA31,PA31,ADC0_IN7 +DFU,PA20 +SDA,PA25 +SCL,PA26 +D27,PA27 +A4,PA28,ADC0_IN4 +A5,PA29,ADC0_IN5 +A6,PA30,ADC0_IN6 +A7,PA31,ADC0_IN7 diff --git a/ports/nrf/boards/feather52/pins.h b/ports/nrf/boards/feather52/pins.h new file mode 100644 index 0000000000..6ad86fa285 --- /dev/null +++ b/ports/nrf/boards/feather52/pins.h @@ -0,0 +1,28 @@ +extern const pin_obj_t pin_PA02; +extern const pin_obj_t pin_PA03; +extern const pin_obj_t pin_PA04; +extern const pin_obj_t pin_PA05; +extern const pin_obj_t pin_PA06; +extern const pin_obj_t pin_PA07; +extern const pin_obj_t pin_PA08; +extern const pin_obj_t pin_PA09; +extern const pin_obj_t pin_PA10; +extern const pin_obj_t pin_PA11; +extern const pin_obj_t pin_PA12; +extern const pin_obj_t pin_PA13; +extern const pin_obj_t pin_PA14; +extern const pin_obj_t pin_PA15; +extern const pin_obj_t pin_PA16; +extern const pin_obj_t pin_PA17; +extern const pin_obj_t pin_PA19; +extern const pin_obj_t pin_PA20; +extern const pin_obj_t pin_PA25; +extern const pin_obj_t pin_PA26; +extern const pin_obj_t pin_PA27; +extern const pin_obj_t pin_PA28; +extern const pin_obj_t pin_PA29; +extern const pin_obj_t pin_PA30; +extern const pin_obj_t pin_PA31; +extern const pin_obj_t * const pin_PAdc1[]; +extern const pin_obj_t * const pin_PAdc2[]; +extern const pin_obj_t * const pin_PAdc3[]; diff --git a/ports/nrf/boards/make-pins.py b/ports/nrf/boards/make-pins.py index 733bd8c33c..1edd2f99a9 100644 --- a/ports/nrf/boards/make-pins.py +++ b/ports/nrf/boards/make-pins.py @@ -233,22 +233,22 @@ class Pins(object): self.board_pins.append(NamedPin(row[0], pin)) def print_named(self, label, named_pins): - print('STATIC const mp_rom_map_elem_t pin_{:s}_pins_locals_dict_table[] = {{'.format(label)) + print('STATIC const mp_rom_map_elem_t {:s}_table[] = {{'.format(label)) for named_pin in named_pins: pin = named_pin.pin() if pin.is_board_pin(): print(' {{ MP_ROM_QSTR(MP_QSTR_{:s}), MP_ROM_PTR(&pin_{:s}) }},'.format(named_pin.name(), pin.cpu_pin_name())) print('};') - print('MP_DEFINE_CONST_DICT(pin_{:s}_pins_locals_dict, pin_{:s}_pins_locals_dict_table);'.format(label, label)); + print('MP_DEFINE_CONST_DICT({:s}, {:s}_table);'.format(label, label)); def print(self): for named_pin in self.cpu_pins: pin = named_pin.pin() if pin.is_board_pin(): pin.print() - self.print_named('cpu', self.cpu_pins) + self.print_named('mcu_pin_globals', self.cpu_pins) print('') - self.print_named('board', self.board_pins) + self.print_named('board_module_globals', self.board_pins) def print_adc(self, adc_num): print(''); diff --git a/ports/nrf/boards/microbit/mpconfigboard.h b/ports/nrf/boards/microbit/mpconfigboard.h index 6dc8b0597f..61c24d642d 100644 --- a/ports/nrf/boards/microbit/mpconfigboard.h +++ b/ports/nrf/boards/microbit/mpconfigboard.h @@ -35,7 +35,7 @@ #define MICROPY_PY_MACHINE_HW_SPI (1) #define MICROPY_PY_MACHINE_TIMER (1) #define MICROPY_PY_MACHINE_RTC (1) -#define MICROPY_PY_MACHINE_I2C (1) +#define MICROPY_PY_MACHINE_I2C (0) #define MICROPY_PY_MACHINE_ADC (1) #define MICROPY_PY_MACHINE_TEMP (1) diff --git a/ports/nrf/boards/nrf52_prefix.c b/ports/nrf/boards/nrf52_prefix.c index 89e5df5b10..f408bdcf45 100644 --- a/ports/nrf/boards/nrf52_prefix.c +++ b/ports/nrf/boards/nrf52_prefix.c @@ -19,7 +19,7 @@ #define PIN(p_port, p_pin, p_af, p_adc_num, p_adc_channel) \ { \ - { &pin_type }, \ + { &mcu_pin_type }, \ .name = MP_QSTR_ ## p_port ## p_pin, \ .port = PORT_ ## p_port, \ .pin = (p_pin), \ diff --git a/ports/nrf/common-hal/analogio/AnalogIn.c b/ports/nrf/common-hal/analogio/AnalogIn.c new file mode 100644 index 0000000000..9923e62f5b --- /dev/null +++ b/ports/nrf/common-hal/analogio/AnalogIn.c @@ -0,0 +1,118 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2016 Scott Shawcroft for Adafruit Industries + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#include "common-hal/analogio/AnalogIn.h" + +#include + +#include "py/gc.h" +#include "py/nlr.h" +#include "py/runtime.h" +#include "py/binary.h" +#include "py/mphal.h" +#include "shared-bindings/analogio/AnalogIn.h" +#include "nrf.h" + +void common_hal_analogio_analogin_construct(analogio_analogin_obj_t* self, const mcu_pin_obj_t *pin) { + if (!pin->adc_channel) { + // No ADC function on that pin + mp_raise_ValueError("Pin does not have ADC capabilities"); + } + + hal_gpio_cfg_pin(pin->port, pin->pin, HAL_GPIO_MODE_INPUT, HAL_GPIO_PULL_DISABLED); + self->pin = pin; +} + +bool common_hal_analogio_analogin_deinited(analogio_analogin_obj_t *self) { + return self->pin == mp_const_none; +} + +void common_hal_analogio_analogin_deinit(analogio_analogin_obj_t *self) { + if (common_hal_analogio_analogin_deinited(self)) { + return; + } + reset_pin(self->pin->pin); + self->pin = mp_const_none; +} + +void analogin_reset() { +} + +uint16_t common_hal_analogio_analogin_get_value(analogio_analogin_obj_t *self) { + // Something else might have used the ADC in a different way, + // so we completely re-initialize it. + + int16_t value; + + NRF_SAADC->RESOLUTION = SAADC_RESOLUTION_VAL_14bit; + NRF_SAADC->ENABLE = 1; + + for (int i = 0; i < 8; i++) { + NRF_SAADC->CH[i].PSELN = SAADC_CH_PSELP_PSELP_NC; + NRF_SAADC->CH[i].PSELP = SAADC_CH_PSELP_PSELP_NC; + } + + NRF_SAADC->CH[0].CONFIG = ((SAADC_CH_CONFIG_RESP_Bypass << SAADC_CH_CONFIG_RESP_Pos) & SAADC_CH_CONFIG_RESP_Msk) + | ((SAADC_CH_CONFIG_RESP_Bypass << SAADC_CH_CONFIG_RESN_Pos) & SAADC_CH_CONFIG_RESN_Msk) + | ((SAADC_CH_CONFIG_GAIN_Gain1_6 << SAADC_CH_CONFIG_GAIN_Pos) & SAADC_CH_CONFIG_GAIN_Msk) + | ((SAADC_CH_CONFIG_REFSEL_Internal << SAADC_CH_CONFIG_REFSEL_Pos) & SAADC_CH_CONFIG_REFSEL_Msk) + | ((SAADC_CH_CONFIG_TACQ_3us << SAADC_CH_CONFIG_TACQ_Pos) & SAADC_CH_CONFIG_TACQ_Msk) + | ((SAADC_CH_CONFIG_MODE_SE << SAADC_CH_CONFIG_MODE_Pos) & SAADC_CH_CONFIG_MODE_Msk); + NRF_SAADC->CH[0].PSELN = self->pin->adc_channel; + NRF_SAADC->CH[0].PSELP = self->pin->adc_channel; + + + NRF_SAADC->RESULT.PTR = (uint32_t)&value; + NRF_SAADC->RESULT.MAXCNT = 1; + + NRF_SAADC->TASKS_START = 0x01UL; + + while (!NRF_SAADC->EVENTS_STARTED); + NRF_SAADC->EVENTS_STARTED = 0x00UL; + + NRF_SAADC->TASKS_SAMPLE = 0x01UL; + + while (!NRF_SAADC->EVENTS_END); + NRF_SAADC->EVENTS_END = 0x00UL; + + NRF_SAADC->TASKS_STOP = 0x01UL; + + while (!NRF_SAADC->EVENTS_STOPPED); + NRF_SAADC->EVENTS_STOPPED = 0x00UL; + + if (value < 0) { + value = 0; + } + + NRF_SAADC->ENABLE = 0; + + // Map value to from 14 to 16 bits + return (value << 2); +} + +float common_hal_analogio_analogin_get_reference_voltage(analogio_analogin_obj_t *self) { + return 3.3f; +} diff --git a/ports/nrf/common-hal/analogio/AnalogIn.h b/ports/nrf/common-hal/analogio/AnalogIn.h new file mode 100644 index 0000000000..95f599e711 --- /dev/null +++ b/ports/nrf/common-hal/analogio/AnalogIn.h @@ -0,0 +1,41 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2016 Scott Shawcroft + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#ifndef MICROPY_INCLUDED_NRF_COMMON_HAL_ANALOGIO_ANALOGIN_H +#define MICROPY_INCLUDED_NRF_COMMON_HAL_ANALOGIO_ANALOGIN_H + +#include "common-hal/microcontroller/Pin.h" + +#include "py/obj.h" + +typedef struct { + mp_obj_base_t base; + const mcu_pin_obj_t * pin; +} analogio_analogin_obj_t; + +void analogin_reset(void); + +#endif // MICROPY_INCLUDED_NRF_COMMON_HAL_ANALOGIO_ANALOGIN_H diff --git a/ports/nrf/common-hal/analogio/AnalogOut.c b/ports/nrf/common-hal/analogio/AnalogOut.c new file mode 100644 index 0000000000..87cb82ffc3 --- /dev/null +++ b/ports/nrf/common-hal/analogio/AnalogOut.c @@ -0,0 +1,76 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2013, 2014 Damien P. George + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#include +#include + +#include "py/mperrno.h" +#include "py/runtime.h" + +#include "shared-bindings/analogio/AnalogOut.h" + + +void common_hal_analogio_analogout_construct(analogio_analogout_obj_t* self, const mcu_pin_obj_t *pin) { +// if (pin->pin != PIN_PA02) { +// mp_raise_ValueError("AnalogOut not supported on given pin"); +// return; +// } +// struct dac_config config_dac; +// dac_get_config_defaults(&config_dac); +// config_dac.reference = DAC_REFERENCE_AVCC; +// enum status_code status = dac_init(&self->dac_instance, DAC, &config_dac); +// if (status != STATUS_OK) { +// mp_raise_OSError(MP_EIO); +// return; +// } +// claim_pin(pin); +// +// struct dac_chan_config config_analogout_chan; +// dac_chan_get_config_defaults(&config_analogout_chan); +// dac_chan_set_config(&self->dac_instance, DAC_CHANNEL_0, &config_analogout_chan); +// dac_chan_enable(&self->dac_instance, DAC_CHANNEL_0); +// +// dac_enable(&self->dac_instance); +} + +bool common_hal_analogio_analogout_deinited(analogio_analogout_obj_t *self) { + return self->deinited; +} + +void common_hal_analogio_analogout_deinit(analogio_analogout_obj_t *self) { +// if (common_hal_analogio_analogout_deinited(self)) { +// return; +// } +// dac_disable(&self->dac_instance); +// dac_chan_disable(&self->dac_instance, DAC_CHANNEL_0); +// reset_pin(PIN_PA02); +// self->deinited = true; +} + +void common_hal_analogio_analogout_set_value(analogio_analogout_obj_t *self, uint16_t value) { + // Input is 16 bit but we only support 10 bit so we shift the input. +// dac_chan_write(&self->dac_instance, DAC_CHANNEL_0, value >> 6); +} diff --git a/ports/nrf/common-hal/analogio/AnalogOut.h b/ports/nrf/common-hal/analogio/AnalogOut.h new file mode 100644 index 0000000000..d47412b40e --- /dev/null +++ b/ports/nrf/common-hal/analogio/AnalogOut.h @@ -0,0 +1,42 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2016 Scott Shawcroft + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#ifndef MICROPY_INCLUDED_NRF_COMMON_HAL_ANALOGIO_ANALOGOUT_H +#define MICROPY_INCLUDED_NRF_COMMON_HAL_ANALOGIO_ANALOGOUT_H + +#include "common-hal/microcontroller/Pin.h" + +//#include "asf/sam0/drivers/dac/dac.h" + +#include "py/obj.h" + +typedef struct { + mp_obj_base_t base; +// struct dac_module dac_instance; + bool deinited; +} analogio_analogout_obj_t; + +#endif // MICROPY_INCLUDED_NRF_COMMON_HAL_ANALOGIO_ANALOGOUT_H diff --git a/ports/nrf/common-hal/analogio/__init__.c b/ports/nrf/common-hal/analogio/__init__.c new file mode 100644 index 0000000000..eea58c77d6 --- /dev/null +++ b/ports/nrf/common-hal/analogio/__init__.c @@ -0,0 +1 @@ +// No analogio module functions. diff --git a/ports/nrf/common-hal/board/__init__.c b/ports/nrf/common-hal/board/__init__.c new file mode 100644 index 0000000000..634760335e --- /dev/null +++ b/ports/nrf/common-hal/board/__init__.c @@ -0,0 +1,34 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2013, 2014 Damien P. George + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#include + +#include "py/runtime.h" +#include "py/mphal.h" +#include "common-hal/microcontroller/Pin.h" + +// Pins aren't actually defined here. They are in the board specific directory +// such as boards/arduino_zero/pins.c. diff --git a/ports/nrf/common-hal/busio/I2C.c b/ports/nrf/common-hal/busio/I2C.c new file mode 100644 index 0000000000..07b067a2cb --- /dev/null +++ b/ports/nrf/common-hal/busio/I2C.c @@ -0,0 +1,207 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2016 Sandeep Mistry All right reserved. + * Copyright (c) 2017 hathach + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#include "shared-bindings/busio/I2C.h" +#include "py/mperrno.h" +#include "py/runtime.h" + +#include "pins.h" +#include "nrf.h" + +void common_hal_busio_i2c_construct(busio_i2c_obj_t *self, const mcu_pin_obj_t* scl, const mcu_pin_obj_t* sda, uint32_t frequency) { + if (scl->pin == sda->pin) { + mp_raise_ValueError("Invalid pins"); + } + + NRF_GPIO->PIN_CNF[scl->pin] = ((uint32_t)GPIO_PIN_CNF_DIR_Input << GPIO_PIN_CNF_DIR_Pos) + | ((uint32_t)GPIO_PIN_CNF_INPUT_Disconnect << GPIO_PIN_CNF_INPUT_Pos) + | ((uint32_t)GPIO_PIN_CNF_PULL_Disabled << GPIO_PIN_CNF_PULL_Pos) + | ((uint32_t)GPIO_PIN_CNF_DRIVE_S0S1 << GPIO_PIN_CNF_DRIVE_Pos) + | ((uint32_t)GPIO_PIN_CNF_SENSE_Disabled << GPIO_PIN_CNF_SENSE_Pos); + + NRF_GPIO->PIN_CNF[sda->pin] = ((uint32_t)GPIO_PIN_CNF_DIR_Input << GPIO_PIN_CNF_DIR_Pos) + | ((uint32_t)GPIO_PIN_CNF_INPUT_Disconnect << GPIO_PIN_CNF_INPUT_Pos) + | ((uint32_t)GPIO_PIN_CNF_PULL_Disabled << GPIO_PIN_CNF_PULL_Pos) + | ((uint32_t)GPIO_PIN_CNF_DRIVE_S0S1 << GPIO_PIN_CNF_DRIVE_Pos) + | ((uint32_t)GPIO_PIN_CNF_SENSE_Disabled << GPIO_PIN_CNF_SENSE_Pos); + + // 1 for I2C, 0 for SPI + self->twi = NRF_TWIM1; + + if ( frequency < 100000 ) { + self->twi->FREQUENCY = TWIM_FREQUENCY_FREQUENCY_K100; + }else if ( frequency < 250000 ) { + self->twi->FREQUENCY = TWIM_FREQUENCY_FREQUENCY_K250; + }else { + self->twi->FREQUENCY = TWIM_FREQUENCY_FREQUENCY_K400; + } + + self->twi->ENABLE = (TWIM_ENABLE_ENABLE_Enabled << TWIM_ENABLE_ENABLE_Pos); + + self->twi->PSEL.SCL = scl->pin; + self->twi->PSEL.SDA = sda->pin; + +} + +bool common_hal_busio_i2c_deinited(busio_i2c_obj_t *self) { + return self->twi->ENABLE == 0; +} + +void common_hal_busio_i2c_deinit(busio_i2c_obj_t *self) { + if (common_hal_busio_i2c_deinited(self)) { + return; + } + + uint8_t scl_pin = self->twi->PSEL.SCL; + uint8_t sda_pin = self->twi->PSEL.SDA; + + self->twi->ENABLE = (TWIM_ENABLE_ENABLE_Disabled << TWIM_ENABLE_ENABLE_Pos); + self->twi->PSEL.SCL = (TWIM_PSEL_SCL_CONNECT_Disconnected << TWIM_PSEL_SCL_CONNECT_Pos); + self->twi->PSEL.SDA = (TWIM_PSEL_SDA_CONNECT_Disconnected << TWIM_PSEL_SDA_CONNECT_Pos); + + reset_pin(scl_pin); + reset_pin(sda_pin); +} + +bool common_hal_busio_i2c_probe(busio_i2c_obj_t *self, uint8_t addr) { + // Write no data when just probing + return 0 == common_hal_busio_i2c_write(self, addr, NULL, 0, true); +} + +bool common_hal_busio_i2c_try_lock(busio_i2c_obj_t *self) { + bool grabbed_lock = false; +// CRITICAL_SECTION_ENTER() + if (!self->has_lock) { + grabbed_lock = true; + self->has_lock = true; + } +// CRITICAL_SECTION_LEAVE(); + return grabbed_lock; +} + +bool common_hal_busio_i2c_has_lock(busio_i2c_obj_t *self) { + return self->has_lock; +} + +void common_hal_busio_i2c_unlock(busio_i2c_obj_t *self) { + self->has_lock = false; +} + +uint8_t common_hal_busio_i2c_write(busio_i2c_obj_t *self, uint16_t addr, const uint8_t *data, size_t len, bool stopBit) { + NRF_TWIM_Type* twi = self->twi; + + twi->ADDRESS = addr; + twi->TASKS_RESUME = 1; + + twi->TXD.PTR = (uint32_t) data; + twi->TXD.MAXCNT = len; + + twi->TASKS_STARTTX = 1; + + // Wait for TX started + while(!twi->EVENTS_TXSTARTED && !twi->EVENTS_ERROR) {} + twi->EVENTS_TXSTARTED = 0; + + // Wait for TX complete + if ( len ) + { + while(!twi->EVENTS_LASTTX && !twi->EVENTS_ERROR) {} + twi->EVENTS_LASTTX = 0x0UL; + } + + if (stopBit || twi->EVENTS_ERROR) + { + twi->TASKS_STOP = 0x1UL; + while(!twi->EVENTS_STOPPED); + twi->EVENTS_STOPPED = 0x0UL; + } + else + { + twi->TASKS_SUSPEND = 0x1UL; + while(!twi->EVENTS_SUSPENDED); + twi->EVENTS_SUSPENDED = 0x0UL; + } + + if (twi->EVENTS_ERROR) + { + twi->EVENTS_ERROR = 0x0UL; + uint32_t error = twi->ERRORSRC; + twi->ERRORSRC = error; + + return error; + } + + return 0; +} + +uint8_t common_hal_busio_i2c_read(busio_i2c_obj_t *self, uint16_t addr, uint8_t *data, size_t len) { + NRF_TWIM_Type* twi = self->twi; + + if(len == 0) return 0; + bool stopBit = true; // should be a parameter + + twi->ADDRESS = addr; + twi->TASKS_RESUME = 0x1UL; + + twi->RXD.PTR = (uint32_t) data; + twi->RXD.MAXCNT = len; + + twi->TASKS_STARTRX = 0x1UL; + + while(!twi->EVENTS_RXSTARTED && !twi->EVENTS_ERROR); + twi->EVENTS_RXSTARTED = 0x0UL; + + while(!twi->EVENTS_LASTRX && !twi->EVENTS_ERROR); + twi->EVENTS_LASTRX = 0x0UL; + + if (stopBit || twi->EVENTS_ERROR) + { + twi->TASKS_STOP = 0x1UL; + while(!twi->EVENTS_STOPPED); + twi->EVENTS_STOPPED = 0x0UL; + } + else + { + twi->TASKS_SUSPEND = 0x1UL; + while(!twi->EVENTS_SUSPENDED); + twi->EVENTS_SUSPENDED = 0x0UL; + } + + if (twi->EVENTS_ERROR) + { + twi->EVENTS_ERROR = 0x0UL; + uint32_t error = twi->ERRORSRC; + twi->ERRORSRC = error; + + return error; + } + + // number of byte read +// (void) _p_twim->RXD.AMOUNT; + + return 0; +} diff --git a/ports/nrf/common-hal/busio/I2C.h b/ports/nrf/common-hal/busio/I2C.h new file mode 100644 index 0000000000..899b9d5aa9 --- /dev/null +++ b/ports/nrf/common-hal/busio/I2C.h @@ -0,0 +1,42 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2016 Scott Shawcroft + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#ifndef MICROPY_INCLUDED_NRF_COMMON_HAL_BUSIO_I2C_H +#define MICROPY_INCLUDED_NRF_COMMON_HAL_BUSIO_I2C_H + +#include "common-hal/microcontroller/Pin.h" + +//#include "hal/include/hal_i2c_m_sync.h" + +#include "py/obj.h" + +typedef struct { + mp_obj_base_t base; + volatile bool has_lock; + NRF_TWIM_Type* twi; +} busio_i2c_obj_t; + +#endif // MICROPY_INCLUDED_NRF_COMMON_HAL_BUSIO_I2C_H diff --git a/ports/nrf/common-hal/busio/SPI.c b/ports/nrf/common-hal/busio/SPI.c new file mode 100644 index 0000000000..3d8fa7ad33 --- /dev/null +++ b/ports/nrf/common-hal/busio/SPI.c @@ -0,0 +1,162 @@ +/* + * SPI Master library for nRF5x. + * Copyright (c) 2015 Arduino LLC + * Copyright (c) 2016 Sandeep Mistry All right reserved. + * Copyright (c) 2017 hathach + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA + */ + + +#include "shared-bindings/busio/SPI.h" +#include "py/mperrno.h" +#include "py/runtime.h" + +#include "nrf.h" +#include "pins.h" + +// Convert frequency to clock-speed-dependent value. Return 0 if out of range. +static uint32_t baudrate_to_reg(const uint32_t baudrate) { + uint32_t value; + + if (baudrate <= 125000) { + value = SPI_FREQUENCY_FREQUENCY_K125; + } else if (baudrate <= 250000) { + value = SPI_FREQUENCY_FREQUENCY_K250; + } else if (baudrate <= 500000) { + value = SPI_FREQUENCY_FREQUENCY_K500; + } else if (baudrate <= 1000000) { + value = SPI_FREQUENCY_FREQUENCY_M1; + } else if (baudrate <= 2000000) { + value = SPI_FREQUENCY_FREQUENCY_M2; + } else if (baudrate <= 4000000) { + value = SPI_FREQUENCY_FREQUENCY_M4; + } else { + value = SPI_FREQUENCY_FREQUENCY_M8; + } + + return value; +} + +void common_hal_busio_spi_construct(busio_spi_obj_t *self, const mcu_pin_obj_t * clock, const mcu_pin_obj_t * mosi, const mcu_pin_obj_t * miso) { + + // 1 for I2C, 0 for SPI + self->spi = NRF_SPI0; + + self->spi->PSELSCK = clock->pin; + self->spi->PSELMOSI = mosi->pin; + self->spi->PSELMISO = miso->pin; +} + +bool common_hal_busio_spi_deinited(busio_spi_obj_t *self) { + return self->spi == NULL; +} + +void common_hal_busio_spi_deinit(busio_spi_obj_t *self) { + if (common_hal_busio_spi_deinited(self)) { + return; + } + + self->spi->PSELSCK = SPI_PSEL_SCK_PSELSCK_Disconnected; + self->spi->PSELMOSI = SPI_PSEL_MOSI_PSELMOSI_Disconnected; + self->spi->PSELMISO = SPI_PSEL_MISO_PSELMISO_Disconnected; + +// reset_pin(self->clock_pin); +// reset_pin(self->MOSI_pin); +// reset_pin(self->MISO_pin); + + self->spi = NULL; +} + +bool common_hal_busio_spi_configure(busio_spi_obj_t *self, uint32_t baudrate, uint8_t polarity, uint8_t phase, uint8_t bits) { + // nrf52 does not support 16 bit + if ( bits != 8 ) return false; + + self->spi->ENABLE = (SPI_ENABLE_ENABLE_Disabled << SPI_ENABLE_ENABLE_Pos); + + uint32_t config = (SPI_CONFIG_ORDER_MsbFirst << SPI_CONFIG_ORDER_Pos); + + config |= ((polarity ? SPI_CONFIG_CPOL_ActiveLow : SPI_CONFIG_CPOL_ActiveHigh) << SPI_CONFIG_CPOL_Pos); + config |= ((phase ? SPI_CONFIG_CPHA_Trailing : SPI_CONFIG_CPHA_Leading ) << SPI_CONFIG_CPHA_Pos); + + self->spi->CONFIG = config; + self->spi->FREQUENCY = baudrate_to_reg(baudrate); + + self->spi->ENABLE = (SPI_ENABLE_ENABLE_Enabled << SPI_ENABLE_ENABLE_Pos); + + return true; +} + +bool common_hal_busio_spi_try_lock(busio_spi_obj_t *self) { + bool grabbed_lock = false; +// CRITICAL_SECTION_ENTER() +// if (!self->has_lock) { + grabbed_lock = true; + self->has_lock = true; +// } +// CRITICAL_SECTION_LEAVE(); + return grabbed_lock; +} + +bool common_hal_busio_spi_has_lock(busio_spi_obj_t *self) { + return self->has_lock; +} + +void common_hal_busio_spi_unlock(busio_spi_obj_t *self) { + self->has_lock = false; +} + +bool common_hal_busio_spi_write(busio_spi_obj_t *self, const uint8_t *data, size_t len) { + if (len == 0) { + return true; + } + + while (len) + { + self->spi->TXD = *data; + + while(!self->spi->EVENTS_READY); + + (void) self->spi->RXD; + data++; + len--; + + self->spi->EVENTS_READY = 0x0UL; + } + + return true; +} + +bool common_hal_busio_spi_read(busio_spi_obj_t *self, uint8_t *data, size_t len, uint8_t write_value) { + if (len == 0) { + return true; + } + + while (len) + { + self->spi->TXD = write_value; + + while(!self->spi->EVENTS_READY); + + *data = self->spi->RXD; + + data++; + len--; + + self->spi->EVENTS_READY = 0x0UL; + } + + return true; +} diff --git a/ports/nrf/common-hal/busio/SPI.h b/ports/nrf/common-hal/busio/SPI.h new file mode 100644 index 0000000000..1de74a9f29 --- /dev/null +++ b/ports/nrf/common-hal/busio/SPI.h @@ -0,0 +1,42 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2016 Scott Shawcroft + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#ifndef MICROPY_INCLUDED_NRF_COMMON_HAL_BUSIO_SPI_H +#define MICROPY_INCLUDED_NRF_COMMON_HAL_BUSIO_SPI_H + +#include "common-hal/microcontroller/Pin.h" + +//#include "hal/include/hal_spi_m_sync.h" + +#include "py/obj.h" + +typedef struct { + mp_obj_base_t base; + NRF_SPI_Type *spi; + bool has_lock; +} busio_spi_obj_t; + +#endif // MICROPY_INCLUDED_NRF_COMMON_HAL_BUSIO_SPI_H diff --git a/ports/nrf/common-hal/busio/__init__.c b/ports/nrf/common-hal/busio/__init__.c new file mode 100644 index 0000000000..41761b6743 --- /dev/null +++ b/ports/nrf/common-hal/busio/__init__.c @@ -0,0 +1 @@ +// No busio module functions. diff --git a/ports/nrf/common-hal/digitalio/DigitalInOut.c b/ports/nrf/common-hal/digitalio/DigitalInOut.c new file mode 100644 index 0000000000..a183faaa78 --- /dev/null +++ b/ports/nrf/common-hal/digitalio/DigitalInOut.c @@ -0,0 +1,169 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2017 Scott Shawcroft for Adafruit Industries + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#include +#include + +#include "py/runtime.h" +#include "py/mphal.h" + +#include "hal/hal_gpio.h" + +#include "common-hal/microcontroller/Pin.h" +#include "shared-bindings/digitalio/DigitalInOut.h" + +digitalinout_result_t common_hal_digitalio_digitalinout_construct( + digitalio_digitalinout_obj_t* self, const mcu_pin_obj_t* pin) { + self->pin = pin; + hal_gpio_cfg_pin(pin->port, pin->pin, HAL_GPIO_MODE_INPUT, HAL_GPIO_PULL_DISABLED); + return DIGITALINOUT_OK; +} + +bool common_hal_digitalio_digitalinout_deinited(digitalio_digitalinout_obj_t* self) { + return self->pin == mp_const_none; +} + +void common_hal_digitalio_digitalinout_deinit(digitalio_digitalinout_obj_t* self) { + if (common_hal_digitalio_digitalinout_deinited(self)) { + return; + } + reset_pin(self->pin->pin); + self->pin = mp_const_none; +} + +void common_hal_digitalio_digitalinout_switch_to_input( + digitalio_digitalinout_obj_t* self, enum digitalio_pull_t pull) { + self->output = false; + + hal_gpio_cfg_pin(self->pin->port, self->pin->pin, HAL_GPIO_MODE_INPUT, HAL_GPIO_PULL_DISABLED); + common_hal_digitalio_digitalinout_set_pull(self, pull); +} + +void common_hal_digitalio_digitalinout_switch_to_output( + digitalio_digitalinout_obj_t* self, bool value, + enum digitalio_drive_mode_t drive_mode) { + const uint8_t pin = self->pin->pin; + + self->output = true; + self->open_drain = (drive_mode == DRIVE_MODE_OPEN_DRAIN); + + hal_gpio_cfg_pin(self->pin->port, pin, HAL_GPIO_MODE_OUTPUT, HAL_GPIO_PULL_DISABLED); + common_hal_digitalio_digitalinout_set_value(self, value); +} + +enum digitalio_direction_t common_hal_digitalio_digitalinout_get_direction( + digitalio_digitalinout_obj_t* self) { + return self->output? DIRECTION_OUTPUT : DIRECTION_INPUT; +} + +void common_hal_digitalio_digitalinout_set_value( + digitalio_digitalinout_obj_t* self, bool value) { + if (value) { + if (self->open_drain) { + hal_gpio_dir_set(self->pin->port, self->pin->pin, HAL_GPIO_MODE_INPUT); + } else { + hal_gpio_pin_set(self->pin->port, self->pin->pin); + hal_gpio_dir_set(self->pin->port, self->pin->pin, HAL_GPIO_MODE_OUTPUT); + } + } else { + hal_gpio_pin_clear(self->pin->port, self->pin->pin); + hal_gpio_dir_set(self->pin->port, self->pin->pin, HAL_GPIO_MODE_OUTPUT); + } +} + +bool common_hal_digitalio_digitalinout_get_value( + digitalio_digitalinout_obj_t* self) { + const uint8_t pin = self->pin->pin; + if (!self->output) { + return hal_gpio_pin_read(self->pin); + } else { + if (self->open_drain && hal_gpio_dir_get(self->pin->port, self->pin->pin) == HAL_GPIO_MODE_INPUT) { + return true; + } else { + return (GPIO_BASE(self->pin->port)->OUT >> pin) & 1; + } + } +} + +void common_hal_digitalio_digitalinout_set_drive_mode( + digitalio_digitalinout_obj_t* self, + enum digitalio_drive_mode_t drive_mode) { + bool value = common_hal_digitalio_digitalinout_get_value(self); + self->open_drain = drive_mode == DRIVE_MODE_OPEN_DRAIN; + // True is implemented differently between modes so reset the value to make + // sure its correct for the new mode. + if (value) { + common_hal_digitalio_digitalinout_set_value(self, value); + } +} + +enum digitalio_drive_mode_t common_hal_digitalio_digitalinout_get_drive_mode( + digitalio_digitalinout_obj_t* self) { + if (self->open_drain) { + return DRIVE_MODE_OPEN_DRAIN; + } else { + return DRIVE_MODE_PUSH_PULL; + } +} + +void common_hal_digitalio_digitalinout_set_pull( + digitalio_digitalinout_obj_t* self, enum digitalio_pull_t pull) { + hal_gpio_pull_t asf_pull = HAL_GPIO_PULL_DISABLED; + switch (pull) { + case PULL_UP: + asf_pull = HAL_GPIO_PULL_UP; + break; + case PULL_DOWN: + asf_pull = HAL_GPIO_PULL_DOWN; + break; + case PULL_NONE: + default: + break; + } + hal_gpio_pull_set(self->pin->port, self->pin->pin, asf_pull); +} + +enum digitalio_pull_t common_hal_digitalio_digitalinout_get_pull( + digitalio_digitalinout_obj_t* self) { + uint32_t pin = self->pin->pin; + if (self->output) { + mp_raise_AttributeError("Cannot get pull while in output mode"); + return PULL_NONE; + } else { + hal_gpio_pull_t pull = hal_gpio_pull_get(self->pin->port, pin); + + switch(pull) + { + case HAL_GPIO_PULL_UP: + return PULL_UP; + + case HAL_GPIO_PULL_DOWN: + return PULL_DOWN; + + default: return PULL_NONE; + } + } +} diff --git a/ports/nrf/common-hal/digitalio/DigitalInOut.h b/ports/nrf/common-hal/digitalio/DigitalInOut.h new file mode 100644 index 0000000000..8089d8bacc --- /dev/null +++ b/ports/nrf/common-hal/digitalio/DigitalInOut.h @@ -0,0 +1,40 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2017 Scott Shawcroft for Adafruit Industries + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#ifndef MICROPY_INCLUDED_NRF_COMMON_HAL_DIGITALIO_DIGITALINOUT_H +#define MICROPY_INCLUDED_NRF_COMMON_HAL_DIGITALIO_DIGITALINOUT_H + +#include "common-hal/microcontroller/Pin.h" +#include "py/obj.h" + +typedef struct { + mp_obj_base_t base; + const mcu_pin_obj_t * pin; + bool output; + bool open_drain; +} digitalio_digitalinout_obj_t; + +#endif // MICROPY_INCLUDED_NRF_COMMON_HAL_DIGITALIO_DIGITALINOUT_H diff --git a/ports/nrf/common-hal/digitalio/__init__.c b/ports/nrf/common-hal/digitalio/__init__.c new file mode 100644 index 0000000000..20fad45959 --- /dev/null +++ b/ports/nrf/common-hal/digitalio/__init__.c @@ -0,0 +1 @@ +// No digitalio module functions. diff --git a/ports/nrf/common-hal/microcontroller/Pin.c b/ports/nrf/common-hal/microcontroller/Pin.c new file mode 100644 index 0000000000..ee07ff09aa --- /dev/null +++ b/ports/nrf/common-hal/microcontroller/Pin.c @@ -0,0 +1,75 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2016 Scott Shawcroft for Adafruit Industries + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#include "common-hal/microcontroller/Pin.h" +#include "shared-bindings/microcontroller/Pin.h" + +#include "py/mphal.h" + +#if 0 + +extern volatile bool adc_in_use; + +bool common_hal_mcu_pin_is_free(const mcu_pin_obj_t* pin) { + if (pin == &pin_TOUT) { + return !adc_in_use; + } + if (pin->gpio_number == NO_GPIO || pin->gpio_number == SPECIAL_CASE) { + return false; + } + return (READ_PERI_REG(pin->peripheral) & + (PERIPHS_IO_MUX_FUNC<gpio_number)) == 0 && + (READ_PERI_REG(pin->peripheral) & PERIPHS_IO_MUX_PULLUP) == 0; +} + +void reset_pins(void) { + for (int i = 0; i < 17; i++) { + // 5 is RXD, 6 is TXD + if ((i > 4 && i < 13) || i == 12) { + continue; + } + uint32_t peripheral = PERIPHS_IO_MUX + i * 4; + PIN_FUNC_SELECT(peripheral, 0); + PIN_PULLUP_DIS(peripheral); + // Disable the pin. + gpio_output_set(0x0, 0x0, 0x0, 1 << i); + } +} +#endif + +bool common_hal_mcu_pin_is_free(const mcu_pin_obj_t* pin) { + return true; +} + +void reset_all_pins(void) { +} + +void reset_pin(uint8_t pin) { + +} + + diff --git a/ports/nrf/common-hal/microcontroller/Pin.h b/ports/nrf/common-hal/microcontroller/Pin.h new file mode 100644 index 0000000000..d7994bc0ce --- /dev/null +++ b/ports/nrf/common-hal/microcontroller/Pin.h @@ -0,0 +1,40 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2016 Scott Shawcroft + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#ifndef MICROPY_INCLUDED_NRF_COMMON_HAL_MICROCONTROLLER_PIN_H +#define MICROPY_INCLUDED_NRF_COMMON_HAL_MICROCONTROLLER_PIN_H + +#include "py/mphal.h" +#include "modules/machine/pin.h" + +//typedef pin_obj_t mcu_pin_obj_t; +#define mcu_pin_obj_t pin_obj_t +void reset_all_pins(void); +void reset_pin(uint8_t pin); +//void claim_pin(const mcu_pin_obj_t* pin); + + +#endif // MICROPY_INCLUDED_NRF_COMMON_HAL_MICROCONTROLLER_PIN_H diff --git a/ports/nrf/common-hal/microcontroller/Processor.c b/ports/nrf/common-hal/microcontroller/Processor.c new file mode 100644 index 0000000000..4e74a49091 --- /dev/null +++ b/ports/nrf/common-hal/microcontroller/Processor.c @@ -0,0 +1,37 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2017 Dan Halbert for Adafruit Industries + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#include "common-hal/microcontroller/Processor.h" + +// TODO port common_hal_mcu_processor +float common_hal_mcu_processor_get_temperature(void) { + return 0; +} + +uint32_t common_hal_mcu_processor_get_frequency(void) { + return 64000000ul; +} + diff --git a/ports/nrf/common-hal/microcontroller/Processor.h b/ports/nrf/common-hal/microcontroller/Processor.h new file mode 100644 index 0000000000..00d95ad4f8 --- /dev/null +++ b/ports/nrf/common-hal/microcontroller/Processor.h @@ -0,0 +1,37 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2017 Dan Halbert for Adafruit Industries + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#ifndef MICROPY_INCLUDED_NRF_COMMON_HAL_MICROCONTROLLER_PROCESSOR_H +#define MICROPY_INCLUDED_NRF_COMMON_HAL_MICROCONTROLLER_PROCESSOR_H + +#include "py/obj.h" + +typedef struct { + mp_obj_base_t base; + // Stores no state currently. +} mcu_processor_obj_t; + +#endif // MICROPY_INCLUDED_NRF_COMMON_HAL_MICROCONTROLLER_PROCESSOR_H diff --git a/ports/nrf/common-hal/microcontroller/__init__.c b/ports/nrf/common-hal/microcontroller/__init__.c new file mode 100644 index 0000000000..ddf0d252ce --- /dev/null +++ b/ports/nrf/common-hal/microcontroller/__init__.c @@ -0,0 +1,51 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2016 Scott Shawcroft for Adafruit Industries + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#include "common-hal/microcontroller/Pin.h" +#include "common-hal/microcontroller/Processor.h" + +#include "shared-bindings/microcontroller/Pin.h" +#include "shared-bindings/microcontroller/Processor.h" + +// TODO porting common_hal_mcu +void common_hal_mcu_delay_us(uint32_t delay) { +// os_delay_us(delay); +} + +void common_hal_mcu_disable_interrupts() { +} + +void common_hal_mcu_enable_interrupts() { +} + +// The singleton microcontroller.Processor object, returned by microcontroller.cpu +// It currently only has properties, and no state. +mcu_processor_obj_t common_hal_mcu_processor_obj = { + .base = { + .type = &mcu_processor_type, + }, +}; + diff --git a/ports/nrf/common-hal/os/__init__.c b/ports/nrf/common-hal/os/__init__.c new file mode 100644 index 0000000000..0e6d63347c --- /dev/null +++ b/ports/nrf/common-hal/os/__init__.c @@ -0,0 +1,88 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2017 Scott Shawcroft for Adafruit Industries + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#include "genhdr/mpversion.h" +#include "py/mpconfig.h" +#include "py/objstr.h" +#include "py/objtuple.h" +#include "py/qstr.h" + +#include "nrf_sdm.h" +#include "nrf_soc.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, "nrf52"); +STATIC const MP_DEFINE_STR_OBJ(os_uname_info_nodename_obj, "nrf52"); + +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) { + uint8_t sd_en = 0; + (void) sd_softdevice_is_enabled(&sd_en); + + if ( sd_en ) + { + return NRF_SUCCESS == sd_rand_application_vector_get(buffer,length); + }else + { + // SoftDevice is not enabled. + NRF_RNG->EVENTS_VALRDY = 0; + NRF_RNG->TASKS_START = 1; + + for (uint32_t i = 0; i < length; i++) { + while (NRF_RNG->EVENTS_VALRDY == 0) { + ; + } + NRF_RNG->EVENTS_VALRDY = 0; + buffer[i] = (uint8_t) NRF_RNG->VALUE; + } + + NRF_RNG->TASKS_STOP = 1; + } + + return true; +} diff --git a/ports/nrf/common-hal/pulseio/PWMOut.c b/ports/nrf/common-hal/pulseio/PWMOut.c new file mode 100644 index 0000000000..ea9ba3f0e2 --- /dev/null +++ b/ports/nrf/common-hal/pulseio/PWMOut.c @@ -0,0 +1,240 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2017 Scott Shawcroft for Adafruit Industries + * Copyright (c) 2016 Damien P. George + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#include +#include "nrf.h" + +#include "py/runtime.h" +#include "common-hal/pulseio/PWMOut.h" +#include "shared-bindings/pulseio/PWMOut.h" + +#define PWM_MAX_MODULE 3 +#define PWM_MAX_CHANNEL 4 + +#define PWM_MAX_FREQ (16000000) + +NRF_PWM_Type* const pwm_arr[PWM_MAX_MODULE] = { NRF_PWM0, NRF_PWM1, NRF_PWM2 }; + +uint16_t _seq0[PWM_MAX_MODULE][PWM_MAX_CHANNEL]; + + +static int pin2channel(NRF_PWM_Type* pwm, uint8_t pin) +{ + for(int i=0; i < PWM_MAX_CHANNEL; i++) + { + if ( pwm->PSEL.OUT[i] == ((uint32_t)pin) ) return i; + } + + return -1; +} + +static int find_free_channel(NRF_PWM_Type* pwm) +{ + for(int i=0; i < PWM_MAX_CHANNEL; i++) + { + if (pwm->PSEL.OUT[i] == 0xFFFFFFFFUL) + { + return i; + } + } + + return -1; +} + +static bool pwm_is_unused(NRF_PWM_Type* pwm) +{ + for(int i=0; i < PWM_MAX_CHANNEL; i++) + { + if (pwm->PSEL.OUT[i] != 0xFFFFFFFFUL) + { + return false; + } + } + + return true; +} + +static void find_new_pwm(pulseio_pwmout_obj_t* self) +{ + // First find unused PWM module + for(int i=0; ipwm = pwm_arr[i]; + self->channel = 0; + return; + } + } + + // Find available channel in a using PWM + for(int i=0; i= 0 ) + { + self->pwm = pwm_arr[i]; + self->channel = (uint8_t) ch; + return; + } + } +} + +void pwmout_reset(void) +{ + for(int i=0; iMODE = PWM_MODE_UPDOWN_Up; + pwm->DECODER = PWM_DECODER_LOAD_Individual; + pwm->LOOP = 0; + pwm->PRESCALER = PWM_PRESCALER_PRESCALER_DIV_1; // default is 500 hz + pwm->COUNTERTOP = (PWM_MAX_FREQ/500); // default is 500 hz + + pwm->SEQ[0].PTR = (uint32_t) _seq0[i]; + pwm->SEQ[0].CNT = PWM_MAX_CHANNEL; // default mode is Individual --> count must be 4 + pwm->SEQ[0].REFRESH = 0; + pwm->SEQ[0].ENDDELAY = 0; + + pwm->SEQ[1].PTR = 0; + pwm->SEQ[1].CNT = 0; + pwm->SEQ[1].REFRESH = 0; + pwm->SEQ[1].ENDDELAY = 0; + + for(int ch =0; ch < PWM_MAX_CHANNEL; ch++) + { + _seq0[i][ch] = (1UL << 15); // polarity = 0 + } + } +} + +void common_hal_pulseio_pwmout_construct(pulseio_pwmout_obj_t* self, + const mcu_pin_obj_t* pin, + uint16_t duty, + uint32_t frequency, + bool variable_frequency) { + self->pwm = NULL; + self->pin = pin; + + // check if mapped to PWM channel already + for(int i=0; ipin); + if ( ch >= 0 ) + { + self->pwm = pwm_arr[i]; + self->channel = (uint8_t) ch; + break; + } + } + + // Haven't mapped before + if ( !self->pwm ) + { + find_new_pwm(self); + } + + if (self->pwm) + { + hal_gpio_cfg_pin(pin->port, pin->pin, HAL_GPIO_MODE_OUTPUT, HAL_GPIO_PULL_DISABLED); + + // disable before mapping pin channel + self->pwm->ENABLE = 0; + + self->pwm->PSEL.OUT[self->channel] = pin->pin; + + self->pwm->COUNTERTOP = (PWM_MAX_FREQ/frequency); + self->freq = frequency; + self->variable_freq = variable_frequency; + + self->pwm->ENABLE = 1; + + common_hal_pulseio_pwmout_set_duty_cycle(self, duty); + } +} + +bool common_hal_pulseio_pwmout_deinited(pulseio_pwmout_obj_t* self) { + return self->pwm == NULL; +} + +void common_hal_pulseio_pwmout_deinit(pulseio_pwmout_obj_t* self) { + if (common_hal_pulseio_pwmout_deinited(self)) { + return; + } + + self->pwm->ENABLE = 0; + + self->pwm->PSEL.OUT[self->channel] = 0xFFFFFFFFUL; + + // re-enable PWM module if there is other active channel + for(int i=0; i < PWM_MAX_CHANNEL; i++) + { + if (self->pwm->PSEL.OUT[i] != 0xFFFFFFFFUL) + { + self->pwm->ENABLE = 1; + break; + } + } + + hal_gpio_cfg_pin(self->pin->port, self->pin->pin, HAL_GPIO_MODE_INPUT, HAL_GPIO_PULL_DISABLED); + + self->pwm = NULL; + self->pin = mp_const_none; +} + +void common_hal_pulseio_pwmout_set_duty_cycle(pulseio_pwmout_obj_t* self, uint16_t duty) { + self->duty = duty; + + uint16_t* p_value = ((uint16_t*)self->pwm->SEQ[0].PTR) + self->channel; + *p_value = ((duty * self->pwm->COUNTERTOP) / 0xFFFF) | (1 << 15); + + self->pwm->TASKS_SEQSTART[0] = 1; +} + +uint16_t common_hal_pulseio_pwmout_get_duty_cycle(pulseio_pwmout_obj_t* self) { + return self->duty; +} + +void common_hal_pulseio_pwmout_set_frequency(pulseio_pwmout_obj_t* self, uint32_t frequency) { + if (frequency == 0 || frequency > 16000000) { + mp_raise_ValueError("Invalid PWM frequency"); + } + + self->freq = frequency; + self->pwm->COUNTERTOP = (PWM_MAX_FREQ/frequency); + self->pwm->TASKS_SEQSTART[0] = 1; +} + +uint32_t common_hal_pulseio_pwmout_get_frequency(pulseio_pwmout_obj_t* self) { + return self->freq; +} + +bool common_hal_pulseio_pwmout_get_variable_frequency(pulseio_pwmout_obj_t* self) { + return self->variable_freq; +} + diff --git a/ports/nrf/common-hal/pulseio/PWMOut.h b/ports/nrf/common-hal/pulseio/PWMOut.h new file mode 100644 index 0000000000..ddb7192a88 --- /dev/null +++ b/ports/nrf/common-hal/pulseio/PWMOut.h @@ -0,0 +1,47 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2017 Scott Shawcroft for Adafruit Industries + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#ifndef MICROPY_INCLUDED_ATMEL_SAMD_COMMON_HAL_PULSEIO_PWMOUT_H +#define MICROPY_INCLUDED_ATMEL_SAMD_COMMON_HAL_PULSEIO_PWMOUT_H + +#include "common-hal/microcontroller/Pin.h" + +#include "py/obj.h" + +typedef struct { + mp_obj_base_t base; + const mcu_pin_obj_t *pin; + NRF_PWM_Type* pwm; + + uint8_t channel; + bool variable_freq; + uint16_t duty; + uint32_t freq; +} pulseio_pwmout_obj_t; + +void pwmout_reset(void); + +#endif // MICROPY_INCLUDED_ATMEL_SAMD_COMMON_HAL_PULSEIO_PWMOUT_H diff --git a/ports/nrf/common-hal/pulseio/PulseIn.c b/ports/nrf/common-hal/pulseio/PulseIn.c new file mode 100644 index 0000000000..a6f1bf10d6 --- /dev/null +++ b/ports/nrf/common-hal/pulseio/PulseIn.c @@ -0,0 +1,87 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2017 Scott Shawcroft for Adafruit Industries + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#include "common-hal/pulseio/PulseIn.h" + +#include + +//#include "asf/common2/services/delay/delay.h" +//#include "asf/sam0/drivers/extint/extint.h" +//#include "asf/sam0/drivers/extint/extint_callback.h" +//#include "asf/sam0/drivers/port/port.h" + +#include "mpconfigport.h" +#include "py/gc.h" +#include "py/runtime.h" +//#include "samd21_pins.h" +#include "shared-bindings/microcontroller/__init__.h" +#include "shared-bindings/pulseio/PulseIn.h" + +//#include "tick.h" + +void pulsein_reset(void) { + +} + +void common_hal_pulseio_pulsein_construct(pulseio_pulsein_obj_t* self, const mcu_pin_obj_t* pin, uint16_t maxlen, bool idle_state) { + mp_raise_NotImplementedError(NULL); +} + +bool common_hal_pulseio_pulsein_deinited(pulseio_pulsein_obj_t* self) { + return 1; +} + +void common_hal_pulseio_pulsein_deinit(pulseio_pulsein_obj_t* self) { + +} + +void common_hal_pulseio_pulsein_pause(pulseio_pulsein_obj_t* self) { + +} + +void common_hal_pulseio_pulsein_resume(pulseio_pulsein_obj_t* self, uint16_t trigger_duration) { + +} + +void common_hal_pulseio_pulsein_clear(pulseio_pulsein_obj_t* self) { + +} + +uint16_t common_hal_pulseio_pulsein_popleft(pulseio_pulsein_obj_t* self) { + return 0; +} + +uint16_t common_hal_pulseio_pulsein_get_maxlen(pulseio_pulsein_obj_t* self) { + return 0xadaf; +} + +uint16_t common_hal_pulseio_pulsein_get_len(pulseio_pulsein_obj_t* self) { + return 0xadaf; +} + +uint16_t common_hal_pulseio_pulsein_get_item(pulseio_pulsein_obj_t* self, int16_t index) { + return 0xadaf; +} diff --git a/ports/nrf/common-hal/pulseio/PulseIn.h b/ports/nrf/common-hal/pulseio/PulseIn.h new file mode 100644 index 0000000000..f577a61311 --- /dev/null +++ b/ports/nrf/common-hal/pulseio/PulseIn.h @@ -0,0 +1,49 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2017 Scott Shawcroft for Adafruit Industries + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#ifndef MICROPY_INCLUDED_ATMEL_SAMD_COMMON_HAL_PULSEIO_PULSEIN_H +#define MICROPY_INCLUDED_ATMEL_SAMD_COMMON_HAL_PULSEIO_PULSEIN_H + +#include "common-hal/microcontroller/Pin.h" + +#include "py/obj.h" + +typedef struct { + mp_obj_base_t base; + uint8_t channel; + uint8_t pin; + uint16_t* buffer; + uint16_t maxlen; + bool idle_state; + volatile uint16_t start; + volatile uint16_t len; + volatile bool first_edge; + uint16_t ticks_per_ms; +} pulseio_pulsein_obj_t; + +void pulsein_reset(void); + +#endif // MICROPY_INCLUDED_ATMEL_SAMD_COMMON_HAL_PULSEIO_PULSEIN_H diff --git a/ports/nrf/common-hal/pulseio/PulseOut.c b/ports/nrf/common-hal/pulseio/PulseOut.c new file mode 100644 index 0000000000..dbeaf6b07a --- /dev/null +++ b/ports/nrf/common-hal/pulseio/PulseOut.c @@ -0,0 +1,62 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2016 Damien P. George + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#include "common-hal/pulseio/PulseOut.h" + +#include + +//#include "asf/sam0/drivers/tc/tc_interrupt.h" +//#include "asf/sam0/drivers/port/port.h" + +#include "mpconfigport.h" +#include "py/gc.h" +#include "py/runtime.h" +//#include "samd21_pins.h" +#include "shared-bindings/pulseio/PulseOut.h" + +//void pulse_finish(struct tc_module *const module) { +// +//} + +void pulseout_reset() { + +} + +void common_hal_pulseio_pulseout_construct(pulseio_pulseout_obj_t* self, const pulseio_pwmout_obj_t* carrier) { + mp_raise_NotImplementedError(NULL); +} + +bool common_hal_pulseio_pulseout_deinited(pulseio_pulseout_obj_t* self) { + return 1; +} + +void common_hal_pulseio_pulseout_deinit(pulseio_pulseout_obj_t* self) { + +} + +void common_hal_pulseio_pulseout_send(pulseio_pulseout_obj_t* self, uint16_t* pulses, uint16_t length) { + +} diff --git a/ports/nrf/common-hal/pulseio/PulseOut.h b/ports/nrf/common-hal/pulseio/PulseOut.h new file mode 100644 index 0000000000..8ade95cd6d --- /dev/null +++ b/ports/nrf/common-hal/pulseio/PulseOut.h @@ -0,0 +1,42 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2017 Scott Shawcroft for Adafruit Industries + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#ifndef MICROPY_INCLUDED_ATMEL_SAMD_COMMON_HAL_PULSEIO_PULSEOUT_H +#define MICROPY_INCLUDED_ATMEL_SAMD_COMMON_HAL_PULSEIO_PULSEOUT_H + +#include "common-hal/microcontroller/Pin.h" + +#include "py/obj.h" + +typedef struct { + mp_obj_base_t base; +// __IO PORT_PINCFG_Type *pincfg; + uint8_t pin; +} pulseio_pulseout_obj_t; + +void pulseout_reset(void); + +#endif // MICROPY_INCLUDED_ATMEL_SAMD_COMMON_HAL_PULSEIO_PULSEOUT_H diff --git a/ports/nrf/common-hal/pulseio/__init__.c b/ports/nrf/common-hal/pulseio/__init__.c new file mode 100644 index 0000000000..2bee925bc7 --- /dev/null +++ b/ports/nrf/common-hal/pulseio/__init__.c @@ -0,0 +1 @@ +// No pulseio module functions. diff --git a/ports/nrf/common-hal/storage/__init__.c b/ports/nrf/common-hal/storage/__init__.c new file mode 100644 index 0000000000..9d94d39690 --- /dev/null +++ b/ports/nrf/common-hal/storage/__init__.c @@ -0,0 +1,39 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2017 Scott Shawcroft for Adafruit Industries + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#include + +#include "py/mperrno.h" +#include "py/runtime.h" +#include "shared-bindings/storage/__init__.h" + +extern volatile bool mp_msc_enabled; + +void common_hal_storage_remount(const char* mount_path, bool readonly) { + if (strcmp(mount_path, "/") != 0) { + mp_raise_OSError(MP_EINVAL); + } +} diff --git a/ports/nrf/common-hal/time/__init__.c b/ports/nrf/common-hal/time/__init__.c new file mode 100644 index 0000000000..dc29e2d6d5 --- /dev/null +++ b/ports/nrf/common-hal/time/__init__.c @@ -0,0 +1,38 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2016 Scott Shawcroft for Adafruit Industries + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#include "py/mphal.h" + +#include "shared-bindings/time/__init__.h" +#include "boards/board.h" + +inline uint64_t common_hal_time_monotonic() { + return ticks_ms; +} + +void common_hal_time_delay_ms(uint32_t delay) { + mp_hal_delay_ms(delay); +} diff --git a/ports/nrf/device/nrf52/startup_nrf52832.c b/ports/nrf/device/nrf52/startup_nrf52832.c index b36ac0d971..614b8c2d32 100644 --- a/ports/nrf/device/nrf52/startup_nrf52832.c +++ b/ports/nrf/device/nrf52/startup_nrf52832.c @@ -35,6 +35,8 @@ extern uint32_t _ebss; typedef void (*func)(void); +#define _start main + extern void _start(void) __attribute__((noreturn)); extern void SystemInit(void); diff --git a/ports/nrf/device/nrf52/startup_nrf52840.c b/ports/nrf/device/nrf52/startup_nrf52840.c index 998696c08e..30634a1b54 100644 --- a/ports/nrf/device/nrf52/startup_nrf52840.c +++ b/ports/nrf/device/nrf52/startup_nrf52840.c @@ -35,6 +35,8 @@ extern uint32_t _ebss; typedef void (*func)(void); +#define _start main + extern void _start(void) __attribute__((noreturn)); extern void SystemInit(void); diff --git a/ports/nrf/drivers/bluetooth/download_ble_stack.sh b/ports/nrf/drivers/bluetooth/download_ble_stack.sh index 537742605b..ab85c42af7 100755 --- a/ports/nrf/drivers/bluetooth/download_ble_stack.sh +++ b/ports/nrf/drivers/bluetooth/download_ble_stack.sh @@ -52,15 +52,33 @@ function download_s132_nrf52_3_0_0 cd - } +function download_s132_nrf52_5_0_0 +{ + echo "" + echo "####################################" + echo "### Downloading s132_nrf52_5.0.0 ###" + echo "####################################" + echo "" + + mkdir -p $1/s132_nrf52_5.0.0 + cd $1/s132_nrf52_5.0.0 + + wget http://www.nordicsemi.com/eng/nordic/download_resource/58987/11/7198220/116068 + mv 116068 temp.zip + unzip -u temp.zip + rm temp.zip + cd - +} SCRIPT_DIR="$(cd -P "$(dirname "${BASH_SOURCE[0]}")" && pwd)" -if [ $# -eq 0 ]; then +if [ $# -eq 0 ]; then echo "No Bluetooth LE stack defined, downloading all." download_s110_nrf51_8_0_0 ${SCRIPT_DIR} download_s132_nrf52_2_0_1 ${SCRIPT_DIR} download_s132_nrf52_3_0_0 ${SCRIPT_DIR} -else + download_s132_nrf52_5_0_0 ${SCRIPT_DIR} +else case $1 in "s110_nrf51" ) download_s110_nrf51_8_0_0 ${SCRIPT_DIR} ;; @@ -68,6 +86,8 @@ else download_s132_nrf52_2_0_1 ${SCRIPT_DIR} ;; "s132_nrf52_3_0_0" ) download_s132_nrf52_3_0_0 ${SCRIPT_DIR} ;; + "s132_nrf52_5_0_0" ) + download_s132_nrf52_5_0_0 ${SCRIPT_DIR} ;; esac fi diff --git a/ports/nrf/fifo.c b/ports/nrf/fifo.c new file mode 100644 index 0000000000..7e8f989c30 --- /dev/null +++ b/ports/nrf/fifo.c @@ -0,0 +1,267 @@ +/******************************************************************************/ +/*! + @file fifo.c + @author hathach (tinyusb.org) + + @section DESCRIPTION + + Light-weight FIFO buffer with basic mutex support + + @section LICENSE + + Software License Agreement (BSD License) + + Copyright (c) 2012, K. Townsend (microBuilder.eu) + All rights reserved. + + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + 1. Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + 2. Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + 3. Neither the name of the copyright holders nor the + names of its contributors may be used to endorse or promote products + derived from this software without specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS ''AS IS'' AND ANY + EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY + DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND + ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*/ +/******************************************************************************/ + +#include "fifo.h" + +/*------------------------------------------------------------------*/ +/* + *------------------------------------------------------------------*/ +#if CFG_FIFO_MUTEX + +#define mutex_lock_if_needed(_ff) if (_ff->mutex) fifo_mutex_lock(_ff->mutex) +#define mutex_unlock_if_needed(_ff) if (_ff->mutex) fifo_mutex_unlock(_ff->mutex) + +#else + +#define mutex_lock_if_needed(_ff) +#define mutex_unlock_if_needed(_ff) + +#endif + +static inline uint16_t min16_of(uint16_t x, uint16_t y) +{ + return (x < y) ? x : y; +} + +static inline bool fifo_initalized(fifo_t* f) +{ + return (f->buffer != NULL) && (f->depth > 0) && (f->item_size > 0); +} + + +/******************************************************************************/ +/*! + @brief Read one byte out of the RX buffer. + + This function will return the byte located at the array index of the + read pointer, and then increment the read pointer index. If the read + pointer exceeds the maximum buffer size, it will roll over to zero. + + @param[in] f + Pointer to the FIFO buffer to manipulate + @param[in] p_buffer + Pointer to the place holder for data read from the buffer + + @returns TRUE if the queue is not empty +*/ +/******************************************************************************/ +bool fifo_read(fifo_t* f, void * p_buffer) +{ + if( !fifo_initalized(f) ) return false; + if( fifo_empty(f) ) return false; + + mutex_lock_if_needed(f); + + memcpy(p_buffer, + f->buffer + (f->rd_idx * f->item_size), + f->item_size); + f->rd_idx = (f->rd_idx + 1) % f->depth; + f->count--; + + mutex_unlock_if_needed(f); + + return true; +} + +/******************************************************************************/ +/*! + @brief This function will read n elements into the array index specified by + the write pointer and increment the write index. If the write index + exceeds the max buffer size, then it will roll over to zero. + + @param[in] f + Pointer to the FIFO buffer to manipulate + @param[in] p_data + The pointer to data location + @param[in] count + Number of element that buffer can afford + + @returns number of bytes read from the FIFO +*/ +/******************************************************************************/ +uint16_t fifo_read_n (fifo_t* f, void * p_buffer, uint16_t count) +{ + if( !fifo_initalized(f) ) return false; + if( fifo_empty(f) ) return false; + + /* Limit up to fifo's count */ + count = min16_of(count, f->count); + if( count == 0 ) return 0; + + mutex_lock_if_needed(f); + + /* Could copy up to 2 portions marked as 'x' if queue is wrapped around + * case 1: ....RxxxxW....... + * case 2: xxxxxW....Rxxxxxx + */ +// uint16_t index2upper = min16_of(count, f->count-f->rd_idx); + + uint8_t* p_buf = (uint8_t*) p_buffer; + uint16_t len = 0; + while( (len < count) && fifo_read(f, p_buf) ) + { + len++; + p_buf += f->item_size; + } + + mutex_unlock_if_needed(f); + + return len; +} + +/******************************************************************************/ +/*! + @brief Reads one item without removing it from the FIFO + + @param[in] f + Pointer to the FIFO buffer to manipulate + @param[in] position + Position to read from in the FIFO buffer + @param[in] p_buffer + Pointer to the place holder for data read from the buffer + + @returns TRUE if the queue is not empty +*/ +/******************************************************************************/ +bool fifo_peek_at(fifo_t* f, uint16_t position, void * p_buffer) +{ + if ( !fifo_initalized(f) ) return false; + if ( position >= f->count ) return false; + + // rd_idx is position=0 + uint16_t index = (f->rd_idx + position) % f->depth; + memcpy(p_buffer, + f->buffer + (index * f->item_size), + f->item_size); + + return true; +} + +/******************************************************************************/ +/*! + @brief Write one element into the RX buffer. + + This function will write one element into the array index specified by + the write pointer and increment the write index. If the write index + exceeds the max buffer size, then it will roll over to zero. + + @param[in] f + Pointer to the FIFO buffer to manipulate + @param[in] p_data + The byte to add to the FIFO + + @returns TRUE if the data was written to the FIFO (overwrittable + FIFO will always return TRUE) +*/ +/******************************************************************************/ +bool fifo_write(fifo_t* f, void const * p_data) +{ + if ( !fifo_initalized(f) ) return false; + if ( fifo_full(f) && !f->overwritable ) return false; + + mutex_lock_if_needed(f); + + memcpy( f->buffer + (f->wr_idx * f->item_size), + p_data, + f->item_size); + + f->wr_idx = (f->wr_idx + 1) % f->depth; + + if (fifo_full(f)) + { + f->rd_idx = f->wr_idx; // keep the full state (rd == wr && len = size) + } + else + { + f->count++; + } + + mutex_unlock_if_needed(f); + + return true; +} + +/******************************************************************************/ +/*! + @brief This function will write n elements into the array index specified by + the write pointer and increment the write index. If the write index + exceeds the max buffer size, then it will roll over to zero. + + @param[in] f + Pointer to the FIFO buffer to manipulate + @param[in] p_data + The pointer to data to add to the FIFO + @param[in] count + Number of element + @return Number of written elements +*/ +/******************************************************************************/ +uint16_t fifo_write_n(fifo_t* f, void const * p_data, uint16_t count) +{ + if ( count == 0 ) return 0; + + uint8_t* p_buf = (uint8_t*) p_data; + + uint16_t len = 0; + while( (len < count) && fifo_write(f, p_buf) ) + { + len++; + p_buf += f->item_size; + } + + return len; +} + +/******************************************************************************/ +/*! + @brief Clear the fifo read and write pointers and set length to zero + + @param[in] f + Pointer to the FIFO buffer to manipulate +*/ +/******************************************************************************/ +void fifo_clear(fifo_t *f) +{ + mutex_lock_if_needed(f); + + f->rd_idx = f->wr_idx = f->count = 0; + + mutex_unlock_if_needed(f); +} diff --git a/ports/nrf/fifo.h b/ports/nrf/fifo.h new file mode 100644 index 0000000000..7b3afba7a2 --- /dev/null +++ b/ports/nrf/fifo.h @@ -0,0 +1,148 @@ +/******************************************************************************/ +/*! + @file fifo.h + @author hathach (tinyusb.org) + + @section LICENSE + + Software License Agreement (BSD License) + + Copyright (c) 2012, K. Townsend (microBuilder.eu) + All rights reserved. + + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + 1. Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + 2. Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + 3. Neither the name of the copyright holders nor the + names of its contributors may be used to endorse or promote products + derived from this software without specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS ''AS IS'' AND ANY + EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY + DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND + ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*/ +/******************************************************************************/ +#ifndef __FIFO_H__ +#define __FIFO_H__ + +#define CFG_FIFO_MUTEX 1 + +#include +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +#if CFG_FIFO_MUTEX + +#include "nrf52.h" + +#define fifo_mutex_t IRQn_Type + +#define fifo_mutex_lock(m) NVIC_DisableIRQ(m) +#define fifo_mutex_unlock(m) NVIC_EnableIRQ(m) + +/* Internal use only */ +#define _mutex_declare(m) .mutex = m + +#else + +#define _mutex_declare(m) + +#endif + +typedef struct _fifo_t +{ + uint8_t* const buffer ; ///< buffer pointer + uint16_t const depth ; ///< max items + uint16_t const item_size ; ///< size of each item + volatile uint16_t count ; ///< number of items in queue + volatile uint16_t wr_idx ; ///< write pointer + volatile uint16_t rd_idx ; ///< read pointer + bool const overwritable; + +#if CFG_FIFO_MUTEX + fifo_mutex_t const mutex; +#endif + +} fifo_t; + +/** + * Macro to declare a fifo + * @param name : name of the fifo + * @param depth : max number of items + * @param type : data type of item + * @param overwritable : whether fifo should be overwrite when full + * @param mutex : mutex object + */ +#define FIFO_DEF(_name, _depth, _type, _overwritable, _mutex)\ + _type _name##_buffer[_depth];\ + fifo_t _name##_fifo = {\ + .buffer = (uint8_t*) _name##_buffer,\ + .depth = _depth,\ + .item_size = sizeof(_type),\ + .overwritable = _overwritable,\ + _mutex_declare(_mutex)\ + };\ + fifo_t* _name = &_name##_fifo + + +void fifo_clear (fifo_t *f); + +bool fifo_write (fifo_t* f, void const * p_data); +uint16_t fifo_write_n (fifo_t* f, void const * p_data, uint16_t count); + +bool fifo_read (fifo_t* f, void * p_buffer); +uint16_t fifo_read_n (fifo_t* f, void * p_buffer, uint16_t count); + +bool fifo_peek_at (fifo_t* f, uint16_t position, void * p_buffer); +static inline bool fifo_peek(fifo_t* f, void * p_buffer) +{ + return fifo_peek_at(f, 0, p_buffer); +} + + +static inline bool fifo_empty(fifo_t* f) +{ + return (f->count == 0); +} + +static inline bool fifo_full(fifo_t* f) +{ + return (f->count == f->depth); +} + +static inline uint16_t fifo_count(fifo_t* f) +{ + return f->count; +} + +static inline uint16_t fifo_remaining(fifo_t* f) +{ + return f->depth - f->count; +} + +static inline uint16_t fifo_depth(fifo_t* f) +{ + return f->depth; +} + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/ports/nrf/hal/hal_gpio.h b/ports/nrf/hal/hal_gpio.h index afd03d0dce..5a86b25444 100644 --- a/ports/nrf/hal/hal_gpio.h +++ b/ports/nrf/hal/hal_gpio.h @@ -45,8 +45,8 @@ #define GPIO_BASE(x) ((NRF_GPIO_Type *)POINTERS[x]) -#define hal_gpio_pin_high(p) (((NRF_GPIO_Type *)(GPIO_BASE((p)->port)))->OUTSET = (p)->pin_mask) -#define hal_gpio_pin_low(p) (((NRF_GPIO_Type *)(GPIO_BASE((p)->port)))->OUTCLR = (p)->pin_mask) +#define hal_gpio_pin_high(p) (((NRF_GPIO_Type *)(GPIO_BASE((p)->port)))->OUTSET = (1 << (p)->pin) ) +#define hal_gpio_pin_low(p) (((NRF_GPIO_Type *)(GPIO_BASE((p)->port)))->OUTCLR = (1 << (p)->pin) ) #define hal_gpio_pin_read(p) (((NRF_GPIO_Type *)(GPIO_BASE((p)->port)))->IN >> ((p)->pin) & 1) typedef enum { @@ -74,6 +74,28 @@ static inline void hal_gpio_cfg_pin(uint8_t port, uint32_t pin_number, hal_gpio_ | mode; } +static inline void hal_gpio_dir_set(uint8_t port, uint32_t pin, hal_gpio_mode_t mode) +{ + GPIO_BASE(port)->PIN_CNF[pin] &= ~GPIO_PIN_CNF_DIR_Msk; + GPIO_BASE(port)->PIN_CNF[pin] |= mode; +} + +static inline hal_gpio_mode_t hal_gpio_dir_get(uint8_t port, uint32_t pin) +{ + return GPIO_BASE(port)->PIN_CNF[pin] & GPIO_PIN_CNF_DIR_Msk; +} + +static inline void hal_gpio_pull_set(uint8_t port, uint32_t pin, hal_gpio_pull_t pull) +{ + GPIO_BASE(port)->PIN_CNF[pin] &= ~GPIO_PIN_CNF_PULL_Msk; + GPIO_BASE(port)->PIN_CNF[pin] |= pull; +} + +static inline hal_gpio_pull_t hal_gpio_pull_get(uint8_t port, uint32_t pin) +{ + return GPIO_BASE(port)->PIN_CNF[pin] & GPIO_PIN_CNF_PULL_Msk; +} + static inline void hal_gpio_out_set(uint8_t port, uint32_t pin_mask) { GPIO_BASE(port)->OUTSET = pin_mask; } @@ -90,6 +112,14 @@ static inline void hal_gpio_pin_clear(uint8_t port, uint32_t pin) { GPIO_BASE(port)->OUTCLR = (1 << pin); } +static inline void hal_gpio_pin_set_value(uint8_t port, uint32_t pin, uint8_t value) { + if (value) { + hal_gpio_pin_set(port, pin); + }else { + hal_gpio_pin_clear(port, pin); + } +} + static inline void hal_gpio_pin_toggle(uint8_t port, uint32_t pin) { uint32_t pin_mask = (1 << pin); uint32_t pins_state = NRF_GPIO->OUT; diff --git a/ports/nrf/hal/hal_uart.c b/ports/nrf/hal/hal_uart.c index 39590272b5..e8d4230816 100644 --- a/ports/nrf/hal/hal_uart.c +++ b/ports/nrf/hal/hal_uart.c @@ -30,9 +30,14 @@ #include "nrf.h" #include "mphalport.h" #include "hal_uart.h" +#include "fifo.h" + +#include "lib/utils/interrupt_char.h" #ifdef HAL_UART_MODULE_ENABLED +FIFO_DEF(_ff_uart, 128, uint8_t, true, UARTE0_UART0_IRQn); + uint32_t hal_uart_baudrate_lookup[] = { UART_BAUDRATE_BAUDRATE_Baud1200, ///< 1200 baud. UART_BAUDRATE_BAUDRATE_Baud2400, ///< 2400 baud. @@ -66,15 +71,11 @@ hal_uart_error_t hal_uart_char_write(NRF_UART_Type * p_instance, uint8_t ch) { } hal_uart_error_t hal_uart_char_read(NRF_UART_Type * p_instance, uint8_t * ch) { - p_instance->ERRORSRC = 0; - while (p_instance->EVENTS_RXDRDY != 1) { - // Wait for RXD data. - } + while ( !fifo_read(_ff_uart, ch) ) { + // wait for fifo data + } - p_instance->EVENTS_RXDRDY = 0; - *ch = p_instance->RXD; - - return p_instance->ERRORSRC; + return HAL_UART_ERROR_NONE; } hal_uart_error_t hal_uart_buffer_write(NRF_UART_Type * p_instance, uint8_t * p_buffer, uint32_t num_of_bytes, uart_complete_cb cb) { @@ -106,6 +107,11 @@ hal_uart_error_t hal_uart_buffer_read(NRF_UART_Type * p_instance, uint8_t * p_bu return err; } +int hal_uart_available(NRF_UART_Type * p_instance) +{ + return fifo_count(_ff_uart); +} + void hal_uart_init(NRF_UART_Type * p_instance, hal_uart_init_t const * p_uart_init) { hal_gpio_cfg_pin(p_uart_init->tx_pin->port, p_uart_init->tx_pin->pin, HAL_GPIO_MODE_OUTPUT, HAL_GPIO_PULL_DISABLED); hal_gpio_cfg_pin(p_uart_init->tx_pin->port, p_uart_init->rx_pin->pin, HAL_GPIO_MODE_INPUT, HAL_GPIO_PULL_DISABLED); @@ -141,6 +147,35 @@ void hal_uart_init(NRF_UART_Type * p_instance, hal_uart_init_t const * p_uart_in p_instance->EVENTS_RXDRDY = 0; p_instance->TASKS_STARTTX = 1; p_instance->TASKS_STARTRX = 1; + + // Adafruit IRQ + fifo + fifo_clear(_ff_uart); + p_instance->INTENSET = UART_INTENSET_RXDRDY_Msk; + NVIC_ClearPendingIRQ(p_uart_init->irq_num); + NVIC_SetPriority(p_uart_init->irq_num, p_uart_init->irq_priority); + NVIC_EnableIRQ(p_uart_init->irq_num); +} + + +void UARTE0_UART0_IRQHandler(void) +{ + NRF_UART_Type * p_instance = NRF_UART0; + + if (p_instance->EVENTS_RXDRDY) + { + uint8_t ch = (uint8_t) p_instance->RXD; + + // Keyboard interrupt + if (mp_interrupt_char != -1 && ch == mp_interrupt_char) + { + mp_keyboard_interrupt(); + }else + { + fifo_write(_ff_uart, &ch); + } + + p_instance->EVENTS_RXDRDY = 0x0UL; + } } #endif // HAL_UART_MODULE_ENABLED diff --git a/ports/nrf/hal/hal_uart.h b/ports/nrf/hal/hal_uart.h index ca0110c3e4..76c09b335f 100644 --- a/ports/nrf/hal/hal_uart.h +++ b/ports/nrf/hal/hal_uart.h @@ -121,5 +121,6 @@ void hal_uart_init(NRF_UART_Type * p_instance, hal_uart_init_t const * p_uart_in hal_uart_error_t hal_uart_char_write(NRF_UART_Type * p_instance, uint8_t ch); hal_uart_error_t hal_uart_char_read(NRF_UART_Type * p_instance, uint8_t * ch); +int hal_uart_available(NRF_UART_Type * p_instance); #endif // HAL_UART_H__ diff --git a/ports/nrf/internal_flash.c b/ports/nrf/internal_flash.c new file mode 100644 index 0000000000..4a1faad564 --- /dev/null +++ b/ports/nrf/internal_flash.c @@ -0,0 +1,208 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2013, 2014 Damien P. George + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ +#include "internal_flash.h" + +#include +#include + +#include "extmod/vfs.h" +#include "extmod/vfs_fat.h" +#include "py/mphal.h" +#include "py/obj.h" +#include "py/runtime.h" +#include "lib/oofatfs/ff.h" +#include "supervisor/shared/rgb_led_status.h" + +#include "nrf.h" +#include "nrf_soc.h" + +// defined in linker +extern uint32_t __fatfs_flash_start_addr[]; +extern uint32_t __fatfs_flash_length[]; + +void internal_flash_init(void) { + // Activity LED for flash writes. + #ifdef MICROPY_HW_LED_MSC + struct port_config pin_conf; + port_get_config_defaults(&pin_conf); + + pin_conf.direction = PORT_PIN_DIR_OUTPUT; + port_pin_set_config(MICROPY_HW_LED_MSC, &pin_conf); + port_pin_set_output_level(MICROPY_HW_LED_MSC, false); + #endif + + #ifdef SAMD51 + hri_mclk_set_AHBMASK_NVMCTRL_bit(MCLK); + #endif + #ifdef SAMD21 + _pm_enable_bus_clock(PM_BUS_APBB, NVMCTRL); + #endif +// flash_init(&internal_flash_desc, NVMCTRL); +} + +uint32_t internal_flash_get_block_size(void) { + return FILESYSTEM_BLOCK_SIZE; +} + +uint32_t internal_flash_get_block_count(void) { + return ((uint32_t) __fatfs_flash_length) / FILESYSTEM_BLOCK_SIZE ; +} + +void internal_flash_flush(void) { +} + +void flash_flush(void) { + internal_flash_flush(); +} + +static uint32_t convert_block_to_flash_addr(uint32_t block) { + return ((uint32_t)__fatfs_flash_start_addr) + block * FILESYSTEM_BLOCK_SIZE; +} + +bool internal_flash_write_block(const uint8_t *src, uint32_t block) { +#ifdef MICROPY_HW_LED_MSC + port_pin_set_output_level(MICROPY_HW_LED_MSC, true); +#endif + temp_status_color(ACTIVE_WRITE); + // non-MBR block, copy to cache + + uint32_t dest = convert_block_to_flash_addr(block); + + uint32_t pagenum = dest / FLASH_PAGE_SIZE; + uint8_t* flash_align = (uint8_t*) (pagenum*FLASH_PAGE_SIZE); + + // Read back current page to update only 512 portion + __ALIGN(4) uint8_t buf[FLASH_PAGE_SIZE]; + memcpy(buf, flash_align, FLASH_PAGE_SIZE); + memcpy(buf + (dest%FLASH_PAGE_SIZE), src, FILESYSTEM_BLOCK_SIZE); + + if (NRF_SUCCESS != sd_flash_page_erase(pagenum)) { + return false; + } + + if (NRF_SUCCESS != sd_flash_write((uint32_t*) flash_align, (uint32_t*) buf, FLASH_PAGE_SIZE/4)) { + return false; + } + + clear_temp_status(); +#ifdef MICROPY_HW_LED_MSC + port_pin_set_output_level(MICROPY_HW_LED_MSC, false); +#endif + return true; +} + +mp_uint_t internal_flash_read_blocks(uint8_t *dest, uint32_t block, uint32_t num_blocks) { + uint32_t src = convert_block_to_flash_addr(block); + memcpy(dest, (uint8_t*) src, FILESYSTEM_BLOCK_SIZE*num_blocks); + return 0; // success +} + +mp_uint_t internal_flash_write_blocks(const uint8_t *src, uint32_t block_num, uint32_t num_blocks) { + for (size_t i = 0; i < num_blocks; i++) { + if (!internal_flash_write_block(src + i * FILESYSTEM_BLOCK_SIZE, block_num + i)) { + return 1; // error + } + } + return 0; // success +} + +/******************************************************************************/ +// MicroPython bindings +// +// Expose the flash as an object with the block protocol. + +// there is a singleton Flash object +STATIC const mp_obj_base_t internal_flash_obj = {&internal_flash_type}; + +STATIC mp_obj_t internal_flash_obj_make_new(const mp_obj_type_t *type, size_t n_args, size_t n_kw, const mp_obj_t *args) { + // check arguments + mp_arg_check_num(n_args, n_kw, 0, 0, false); + + // return singleton object + return (mp_obj_t)&internal_flash_obj; +} + +STATIC mp_obj_t internal_flash_obj_readblocks(mp_obj_t self, mp_obj_t block_num, mp_obj_t buf) { + mp_buffer_info_t bufinfo; + mp_get_buffer_raise(buf, &bufinfo, MP_BUFFER_WRITE); + mp_uint_t ret = internal_flash_read_blocks(bufinfo.buf, mp_obj_get_int(block_num), bufinfo.len / FILESYSTEM_BLOCK_SIZE); + return MP_OBJ_NEW_SMALL_INT(ret); +} +STATIC MP_DEFINE_CONST_FUN_OBJ_3(internal_flash_obj_readblocks_obj, internal_flash_obj_readblocks); + +STATIC mp_obj_t internal_flash_obj_writeblocks(mp_obj_t self, mp_obj_t block_num, mp_obj_t buf) { + mp_buffer_info_t bufinfo; + mp_get_buffer_raise(buf, &bufinfo, MP_BUFFER_READ); + mp_uint_t ret = internal_flash_write_blocks(bufinfo.buf, mp_obj_get_int(block_num), bufinfo.len / FILESYSTEM_BLOCK_SIZE); + return MP_OBJ_NEW_SMALL_INT(ret); +} +STATIC MP_DEFINE_CONST_FUN_OBJ_3(internal_flash_obj_writeblocks_obj, internal_flash_obj_writeblocks); + +STATIC mp_obj_t internal_flash_obj_ioctl(mp_obj_t self, mp_obj_t cmd_in, mp_obj_t arg_in) { + mp_int_t cmd = mp_obj_get_int(cmd_in); + switch (cmd) { + case BP_IOCTL_INIT: internal_flash_init(); return MP_OBJ_NEW_SMALL_INT(0); + case BP_IOCTL_DEINIT: internal_flash_flush(); return MP_OBJ_NEW_SMALL_INT(0); // TODO properly + case BP_IOCTL_SYNC: internal_flash_flush(); return MP_OBJ_NEW_SMALL_INT(0); + case BP_IOCTL_SEC_COUNT: return MP_OBJ_NEW_SMALL_INT(internal_flash_get_block_count()); + case BP_IOCTL_SEC_SIZE: return MP_OBJ_NEW_SMALL_INT(internal_flash_get_block_size()); + default: return mp_const_none; + } +} +STATIC MP_DEFINE_CONST_FUN_OBJ_3(internal_flash_obj_ioctl_obj, internal_flash_obj_ioctl); + +STATIC const mp_rom_map_elem_t internal_flash_obj_locals_dict_table[] = { + { MP_ROM_QSTR(MP_QSTR_readblocks), MP_ROM_PTR(&internal_flash_obj_readblocks_obj) }, + { MP_ROM_QSTR(MP_QSTR_writeblocks), MP_ROM_PTR(&internal_flash_obj_writeblocks_obj) }, + { MP_ROM_QSTR(MP_QSTR_ioctl), MP_ROM_PTR(&internal_flash_obj_ioctl_obj) }, +}; + +STATIC MP_DEFINE_CONST_DICT(internal_flash_obj_locals_dict, internal_flash_obj_locals_dict_table); + +const mp_obj_type_t internal_flash_type = { + { &mp_type_type }, + .name = MP_QSTR_InternalFlash, + .make_new = internal_flash_obj_make_new, + .locals_dict = (mp_obj_t)&internal_flash_obj_locals_dict, +}; + +void flash_init_vfs(fs_user_mount_t *vfs) { + vfs->base.type = &mp_fat_vfs_type; + vfs->flags |= FSUSER_NATIVE | FSUSER_HAVE_IOCTL; + vfs->fatfs.drv = vfs; + +// vfs->fatfs.part = 1; // flash filesystem lives on first partition + vfs->readblocks[0] = (mp_obj_t)&internal_flash_obj_readblocks_obj; + vfs->readblocks[1] = (mp_obj_t)&internal_flash_obj; + vfs->readblocks[2] = (mp_obj_t)internal_flash_read_blocks; // native version + + vfs->writeblocks[0] = (mp_obj_t)&internal_flash_obj_writeblocks_obj; + vfs->writeblocks[1] = (mp_obj_t)&internal_flash_obj; + vfs->writeblocks[2] = (mp_obj_t)internal_flash_write_blocks; // native version + + vfs->u.ioctl[0] = (mp_obj_t)&internal_flash_obj_ioctl_obj; + vfs->u.ioctl[1] = (mp_obj_t)&internal_flash_obj; +} diff --git a/ports/nrf/internal_flash.h b/ports/nrf/internal_flash.h new file mode 100644 index 0000000000..db41065fe5 --- /dev/null +++ b/ports/nrf/internal_flash.h @@ -0,0 +1,61 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2013, 2014 Damien P. George + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ +#ifndef MICROPY_INCLUDED_ATMEL_SAMD_INTERNAL_FLASH_H +#define MICROPY_INCLUDED_ATMEL_SAMD_INTERNAL_FLASH_H + +#include +#include + +#include "mpconfigport.h" + +#define FLASH_ROOT_POINTERS + +#define FLASH_PAGE_SIZE 0x1000 +#define CIRCUITPY_INTERNAL_NVM_SIZE 0 + +#define INTERNAL_FLASH_SYSTICK_MASK (0x1ff) // 512ms +#define INTERNAL_FLASH_IDLE_TICK(tick) (((tick) & INTERNAL_FLASH_SYSTICK_MASK) == 2) + +void internal_flash_init(void); +uint32_t internal_flash_get_block_size(void); +uint32_t internal_flash_get_block_count(void); +void internal_flash_irq_handler(void); +void internal_flash_flush(void); +bool internal_flash_read_block(uint8_t *dest, uint32_t block); +bool internal_flash_write_block(const uint8_t *src, uint32_t block); + +// these return 0 on success, non-zero on error +mp_uint_t internal_flash_read_blocks(uint8_t *dest, uint32_t block_num, uint32_t num_blocks); +mp_uint_t internal_flash_write_blocks(const uint8_t *src, uint32_t block_num, uint32_t num_blocks); + +extern const struct _mp_obj_type_t internal_flash_type; + +struct _fs_user_mount_t; + +void flash_init_vfs(struct _fs_user_mount_t *vfs); +void flash_flush(void); + +#endif // MICROPY_INCLUDED_ATMEL_SAMD_INTERNAL_FLASH_H diff --git a/ports/nrf/main.c b/ports/nrf/main.c deleted file mode 100644 index 92f578cda1..0000000000 --- a/ports/nrf/main.c +++ /dev/null @@ -1,265 +0,0 @@ -/* - * This file is part of the MicroPython project, http://micropython.org/ - * - * The MIT License (MIT) - * - * Copyright (c) 2013, 2014 Damien P. George - * Copyright (c) 2015 Glenn Ruben Bakke - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. - */ - -#include -#include -#include - -#include "py/nlr.h" -#include "py/mperrno.h" -#include "py/lexer.h" -#include "py/parse.h" -#include "py/obj.h" -#include "py/runtime.h" -#include "py/stackctrl.h" -#include "py/gc.h" -#include "py/compile.h" -#include "lib/utils/pyexec.h" -#include "readline.h" -#include "gccollect.h" -#include "modmachine.h" -#include "modmusic.h" -#include "led.h" -#include "uart.h" -#include "nrf.h" -#include "pin.h" -#include "spi.h" -#include "i2c.h" -#include "rtc.h" -#if MICROPY_PY_MACHINE_HW_PWM -#include "pwm.h" -#endif -#include "timer.h" - -#if (MICROPY_PY_BLE_NUS) -#include "ble_uart.h" -#endif - -void do_str(const char *src, mp_parse_input_kind_t input_kind) { - mp_lexer_t *lex = mp_lexer_new_from_str_len(MP_QSTR__lt_stdin_gt_, src, strlen(src), 0); - if (lex == NULL) { - printf("MemoryError: lexer could not allocate memory\n"); - return; - } - - nlr_buf_t nlr; - if (nlr_push(&nlr) == 0) { - qstr source_name = lex->source_name; - mp_parse_tree_t pn = mp_parse(lex, input_kind); - mp_obj_t module_fun = mp_compile(&pn, source_name, MP_EMIT_OPT_NONE, true); - mp_call_function_0(module_fun); - nlr_pop(); - } else { - // uncaught exception - mp_obj_print_exception(&mp_plat_print, (mp_obj_t)nlr.ret_val); - } -} - -extern uint32_t _heap_start; -extern uint32_t _heap_end; - -int main(int argc, char **argv) { - -soft_reset: - mp_stack_set_top(&_ram_end); - - // Stack limit should be less than real stack size, so we have a chance - // to recover from limit hit. (Limit is measured in bytes.) - mp_stack_set_limit((char*)&_ram_end - (char*)&_heap_end - 400); - - machine_init(); - - gc_init(&_heap_start, &_heap_end); - - mp_init(); - mp_obj_list_init(mp_sys_path, 0); - mp_obj_list_append(mp_sys_path, MP_OBJ_NEW_QSTR(MP_QSTR_)); // current dir (or base dir of the script) - mp_obj_list_init(mp_sys_argv, 0); - - pyb_set_repl_info(MP_OBJ_NEW_SMALL_INT(0)); - - readline_init0(); - -#if MICROPY_PY_MACHINE_HW_SPI - spi_init0(); -#endif - -#if MICROPY_PY_MACHINE_I2C - i2c_init0(); -#endif - -#if MICROPY_PY_MACHINE_HW_PWM - pwm_init0(); -#endif - -#if MICROPY_PY_MACHINE_RTC - rtc_init0(); -#endif - -#if MICROPY_PY_MACHINE_TIMER - timer_init0(); -#endif - - uart_init0(); - -#if (MICROPY_PY_BLE_NUS == 0) - { - mp_obj_t args[2] = { - MP_OBJ_NEW_SMALL_INT(0), - MP_OBJ_NEW_SMALL_INT(115200), - }; - MP_STATE_PORT(pyb_stdio_uart) = machine_hard_uart_type.make_new((mp_obj_t)&machine_hard_uart_type, MP_ARRAY_SIZE(args), 0, args); - } -#endif - -pin_init0(); - -#if MICROPY_HW_HAS_SDCARD - // if an SD card is present then mount it on /sd/ - if (sdcard_is_present()) { - // create vfs object - fs_user_mount_t *vfs = m_new_obj_maybe(fs_user_mount_t); - if (vfs == NULL) { - goto no_mem_for_sd; - } - vfs->str = "/sd"; - vfs->len = 3; - vfs->flags = FSUSER_FREE_OBJ; - sdcard_init_vfs(vfs); - - // put the sd device in slot 1 (it will be unused at this point) - MP_STATE_PORT(fs_user_mount)[1] = vfs; - - FRESULT res = f_mount(&vfs->fatfs, vfs->str, 1); - if (res != FR_OK) { - printf("PYB: can't mount SD card\n"); - MP_STATE_PORT(fs_user_mount)[1] = NULL; - m_del_obj(fs_user_mount_t, vfs); - } else { - // TODO these should go before the /flash entries in the path - mp_obj_list_append(mp_sys_path, MP_OBJ_NEW_QSTR(MP_QSTR__slash_sd)); - mp_obj_list_append(mp_sys_path, MP_OBJ_NEW_QSTR(MP_QSTR__slash_sd_slash_lib)); - - // use SD card as current directory - f_chdrive("/sd"); - } - no_mem_for_sd:; - } -#endif - -#if (MICROPY_HW_HAS_LED) - led_init(); - - do_str("import pyb\r\n" \ - "pyb.LED(1).on()", - MP_PARSE_FILE_INPUT); -#endif - - // Main script is finished, so now go into REPL mode. - // The REPL mode can change, or it can request a soft reset. - int ret_code = 0; - -#if MICROPY_PY_BLE_NUS - ble_uart_init0(); - while (!ble_uart_enabled()) { - ; - } -#endif - - for (;;) { - if (pyexec_mode_kind == PYEXEC_MODE_RAW_REPL) { - if (pyexec_raw_repl() != 0) { - break; - } - } else { - ret_code = pyexec_friendly_repl(); - if (ret_code != 0) { - break; - } - } - } - - mp_deinit(); - - if (ret_code == PYEXEC_FORCED_EXIT) { - NVIC_SystemReset(); - } else { - goto soft_reset; - } - - return 0; -} - -#if !MICROPY_VFS -mp_lexer_t *mp_lexer_new_from_file(const char *filename) { - mp_raise_OSError(MP_ENOENT); -} - -mp_import_stat_t mp_import_stat(const char *path) { - return MP_IMPORT_STAT_NO_EXIST; -} - -STATIC mp_obj_t mp_builtin_open(size_t n_args, const mp_obj_t *args, mp_map_t *kwargs) { - mp_raise_OSError(MP_EPERM); -} -MP_DEFINE_CONST_FUN_OBJ_KW(mp_builtin_open_obj, 1, mp_builtin_open); -#endif - -void HardFault_Handler(void) -{ -#if NRF52 - static volatile uint32_t reg; - static volatile uint32_t reg2; - static volatile uint32_t bfar; - reg = SCB->HFSR; - reg2 = SCB->CFSR; - bfar = SCB->BFAR; - for (int i = 0; i < 0; i++) - { - (void)reg; - (void)reg2; - (void)bfar; - } -#endif -} - -void NORETURN __fatal_error(const char *msg) { - while (1); -} - -void nlr_jump_fail(void *val) { - printf("FATAL: uncaught exception %p\n", val); - mp_obj_print_exception(&mp_plat_print, (mp_obj_t)val); - __fatal_error(""); -} - -void MP_WEAK __assert_func(const char *file, int line, const char *func, const char *expr) { - printf("Assertion '%s' failed, at file %s:%d\n", expr, file, line); - __fatal_error("Assertion failed"); -} - -void _start(void) {main(0, NULL);} diff --git a/ports/nrf/modules/machine/pin.c b/ports/nrf/modules/machine/pin.c index 62160d785f..d7306a4991 100644 --- a/ports/nrf/modules/machine/pin.c +++ b/ports/nrf/modules/machine/pin.c @@ -194,7 +194,7 @@ STATIC void pin_print(const mp_print_t *print, mp_obj_t self_in, mp_print_kind_t mp_printf(print, "Pin(Pin.cpu.%q, mode=Pin.", self->name); mp_printf(print, "port=0x%x, ", self->port); mp_printf(print, "pin=0x%x, ", self->pin); - mp_printf(print, "pin_mask=0x%x,", self->pin_mask); +// mp_printf(print, "pin_mask=0x%x,", self->pin_mask); /* uint32_t mode = pin_get_mode(self); @@ -567,7 +567,7 @@ STATIC const mp_rom_map_elem_t pin_locals_dict_table[] = { { MP_ROM_QSTR(MP_QSTR_AF_OD), MP_ROM_INT(GPIO_MODE_AF_OD) }, { MP_ROM_QSTR(MP_QSTR_PULL_NONE), MP_ROM_INT(GPIO_NOPULL) }, */ -#include "genhdr/pins_af_const.h" +//#include "genhdr/pins_af_const.h" }; STATIC MP_DEFINE_CONST_DICT(pin_locals_dict, pin_locals_dict_table); diff --git a/ports/nrf/modules/machine/pin.h b/ports/nrf/modules/machine/pin.h index 1935a0d263..117fb72896 100644 --- a/ports/nrf/modules/machine/pin.h +++ b/ports/nrf/modules/machine/pin.h @@ -51,17 +51,21 @@ typedef struct { typedef struct { mp_obj_base_t base; qstr name; - uint32_t port : 4; - uint32_t pin : 5; // Some ARM processors use 32 bits/PORT - uint32_t num_af : 4; - uint32_t adc_channel : 5; // Some ARM processors use 32 bits/PORT - uint32_t adc_num : 3; // 1 bit per ADC - uint32_t pin_mask; + + uint32_t port : 1; + uint32_t pin : 5; // Some ARM processors use 32 bits/PORT + uint32_t num_af : 4; + uint32_t adc_channel : 4; // 0 is no ADC, ADC channel from 1 to 8 + +// uint32_t pin_mask; pin_gpio_t *gpio; const pin_af_obj_t *af; uint32_t pull; } pin_obj_t; +// Adafruit +extern const mp_obj_type_t mcu_pin_type; + extern const mp_obj_type_t pin_type; extern const mp_obj_type_t pin_af_type; @@ -84,8 +88,16 @@ typedef struct { extern const mp_obj_type_t pin_board_pins_obj_type; extern const mp_obj_type_t pin_cpu_pins_obj_type; -extern const mp_obj_dict_t pin_cpu_pins_locals_dict; -extern const mp_obj_dict_t pin_board_pins_locals_dict; +//extern const mp_obj_dict_t pin_cpu_pins_locals_dict; +//extern const mp_obj_dict_t pin_board_pins_locals_dict; + +// Adafruit modification for CircuitPython board module +extern const mp_obj_dict_t mcu_pin_globals; +extern const mp_obj_dict_t board_module_globals; + +#define pin_cpu_pins_locals_dict mcu_pin_globals +#define pin_board_pins_locals_dict board_module_globals + MP_DECLARE_CONST_FUN_OBJ_KW(pin_init_obj); diff --git a/ports/nrf/modules/machine/pwm.c b/ports/nrf/modules/machine/pwm.c index eaba96606f..6a98677af1 100644 --- a/ports/nrf/modules/machine/pwm.c +++ b/ports/nrf/modules/machine/pwm.c @@ -34,7 +34,8 @@ #if MICROPY_PY_MACHINE_HW_PWM #include "pin.h" -#include "genhdr/pins.h" +//#include "genhdr/pins.h" +#include "pins.h" #include "pwm.h" #if NRF52 diff --git a/ports/nrf/modules/machine/spi.c b/ports/nrf/modules/machine/spi.c index 0a82f1db52..5c097fd765 100644 --- a/ports/nrf/modules/machine/spi.c +++ b/ports/nrf/modules/machine/spi.c @@ -33,7 +33,8 @@ #include "py/mphal.h" #include "extmod/machine_spi.h" #include "pin.h" -#include "genhdr/pins.h" +//#include "genhdr/pins.h" +#include "pins.h" #include "spi.h" #include "hal_spi.h" diff --git a/ports/nrf/modules/machine/uart.c b/ports/nrf/modules/machine/uart.c index b99afef622..26b9ae7d36 100644 --- a/ports/nrf/modules/machine/uart.c +++ b/ports/nrf/modules/machine/uart.c @@ -35,7 +35,8 @@ #include "py/mperrno.h" #include "py/mphal.h" #include "pin.h" -#include "genhdr/pins.h" +//#include "genhdr/pins.h" +#include "pins.h" #include "uart.h" #include "mpconfigboard.h" @@ -65,6 +66,8 @@ void uart_init0(void) { // reset the UART handles memset(&UARTHandle0, 0, sizeof(UART_HandleTypeDef)); UARTHandle0.p_instance = UART_BASE(0); + UARTHandle0.init.irq_num = UARTE0_UART0_IRQn; + #if NRF52840_XXAA memset(&UARTHandle1, 0, sizeof(UART_HandleTypeDef)); UARTHandle0.p_instance = UART_BASE(1); @@ -82,13 +85,13 @@ STATIC int uart_find(mp_obj_t id) { "UART(%d) does not exist", uart_id)); } -void uart_irq_handler(mp_uint_t uart_id) { - -} +//void uart_irq_handler(mp_uint_t uart_id) { +// +//} bool uart_rx_any(machine_hard_uart_obj_t *uart_obj) { // TODO: uart will block for now. - return true; + return hal_uart_available(uart_obj->uart->p_instance) > 0; } int uart_rx_char(machine_hard_uart_obj_t * self) { diff --git a/ports/nrf/modules/uos/moduos.c b/ports/nrf/modules/uos/moduos.c deleted file mode 100644 index 21ea2cde67..0000000000 --- a/ports/nrf/modules/uos/moduos.c +++ /dev/null @@ -1,174 +0,0 @@ -/* - * This file is part of the MicroPython project, http://micropython.org/ - * - * The MIT License (MIT) - * - * Copyright (c) 2013, 2014 Damien P. George - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. - */ - -#include -#include - -#include "py/mpstate.h" -#include "py/runtime.h" -#include "py/objtuple.h" -#include "py/objstr.h" -#include "lib/oofatfs/ff.h" -#include "lib/oofatfs/diskio.h" -#include "extmod/vfs.h" -#include "extmod/vfs_fat.h" -#include "genhdr/mpversion.h" -//#include "timeutils.h" -//#include "rng.h" -#include "uart.h" -//#include "portmodules.h" - -/// \module os - basic "operating system" services -/// -/// The `os` module contains functions for filesystem access and `urandom`. -/// -/// The filesystem has `/` as the root directory, and the available physical -/// drives are accessible from here. They are currently: -/// -/// /flash -- the internal flash filesystem -/// /sd -- the SD card (if it exists) -/// -/// On boot up, the current directory is `/flash` if no SD card is inserted, -/// otherwise it is `/sd`. - -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, "pyboard"); -STATIC const MP_DEFINE_STR_OBJ(os_uname_info_nodename_obj, "pyboard"); -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 -); - -STATIC mp_obj_t os_uname(void) { - return (mp_obj_t)&os_uname_info_obj; -} -STATIC MP_DEFINE_CONST_FUN_OBJ_0(os_uname_obj, os_uname); - -#if MICROPY_VFS -/// \function sync() -/// Sync all filesystems. -STATIC mp_obj_t os_sync(void) { - for (mp_vfs_mount_t *vfs = MP_STATE_VM(vfs_mount_table); vfs != NULL; vfs = vfs->next) { - // this assumes that vfs->obj is fs_user_mount_t with block device functions - disk_ioctl(MP_OBJ_TO_PTR(vfs->obj), CTRL_SYNC, NULL); - } - return mp_const_none; -} -MP_DEFINE_CONST_FUN_OBJ_0(mod_os_sync_obj, os_sync); -#endif - -#if MICROPY_HW_ENABLE_RNG -/// \function urandom(n) -/// Return a bytes object with n random bytes, generated by the hardware -/// random number generator. -STATIC mp_obj_t os_urandom(mp_obj_t num) { - mp_int_t n = mp_obj_get_int(num); - vstr_t vstr; - vstr_init_len(&vstr, n); - for (int i = 0; i < n; i++) { - vstr.buf[i] = rng_get(); - } - return mp_obj_new_str_from_vstr(&mp_type_bytes, &vstr); -} -STATIC MP_DEFINE_CONST_FUN_OBJ_1(os_urandom_obj, os_urandom); -#endif - -// Get or set the UART object that the REPL is repeated on. -// TODO should accept any object with read/write methods. -STATIC mp_obj_t os_dupterm(mp_uint_t n_args, const mp_obj_t *args) { - if (n_args == 0) { - if (MP_STATE_PORT(pyb_stdio_uart) == NULL) { - return mp_const_none; - } else { - return MP_STATE_PORT(pyb_stdio_uart); - } - } else { - if (args[0] == mp_const_none) { - MP_STATE_PORT(pyb_stdio_uart) = NULL; - } else if (mp_obj_get_type(args[0]) == &machine_hard_uart_type) { - MP_STATE_PORT(pyb_stdio_uart) = args[0]; - } else { - mp_raise_ValueError("need a UART object"); - } - return mp_const_none; - } -} -MP_DEFINE_CONST_FUN_OBJ_VAR_BETWEEN(mod_os_dupterm_obj, 0, 1, os_dupterm); - -STATIC const mp_rom_map_elem_t os_module_globals_table[] = { - { MP_ROM_QSTR(MP_QSTR___name__), MP_ROM_QSTR(MP_QSTR_uos) }, - - { MP_ROM_QSTR(MP_QSTR_uname), MP_ROM_PTR(&os_uname_obj) }, - -#if MICROPY_VFS - { MP_ROM_QSTR(MP_QSTR_chdir), MP_ROM_PTR(&mp_vfs_chdir_obj) }, - { MP_ROM_QSTR(MP_QSTR_getcwd), MP_ROM_PTR(&mp_vfs_getcwd_obj) }, - { MP_ROM_QSTR(MP_QSTR_listdir), MP_ROM_PTR(&mp_vfs_listdir_obj) }, - { MP_ROM_QSTR(MP_QSTR_mkdir), MP_ROM_PTR(&mp_vfs_mkdir_obj) }, - { MP_ROM_QSTR(MP_QSTR_remove), MP_ROM_PTR(&mp_vfs_remove_obj) }, - { MP_ROM_QSTR(MP_QSTR_rename), MP_ROM_PTR(&mp_vfs_rename_obj) }, - { MP_ROM_QSTR(MP_QSTR_rmdir), MP_ROM_PTR(&mp_vfs_rmdir_obj) }, - { MP_ROM_QSTR(MP_QSTR_stat), MP_ROM_PTR(&mp_vfs_stat_obj) }, - { MP_ROM_QSTR(MP_QSTR_statvfs), MP_ROM_PTR(&mp_vfs_statvfs_obj) }, - { MP_ROM_QSTR(MP_QSTR_unlink), MP_ROM_PTR(&mp_vfs_remove_obj) }, // unlink aliases to remove - - { MP_ROM_QSTR(MP_QSTR_sync), MP_ROM_PTR(&mod_os_sync_obj) }, -#endif - - /// \constant sep - separation character used in paths - { MP_ROM_QSTR(MP_QSTR_sep), MP_ROM_QSTR(MP_QSTR__slash_) }, - -#if MICROPY_HW_ENABLE_RNG - { MP_ROM_QSTR(MP_QSTR_urandom), MP_ROM_PTR(&os_urandom_obj) }, -#endif - - // these are MicroPython extensions - { MP_ROM_QSTR(MP_QSTR_dupterm), MP_ROM_PTR(&mod_os_dupterm_obj) }, -#if MICROPY_VFS - { MP_ROM_QSTR(MP_QSTR_mount), MP_ROM_PTR(&mp_vfs_mount_obj) }, - { MP_ROM_QSTR(MP_QSTR_umount), MP_ROM_PTR(&mp_vfs_umount_obj) }, - { MP_ROM_QSTR(MP_QSTR_VfsFat), MP_ROM_PTR(&mp_fat_vfs_type) }, -#endif -}; - -STATIC MP_DEFINE_CONST_DICT(os_module_globals, os_module_globals_table); - -const mp_obj_module_t mp_module_uos = { - .base = { &mp_type_module }, - .globals = (mp_obj_dict_t*)&os_module_globals, -}; diff --git a/ports/nrf/mpconfigport.h b/ports/nrf/mpconfigport.h index 46ad669119..7e23486adb 100644 --- a/ports/nrf/mpconfigport.h +++ b/ports/nrf/mpconfigport.h @@ -30,41 +30,45 @@ #include // options to control how MicroPython is built -#ifndef MICROPY_VFS -#define MICROPY_VFS (1) -#endif -#define MICROPY_VFS_FAT (MICROPY_VFS) -#define MICROPY_ALLOC_PATH_MAX (512) -#define MICROPY_PERSISTENT_CODE_LOAD (0) -#define MICROPY_EMIT_THUMB (0) -#define MICROPY_EMIT_INLINE_THUMB (0) -#define MICROPY_COMP_MODULE_CONST (0) -#define MICROPY_COMP_TRIPLE_TUPLE_ASSIGN (0) -#define MICROPY_READER_VFS (MICROPY_VFS) -#define MICROPY_ENABLE_GC (1) -#define MICROPY_ENABLE_FINALISER (1) -#define MICROPY_STACK_CHECK (0) -#define MICROPY_HELPER_REPL (1) -#define MICROPY_REPL_EMACS_KEYS (0) -#define MICROPY_REPL_AUTO_INDENT (1) -#define MICROPY_ENABLE_SOURCE_LINE (0) -#define MICROPY_LONGINT_IMPL (MICROPY_LONGINT_IMPL_MPZ) +#define MICROPY_ALLOC_PATH_MAX (512) +#define MICROPY_PERSISTENT_CODE_LOAD (1) +#define MICROPY_EMIT_THUMB (0) +#define MICROPY_EMIT_INLINE_THUMB (0) +#define MICROPY_COMP_MODULE_CONST (0) +#define MICROPY_COMP_TRIPLE_TUPLE_ASSIGN (0) +#define MICROPY_READER_VFS (MICROPY_VFS) +#define MICROPY_ENABLE_GC (1) +#define MICROPY_ENABLE_FINALISER (1) +#define MICROPY_STACK_CHECK (0) +#define MICROPY_HELPER_REPL (1) +#define MICROPY_REPL_EMACS_KEYS (0) +#define MICROPY_REPL_AUTO_INDENT (1) +#define MICROPY_ENABLE_SOURCE_LINE (0) +//CP UPDATE: See mpconfigport.h for LONGINT implementation +#define MICROPY_LONGINT_IMPL (MICROPY_LONGINT_IMPL_MPZ) #if NRF51 -#define MICROPY_FLOAT_IMPL (MICROPY_FLOAT_IMPL_NONE) +#define MICROPY_FLOAT_IMPL (MICROPY_FLOAT_IMPL_NONE) #else -#define MICROPY_FLOAT_IMPL (MICROPY_FLOAT_IMPL_FLOAT) +#define MICROPY_FLOAT_IMPL (MICROPY_FLOAT_IMPL_FLOAT) #endif -#define MICROPY_OPT_COMPUTED_GOTO (0) +#define MICROPY_OPT_COMPUTED_GOTO (0) #define MICROPY_OPT_CACHE_MAP_LOOKUP_IN_BYTECODE (0) -#define MICROPY_OPT_MPZ_BITWISE (0) +#define MICROPY_OPT_MPZ_BITWISE (0) // fatfs configuration used in ffconf.h -#define MICROPY_FATFS_ENABLE_LFN (1) -#define MICROPY_FATFS_LFN_CODE_PAGE (437) /* 1=SFN/ANSI 437=LFN/U.S.(OEM) */ -#define MICROPY_FATFS_USE_LABEL (1) -#define MICROPY_FATFS_RPATH (2) -#define MICROPY_FATFS_MULTI_PARTITION (1) +#define MICROPY_FATFS_ENABLE_LFN (1) +#define MICROPY_FATFS_LFN_CODE_PAGE (437) /* 1=SFN/ANSI 437=LFN/U.S.(OEM) */ +#define MICROPY_FATFS_USE_LABEL (1) +#define MICROPY_FATFS_RPATH (2) +#define MICROPY_FATFS_MULTI_PARTITION (0) +#define MICROPY_FATFS_NUM_PERSISTENT (1) + +//#define MICROPY_FATFS_MAX_SS (4096) +#define FILESYSTEM_BLOCK_SIZE (512) + +#define MICROPY_VFS (1) +#define MICROPY_VFS_FAT (MICROPY_VFS) // TODO these should be generic, not bound to fatfs #define mp_type_fileio fatfs_type_fileio @@ -77,101 +81,104 @@ #define mp_builtin_open_obj mp_vfs_open_obj #endif -#define MICROPY_STREAMS_NON_BLOCK (1) -#define MICROPY_MODULE_WEAK_LINKS (1) -#define MICROPY_CAN_OVERRIDE_BUILTINS (1) -#define MICROPY_USE_INTERNAL_ERRNO (1) -#define MICROPY_PY_FUNCTION_ATTRS (1) -#define MICROPY_PY_BUILTINS_STR_UNICODE (0) -#define MICROPY_PY_BUILTINS_STR_CENTER (0) -#define MICROPY_PY_BUILTINS_STR_PARTITION (0) -#define MICROPY_PY_BUILTINS_STR_SPLITLINES (0) -#define MICROPY_PY_BUILTINS_MEMORYVIEW (1) -#define MICROPY_PY_BUILTINS_FROZENSET (1) -#define MICROPY_PY_BUILTINS_EXECFILE (0) -#define MICROPY_PY_BUILTINS_COMPILE (1) -#define MICROPY_PY_BUILTINS_HELP (1) -#define MICROPY_PY_BUILTINS_HELP_TEXT nrf5_help_text -#define MICROPY_PY_BUILTINS_HELP_MODULES (1) -#define MICROPY_MODULE_BUILTIN_INIT (1) -#define MICROPY_PY_ALL_SPECIAL_METHODS (0) -#define MICROPY_PY_MICROPYTHON_MEM_INFO (1) -#define MICROPY_PY_ARRAY_SLICE_ASSIGN (0) -#define MICROPY_PY_BUILTINS_SLICE_ATTRS (0) -#define MICROPY_PY_SYS_EXIT (1) -#define MICROPY_PY_SYS_MAXSIZE (1) -#define MICROPY_PY_SYS_STDFILES (0) -#define MICROPY_PY_SYS_STDIO_BUFFER (0) -#define MICROPY_PY_COLLECTIONS_ORDEREDDICT (0) -#define MICROPY_PY_MATH_SPECIAL_FUNCTIONS (0) -#define MICROPY_PY_CMATH (0) -#define MICROPY_PY_IO (0) -#define MICROPY_PY_IO_FILEIO (0) -#define MICROPY_PY_UERRNO (0) -#define MICROPY_PY_UBINASCII (0) -#define MICROPY_PY_URANDOM (0) -#define MICROPY_PY_URANDOM_EXTRA_FUNCS (0) -#define MICROPY_PY_UCTYPES (0) -#define MICROPY_PY_UZLIB (0) -#define MICROPY_PY_UJSON (0) -#define MICROPY_PY_URE (0) -#define MICROPY_PY_UHEAPQ (0) -#define MICROPY_PY_UHASHLIB (0) -#define MICROPY_PY_UTIME_MP_HAL (1) -#define MICROPY_PY_MACHINE (1) -#define MICROPY_PY_MACHINE_PULSE (0) -#define MICROPY_PY_MACHINE_I2C_MAKE_NEW machine_hard_i2c_make_new -#define MICROPY_PY_MACHINE_SPI (0) -#define MICROPY_PY_MACHINE_SPI_MIN_DELAY (0) -#define MICROPY_PY_FRAMEBUF (0) +#define MICROPY_STREAMS_NON_BLOCK (1) +#define MICROPY_MODULE_WEAK_LINKS (1) +#define MICROPY_CAN_OVERRIDE_BUILTINS (1) +#define MICROPY_USE_INTERNAL_ERRNO (1) +#define MICROPY_PY_FUNCTION_ATTRS (1) +#define MICROPY_PY_BUILTINS_STR_UNICODE (1) +#define MICROPY_PY_BUILTINS_STR_CENTER (0) +#define MICROPY_PY_BUILTINS_STR_PARTITION (0) +#define MICROPY_PY_BUILTINS_STR_SPLITLINES (0) +#define MICROPY_PY_BUILTINS_MEMORYVIEW (1) +#define MICROPY_PY_BUILTINS_FROZENSET (1) +#define MICROPY_PY_BUILTINS_EXECFILE (0) +#define MICROPY_PY_BUILTINS_COMPILE (1) +#define MICROPY_PY_BUILTINS_HELP (1) +#define MICROPY_PY_BUILTINS_HELP_TEXT nrf5_help_text +#define MICROPY_PY_BUILTINS_HELP_MODULES (1) +#define MICROPY_PY_BUILTINS_INPUT (1) +#define MICROPY_MODULE_BUILTIN_INIT (1) +#define MICROPY_PY_ALL_SPECIAL_METHODS (0) +#define MICROPY_PY_MICROPYTHON_MEM_INFO (1) +#define MICROPY_PY_ARRAY_SLICE_ASSIGN (0) +#define MICROPY_PY_BUILTINS_SLICE_ATTRS (0) +#define MICROPY_PY_SYS_EXIT (1) +#define MICROPY_PY_SYS_MAXSIZE (1) +#define MICROPY_PY_SYS_STDFILES (0) +#define MICROPY_PY_SYS_STDIO_BUFFER (0) +#define MICROPY_PY_COLLECTIONS_ORDEREDDICT (0) +#define MICROPY_PY_MATH_SPECIAL_FUNCTIONS (0) +#define MICROPY_PY_CMATH (0) +#define MICROPY_PY_IO (0) +#define MICROPY_PY_IO_FILEIO (0) +#define MICROPY_PY_UERRNO (0) +#define MICROPY_PY_UBINASCII (0) +#define MICROPY_PY_URANDOM (0) +#define MICROPY_PY_URANDOM_EXTRA_FUNCS (0) +#define MICROPY_PY_UCTYPES (0) +#define MICROPY_PY_UZLIB (0) +#define MICROPY_PY_UJSON (0) +#define MICROPY_PY_URE (0) +#define MICROPY_PY_UHEAPQ (0) +#define MICROPY_PY_UHASHLIB (0) +#define MICROPY_PY_UTIME_MP_HAL (1) +#define MICROPY_PY_MACHINE (1) +#define MICROPY_PY_MACHINE_PULSE (0) +#define MICROPY_PY_MACHINE_I2C_MAKE_NEW machine_hard_i2c_make_new +#define MICROPY_PY_MACHINE_SPI (0) +#define MICROPY_PY_MACHINE_SPI_MIN_DELAY (0) +#define MICROPY_PY_FRAMEBUF (0) + +#define MICROPY_KBD_EXCEPTION (1) #ifndef MICROPY_HW_LED_COUNT -#define MICROPY_HW_LED_COUNT (0) +#define MICROPY_HW_LED_COUNT (0) #endif #ifndef MICROPY_HW_LED_PULLUP -#define MICROPY_HW_LED_PULLUP (0) +#define MICROPY_HW_LED_PULLUP (0) #endif #ifndef MICROPY_PY_MUSIC -#define MICROPY_PY_MUSIC (0) +#define MICROPY_PY_MUSIC (0) #endif #ifndef MICROPY_PY_MACHINE_ADC -#define MICROPY_PY_MACHINE_ADC (0) +#define MICROPY_PY_MACHINE_ADC (0) #endif #ifndef MICROPY_PY_MACHINE_I2C -#define MICROPY_PY_MACHINE_I2C (0) +#define MICROPY_PY_MACHINE_I2C (0) #endif #ifndef MICROPY_PY_MACHINE_HW_SPI -#define MICROPY_PY_MACHINE_HW_SPI (1) +#define MICROPY_PY_MACHINE_HW_SPI (1) #endif #ifndef MICROPY_PY_MACHINE_HW_PWM -#define MICROPY_PY_MACHINE_HW_PWM (0) +#define MICROPY_PY_MACHINE_HW_PWM (0) #endif #ifndef MICROPY_PY_MACHINE_SOFT_PWM -#define MICROPY_PY_MACHINE_SOFT_PWM (0) +#define MICROPY_PY_MACHINE_SOFT_PWM (0) #endif #ifndef MICROPY_PY_MACHINE_TIMER -#define MICROPY_PY_MACHINE_TIMER (0) +#define MICROPY_PY_MACHINE_TIMER (0) #endif #ifndef MICROPY_PY_MACHINE_RTC -#define MICROPY_PY_MACHINE_RTC (0) +#define MICROPY_PY_MACHINE_RTC (0) #endif #ifndef MICROPY_PY_HW_RNG -#define MICROPY_PY_HW_RNG (1) +#define MICROPY_PY_HW_RNG (1) #endif #define MICROPY_ENABLE_EMERGENCY_EXCEPTION_BUF (1) -#define MICROPY_EMERGENCY_EXCEPTION_BUF_SIZE (0) +#define MICROPY_EMERGENCY_EXCEPTION_BUF_SIZE (0) // if sdk is in use, import configuration #if BLUETOOTH_SD @@ -203,19 +210,27 @@ typedef unsigned int mp_uint_t; // must be pointer size typedef long mp_off_t; // extra built in modules to add to the list of known ones + +extern const struct _mp_obj_module_t microcontroller_module; +extern const struct _mp_obj_module_t analogio_module; +extern const struct _mp_obj_module_t digitalio_module; +extern const struct _mp_obj_module_t pulseio_module; +extern const struct _mp_obj_module_t busio_module; +extern const struct _mp_obj_module_t board_module; +extern const struct _mp_obj_module_t os_module; +extern const struct _mp_obj_module_t random_module; +extern const struct _mp_obj_module_t storage_module; +extern const struct _mp_obj_module_t time_module; +extern const struct _mp_obj_module_t supervisor_module; + extern const struct _mp_obj_module_t pyb_module; extern const struct _mp_obj_module_t machine_module; extern const struct _mp_obj_module_t mp_module_utime; -extern const struct _mp_obj_module_t mp_module_uos; extern const struct _mp_obj_module_t mp_module_ubluepy; extern const struct _mp_obj_module_t music_module; extern const struct _mp_obj_module_t random_module; -#if MICROPY_PY_UBLUEPY -#define UBLUEPY_MODULE { MP_ROM_QSTR(MP_QSTR_ubluepy), MP_ROM_PTR(&mp_module_ubluepy) }, -#else -#define UBLUEPY_MODULE -#endif +extern const struct _mp_obj_module_t ble_module; #if MICROPY_PY_MUSIC #define MUSIC_MODULE { MP_ROM_QSTR(MP_QSTR_music), MP_ROM_PTR(&music_module) }, @@ -229,7 +244,11 @@ extern const struct _mp_obj_module_t random_module; #define RANDOM_MODULE #endif -#if BLUETOOTH_SD +#if MICROPY_PY_UBLUEPY +#define UBLUEPY_MODULE { MP_ROM_QSTR(MP_QSTR_ubluepy), MP_ROM_PTR(&mp_module_ubluepy) }, +#else +#define UBLUEPY_MODULE +#endif #if MICROPY_PY_BLE extern const struct _mp_obj_module_t ble_module; @@ -239,43 +258,38 @@ extern const struct _mp_obj_module_t ble_module; #endif #define MICROPY_PORT_BUILTIN_MODULES \ - { MP_ROM_QSTR(MP_QSTR_pyb), MP_ROM_PTR(&pyb_module) }, \ - { MP_ROM_QSTR(MP_QSTR_machine), MP_ROM_PTR(&machine_module) }, \ - { MP_ROM_QSTR(MP_QSTR_utime), MP_ROM_PTR(&mp_module_utime) }, \ - { MP_ROM_QSTR(MP_QSTR_time), MP_ROM_PTR(&mp_module_utime) }, \ - { MP_ROM_QSTR(MP_QSTR_uos), MP_ROM_PTR(&mp_module_uos) }, \ - BLE_MODULE \ - MUSIC_MODULE \ - UBLUEPY_MODULE \ - RANDOM_MODULE \ - - -#else -extern const struct _mp_obj_module_t ble_module; -#define MICROPY_PORT_BUILTIN_MODULES \ - { MP_ROM_QSTR(MP_QSTR_pyb), MP_ROM_PTR(&pyb_module) }, \ - { MP_ROM_QSTR(MP_QSTR_machine), MP_ROM_PTR(&machine_module) }, \ - { MP_ROM_QSTR(MP_QSTR_utime), MP_ROM_PTR(&mp_module_utime) }, \ - { MP_ROM_QSTR(MP_QSTR_uos), MP_ROM_PTR(&mp_module_uos) }, \ + { MP_OBJ_NEW_QSTR (MP_QSTR_board ), (mp_obj_t)&board_module }, \ + { MP_OBJ_NEW_QSTR (MP_QSTR_busio ), (mp_obj_t)&busio_module }, \ + { MP_OBJ_NEW_QSTR (MP_QSTR_analogio ), (mp_obj_t)&analogio_module }, \ + { MP_OBJ_NEW_QSTR (MP_QSTR_digitalio ), (mp_obj_t)&digitalio_module }, \ + { MP_OBJ_NEW_QSTR (MP_QSTR_pulseio ), (mp_obj_t)&pulseio_module }, \ + { MP_OBJ_NEW_QSTR (MP_QSTR_microcontroller ), (mp_obj_t)µcontroller_module }, \ + { MP_OBJ_NEW_QSTR (MP_QSTR_os ), (mp_obj_t)&os_module }, \ + { MP_OBJ_NEW_QSTR (MP_QSTR_random ), (mp_obj_t)&random_module }, \ + { MP_OBJ_NEW_QSTR (MP_QSTR_storage ), (mp_obj_t)&storage_module },\ + { MP_OBJ_NEW_QSTR (MP_QSTR_supervisor ), (mp_obj_t)&supervisor_module }, \ + { MP_OBJ_NEW_QSTR (MP_QSTR_time ), (mp_obj_t)&time_module }, \ + { MP_ROM_QSTR (MP_QSTR_pyb ), MP_ROM_PTR(&pyb_module) }, \ + { MP_ROM_QSTR (MP_QSTR_utime ), MP_ROM_PTR(&mp_module_utime) }, \ MUSIC_MODULE \ RANDOM_MODULE \ + /*BLE_MODULE \ + UBLUEPY_MODULE \*/ -#endif // BLUETOOTH_SD - #define MICROPY_PORT_BUILTIN_MODULE_WEAK_LINKS \ - { MP_ROM_QSTR(MP_QSTR_os), MP_ROM_PTR(&mp_module_uos) }, \ - { MP_ROM_QSTR(MP_QSTR_time), MP_ROM_PTR(&mp_module_utime) }, \ + { MP_ROM_QSTR (MP_QSTR_time ), MP_ROM_PTR(&mp_module_utime) }, \ // extra built in names to add to the global namespace #define MICROPY_PORT_BUILTINS \ - { MP_ROM_QSTR(MP_QSTR_help), MP_ROM_PTR(&mp_builtin_help_obj) }, \ - { MP_ROM_QSTR(MP_QSTR_open), MP_ROM_PTR(&mp_builtin_open_obj) }, \ + { MP_ROM_QSTR (MP_QSTR_help), MP_ROM_PTR(&mp_builtin_help_obj) }, \ + { MP_OBJ_NEW_QSTR (MP_QSTR_input), (mp_obj_t)&mp_builtin_input_obj }, \ + { MP_ROM_QSTR (MP_QSTR_open), MP_ROM_PTR(&mp_builtin_open_obj) }, \ // extra constants #define MICROPY_PORT_CONSTANTS \ - { MP_ROM_QSTR(MP_QSTR_pyb), MP_ROM_PTR(&pyb_module) }, \ - { MP_ROM_QSTR(MP_QSTR_machine), MP_ROM_PTR(&machine_module) }, \ + { MP_ROM_QSTR (MP_QSTR_pyb ), MP_ROM_PTR(&pyb_module) }, \ + { MP_ROM_QSTR (MP_QSTR_machine ), MP_ROM_PTR(&machine_module) }, \ BLE_MODULE \ #define MP_STATE_PORT MP_STATE_VM @@ -308,5 +322,6 @@ extern const struct _mp_obj_module_t ble_module; #include #define MICROPY_PIN_DEFS_PORT_H "pin_defs_nrf5.h" +#define CIRCUITPY_BOOT_OUTPUT_FILE "/boot_out.txt" #endif diff --git a/ports/nrf/mpconfigport.mk b/ports/nrf/mpconfigport.mk new file mode 100644 index 0000000000..dc29a92cf5 --- /dev/null +++ b/ports/nrf/mpconfigport.mk @@ -0,0 +1,4 @@ +# Define an equivalent for MICROPY_LONGINT_IMPL, to pass to $(MPY-TOOL) in py/mkrules.mk +# $(MPY-TOOL) needs to know what kind of longint to use (if any) to freeze long integers. +# This should correspond to the MICROPY_LONGINT_IMPL definition in mpconfigport.h. +MPY_TOOL_LONGINT_IMPL = -mlongint-impl=mpz diff --git a/ports/nrf/mphalport.c b/ports/nrf/mphalport.c index 1abd4b186a..957d3535d2 100644 --- a/ports/nrf/mphalport.c +++ b/ports/nrf/mphalport.c @@ -30,7 +30,10 @@ #include "py/mpstate.h" #include "py/mphal.h" #include "py/mperrno.h" -#include "uart.h" +#include "hal_uart.h" + +#define UART_INSTANCE UART_BASE(0) +FIL* boot_output_file; // this table converts from HAL_StatusTypeDef to POSIX errno const byte mp_hal_status_to_errno_table[4] = { @@ -44,31 +47,36 @@ NORETURN void mp_hal_raise(HAL_StatusTypeDef status) { nlr_raise(mp_obj_new_exception_arg1(&mp_type_OSError, MP_OBJ_NEW_SMALL_INT(mp_hal_status_to_errno_table[status]))); } -void mp_hal_set_interrupt_char(int c) { - -} - #if (MICROPY_PY_BLE_NUS == 0) int mp_hal_stdin_rx_chr(void) { for (;;) { - if (MP_STATE_PORT(pyb_stdio_uart) != NULL && uart_rx_any(MP_STATE_PORT(pyb_stdio_uart))) { - return uart_rx_char(MP_STATE_PORT(pyb_stdio_uart)); + if ( hal_uart_available(UART_INSTANCE) ) { + uint8_t ch; + hal_uart_char_read(UART_INSTANCE, &ch); + return (int) ch; } } return 0; } +bool mp_hal_stdin_any(void) { + return hal_uart_available(UART_INSTANCE); +} + void mp_hal_stdout_tx_strn(const char *str, mp_uint_t len) { - if (MP_STATE_PORT(pyb_stdio_uart) != NULL) { - uart_tx_strn(MP_STATE_PORT(pyb_stdio_uart), str, len); - } + while(len--) { + hal_uart_char_write(UART_INSTANCE, *str++); + } } void mp_hal_stdout_tx_strn_cooked(const char *str, mp_uint_t len) { - if (MP_STATE_PORT(pyb_stdio_uart) != NULL) { - uart_tx_strn_cooked(MP_STATE_PORT(pyb_stdio_uart), str, len); + while(len--){ + if (*str == '\n') { + hal_uart_char_write(UART_INSTANCE, '\r'); } + hal_uart_char_write(UART_INSTANCE, *str++); + } } #endif diff --git a/ports/nrf/mphalport.h b/ports/nrf/mphalport.h index 4e4e117033..3334fd7fe9 100644 --- a/ports/nrf/mphalport.h +++ b/ports/nrf/mphalport.h @@ -32,6 +32,8 @@ #include "pin.h" #include "hal_gpio.h" +#include "lib/oofatfs/ff.h" + typedef enum { HAL_OK = 0x00, @@ -40,6 +42,8 @@ typedef enum HAL_TIMEOUT = 0x03 } HAL_StatusTypeDef; +extern FIL* boot_output_file; + static inline uint32_t hal_tick_fake(void) { return 0; } @@ -53,6 +57,7 @@ void mp_hal_set_interrupt_char(int c); // -1 to disable int mp_hal_stdin_rx_chr(void); void mp_hal_stdout_tx_str(const char *str); +bool mp_hal_stdin_any(void); #define mp_hal_pin_obj_t const pin_obj_t* #define mp_hal_get_pin_obj(o) pin_find(o) diff --git a/ports/nrf/supervisor/filesystem.c b/ports/nrf/supervisor/filesystem.c new file mode 100644 index 0000000000..5d622725b4 --- /dev/null +++ b/ports/nrf/supervisor/filesystem.c @@ -0,0 +1,88 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2017 Scott Shawcroft for Adafruit Industries + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#include "extmod/vfs_fat.h" +#include "lib/oofatfs/ff.h" +#include "lib/oofatfs/diskio.h" + +#include "py/mpstate.h" + +#include "internal_flash.h" + +fs_user_mount_t fs_user_mount_flash; +mp_vfs_mount_t mp_vfs_mount_flash; + + +void filesystem_init(bool create_allowed) { + // init the vfs object + fs_user_mount_t *vfs_fat = &fs_user_mount_flash; + vfs_fat->flags = 0; + flash_init_vfs(vfs_fat); + + // try to mount the flash + FRESULT res = f_mount(&vfs_fat->fatfs); + + if (res == FR_NO_FILESYSTEM && create_allowed) { + // no filesystem so create a fresh one + uint8_t working_buf[_MAX_SS]; + res = f_mkfs(&vfs_fat->fatfs, FM_FAT | FM_SFD, 4096, working_buf, sizeof(working_buf)); + // Flush the new file system to make sure its repaired immediately. + flash_flush(); + if (res != FR_OK) { + return; + } + + // set label + f_setlabel(&vfs_fat->fatfs, "CIRCUITPY"); + flash_flush(); + + // create lib folder + f_mkdir(&vfs_fat->fatfs, "/lib"); + } else if (res != FR_OK) { + return; + } + mp_vfs_mount_t *vfs = &mp_vfs_mount_flash; + vfs->str = "/"; + vfs->len = 1; + vfs->obj = MP_OBJ_FROM_PTR(vfs_fat); + vfs->next = NULL; + MP_STATE_VM(vfs_mount_table) = vfs; + + // The current directory is used as the boot up directory. + // It is set to the internal flash filesystem by default. + MP_STATE_PORT(vfs_cur) = vfs; +} + +void filesystem_flush(void) { + flash_flush(); +} + +void filesystem_writable_by_python(bool writable) { +} + +bool filesystem_present(void) { + return true; +} diff --git a/ports/nrf/supervisor/port.c b/ports/nrf/supervisor/port.c new file mode 100644 index 0000000000..4ac9c08e01 --- /dev/null +++ b/ports/nrf/supervisor/port.c @@ -0,0 +1,79 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2017 Scott Shawcroft for Adafruit Industries + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#include +#include "supervisor/port.h" +#include "boards/board.h" + +#include "common-hal/microcontroller/Pin.h" +#include "common-hal/pulseio/PWMOut.h" + +safe_mode_t port_init(void) { + board_init(); + +#if 0 + // Configure millisecond timer initialization. + tick_init(); + + #ifdef CIRCUITPY_CANARY_WORD + // Run in safe mode if the canary is corrupt. + if (_ezero != CIRCUITPY_CANARY_WORD) { + return HARD_CRASH; + } + #endif + + if (board_requests_safe_mode()) { + return USER_SAFE_MODE; + } +#endif + + return NO_SAFE_MODE; +} + +void reset_port(void) { + pwmout_reset(); + reset_all_pins(); +} + + +void HardFault_Handler(void) +{ +#if NRF52 +// static volatile uint32_t reg; +// static volatile uint32_t reg2; +// static volatile uint32_t bfar; +// reg = SCB->HFSR; +// reg2 = SCB->CFSR; +// bfar = SCB->BFAR; +// for (int i = 0; i < 0; i++) +// { +// (void)reg; +// (void)reg2; +// (void)bfar; +// } +#endif +} + diff --git a/ports/nrf/supervisor/serial.c b/ports/nrf/supervisor/serial.c new file mode 100644 index 0000000000..465c8394c5 --- /dev/null +++ b/ports/nrf/supervisor/serial.c @@ -0,0 +1,77 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2017 Scott Shawcroft for Adafruit Industries + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#include "supervisor/serial.h" + +#include "py/obj.h" +#include "py/runtime.h" +#include "mphalport.h" +#include "pins.h" +#include "hal_uart.h" + +void serial_init(void) { +// uart_init0(); +// +// mp_obj_t args[2] = { +// MP_OBJ_NEW_SMALL_INT(0), +// MP_OBJ_NEW_SMALL_INT(115200), +// }; +// MP_STATE_PORT(pyb_stdio_uart) = machine_hard_uart_type.make_new((mp_obj_t)&machine_hard_uart_type, MP_ARRAY_SIZE(args), 0, args); + + hal_uart_init_t param = + { + .id = 0, + .rx_pin = &MICROPY_HW_UART1_RX, + .tx_pin = &MICROPY_HW_UART1_TX, + .rts_pin = NULL, + .cts_pin = NULL, + .flow_control = MICROPY_HW_UART1_HWFC ? true : false, + .use_parity = false, + .baud_rate = HAL_UART_BAUD_115K2, + .irq_priority = 6, + .irq_num = UARTE0_UART0_IRQn + }; + + hal_uart_init( UART_BASE(0), ¶m); +} + + +bool serial_connected(void) { + return true; +} + +char serial_read(void) { + return (char) mp_hal_stdin_rx_chr(); +} + +bool serial_bytes_available(void) { + return mp_hal_stdin_any(); +} + +void serial_write(const char* text) { + mp_hal_stdout_tx_str(text); +} + diff --git a/supervisor/port.h b/supervisor/port.h index 2f7bc64448..f30d87b47b 100644 --- a/supervisor/port.h +++ b/supervisor/port.h @@ -57,4 +57,8 @@ void reset_port(void); // Reset the rest of the board. void reset_board(void); +#ifdef NRF52_SERIES +void HardFault_Handler(void); +#endif + #endif // MICROPY_INCLUDED_SUPERVISOR_PORT_H diff --git a/tools/build_adafruit_bins.sh b/tools/build_adafruit_bins.sh index 47fe7c66ad..ae9c256d24 100755 --- a/tools/build_adafruit_bins.sh +++ b/tools/build_adafruit_bins.sh @@ -1,7 +1,8 @@ rm -rf ports/atmel-samd/build* rm -rf ports/esp8266/build* +rm -rf ports/nrf/build* -ATMEL_BOARDS="arduino_zero circuitplayground_express feather_m0_basic feather_m0_adalogger feather_m0_express metro_m0_express metro_m4_express trinket_m0 gemma_m0" +ATMEL_BOARDS="arduino_zero circuitplayground_express feather_m0_basic feather_m0_adalogger feather_m0_express metro_m0_express metro_m4_express trinket_m0 gemma_m0 feather52" ROSIE_SETUPS="rosie-ci" PARALLEL="-j 5" @@ -16,8 +17,13 @@ else fi for board in $boards; do - make $PARALLEL -C ports/atmel-samd BOARD=$board - (( exit_status = exit_status || $? )) + if [ $board == "feather52" ]; then + make $PARALLEL -C ports/nrf BOARD=feather52 + (( exit_status = exit_status || $? )) + else + make $PARALLEL -C ports/atmel-samd BOARD=$board + (( exit_status = exit_status || $? )) + fi done if [ -z "$TRAVIS" ]; then make $PARALLEL -C ports/esp8266 BOARD=feather_huzzah @@ -40,10 +46,15 @@ fi for board in $boards; do mkdir -p bin/$board/ - cp ports/atmel-samd/build-$board/firmware.bin bin/$board/adafruit-circuitpython-$board-$version.bin - (( exit_status = exit_status || $? )) - cp ports/atmel-samd/build-$board/firmware.uf2 bin/$board/adafruit-circuitpython-$board-$version.uf2 - (( exit_status = exit_status || $? )) + if [ $board == "feather52" ]; then + cp ports/nrf/build-$board/firmware.bin bin/$board/adafruit-circuitpython-$board-$version.bin + (( exit_status = exit_status || $? )) + else + cp ports/atmel-samd/build-$board/firmware.bin bin/$board/adafruit-circuitpython-$board-$version.bin + (( exit_status = exit_status || $? )) + cp ports/atmel-samd/build-$board/firmware.uf2 bin/$board/adafruit-circuitpython-$board-$version.uf2 + (( exit_status = exit_status || $? )) + fi # Only upload to Rosie if its a pull request. if [ "$TRAVIS" == "true" ]; then for rosie in $ROSIE_SETUPS; do