diff --git a/.gitmodules b/.gitmodules index 4861053fe9..0146de4c65 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 = git@github.com:adafruit/nRF52_nrfutil.git 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..48a77357da 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,17 +11,18 @@ 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 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 @@ -34,10 +35,9 @@ 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- @@ -120,7 +120,6 @@ SRC_HAL = $(addprefix hal/,\ hal_spi.c \ hal_spie.c \ hal_time.c \ - hal_rtc.c \ hal_timer.c \ hal_twi.c \ hal_adc.c \ @@ -136,17 +135,19 @@ SRC_HAL += $(addprefix hal/,\ ) endif + SRC_C += \ - main.c \ mphalport.c \ help.c \ - gccollect.c \ pin_named_pins.c \ fatfs_port.c \ drivers/softpwm.c \ drivers/ticker.c \ drivers/bluetooth/ble_drv.c \ drivers/bluetooth/ble_uart.c \ + boards/$(BOARD)/board.c \ + lib/utils/context_manager_helpers.c \ + fifo.c \ DRIVERS_SRC_C += $(addprefix modules/,\ machine/modmachine.c \ @@ -156,7 +157,6 @@ 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 \ @@ -183,13 +183,38 @@ 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 \ + time/__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 \ + util.c + +SRC_COMMON_HAL_EXPANDED = $(addprefix shared-bindings/, $(SRC_COMMON_HAL)) \ + $(addprefix shared-bindings/, $(SRC_BINDINGS_ENUMS)) \ + $(addprefix common-hal/, $(SRC_COMMON_HAL)) + 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 += $(PY_O) $(SUPERVISOR_O) $(addprefix $(BUILD)/, $(SRC_C:.c=.o)) OBJ += $(addprefix $(BUILD)/, $(SRC_LIB:.c=.o)) OBJ += $(addprefix $(BUILD)/, $(SRC_HAL:.c=.o)) OBJ += $(addprefix $(BUILD)/, $(DRIVERS_SRC_C:.c=.o)) +OBJ += $(addprefix $(BUILD)/, $(SRC_COMMON_HAL_EXPANDED:.c=.o)) OBJ += $(BUILD)/pins_gen.o $(BUILD)/$(FATFS_DIR)/ff.o: COPT += -Os @@ -245,7 +270,7 @@ $(BUILD)/$(OUTPUT_FILENAME).elf: $(OBJ) $(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) $(SRC_LIB) $(DRIVERS_SRC_C) $(SRC_COMMON_HAL_EXPANDED) # Append any auto-generated sources that are needed by sources listed in # SRC_QSTR 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/feather52/README.md b/ports/nrf/boards/feather52/README.md index e05d899533..3a6fc85c98 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,50 @@ $ 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 libs/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`) +#### REPL over BLE support -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: +To build a CircuitPython binary with BLE support (S132) include `SD=s132` +as part of 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 +95,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 +109,49 @@ 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). diff --git a/ports/nrf/boards/feather52/board.c b/ports/nrf/boards/feather52/board.c new file mode 100644 index 0000000000..0f4cf4e305 --- /dev/null +++ b/ports/nrf/boards/feather52/board.c @@ -0,0 +1,122 @@ +/* + * 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" + +#if 0 +#include "common-hal/microcontroller/Pin.h" +#include "hal/include/hal_gpio.h" +#include "shared-bindings/digitalio/DigitalInOut.h" +#include "shared-bindings/neopixel_write/__init__.h" +#endif + +// 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/custom_nrf52832_dfu_app_2.0.1.ld b/ports/nrf/boards/feather52/custom_nrf52832_dfu_app_2.0.1.ld index 824b6becfe..57076266f4 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,7 +5,9 @@ ------------------------------------------------------------------------ START ADDR END ADDR SIZE DESCRIPTION ---------- ---------- ------- ----------------------------------------- - 0x00074000..0x00080000 ( 48KB) Serial + OTA Bootloader + 0x0007F000..0x0007FFFF ( 4KB) Bootloader Settings + 0x0007E000..0x0007EFFF ( 4KB) Master Boot Record Params + 0x00074000..0x0007DFFF ( 40KB) Serial + OTA Bootloader 0x0006D000..0x00073FFF ( 28KB) Private Config Data (Bonding, Keys, etc.) 0x00055000..0x0006CFFF ( 96KB) User Filesystem 0x0001C000..0x00054FFF (228KB) Application Code @@ -24,7 +26,7 @@ MEMORY /* 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 +37,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..d9705ba15a 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,7 +5,9 @@ ------------------------------------------------------------------------ START ADDR END ADDR SIZE DESCRIPTION ---------- ---------- ------- ----------------------------------------- - 0x00074000..0x00080000 ( 48KB) Serial + OTA Bootloader + 0x0007F000..0x0007FFFF ( 4KB) Bootloader Settings + 0x0007E000..0x0007EFFF ( 4KB) Master Boot Record Params + 0x00074000..0x0007DFFF ( 40KB) Serial + OTA Bootloader 0x0006D000..0x00073FFF ( 28KB) Private Config Data (Bonding, Keys, etc.) 0x00055000..0x0006CFFF ( 96KB) User Filesystem 0x00023000..0x00054FFF (200KB) Application Code @@ -24,7 +26,7 @@ MEMORY /* 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/mpconfigboard.h b/ports/nrf/boards/feather52/mpconfigboard.h index fca9274b79..4ba73f4478 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) @@ -74,3 +72,8 @@ #define MICROPY_HW_PWM2_NAME "PWM2" #define HELP_TEXT_BOARD_LED "1,2" + + + +#define PORT_HEAP_SIZE (16*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.csv b/ports/nrf/boards/feather52/pins.csv index b7017602a7..581525cfed 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 +11,PA11 +SCK,PA12 +MOSI,PA13 +MISO,PA14 +15,PA15 +16,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 +27,PA27 +A4,PA28,ADC0_IN4 +A5,PA29,ADC0_IN5 +A6,PA30,ADC0_IN6 +A7,PA31,ADC0_IN7 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/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/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/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/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..c5cd2839e4 100644 --- a/ports/nrf/hal/hal_gpio.h +++ b/ports/nrf/hal/hal_gpio.h @@ -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..642ab0d920 100644 --- a/ports/nrf/hal/hal_uart.c +++ b/ports/nrf/hal/hal_uart.c @@ -30,9 +30,12 @@ #include "nrf.h" #include "mphalport.h" #include "hal_uart.h" +#include "fifo.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 +69,21 @@ 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. - } +// p_instance->ERRORSRC = 0; +// while (p_instance->EVENTS_RXDRDY != 1) { +// // Wait for RXD data. +// } +// +// p_instance->EVENTS_RXDRDY = 0; +// *ch = p_instance->RXD; +// +// return p_instance->ERRORSRC; - p_instance->EVENTS_RXDRDY = 0; - *ch = p_instance->RXD; + while ( !fifo_read(_ff_uart, ch) ) { + // wait for fifo data + } - 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 +115,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 +155,27 @@ 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; + 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/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.h b/ports/nrf/modules/machine/pin.h index 1935a0d263..e9a8c031b1 100644 --- a/ports/nrf/modules/machine/pin.h +++ b/ports/nrf/modules/machine/pin.h @@ -62,6 +62,9 @@ typedef struct { 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 +87,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/uart.c b/ports/nrf/modules/machine/uart.c index b99afef622..f034299643 100644 --- a/ports/nrf/modules/machine/uart.c +++ b/ports/nrf/modules/machine/uart.c @@ -65,6 +65,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 +84,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/mpconfigport.h b/ports/nrf/mpconfigport.h index 46ad669119..90bd5c71f0 100644 --- a/ports/nrf/mpconfigport.h +++ b/ports/nrf/mpconfigport.h @@ -48,6 +48,7 @@ #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) @@ -203,6 +204,12 @@ 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 board_module; +extern const struct _mp_obj_module_t digitalio_module; +extern const struct _mp_obj_module_t time_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; @@ -253,10 +260,14 @@ extern const struct _mp_obj_module_t ble_module; #else extern const struct _mp_obj_module_t ble_module; #define MICROPY_PORT_BUILTIN_MODULES \ + { MP_OBJ_NEW_QSTR(MP_QSTR_board), (mp_obj_t)&board_module }, \ + { MP_OBJ_NEW_QSTR(MP_QSTR_digitalio), (mp_obj_t)&digitalio_module }, \ + { MP_OBJ_NEW_QSTR(MP_QSTR_microcontroller), (mp_obj_t)µcontroller_module }, \ { 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_time), (mp_obj_t)&time_module }, \ MUSIC_MODULE \ RANDOM_MODULE \ 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..68abad49f0 100644 --- a/ports/nrf/mphalport.c +++ b/ports/nrf/mphalport.c @@ -59,6 +59,11 @@ int mp_hal_stdin_rx_chr(void) { return 0; } +bool mp_hal_stdin_any(void) +{ + return uart_rx_any(MP_STATE_PORT(pyb_stdio_uart)); +} + 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); diff --git a/ports/nrf/mphalport.h b/ports/nrf/mphalport.h index 4e4e117033..787cfba8cf 100644 --- a/ports/nrf/mphalport.h +++ b/ports/nrf/mphalport.h @@ -53,6 +53,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/pins.h b/ports/nrf/pins.h new file mode 100644 index 0000000000..ce6094aeb6 --- /dev/null +++ b/ports/nrf/pins.h @@ -0,0 +1,32 @@ +/* + * This file is part of the Micro Python 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_PINS_H +#define MICROPY_INCLUDED_NRF_PINS_H + + + +#endif // MICROPY_INCLUDED_NRF_PINS_H diff --git a/ports/nrf/supervisor/filesystem.c b/ports/nrf/supervisor/filesystem.c new file mode 100644 index 0000000000..7523f8b4fe --- /dev/null +++ b/ports/nrf/supervisor/filesystem.c @@ -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. + */ + +#include "supervisor/filesystem.h" + +void filesystem_init(bool create_allowed) { +} + +void filesystem_flush(void) { +} + +void filesystem_writable_by_python(bool writable) { +} + +bool filesystem_present(void) { + return false; +} diff --git a/ports/nrf/supervisor/port.c b/ports/nrf/supervisor/port.c new file mode 100644 index 0000000000..a3e52d0359 --- /dev/null +++ b/ports/nrf/supervisor/port.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 "supervisor/port.h" +#include "boards/board.h" + +#if 0 +// ASF 4 +#include "atmel_start_pins.h" +#include "hal/include/hal_delay.h" +#include "hal/include/hal_gpio.h" +#include "hal/include/hal_init.h" +#include "hal/include/hal_usb_device.h" +#include "hpl/gclk/hpl_gclk_base.h" +#include "hpl/pm/hpl_pm_base.h" + +#include "tick.h" +#endif + +#include "common-hal/microcontroller/Pin.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) { + 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..0b844fa018 --- /dev/null +++ b/ports/nrf/supervisor/serial.c @@ -0,0 +1,59 @@ +/* + * 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 "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); +} + +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); +} +