nRF52 update with internal file system support

crypto-aes
microbuilder 5 years ago
parent 36ec29d4e8
commit 60a23f0fb6

3
.gitmodules vendored

@ -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

@ -0,0 +1 @@
Subproject commit 07b43832ee53a4a248c30f5a3014e2632d8aeb88

@ -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,31 @@ 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/pyexec.c \
lib/libc/string0.c \
lib/mp-readline/readline.c \
internal_flash.c \
DRIVERS_SRC_C += $(addprefix modules/,\
machine/modmachine.c \
@ -156,11 +165,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 +186,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 +302,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 +317,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 +351,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

@ -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 <stdbool.h>
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

@ -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) }
}

@ -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,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)

@ -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 <string.h>
#include <stdbool.h>
#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);
}

@ -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.

@ -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"
INCLUDE "boards/common.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 */

@ -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)

@ -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()

@ -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)

@ -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

@ -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, \

@ -0,0 +1,124 @@
// 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 <stdio.h>
#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) },
};
MP_DEFINE_CONST_DICT(board_module_globals, board_module_globals_table);

@ -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

1 PA2,PA2,ADC0_IN0 A0,PA2,ADC0_IN0
2 PA3,PA3,ADC0_IN1 A1,PA3,ADC0_IN1
3 PA4,PA4,ADC0_IN2 A2,PA4,ADC0_IN2
4 PA5,PA5,ADC0_IN3 A3,PA5,ADC0_IN3
5 UART_TX,PA6 TX,PA6
6 PA7,PA7 PA7,PA7
7 UART_RX,PA8 RX,PA8
8 NFC1,PA9 NFC1,PA9
9 NFC2,PA10 NFC2,PA10
10 PA11,PA11 D11,PA11
11 SPI_SCK,PA12 SCK,PA12
12 SPI_MOSI,PA13 MOSI,PA13
13 SPI_MISO,PA14 MISO,PA14
14 PA15,PA15 D15,PA15
15 PA16,PA16 D16,PA16
16 LED1,PA17 LED1,PA17
17 LED2,PA19 LED2,PA19
18 PA20,PA20 DFU,PA20
19 I2C_SDA,PA25 SDA,PA25
20 I2C_SCL,PA26 SCL,PA26
21 PA27,PA27 D27,PA27
22 PA28,PA28,ADC0_IN4 A4,PA28,ADC0_IN4
23 PA29,PA29,ADC0_IN5 A5,PA29,ADC0_IN5
24 PA30,PA30,ADC0_IN6 A6,PA30,ADC0_IN6
25 PA31,PA31,ADC0_IN7 A7,PA31,ADC0_IN7

@ -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[];

@ -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('');

@ -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)

@ -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), \

@ -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 <string.h>
#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;
}

@ -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

@ -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 <stdint.h>
#include <string.h>
#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);
}

@ -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

@ -0,0 +1 @@
// No analogio module functions.

@ -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 <string.h>
#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.

@ -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