Merge branch 'master' into nrf52840_usbboot

This commit is contained in:
hathach 2018-06-25 17:12:24 +07:00
commit f5be5ed6ee
80 changed files with 246 additions and 5514 deletions

3
.gitmodules vendored
View File

@ -70,3 +70,6 @@
[submodule "ports/atmel-samd/peripherals"]
path = ports/atmel-samd/peripherals
url = https://github.com/adafruit/samd-peripherals.git
[submodule "ports/nrf/nrfx"]
path = ports/nrf/nrfx
url = https://github.com/NordicSemiconductor/nrfx.git

View File

@ -116,6 +116,7 @@ exclude_patterns = ["**/build*",
"ports/nrf/drivers",
"ports/nrf/hal",
"ports/nrf/modules",
"ports/nrf/nrfx",
"ports/pic16bit",
"ports/qemu-arm",
"ports/stm32",

View File

@ -18,6 +18,8 @@ STATIC const mp_rom_map_elem_t board_global_dict_table[] = {
{ MP_OBJ_NEW_QSTR(MP_QSTR_D1), MP_ROM_PTR(&pin_PA17) },
{ MP_OBJ_NEW_QSTR(MP_QSTR_TX), MP_ROM_PTR(&pin_PA17) },
{ MP_OBJ_NEW_QSTR(MP_QSTR_D2), MP_ROM_PTR(&pin_PA07) },
{ MP_OBJ_NEW_QSTR(MP_QSTR_D3), MP_ROM_PTR(&pin_PB22) },
{ MP_OBJ_NEW_QSTR(MP_QSTR_D4), MP_ROM_PTR(&pin_PA14) },
{ MP_OBJ_NEW_QSTR(MP_QSTR_D5), MP_ROM_PTR(&pin_PA15) },
{ MP_OBJ_NEW_QSTR(MP_QSTR_D7), MP_ROM_PTR(&pin_PA18) },
{ MP_OBJ_NEW_QSTR(MP_QSTR_D9), MP_ROM_PTR(&pin_PA19) },

View File

@ -1,6 +1,6 @@
# Select the board to build for: if not given on the command line,
# then default to feather52.
BOARD ?= feather52
# then default to feather52832.
BOARD ?= feather52832
ifeq ($(wildcard boards/$(BOARD)/.),)
$(error Invalid BOARD specified)
endif
@ -12,24 +12,17 @@ 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
# If the build directory is not given, make it reflect the board name
BUILD ?= $(if $(SD),build-$(BOARD)-$(SD_LOWER),build-$(BOARD))
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 ../../py/mkenv.mk
include boards/$(BOARD)/mpconfigboard.mk
-include mpconfigport.mk
ifneq ($(SD), )
include drivers/bluetooth/bluetooth_common.mk
endif
# qstr definitions (must come before including py.mk)
QSTR_DEFS = qstrdefsport.h $(BUILD)/pins_qstr.h
@ -44,43 +37,33 @@ FATFS_DIR = lib/oofatfs
CROSS_COMPILE = arm-none-eabi-
MCU_VARIANT_UPPER = $(shell echo $(MCU_VARIANT) | tr '[:lower:]' '[:upper:]')
INC += -I.
INC += -I../..
INC += -I$(BUILD)
INC += -I$(BUILD)/genhdr
INC += -I./../../lib/cmsis/inc
INC += -I./boards/$(BOARD)
INC += -I./device
INC += -I./device/$(MCU_VARIANT)
INC += -I./hal
INC += -I./hal/$(MCU_VARIANT)
INC += -I./modules/machine
INC += -I./modules/ubluepy
INC += -I./modules/music
INC += -I./modules/random
INC += -I./modules/ble
INC += -I../../lib/mp-readline
INC += -I./drivers/bluetooth
INC += -I./drivers
NRF_DEFINES += -D$(MCU_VARIANT_UPPER)
NRF_DEFINES += -DCONFIG_GPIO_AS_PINRESET
CFLAGS_CORTEX_M = -mthumb -mabi=aapcs -fsingle-precision-constant -Wdouble-promotion
CFLAGS_MCU_m4 = $(CFLAGS_CORTEX_M) -mtune=cortex-m4 -mcpu=cortex-m4 -mfpu=fpv4-sp-d16 -mfloat-abi=hard
CFLAGS_MCU_m0 = $(CFLAGS_CORTEX_M) --short-enums -mtune=cortex-m0 -mcpu=cortex-m0 -mfloat-abi=soft -fno-builtin
CFLAGS += $(CFLAGS_MCU_$(MCU_SERIES))
CFLAGS += -mthumb -mabi=aapcs -fsingle-precision-constant -Wdouble-promotion
CFLAGS += -mtune=cortex-m4 -mcpu=cortex-m4 -mfpu=fpv4-sp-d16 -mfloat-abi=hard
CFLAGS += $(INC) -Wall -Werror -ansi -std=gnu99 -nostdlib $(COPT) $(NRF_DEFINES) $(CFLAGS_MOD)
CFLAGS += -fno-strict-aliasing
CFLAGS += -fstack-usage
CFLAGS += -fdata-sections -ffunction-sections
CFLAGS += -Iboards/$(BOARD)
CFLAGS += -DNRF5_HAL_H='<$(MCU_VARIANT)_hal.h>'
CFLAGS += -D__START=main
LDFLAGS = $(CFLAGS)
LDFLAGS += -Xlinker -Map=$(@:.elf=.map)
@ -97,17 +80,13 @@ CFLAGS += -Os -DNDEBUG
LDFLAGS += -Os
endif
LIBS = \
ifeq ($(MCU_VARIANT), nrf52)
LIBM_FILE_NAME = $(shell $(CC) $(CFLAGS) -print-file-name=libm.a)
LIBC_FILE_NAME = $(shell $(CC) $(CFLAGS) -print-file-name=libc.a)
LIBGCC_FILE_NAME = $(shell $(CC) $(CFLAGS) -print-libgcc-file-name)
LIBS += -L $(dir $(LIBM_FILE_NAME)) -lm
LIBS := -L $(dir $(LIBM_FILE_NAME)) -lm
LIBS += -L $(dir $(LIBC_FILE_NAME)) -lc
LIBS += -L $(dir $(LIBGCC_FILE_NAME)) -lgcc
endif
SRC_HAL = $(addprefix hal/,\
hal_uart.c \
@ -122,19 +101,12 @@ SRC_HAL = $(addprefix hal/,\
hal_temp.c \
hal_gpio.c \
hal_rng.c \
)
ifeq ($(MCU_VARIANT), nrf52)
SRC_HAL += $(addprefix hal/,\
hal_pwm.c \
)
endif
SRC_C += \
mphalport.c \
help.c \
pin_named_pins.c \
fatfs_port.c \
fifo.c \
tick.c \
@ -143,7 +115,7 @@ SRC_C += \
drivers/bluetooth/ble_drv.c \
drivers/bluetooth/ble_uart.c \
boards/$(BOARD)/board.c \
device/$(MCU_VARIANT)/system_$(MCU_SUB_VARIANT).c \
nrfx/mdk/system_$(MCU_SUB_VARIANT).c \
device/$(MCU_VARIANT)/startup_$(MCU_SUB_VARIANT).c \
lib/oofatfs/ff.c \
lib/oofatfs/option/ccsbcs.c \
@ -158,18 +130,6 @@ SRC_C += \
DRIVERS_SRC_C += $(addprefix modules/,\
machine/modmachine.c \
machine/uart.c \
machine/spi.c \
machine/i2c.c \
machine/adc.c \
machine/pin.c \
machine/timer.c \
machine/pwm.c \
machine/led.c \
machine/temp.c \
utime/modutime.c \
pyb/modpyb.c \
ubluepy/modubluepy.c \
ubluepy/ubluepy_peripheral.c \
ubluepy/ubluepy_service.c \
@ -180,13 +140,10 @@ DRIVERS_SRC_C += $(addprefix modules/,\
ubluepy/ubluepy_descriptor.c \
ubluepy/ubluepy_scanner.c \
ubluepy/ubluepy_scan_entry.c \
music/modmusic.c \
music/musictunes.c \
ble/modble.c \
random/modrandom.c \
)
SRC_COMMON_HAL += \
board/__init__.c \
digitalio/__init__.c \
@ -208,8 +165,8 @@ SRC_COMMON_HAL += \
pulseio/PulseOut.c \
pulseio/PWMOut.c \
storage/__init__.c \
supervisor/__init__.c \
supervisor/Runtime.c \
supervisor/__init__.c \
supervisor/Runtime.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.
@ -346,10 +303,10 @@ SRC_QSTR_AUTO_DEPS +=
$(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)/%_gen.c $(HEADER_BUILD)/%.h $(HEADER_BUILD)/%_af_const.h $(BUILD)/%_qstr.h: boards/$(BOARD)/%.csv $(MAKE_PINS) $(AF_FILE) $(PREFIX_FILE) | $(HEADER_BUILD)
# both pins_g.c and pins.h
$(BUILD)/%_gen.c $(HEADER_BUILD)/%.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)
$(Q)$(PYTHON) $(MAKE_PINS) --board $(BOARD_PINS) --af $(AF_FILE) --prefix $(PREFIX_FILE) --hdr $(GEN_PINS_HDR) --qstr $(GEN_PINS_QSTR) > $(GEN_PINS_SRC)
$(BUILD)/pins_gen.o: $(BUILD)/pins_gen.c
$(call compile_c)
@ -361,8 +318,6 @@ PREFIX_FILE = boards/$(MCU_VARIANT)_prefix.c
GEN_PINS_SRC = $(BUILD)/pins_gen.c
GEN_PINS_HDR = $(HEADER_BUILD)/pins.h
GEN_PINS_QSTR = $(BUILD)/pins_qstr.h
GEN_PINS_AF_CONST = $(HEADER_BUILD)/pins_af_const.h
GEN_PINS_AF_PY = $(BUILD)/pins_af.py
ifneq ($(FROZEN_DIR),)
# To use frozen source modules, put your .py files in a subdirectory (eg scripts/)

View File

@ -51,7 +51,7 @@ Prerequisite steps for building the nrf port:
git submodule update --init
make -C mpy-cross
By default, the feather52 (nRF52832) is used as compile target. To build and flash issue the following command inside the ports/nrf/ folder:
By default, the feather52832 is used as compile target. To build and flash issue the following command inside the ports/nrf/ folder:
make
make flash
@ -82,7 +82,7 @@ Note: further tuning of features to include in bluetooth or even setting up the
Target Board (BOARD) | Bluetooth Stack (SD) | Bluetooth Support | Flash Util
---------------------|-------------------------|------------------------|-------------------------------
pca10040 | s132 | Peripheral and Scanner | [Segger](#segger-targets)
feather52 | s132 | Peripheral and Scanner | [UART DFU](#dfu-targets)
feather52832 | s132 | Peripheral and Scanner | [UART DFU](#dfu-targets)
pca10056 | s140 | Peripheral and Scanner | [Segger](#segger-targets)
## Segger Targets
@ -113,11 +113,11 @@ note: On Linux it might be required to link SEGGER's `libjlinkarm.so` inside nrf
* dfu-gen: Generates a Firmware zip to be used by the DFU flash application.
* dfu-flash: Triggers the DFU flash application to upload the firmware from the generated Firmware zip file.
Example on how to generate and flash feather52 target:
Example on how to generate and flash feather52832 target:
make BOARD=feather52 SD=s132
make BOARD=feather52 SD=s132 dfu-gen
make BOARD=feather52 SD=s132 dfu-flash
make BOARD=feather52832 SD=s132
make BOARD=feather52832 SD=s132 dfu-gen
make BOARD=feather52832 SD=s132 dfu-flash
## Bluetooth LE REPL

View File

@ -47,12 +47,12 @@ $ sudo python setup.py install
#### REPL over UART (default settings)
To build a CircuitPython binary with default settings for the
`feather52` target enter:
`feather52832` target enter:
> **NOTE:** `BOARD=feather52` is the default option and isn't stricly required.
> **NOTE:** `BOARD=feather52832` is the default option and isn't stricly required.
```
$ make BOARD=feather52 V=1
$ make BOARD=feather52832 V=1
```
#### REPL over BLE UART (AKA 'NUS')
@ -68,7 +68,7 @@ set to `1` in the `#elif (BLUETOOTH_SD == 132)` section:
... then build as normal, via:
```
$ make BOARD=feather52 V=1
$ make BOARD=feather52832 V=1
```
You can then connect over BLE UART using an application like Bluefruit LE
@ -95,7 +95,7 @@ Feather52 boards to a single-bank CircuitPython compatible version:
By default s132 v2.0.1 is used when no `SOFTDEV_VERSION` field is passed in:
```
$ make BOARD=feather52 SERIAL=/dev/tty.SLAB_USBtoUART boot-flash
$ make BOARD=feather52832 SERIAL=/dev/tty.SLAB_USBtoUART boot-flash
```
#### S132 v5.0.0 (BLE5, experimental):
@ -103,7 +103,7 @@ $ make BOARD=feather52 SERIAL=/dev/tty.SLAB_USBtoUART boot-flash
To enable BLE5 support and the latest S132 release, flash the v5.0.0 bootloader via:
```
$ make BOARD=feather52 SERIAL=/dev/tty.SLAB_USBtoUART SOFTDEV_VERSION=5.0.0 boot-flash
$ make BOARD=feather52832 SERIAL=/dev/tty.SLAB_USBtoUART SOFTDEV_VERSION=5.0.0 boot-flash
```
### 2. Generate and flash a CircuitPython DFU .zip package over serial
@ -117,7 +117,7 @@ image, as described earlier in this readme.
> The name of the serial port target will vary, depending on your OS.
```
$ make BOARD=feather52 SERIAL=/dev/tty.SLAB_USBtoUART dfu-gen dfu-flash
$ make BOARD=feather52832 SERIAL=/dev/tty.SLAB_USBtoUART dfu-gen dfu-flash
```
By default, CircuitPython will build with **BLE** support enabled using
@ -125,7 +125,7 @@ By default, CircuitPython will build with **BLE** support enabled using
SD family or version you can enter the optional fields as shown below:
```
$ make BOARD=feather52 SERIAL=/dev/tty.SLAB_USBtoUART SD=s132 SOFTDEV_VERSION=5.0.0 dfu-gen dfu-flash
$ make BOARD=feather52832 SERIAL=/dev/tty.SLAB_USBtoUART SD=s132 SOFTDEV_VERSION=5.0.0 dfu-gen dfu-flash
```
## Working with CircuitPython

View File

@ -28,14 +28,6 @@
#define MICROPY_HW_MCU_NAME "NRF52832"
#define MICROPY_PY_SYS_PLATFORM "nrf52"
#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 (0)
#define MICROPY_PY_MACHINE_I2C (1)
#define MICROPY_PY_MACHINE_ADC (1)
#define MICROPY_PY_MACHINE_TEMP (1)
#define MICROPY_HW_HAS_LED (1)
#define MICROPY_HW_HAS_SWITCH (0)
#define MICROPY_HW_HAS_FLASH (0)

View File

@ -1,6 +1,6 @@
MCU_SERIES = m4
MCU_VARIANT = nrf52
MCU_SUB_VARIANT = nrf52832
MCU_SUB_VARIANT = nrf52
SOFTDEV_VERSION ?= 2.0.1
LD_FILE = boards/feather52832/custom_nrf52832_dfu_app_$(SOFTDEV_VERSION).ld
@ -15,11 +15,6 @@ else
NRFUTIL = nrfutil
endif
ifeq ($(SD), )
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)
endif
CFLAGS += -DADAFRUIT_FEATHER52
check_defined = \

View File

@ -1,4 +0,0 @@
# This file is a placeholder to enable building with 'SD=s132' flag
# The actual config data is stored in the file referenced below, regardless
# of whether S132 is actively used or not.
include boards/$(BOARD)/mpconfigboard.mk

View File

@ -1,7 +1,7 @@
A0,P0_02,ADC0_IN0
A1,P0_03,ADC0_IN1
A2,P0_04,ADC0_IN2
A3,P0_05,ADC0_IN3
A0,P0_02
A1,P0_03
A2,P0_04
A3,P0_05
TX,P0_06
RX,P0_08
NFC1,P0_09
@ -18,7 +18,7 @@ DFU,P0_20
SDA,P0_25
SCL,P0_26
D27,P0_27
A4,P0_28,ADC0_IN4
A5,P0_29,ADC0_IN5
A6,P0_30,ADC0_IN6
A7,P0_31,ADC0_IN7
A4,P0_28
A5,P0_29
A6,P0_30
A7,P0_31

1 A0,P0_02,ADC0_IN0 A0 P0_02
2 A1,P0_03,ADC0_IN1 A1 P0_03
3 A2,P0_04,ADC0_IN2 A2 P0_04
4 A3,P0_05,ADC0_IN3 A3 P0_05
5 TX,P0_06 TX P0_06
6 RX,P0_08 RX P0_08
7 NFC1,P0_09 NFC1 P0_09
18 SDA,P0_25 SDA P0_25
19 SCL,P0_26 SCL P0_26
20 D27,P0_27 D27 P0_27
21 A4,P0_28,ADC0_IN4 A4 P0_28
22 A5,P0_29,ADC0_IN5 A5 P0_29
23 A6,P0_30,ADC0_IN6 A6 P0_30
24 A7,P0_31,ADC0_IN7 A7 P0_31

View File

@ -30,14 +30,6 @@
#define MICROPY_HW_MCU_NAME "NRF52840"
#define MICROPY_PY_SYS_PLATFORM "nrf52840"
#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_I2C (1)
#define MICROPY_PY_MACHINE_ADC (1)
#define MICROPY_PY_MACHINE_TEMP (1)
#define MICROPY_HW_HAS_LED (1)
#define MICROPY_HW_HAS_SWITCH (0)
#define MICROPY_HW_HAS_FLASH (0)

View File

@ -1,4 +1,36 @@
# This file is a placeholder to enable building with 'SD=s140' flag
# The actual config data is stored in the file referenced below, regardless
# of whether S140 is actively used or not.
include boards/$(BOARD)/mpconfigboard.mk
MCU_SERIES = m4
MCU_VARIANT = nrf52
MCU_SUB_VARIANT = nrf52840
SOFTDEV_VERSION ?= 6.0.0
LD_FILE = boards/feather52840/bluefruit_nrf52840_s140_6.0.0.ld
BOOTLOADER_FILENAME = boards/feather52840/bootloader/feather52840_bootloader_6.0.0_s140_single
NRF_DEFINES += -DNRF52840_XXAA
ifeq ($(OS),Windows_NT)
NRFUTIL = ../../lib/nrfutil/binaries/win32/nrfutil.exe
else
NRFUTIL = nrfutil
endif
CFLAGS += -DADAFRUIT_FEATHER52840
check_defined = \
$(strip $(foreach 1,$1, \
$(call __check_defined,$1,$(strip $(value 2)))))
__check_defined = \
$(if $(value $1),, \
$(error Undefined make flag: $1$(if $2, ($2))))
.PHONY: dfu-gen dfu-flash boot-flash
dfu-gen:
$(NRFUTIL) dfu genpkg --sd-req 0xFFFE --dev-type 0x0052 --application $(BUILD)/$(OUTPUT_FILENAME).hex $(BUILD)/dfu-package.zip
dfu-flash:
@:$(call check_defined, SERIAL, example: SERIAL=/dev/ttyUSB0)
$(NRFUTIL) --verbose dfu serial --package $(BUILD)/dfu-package.zip -p $(SERIAL) -b 115200
boot-flash:
nrfjprog --program $(BOOTLOADER_FILENAME).hex -f nrf52 --chiperase --reset

View File

@ -1,47 +0,0 @@
MCU_SERIES = m4
MCU_VARIANT = nrf52
MCU_SUB_VARIANT = nrf52840
SOFTDEV_VERSION ?= 6.0.0
LD_FILE = boards/feather52840/bluefruit_nrf52840_s140_6.0.0.ld
BOOT_UART_FILE = boards/feather52840/bootloader/uart/feather52840_bootloader_6.0.0_s140_single
BOOT_USB_FILE = boards/feather52840/bootloader/usb/feather52840_bootloader_6.0.0_s140_single
BOOT_SETTING_ADDR = 0xFF000
NRF_DEFINES += -DNRF52840_XXAA
ifeq ($(OS),Windows_NT)
NRFUTIL = ../../lib/nrfutil/binaries/win32/nrfutil.exe
else
NRFUTIL = nrfutil
endif
CFLAGS += -DADAFRUIT_FEATHER52840
ifeq ($(SD), )
INC += -Idrivers/bluetooth/s140_$(MCU_VARIANT)_$(SOFTDEV_VERSION)/s140_$(MCU_VARIANT)_$(SOFTDEV_VERSION)_API/include
INC += -Idrivers/bluetooth/s140_$(MCU_VARIANT)_$(SOFTDEV_VERSION)/s140_$(MCU_VARIANT)_$(SOFTDEV_VERSION)_API/include/$(MCU_VARIANT)
endif
check_defined = \
$(strip $(foreach 1,$1, \
$(call __check_defined,$1,$(strip $(value 2)))))
__check_defined = \
$(if $(value $1),, \
$(error Undefined make flag: $1$(if $2, ($2))))
.PHONY: dfu-gen dfu-flash boot-flash boot-usb-flash
dfu-gen:
$(NRFUTIL) dfu genpkg --sd-req 0xFFFE --dev-type 0x0052 --application $(BUILD)/$(OUTPUT_FILENAME).hex $(BUILD)/dfu-package.zip
dfu-flash:
@:$(call check_defined, SERIAL, example: SERIAL=/dev/ttyACM0)
$(NRFUTIL) --verbose dfu serial --package $(BUILD)/dfu-package.zip -p $(SERIAL) -b 115200 --singlebank
dfu-bootloader:
@:$(call check_defined, SERIAL, example: SERIAL=/dev/ttyACM0)
$(NRFUTIL) --verbose dfu serial --package $(BOOT_USB_FILE).zip -p $(SERIAL) -b 115200
bootloader:
nrfjprog --program $(BOOT_USB_FILE).hex -f nrf52 --chiperase --reset

View File

@ -1,9 +1,9 @@
P0_00,P0_00
P0_01,P0_01
P0_02,P0_02,ADC0_IN0
P0_03,P0_03,ADC0_IN1
P0_04,P0_04,ADC0_IN2
P0_05,P0_05,ADC0_IN3
P0_02,P0_02
P0_03,P0_03
P0_04,P0_04
P0_05,P0_05
P0_06,P0_06
P0_07,P0_07
P0_08,P0_08
@ -26,10 +26,10 @@ P0_24,P0_24
P0_25,P0_25
P0_26,P0_26
P0_27,P0_27
P0_28,P0_28,ADC0_IN4
P0_29,P0_29,ADC0_IN5
P0_30,P0_30,ADC0_IN6
P0_31,P0_31,ADC0_IN7
P0_28,P0_28
P0_29,P0_29
P0_30,P0_30
P0_31,P0_31
P1_00,P1_00
P1_01,P1_01
P1_02,P1_02

1 P0_00,P0_00 P0_00 P0_00
2 P0_01,P0_01 P0_01 P0_01
3 P0_02,P0_02,ADC0_IN0 P0_02 P0_02
4 P0_03,P0_03,ADC0_IN1 P0_03 P0_03
5 P0_04,P0_04,ADC0_IN2 P0_04 P0_04
6 P0_05,P0_05,ADC0_IN3 P0_05 P0_05
7 P0_06,P0_06 P0_06 P0_06
8 P0_07,P0_07 P0_07 P0_07
9 P0_08,P0_08 P0_08 P0_08
26 P0_25,P0_25 P0_25 P0_25
27 P0_26,P0_26 P0_26 P0_26
28 P0_27,P0_27 P0_27 P0_27
29 P0_28,P0_28,ADC0_IN4 P0_28 P0_28
30 P0_29,P0_29,ADC0_IN5 P0_29 P0_29
31 P0_30,P0_30,ADC0_IN6 P0_30 P0_30
32 P0_31,P0_31,ADC0_IN7 P0_31 P0_31
33 P1_00,P1_00 P1_00 P1_00
34 P1_01,P1_01 P1_01 P1_01
35 P1_02,P1_02 P1_02 P1_02

View File

@ -23,18 +23,6 @@ def parse_port_pin(name_str):
return (port, int(pin_str))
def split_name_num(name_num):
num = None
for num_idx in range(len(name_num) - 1, -1, -1):
if not name_num[num_idx].isdigit():
name = name_num[0:num_idx + 1]
num_str = name_num[num_idx + 1:]
if len(num_str) > 0:
num = int(num_str)
break
return name, num
class Pin(object):
"""Holds the information associated with a pin."""
@ -54,10 +42,9 @@ class Pin(object):
self.board_pin = True
def parse_adc(self, adc_str):
if (adc_str[:3] != 'ADC'):
if (adc_str[:3] != 'AIN'):
return
(adc, channel) = adc_str.split('_IN')
self.adc_channel = 'SAADC_CH_PSELP_PSELP_AnalogInput%d' % int(channel)
self.adc_channel = 'SAADC_CH_PSELP_PSELP_AnalogInput%d' % int(adc_str[3])
def print(self):
print('const pin_obj_t pin_{:s} = PIN({:s}, {:d}, {:d}, {:s});'.format(
@ -94,20 +81,17 @@ class Pins(object):
if pin.port == port_num and pin.pin == pin_num:
return pin
def parse_af_file(self, filename, pinname_col, af_col, af_col_end):
def parse_af_file(self, filename):
with open(filename, 'r') as csvfile:
rows = csv.reader(csvfile)
for row in rows:
try:
(port_num, pin_num) = parse_port_pin(row[pinname_col])
(port_num, pin_num) = parse_port_pin(row[0])
except:
continue
pin = Pin(port_num, pin_num)
for af_idx in range(af_col, len(row)):
if af_idx < af_col_end:
pin.parse_af(af_idx - af_col, row[af_idx])
elif af_idx == af_col_end:
pin.parse_adc(row[af_idx])
if len(row) > 1:
pin.parse_adc(row[1])
self.cpu_pins.append(NamedPin(pin.cpu_pin_name(), pin))
def parse_board_file(self, filename):
@ -121,8 +105,6 @@ class Pins(object):
pin = self.find_pin(port_num, pin_num)
if pin:
pin.set_is_board_pin()
if len(row) == 3:
pin.parse_adc(row[2])
self.board_pins.append(NamedPin(row[0], pin))
def print_named(self, label, named_pins):
@ -173,19 +155,7 @@ def main():
"-a", "--af",
dest="af_filename",
help="Specifies the alternate function file for the chip",
default="nrf.csv"
)
parser.add_argument(
"--af-const",
dest="af_const_filename",
help="Specifies header file for alternate function constants.",
default="build/pins_af_const.h"
)
parser.add_argument(
"--af-py",
dest="af_py_filename",
help="Specifies the filename for the python alternate function mappings.",
default="build/pins_af.py"
default="nrf_af.csv"
)
parser.add_argument(
"-b", "--board",
@ -218,7 +188,7 @@ def main():
print('//')
if args.af_filename:
print('// --af {:s}'.format(args.af_filename))
pins.parse_af_file(args.af_filename, 1, 2, 2)
pins.parse_af_file(args.af_filename)
if args.board_filename:
print('// --board {:s}'.format(args.board_filename))

View File

@ -10,7 +10,7 @@
{ \
{ &mcu_pin_type }, \
.name = MP_QSTR_ ## p_name, \
.port = PORT_ ## p_port, \
.port = (p_port), \
.pin = (p_pin), \
.adc_channel = p_adc_channel, \
.adc_channel = (p_adc_channel), \
}

View File

@ -30,14 +30,6 @@
#define MICROPY_HW_MCU_NAME "NRF52832"
#define MICROPY_PY_SYS_PLATFORM "nrf52-DK"
#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_I2C (1)
#define MICROPY_PY_MACHINE_ADC (1)
#define MICROPY_PY_MACHINE_TEMP (1)
#define MICROPY_HW_HAS_LED (1)
#define MICROPY_HW_HAS_SWITCH (0)
#define MICROPY_HW_HAS_FLASH (0)

View File

@ -1,6 +1,12 @@
MCU_SERIES = m4
MCU_VARIANT = nrf52
MCU_SUB_VARIANT = nrf52832
LD_FILE = boards/nrf52832_512k_64k.ld
MCU_SUB_VARIANT = nrf52
SOFTDEV_VERSION ?= 5.0.0
ifeq ($(SD),)
LD_FILE = boards/nrf52832_512k_64k.ld
else
LD_FILE = boards/nrf52832_512k_64k_s132_$(SOFTDEV_VERSION).ld
endif
NRF_DEFINES += -DNRF52832_XXAA

View File

@ -1,8 +0,0 @@
MCU_SERIES = m4
MCU_VARIANT = nrf52
MCU_SUB_VARIANT = nrf52832
SOFTDEV_VERSION = 5.0.0
LD_FILE = boards/nrf52832_512k_64k_s132_$(SOFTDEV_VERSION).ld
NRF_DEFINES += -DNRF52832_XXAA

View File

@ -4,10 +4,10 @@ import gamepad
import time
pad = gamepad.GamePad(
digitalio.DigitalInOut(board.PA11),
digitalio.DigitalInOut(board.PA12),
digitalio.DigitalInOut(board.PA24),
digitalio.DigitalInOut(board.PA25),
digitalio.DigitalInOut(board.P0_11),
digitalio.DigitalInOut(board.P0_12),
digitalio.DigitalInOut(board.P0_24),
digitalio.DigitalInOut(board.P0_25),
)
prev_buttons = 0

View File

@ -30,14 +30,6 @@
#define MICROPY_HW_MCU_NAME "NRF52840"
#define MICROPY_PY_SYS_PLATFORM "nrf52840-PDK"
#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_I2C (1)
#define MICROPY_PY_MACHINE_ADC (1)
#define MICROPY_PY_MACHINE_TEMP (1)
#define MICROPY_HW_HAS_LED (1)
#define MICROPY_HW_HAS_SWITCH (0)
#define MICROPY_HW_HAS_FLASH (0)

View File

@ -3,11 +3,10 @@ MCU_VARIANT = nrf52
MCU_SUB_VARIANT = nrf52840
SOFTDEV_VERSION ?= 6.0.0
LD_FILE = boards/nrf52840_1M_256k.ld
ifeq ($(SD),)
LD_FILE = boards/nrf52840_1M_256k.ld
else
LD_FILE = boards/nrf52840_1M_256k_s140_$(SOFTDEV_VERSION).ld
endif
NRF_DEFINES += -DNRF52840_XXAA
ifeq ($(SD), )
INC += -Idrivers/bluetooth/s140_$(MCU_VARIANT)_$(SOFTDEV_VERSION)/s140_$(MCU_SUB_VARIANT)_$(SOFTDEV_VERSION)_API/include
INC += -Idrivers/bluetooth/s140_$(MCU_VARIANT)_$(SOFTDEV_VERSION)/s140_$(MCU_SUB_VARIANT)_$(SOFTDEV_VERSION)_API/include/$(MCU_VARIANT)
endif

View File

@ -1,8 +0,0 @@
MCU_SERIES = m4
MCU_VARIANT = nrf52
MCU_SUB_VARIANT = nrf52840
SOFTDEV_VERSION ?= 6.0.0
LD_FILE = boards/nrf52840_1M_256k_s140_$(SOFTDEV_VERSION).ld
NRF_DEFINES += -DNRF52840_XXAA

View File

@ -1,9 +1,9 @@
P0_00,PA0
P0_00,P0_01
P0_01,P0_01
P0_02,P0_02,ADC0_IN0
P0_03,P0_03,ADC0_IN1
P0_04,P0_04,ADC0_IN2
P0_05,P0_05,ADC0_IN3
P0_02,P0_02
P0_03,P0_03
P0_04,P0_04
P0_05,P0_05
P0_06,P0_06
P0_07,P0_07
P0_08,P0_08
@ -26,10 +26,10 @@ P0_24,P0_24
P0_25,P0_25
P0_26,P0_26
P0_27,P0_27
P0_28,P0_28,ADC0_IN4
P0_29,P0_29,ADC0_IN5
P0_30,P0_30,ADC0_IN6
P0_31,P0_31,ADC0_IN7
P0_28,P0_28
P0_29,P0_29
P0_30,P0_30
P0_31,P0_31
P1_00,P1_00
P1_01,P1_01
P1_02,P1_02

1 P0_00,PA0 P0_00 P0_01
2 P0_01,P0_01 P0_01 P0_01
3 P0_02,P0_02,ADC0_IN0 P0_02 P0_02
4 P0_03,P0_03,ADC0_IN1 P0_03 P0_03
5 P0_04,P0_04,ADC0_IN2 P0_04 P0_04
6 P0_05,P0_05,ADC0_IN3 P0_05 P0_05
7 P0_06,P0_06 P0_06 P0_06
8 P0_07,P0_07 P0_07 P0_07
9 P0_08,P0_08 P0_08 P0_08
26 P0_25,P0_25 P0_25 P0_25
27 P0_26,P0_26 P0_26 P0_26
28 P0_27,P0_27 P0_27 P0_27
29 P0_28,P0_28,ADC0_IN4 P0_28 P0_28
30 P0_29,P0_29,ADC0_IN5 P0_29 P0_29
31 P0_30,P0_30,ADC0_IN6 P0_30 P0_30
32 P0_31,P0_31,ADC0_IN7 P0_31 P0_31
33 P1_00,P1_00 P1_00 P1_00
34 P1_01,P1_01 P1_01 P1_01
35 P1_02,P1_02 P1_02 P1_02

View File

@ -27,14 +27,11 @@
#ifndef MICROPY_INCLUDED_NRF_COMMON_HAL_MICROCONTROLLER_PIN_H
#define MICROPY_INCLUDED_NRF_COMMON_HAL_MICROCONTROLLER_PIN_H
#include "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

View File

@ -30,6 +30,8 @@
#include <string.h>
#include <stdbool.h>
#define NRF52 // Needed for SD132 v2
#include "py/runtime.h"
#include "ble_drv.h"
#include "mpconfigport.h"

View File

@ -1,35 +0,0 @@
"""
Example for pca10040 / nrf52832 to show how mount
and list a sdcard connected over SPI.
Direct wireing on SD card (SPI):
______________________________
| \
| 9. | NC | \
| 1. | ~CS | |
| 2. | MOSI | |
| 3. | GND | |
| 4. | VCC3.3| |
| 5. | SCK | |
| 6. | GND | |
| 7. | MISO | |
| 8. | NC | |
| |
---------------------------------
"""
import os
from machine import SPI, Pin
from sdcard import SDCard
def mnt():
cs = Pin("A22", mode=Pin.OUT)
sd = SDCard(SPI(0), cs)
os.mount(sd, '/')
def list():
files = os.listdir()
print(files)

View File

@ -1,13 +0,0 @@
#
# Example usage where "A3" is the Buzzer pin.
#
# from musictest import play
# play("A3")
#
from machine import Pin
import music
def play(pin_str):
p = Pin(pin_str, mode=Pin.OUT)
music.play(music.PRELUDE, pin=p)

View File

@ -1,15 +0,0 @@
import time
from machine import PWM, Pin
def pulse():
for i in range(0, 101):
p = PWM(0, Pin("A17", mode=Pin.OUT), freq=PWM.FREQ_16MHZ, duty=i, period=16000)
p.init()
time.sleep_ms(10)
p.deinit()
for i in range(0, 101):
p = PWM(0, Pin("A17", mode=Pin.OUT), freq=PWM.FREQ_16MHZ, duty=100-i, period=16000)
p.init()
time.sleep_ms(10)
p.deinit()

View File

@ -1,50 +0,0 @@
# This file is part of the MicroPython project, http://micropython.org/
#
# The MIT License (MIT)
#
# Copyright (c) 2017 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
import time
from machine import PWM, Pin
class Servo():
def __init__(self, pin_name=""):
if pin_name:
self.pin = Pin(pin_name, mode=Pin.OUT, pull=Pin.PULL_DOWN)
else:
self.pin = Pin("A22", mode=Pin.OUT, pull=Pin.PULL_DOWN)
def left(self):
p = PWM(0, self.pin, freq=PWM.FREQ_125KHZ, pulse_width=105, period=2500, mode=PWM.MODE_HIGH_LOW)
p.init()
time.sleep_ms(200)
p.deinit()
def center(self):
p = PWM(0, self.pin, freq=PWM.FREQ_125KHZ, pulse_width=188, period=2500, mode=PWM.MODE_HIGH_LOW)
p.init()
time.sleep_ms(200)
p.deinit()
def right(self):
p = PWM(0, self.pin, freq=PWM.FREQ_125KHZ, pulse_width=275, period=2500, mode=PWM.MODE_HIGH_LOW)
p.init()
time.sleep_ms(200)
p.deinit()

View File

@ -1,213 +0,0 @@
# This file is part of the MicroPython project, http://micropython.org/
#
# The MIT License (MIT)
#
# Copyright (c) 2017 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
# MicroPython controller for PowerUp 3.0 paper airplane
# https://www.poweruptoys.com/products/powerup-v3
#
# Examples is written for nrf52832, pca10040 using s132 bluetooth stack.
#
# Joystick shield pin mapping:
# - analog stick x-direction - ADC0 - P0.02/"A02"
# - buttons P0.13 - P0.16 / "A13", "A14", "A15", "A16"
#
# Example usage:
#
# from powerup import PowerUp3
# p = PowerUp3()
import time
from machine import ADC
from machine import Pin
from ubluepy import Peripheral, Scanner, constants
def bytes_to_str(bytes):
string = ""
for b in bytes:
string += chr(b)
return string
def get_device_names(scan_entries):
dev_names = []
for e in scan_entries:
scan = e.getScanData()
if scan:
for s in scan:
if s[0] == constants.ad_types.AD_TYPE_COMPLETE_LOCAL_NAME:
dev_names.append((e, bytes_to_str(s[2])))
return dev_names
def find_device_by_name(name):
s = Scanner()
scan_res = s.scan(500)
device_names = get_device_names(scan_res)
for dev in device_names:
if name == dev[1]:
return dev[0]
class PowerUp3:
def __init__(self):
self.x_adc = ADC(1)
self.btn_speed_up = Pin("A13", mode=Pin.IN, pull=Pin.PULL_UP)
self.btn_speed_down = Pin("A15", mode=Pin.IN, pull=Pin.PULL_UP)
self.btn_speed_full = Pin("A14", mode=Pin.IN, pull=Pin.PULL_UP)
self.btn_speed_off = Pin("A16", mode=Pin.IN, pull=Pin.PULL_UP)
self.x_mid = 0
self.calibrate()
self.connect()
self.loop()
def read_stick_x(self):
return self.x_adc.value()
def button_speed_up(self):
return not bool(self.btn_speed_up.value())
def button_speed_down(self):
return not bool(self.btn_speed_down.value())
def button_speed_full(self):
return not bool(self.btn_speed_full.value())
def button_speed_off(self):
return not bool(self.btn_speed_off.value())
def calibrate(self):
self.x_mid = self.read_stick_x()
def __str__(self):
return "calibration x: %i, y: %i" % (self.x_mid)
def map_chars(self):
s = self.p.getServices()
service_batt = s[3]
service_control = s[4]
self.char_batt_lvl = service_batt.getCharacteristics()[0]
self.char_control_speed = service_control.getCharacteristics()[0]
self.char_control_angle = service_control.getCharacteristics()[2]
def battery_level(self):
return int(self.char_batt_lvl.read()[0])
def speed(self, new_speed=None):
if new_speed == None:
return int(self.char_control_speed.read()[0])
else:
self.char_control_speed.write(bytearray([new_speed]))
def angle(self, new_angle=None):
if new_angle == None:
return int(self.char_control_angle.read()[0])
else:
self.char_control_angle.write(bytearray([new_angle]))
def connect(self):
dev = None
# connect to the airplane
while not dev:
dev = find_device_by_name("TailorToys PowerUp")
if dev:
self.p = Peripheral()
self.p.connect(dev.addr())
# locate interesting characteristics
self.map_chars()
def rudder_center(self):
if self.old_angle != 0:
self.old_angle = 0
self.angle(0)
def rudder_left(self, angle):
steps = (angle // self.interval_size_left)
new_angle = 60 - steps
if self.old_angle != new_angle:
self.angle(new_angle)
self.old_angle = new_angle
def rudder_right(self, angle):
steps = (angle // self.interval_size_right)
new_angle = -steps
if self.old_angle != new_angle:
self.angle(new_angle)
self.old_angle = new_angle
def throttle(self, speed):
if (speed > 200):
speed = 200
elif (speed < 0):
speed = 0
if self.old_speed != speed:
self.speed(speed)
self.old_speed = speed
def loop(self):
adc_threshold = 10
right_threshold = self.x_mid + adc_threshold
left_threshold = self.x_mid - adc_threshold
self.interval_size_left = self.x_mid // 60
self.interval_size_right = (255 - self.x_mid) // 60
self.old_angle = 0
self.old_speed = 0
while True:
time.sleep_ms(100)
# read out new angle
new_angle = self.read_stick_x()
if (new_angle < 256):
if (new_angle > right_threshold):
self.rudder_right(new_angle - self.x_mid)
elif (new_angle < left_threshold):
self.rudder_left(new_angle)
else:
self.rudder_center()
# read out new speed
new_speed = self.old_speed
if self.button_speed_up():
new_speed += 25
elif self.button_speed_down():
new_speed -= 25
elif self.button_speed_full():
new_speed = 200
elif self.button_speed_off():
new_speed = 0
else:
pass
self.throttle(new_speed)

View File

@ -1,210 +0,0 @@
# This file is part of the MicroPython project, http://micropython.org/
#
# The MIT License (MIT)
#
# Copyright (c) 2016 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.
"""
MicroPython Seeedstudio TFT Shield V2 driver, SPI interfaces, Analog GPIO
Contains SD-card reader, LCD and Touch sensor
The pca10040 pin layout is used as reference.
Example usage of LCD:
from seeedstudio_tft_shield_v2 import ILI9341
lcd = ILI9341(240, 320)
lcd.text("Hello World!, 32, 32)
lcd.show()
Example usage of SD card reader:
import os
from seeedstudio_tft_shield_v2 import mount_tf
tf = mount_tf()
os.listdir()
"""
import os
import time
import framebuf
from machine import SPI, Pin
from sdcard import SDCard
def mount_tf(self, mount_point="/"):
sd = SDCard(SPI(0), Pin("A15", mode=Pin.OUT))
os.mount(sd, mount_point)
class ILI9341:
def __init__(self, width, height):
self.width = width
self.height = height
self.pages = self.height // 8
self.buffer = bytearray(self.pages * self.width)
self.framebuf = framebuf.FrameBuffer(self.buffer, self.width, self.height, framebuf.MONO_VLSB)
self.spi = SPI(0)
# chip select
self.cs = Pin("A16", mode=Pin.OUT, pull=Pin.PULL_UP)
# command
self.dc = Pin("A17", mode=Pin.OUT, pull=Pin.PULL_UP)
# initialize all pins high
self.cs.high()
self.dc.high()
self.spi.init(baudrate=8000000, phase=0, polarity=0)
self.init_display()
def init_display(self):
time.sleep_ms(500)
self.write_cmd(0x01)
time.sleep_ms(200)
self.write_cmd(0xCF)
self.write_data(bytearray([0x00, 0x8B, 0x30]))
self.write_cmd(0xED)
self.write_data(bytearray([0x67, 0x03, 0x12, 0x81]))
self.write_cmd(0xE8)
self.write_data(bytearray([0x85, 0x10, 0x7A]))
self.write_cmd(0xCB)
self.write_data(bytearray([0x39, 0x2C, 0x00, 0x34, 0x02]))
self.write_cmd(0xF7)
self.write_data(bytearray([0x20]))
self.write_cmd(0xEA)
self.write_data(bytearray([0x00, 0x00]))
# Power control
self.write_cmd(0xC0)
# VRH[5:0]
self.write_data(bytearray([0x1B]))
# Power control
self.write_cmd(0xC1)
# SAP[2:0];BT[3:0]
self.write_data(bytearray([0x10]))
# VCM control
self.write_cmd(0xC5)
self.write_data(bytearray([0x3F, 0x3C]))
# VCM control2
self.write_cmd(0xC7)
self.write_data(bytearray([0xB7]))
# Memory Access Control
self.write_cmd(0x36)
self.write_data(bytearray([0x08]))
self.write_cmd(0x3A)
self.write_data(bytearray([0x55]))
self.write_cmd(0xB1)
self.write_data(bytearray([0x00, 0x1B]))
# Display Function Control
self.write_cmd(0xB6)
self.write_data(bytearray([0x0A, 0xA2]))
# 3Gamma Function Disable
self.write_cmd(0xF2)
self.write_data(bytearray([0x00]))
# Gamma curve selected
self.write_cmd(0x26)
self.write_data(bytearray([0x01]))
# Set Gamma
self.write_cmd(0xE0)
self.write_data(bytearray([0x0F, 0x2A, 0x28, 0x08, 0x0E, 0x08, 0x54, 0XA9, 0x43, 0x0A, 0x0F, 0x00, 0x00, 0x00, 0x00]))
# Set Gamma
self.write_cmd(0XE1)
self.write_data(bytearray([0x00, 0x15, 0x17, 0x07, 0x11, 0x06, 0x2B, 0x56, 0x3C, 0x05, 0x10, 0x0F, 0x3F, 0x3F, 0x0F]))
# Exit Sleep
self.write_cmd(0x11)
time.sleep_ms(120)
# Display on
self.write_cmd(0x29)
time.sleep_ms(500)
self.fill(0)
def show(self):
# set col
self.write_cmd(0x2A)
self.write_data(bytearray([0x00, 0x00]))
self.write_data(bytearray([0x00, 0xef]))
# set page
self.write_cmd(0x2B)
self.write_data(bytearray([0x00, 0x00]))
self.write_data(bytearray([0x01, 0x3f]))
self.write_cmd(0x2c);
num_of_pixels = self.height * self.width
for row in range(0, self.pages):
for pixel_pos in range(0, 8):
for col in range(0, self.width):
compressed_pixel = self.buffer[row * 240 + col]
if ((compressed_pixel >> pixel_pos) & 0x1) == 0:
self.write_data(bytearray([0x00, 0x00]))
else:
self.write_data(bytearray([0xFF, 0xFF]))
def fill(self, col):
self.framebuf.fill(col)
def pixel(self, x, y, col):
self.framebuf.pixel(x, y, col)
def scroll(self, dx, dy):
self.framebuf.scroll(dx, dy)
def text(self, string, x, y, col=1):
self.framebuf.text(string, x, y, col)
def write_cmd(self, cmd):
self.dc.low()
self.cs.low()
self.spi.write(bytearray([cmd]))
self.cs.high()
def write_data(self, buf):
self.dc.high()
self.cs.low()
self.spi.write(buf)
self.cs.high()

View File

@ -1,27 +0,0 @@
# NOTE: Modified version to align with implemented I2C API in nrf port.
#
# Examples usage of SSD1306_SPI on pca10040
#
# from machine import Pin, SPI
# from ssd1306 import SSD1306_SPI
# spi = SPI(0, baudrate=40000000)
# dc = Pin.board.PA11
# res = Pin.board.PA12
# cs = Pin.board.PA13
# disp = SSD1306_SPI(128, 64, spi, dc, res, cs)
#
#
# Example usage of SSD1306_I2C on pca10040
#
# from machine import Pin, I2C
# from ssd1306_mod import SSD1306_I2C_Mod
# i2c = I2C(0, Pin.board.PA3, Pin.board.PA4)
# disp = SSD1306_I2C_Mod(128, 64, i2c)
from ssd1306 import SSD1306_I2C
class SSD1306_I2C_Mod(SSD1306_I2C):
def write_data(self, buf):
buffer = bytearray([0x40]) + buf # Co=0, D/C#=1
self.i2c.writeto(self.addr, buffer)

View File

@ -94,7 +94,7 @@ void GPIOTE_IRQHandler(void) {
GPIOTE_BASE->EVENTS_IN[3] = 0;
m_callback(HAL_GPIO_EVENT_CHANNEL_3);
}
#if NRF52
if (GPIOTE_BASE->EVENTS_IN[4]) {
GPIOTE_BASE->EVENTS_IN[4] = 0;
m_callback(HAL_GPIO_EVENT_CHANNEL_4);
@ -111,7 +111,6 @@ void GPIOTE_IRQHandler(void) {
GPIOTE_BASE->EVENTS_IN[7] = 0;
m_callback(HAL_GPIO_EVENT_CHANNEL_7);
}
#endif
}
#endif // if 0

View File

@ -29,18 +29,12 @@
#include "nrf.h"
#if NRF51
#define POINTERS (const uint32_t[]){NRF_GPIO_BASE}
#ifdef NRF52832_XXAA
#define POINTERS (const uint32_t[]){NRF_P0_BASE}
#endif
#if NRF52
#ifdef NRF52832_XXAA
#define POINTERS (const uint32_t[]){NRF_P0_BASE}
#endif
#ifdef NRF52840_XXAA
#define POINTERS (const uint32_t[]){NRF_P0_BASE, NRF_P1_BASE}
#endif
#ifdef NRF52840_XXAA
#define POINTERS (const uint32_t[]){NRF_P0_BASE, NRF_P1_BASE}
#endif
#define GPIO_BASE(x) ((NRF_GPIO_Type *)POINTERS[x])
@ -133,12 +127,10 @@ typedef enum {
HAL_GPIO_EVENT_CHANNEL_1,
HAL_GPIO_EVENT_CHANNEL_2,
HAL_GPIO_EVENT_CHANNEL_3,
#if NRF52
HAL_GPIO_EVENT_CHANNEL_4,
HAL_GPIO_EVENT_CHANNEL_5,
HAL_GPIO_EVENT_CHANNEL_6,
HAL_GPIO_EVENT_CHANNEL_7
#endif
} hal_gpio_event_channel_t;
typedef struct {

View File

@ -37,11 +37,8 @@
#define BLUETOOTH_STACK_ENABLED() (ble_drv_stack_enabled())
#ifdef NRF51
#include "nrf_soc.h"
#elif defined(NRF52)
#include "nrf_nvic.h"
#endif
#define NRF52
#include "nrf_nvic.h"
#endif // BLUETOOTH_SD
static inline void hal_irq_clear(uint32_t irq_num) {

View File

@ -31,10 +31,6 @@
#include "nrf.h"
// TODO: nrf51 series need Soft PWM. Not part of HAL.
#if NRF52
#define PWM0 ((NRF_PWM_Type *)NRF_PWM0_BASE)
#define PWM0_IRQ_NUM PWM1_IRQn
#define PWM1 ((NRF_PWM_Type *)NRF_PWM1_BASE)
@ -42,15 +38,11 @@
#define PWM2 ((NRF_PWM_Type *)NRF_PWM2_BASE)
#define PWM2_IRQ_NUM PWM2_IRQn
#if 0 // TODO: nrf52840
#ifdef NRF52840_XXAA
#define PWM3 ((NRF_PWM_Type *)NRF_PWM3_BASE)
#define PWM3_IRQ_NUM PWM3_IRQn
#endif
#else
#error "Device not supported."
#endif
/**
* @brief PWM frequency type definition
*/

View File

@ -110,14 +110,10 @@ void RTC1_IRQHandler(void)
common_irq_handler(1);
}
#if NRF52
void RTC2_IRQHandler(void)
{
common_irq_handler(2);
}
#endif // NRF52
#endif // HAL_RTC_MODULE_ENABLED

View File

@ -29,21 +29,12 @@
#include "nrf.h"
#if NRF51
#define RTC_BASE_POINTERS (const uint32_t[]){NRF_RTC0_BASE, \
NRF_RTC1_BASE}
#define RTC_IRQ_VALUES (const uint32_t[]){RTC0_IRQn, \
RTC1_IRQn}
#endif
#if NRF52
#define RTC_BASE_POINTERS (const uint32_t[]){NRF_RTC0_BASE, \
NRF_RTC1_BASE, \
NRF_RTC2_BASE}
#define RTC_IRQ_VALUES (const uint32_t[]){RTC0_IRQn, \
RTC1_IRQn, \
RTC2_IRQn}
#endif
#define RTC_BASE_POINTERS (const uint32_t[]){NRF_RTC0_BASE, \
NRF_RTC1_BASE, \
NRF_RTC2_BASE}
#define RTC_IRQ_VALUES (const uint32_t[]){RTC0_IRQn, \
RTC1_IRQn, \
RTC2_IRQn}
#define RTC_BASE(x) ((NRF_RTC_Type *)RTC_BASE_POINTERS[x])
#define RTC_IRQ_NUM(x) (RTC_IRQ_VALUES[x])

View File

@ -30,31 +30,24 @@
#include <stdbool.h>
#include "nrf.h"
#if NRF51
#define SPI_BASE_POINTERS (const uint32_t[]){NRF_SPI0_BASE, NRF_SPI1_BASE}
#define SPI_IRQ_VALUES (const uint32_t[]){SPI0_TWI0_IRQn, SPI1_TWI1_IRQn}
#ifdef NRF52832_XXAA
#define SPI_BASE_POINTERS (const uint32_t[]){NRF_SPI0_BASE, \
NRF_SPI1_BASE, \
NRF_SPI2_BASE}
#define SPI_IRQ_VALUES (const uint32_t[]){SPIM0_SPIS0_TWIM0_TWIS0_SPI0_TWI0_IRQn, \
SPIM1_SPIS1_TWIM1_TWIS1_SPI1_TWI1_IRQn, \
SPIM2_SPIS2_SPI2_IRQn}
#endif
#if NRF52
#ifdef NRF52832_XXAA
#define SPI_BASE_POINTERS (const uint32_t[]){NRF_SPI0_BASE, \
NRF_SPI1_BASE, \
NRF_SPI2_BASE}
#define SPI_IRQ_VALUES (const uint32_t[]){SPIM0_SPIS0_TWIM0_TWIS0_SPI0_TWI0_IRQn, \
SPIM1_SPIS1_TWIM1_TWIS1_SPI1_TWI1_IRQn, \
SPIM2_SPIS2_SPI2_IRQn}
#endif
#ifdef NRF52840_XXAA
#define SPI_BASE_POINTERS (const uint32_t[]){NRF_SPI0_BASE, \
NRF_SPI1_BASE, \
NRF_SPI2_BASE, \
NRF_SPIM3_BASE}
#define SPI_IRQ_VALUES (const uint32_t[]){SPIM0_SPIS0_TWIM0_TWIS0_SPI0_TWI0_IRQn, \
SPIM1_SPIS1_TWIM1_TWIS1_SPI1_TWI1_IRQn, \
SPIM2_SPIS2_SPI2_IRQn, \
SPIM3_IRQn}
#endif
#ifdef NRF52840_XXAA
#define SPI_BASE_POINTERS (const uint32_t[]){NRF_SPI0_BASE, \
NRF_SPI1_BASE, \
NRF_SPI2_BASE, \
NRF_SPIM3_BASE}
#define SPI_IRQ_VALUES (const uint32_t[]){SPIM0_SPIS0_TWIM0_TWIS0_SPI0_TWI0_IRQn, \
SPIM1_SPIS1_TWIM1_TWIS1_SPI1_TWI1_IRQn, \
SPIM2_SPIS2_SPI2_IRQn, \
SPIM3_IRQn}
#endif
#define SPI_BASE(x) ((NRF_SPI_Type *)SPI_BASE_POINTERS[x])

View File

@ -88,8 +88,6 @@ void TIMER2_IRQHandler(void) {
common_irq_handler(2);
}
#if NRF52
void TIMER3_IRQHandler(void) {
common_irq_handler(3);
}
@ -98,6 +96,4 @@ void TIMER4_IRQHandler(void) {
common_irq_handler(4);
}
#endif
#endif // HAL_TIMER_MODULE_ENABLED

View File

@ -29,27 +29,16 @@
#include "nrf.h"
#if NRF51
#define TIMER_BASE_POINTERS (const uint32_t[]){NRF_TIMER0_BASE, \
NRF_TIMER1_BASE, \
NRF_TIMER2_BASE}
#define TIMER_IRQ_VALUES (const uint32_t[]){TIMER0_IRQn, \
TIMER1_IRQn, \
TIMER2_IRQn}
#endif
#if NRF52
#define TIMER_BASE_POINTERS (const uint32_t[]){NRF_TIMER0_BASE, \
NRF_TIMER1_BASE, \
NRF_TIMER1_BASE, \
NRF_TIMER1_BASE, \
NRF_TIMER2_BASE}
#define TIMER_IRQ_VALUES (const uint32_t[]){TIMER0_IRQn, \
#define TIMER_BASE_POINTERS (const uint32_t[]){NRF_TIMER0_BASE, \
NRF_TIMER1_BASE, \
NRF_TIMER1_BASE, \
NRF_TIMER1_BASE, \
NRF_TIMER2_BASE}
#define TIMER_IRQ_VALUES (const uint32_t[]){TIMER0_IRQn, \
TIMER1_IRQn, \
TIMER2_IRQn, \
TIMER3_IRQn, \
TIMER4_IRQn}
#endif
#define TIMER_BASE(x) ((NRF_TIMER_Type *)TIMER_BASE_POINTERS[x])
#define TIMER_IRQ_NUM(x) (TIMER_IRQ_VALUES[x])

View File

@ -32,20 +32,9 @@
#define TWI_BASE_POINTERS (const uint32_t[]){NRF_TWI0_BASE, NRF_TWI1_BASE}
#define TWI_BASE(x) ((NRF_TWI_Type *)TWI_BASE_POINTERS[x])
#if NRF51
#define TWI_IRQ_VALUES (const uint32_t[]){SPI0_TWI0_IRQn, SPI1_TWI1_IRQn}
#elif NRF52
#define TWI_IRQ_VALUES (const uint32_t[]){SPIM0_SPIS0_TWIM0_TWIS0_SPI0_TWI0_IRQn, \
SPIM1_SPIS1_TWIM1_TWIS1_SPI1_TWI1_IRQn}
#endif
#if NRF52
/**
* @brief TWIM Configuration Structure definition
*/
@ -58,8 +47,6 @@ typedef struct {
typedef struct {
} hal_twis_init_t;
#endif
/**
* @brief TWI clock frequency type definition
*/

View File

@ -32,37 +32,24 @@
#include "nrf.h"
#if NRF51
#define UART_HWCONTROL_NONE ((uint32_t)UART_CONFIG_HWFC_Disabled << UART_CONFIG_HWFC_Pos)
#define UART_HWCONTROL_RTS_CTS ((uint32_t)(UART_CONFIG_HWFC_Enabled << UART_CONFIG_HWFC_Pos)
#define IS_UART_HARDWARE_FLOW_CONTROL(CONTROL)\
(((CONTROL) == UART_HWCONTROL_NONE) || \
((CONTROL) == UART_HWCONTROL_RTS_CTS))
#define UART_HWCONTROL_NONE ((uint32_t)UARTE_CONFIG_HWFC_Disabled << UARTE_CONFIG_HWFC_Pos)
#define UART_HWCONTROL_RTS_CTS ((uint32_t)(UARTE_CONFIG_HWFC_Enabled << UARTE_CONFIG_HWFC_Pos)
#define IS_UART_HARDWARE_FLOW_CONTROL(CONTROL)\
(((CONTROL) == UART_HWCONTROL_NONE) || \
((CONTROL) == UART_HWCONTROL_RTS_CTS))
#ifdef HAL_UART_MODULE_ENABLED
#define UART_BASE_POINTERS (const uint32_t[]){NRF_UART0_BASE}
#define UART_IRQ_VALUES (const uint32_t[]){UART0_IRQn}
#elif NRF52
#define UART_HWCONTROL_NONE ((uint32_t)UARTE_CONFIG_HWFC_Disabled << UARTE_CONFIG_HWFC_Pos)
#define UART_HWCONTROL_RTS_CTS ((uint32_t)(UARTE_CONFIG_HWFC_Enabled << UARTE_CONFIG_HWFC_Pos)
#define IS_UART_HARDWARE_FLOW_CONTROL(CONTROL)\
(((CONTROL) == UART_HWCONTROL_NONE) || \
((CONTROL) == UART_HWCONTROL_RTS_CTS))
#ifdef HAL_UART_MODULE_ENABLED
#define UART_BASE_POINTERS (const uint32_t[]){NRF_UART0_BASE}
#define UART_IRQ_VALUES (const uint32_t[]){UARTE0_UART0_IRQn}
#else // HAL_UARTE_MODULE_ENABLED
#ifdef NRF52832_XXAA
#define UART_BASE_POINTERS (const uint32_t[]){NRF_UARTE0_BASE}
#define UART_IRQ_VALUES (const uint32_t[]){UARTE0_UART0_IRQn}
#else // HAL_UARTE_MODULE_ENABLED
#ifdef NRF52832_XXAA
#define UART_BASE_POINTERS (const uint32_t[]){NRF_UARTE0_BASE}
#define UART_IRQ_VALUES (const uint32_t[]){UARTE0_UART0_IRQn}
#elif NRF52840_XXAA
#define UART_BASE_POINTERS (const uint32_t[]){NRF_UARTE0_BASE, \
NRF_UARTE1_BASE}
#define UART_IRQ_VALUES (const uint32_t[]){UARTE0_UART0_IRQn, \
UARTE1_IRQn}
#endif // HAL_UARTE_MODULE_ENABLED
#endif
#else
#error "Device not supported."
#elif NRF52840_XXAA
#define UART_BASE_POINTERS (const uint32_t[]){NRF_UARTE0_BASE, \
NRF_UARTE1_BASE}
#define UART_IRQ_VALUES (const uint32_t[]){UARTE0_UART0_IRQn, \
UARTE1_IRQn}
#endif // HAL_UARTE_MODULE_ENABLED
#endif
#define UART_BASE(x) ((NRF_UART_Type *)UART_BASE_POINTERS[x])

View File

@ -30,7 +30,6 @@
#if MICROPY_PY_BLE
#include "led.h"
#include "mpconfigboard.h"
#include "ble_drv.h"

View File

@ -1,144 +0,0 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2017 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 <stdio.h>
#include <string.h>
#include "py/nlr.h"
#include "py/runtime.h"
#include "py/mphal.h"
#include "adc.h"
#include "hal_adc.h"
#if MICROPY_PY_MACHINE_ADC
typedef struct _machine_adc_obj_t {
mp_obj_base_t base;
ADC_HandleTypeDef *adc;
} machine_adc_obj_t;
ADC_HandleTypeDef ADCHandle0 = {.config.channel = 0};
ADC_HandleTypeDef ADCHandle1 = {.config.channel = 1};
ADC_HandleTypeDef ADCHandle2 = {.config.channel = 2};
ADC_HandleTypeDef ADCHandle3 = {.config.channel = 3};
ADC_HandleTypeDef ADCHandle4 = {.config.channel = 4};
ADC_HandleTypeDef ADCHandle5 = {.config.channel = 5};
ADC_HandleTypeDef ADCHandle6 = {.config.channel = 6};
ADC_HandleTypeDef ADCHandle7 = {.config.channel = 7};
STATIC const machine_adc_obj_t machine_adc_obj[] = {
{{&machine_adc_type}, &ADCHandle0},
{{&machine_adc_type}, &ADCHandle1},
{{&machine_adc_type}, &ADCHandle2},
{{&machine_adc_type}, &ADCHandle3},
{{&machine_adc_type}, &ADCHandle4},
{{&machine_adc_type}, &ADCHandle5},
{{&machine_adc_type}, &ADCHandle6},
{{&machine_adc_type}, &ADCHandle7},
};
STATIC int adc_find(mp_obj_t id) {
// given an integer id
int adc_id = mp_obj_get_int(id);
int adc_idx = adc_id;
if (adc_idx >= 0 && adc_idx <= MP_ARRAY_SIZE(machine_adc_obj)
&& machine_adc_obj[adc_idx].adc != NULL) {
return adc_idx;
}
nlr_raise(mp_obj_new_exception_msg_varg(&mp_type_ValueError,
"ADC(%d) does not exist", adc_id));
}
/// \method __str__()
/// Return a string describing the ADC object.
STATIC void machine_adc_print(const mp_print_t *print, mp_obj_t o, mp_print_kind_t kind) {
machine_adc_obj_t *self = o;
(void)self;
mp_printf(print, "ADC()");
}
/******************************************************************************/
/* MicroPython bindings for machine API */
// for make_new
enum {
ARG_NEW_PIN,
};
STATIC mp_obj_t machine_adc_make_new(const mp_obj_type_t *type, size_t n_args, size_t n_kw, const mp_obj_t *all_args) {
static const mp_arg_t allowed_args[] = {
{ ARG_NEW_PIN, MP_ARG_OBJ, {.u_obj = MP_OBJ_NEW_SMALL_INT(-1) } },
};
// parse args
mp_arg_val_t args[MP_ARRAY_SIZE(allowed_args)];
mp_arg_parse_all_kw_array(n_args, n_kw, all_args, MP_ARRAY_SIZE(allowed_args), allowed_args, args);
int adc_id = adc_find(args[ARG_NEW_PIN].u_obj);
const machine_adc_obj_t *self = &machine_adc_obj[adc_id];
return MP_OBJ_FROM_PTR(self);
}
/// \method value()
/// Read adc level.
mp_obj_t machine_adc_value(mp_obj_t self_in) {
machine_adc_obj_t *self = self_in;
return MP_OBJ_NEW_SMALL_INT(hal_adc_channel_value(&self->adc->config));
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(mp_machine_adc_value_obj, machine_adc_value);
/// \method battery_level()
/// Get battery level in percentage.
mp_obj_t machine_adc_battery_level(void) {
return MP_OBJ_NEW_SMALL_INT(hal_adc_battery_level());
}
STATIC MP_DEFINE_CONST_FUN_OBJ_0(mp_machine_adc_battery_level_obj, machine_adc_battery_level);
STATIC const mp_rom_map_elem_t machine_adc_locals_dict_table[] = {
// instance methods
{ MP_ROM_QSTR(MP_QSTR_value), MP_ROM_PTR(&mp_machine_adc_value_obj) },
// class methods
{ MP_ROM_QSTR(MP_QSTR_battery_level), MP_ROM_PTR(&mp_machine_adc_battery_level_obj) },
};
STATIC MP_DEFINE_CONST_DICT(machine_adc_locals_dict, machine_adc_locals_dict_table);
const mp_obj_type_t machine_adc_type = {
{ &mp_type_type },
.name = MP_QSTR_ADC,
.make_new = machine_adc_make_new,
.locals_dict = (mp_obj_dict_t*)&machine_adc_locals_dict,
.print = machine_adc_print,
};
#endif // MICROPY_PY_MACHINE_ADC

View File

@ -1,34 +0,0 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2017 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.
*/
#ifndef ADC_H__
#define ADC_H__
#include "hal_adc.h"
extern const mp_obj_type_t machine_adc_type;
#endif // ADC_H__

View File

@ -1,163 +0,0 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2017 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 <stdio.h>
#include <string.h>
#include "py/nlr.h"
#include "py/runtime.h"
#include "py/mphal.h"
#include "extmod/machine_i2c.h"
#include "i2c.h"
#include "hal_twi.h"
#if MICROPY_PY_MACHINE_I2C
STATIC const mp_obj_type_t machine_hard_i2c_type;
typedef struct _machine_hard_i2c_obj_t {
mp_obj_base_t base;
TWI_HandleTypeDef *i2c;
} machine_hard_i2c_obj_t;
TWI_HandleTypeDef I2CHandle0 = {.instance = NULL, .init.id = 0};
TWI_HandleTypeDef I2CHandle1 = {.instance = NULL, .init.id = 1};
STATIC const machine_hard_i2c_obj_t machine_hard_i2c_obj[] = {
{{&machine_hard_i2c_type}, &I2CHandle0},
{{&machine_hard_i2c_type}, &I2CHandle1},
};
void i2c_init0(void) {
// reset the I2C handles
memset(&I2CHandle0, 0, sizeof(TWI_HandleTypeDef));
I2CHandle0.instance = TWI_BASE(0);
memset(&I2CHandle1, 0, sizeof(TWI_HandleTypeDef));
I2CHandle0.instance = TWI_BASE(1);
}
STATIC int i2c_find(mp_obj_t id) {
// given an integer id
int i2c_id = mp_obj_get_int(id);
if (i2c_id >= 0 && i2c_id <= MP_ARRAY_SIZE(machine_hard_i2c_obj)
&& machine_hard_i2c_obj[i2c_id].i2c != NULL) {
return i2c_id;
}
nlr_raise(mp_obj_new_exception_msg_varg(&mp_type_ValueError,
"I2C(%d) does not exist", i2c_id));
}
STATIC void machine_hard_i2c_print(const mp_print_t *print, mp_obj_t o, mp_print_kind_t kind) {
machine_hard_i2c_obj_t *self = o;
mp_printf(print, "I2C(%u, scl=(port=%u, pin=%u), sda=(port=%u, pin=%u))",
self->i2c->init.id,
self->i2c->init.scl_pin->port,
self->i2c->init.scl_pin->pin,
self->i2c->init.sda_pin->port,
self->i2c->init.sda_pin->pin);
}
/******************************************************************************/
/* MicroPython bindings for machine API */
// for make_new
enum {
ARG_NEW_id,
ARG_NEW_scl,
ARG_NEW_sda,
ARG_NEW_freq,
ARG_NEW_timeout,
};
mp_obj_t machine_hard_i2c_make_new(const mp_obj_type_t *type, size_t n_args, size_t n_kw, const mp_obj_t *all_args) {
static const mp_arg_t allowed_args[] = {
{ ARG_NEW_id, MP_ARG_REQUIRED | MP_ARG_OBJ },
{ ARG_NEW_scl, MP_ARG_OBJ, {.u_obj = MP_OBJ_NULL} },
{ ARG_NEW_sda, MP_ARG_OBJ, {.u_obj = MP_OBJ_NULL} },
};
// parse args
mp_arg_val_t args[MP_ARRAY_SIZE(allowed_args)];
mp_arg_parse_all_kw_array(n_args, n_kw, all_args, MP_ARRAY_SIZE(allowed_args), allowed_args, args);
// get static peripheral object
int i2c_id = i2c_find(args[ARG_NEW_id].u_obj);
const machine_hard_i2c_obj_t *self = &machine_hard_i2c_obj[i2c_id];
if (args[ARG_NEW_scl].u_obj != MP_OBJ_NULL) {
self->i2c->init.scl_pin = args[ARG_NEW_scl].u_obj;
} else {
nlr_raise(mp_obj_new_exception_msg_varg(&mp_type_ValueError,
"I2C SCL Pin not set"));
}
if (args[ARG_NEW_sda].u_obj != MP_OBJ_NULL) {
self->i2c->init.sda_pin = args[ARG_NEW_sda].u_obj;
} else {
nlr_raise(mp_obj_new_exception_msg_varg(&mp_type_ValueError,
"I2C SDA Pin not set"));
}
self->i2c->init.freq = HAL_TWI_FREQ_100_Kbps;
hal_twi_master_init(self->i2c->instance, &self->i2c->init);
return MP_OBJ_FROM_PTR(self);
}
#include <stdio.h>
int machine_hard_i2c_readfrom(mp_obj_base_t *self_in, uint16_t addr, uint8_t *dest, size_t len, bool stop) {
machine_hard_i2c_obj_t *self = (machine_hard_i2c_obj_t *)self_in;
hal_twi_master_rx(self->i2c->instance, addr, len, dest, stop);
return 0;
}
int machine_hard_i2c_writeto(mp_obj_base_t *self_in, uint16_t addr, const uint8_t *src, size_t len, bool stop) {
machine_hard_i2c_obj_t *self = (machine_hard_i2c_obj_t *)self_in;
hal_twi_master_tx(self->i2c->instance, addr, len, src, stop);
return 0;
}
STATIC const mp_machine_i2c_p_t machine_hard_i2c_p = {
.readfrom = machine_hard_i2c_readfrom,
.writeto = machine_hard_i2c_writeto,
};
STATIC const mp_obj_type_t machine_hard_i2c_type = {
{ &mp_type_type },
.name = MP_QSTR_I2C,
.print = machine_hard_i2c_print,
.make_new = machine_hard_i2c_make_new,
.protocol = &machine_hard_i2c_p,
.locals_dict = (mp_obj_dict_t*)&mp_machine_soft_i2c_locals_dict,
};
#endif // MICROPY_PY_MACHINE_I2C

View File

@ -1,36 +0,0 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2017 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.
*/
#ifndef I2C_H__
#define I2C_H__
#include "hal_twi.h"
extern const mp_obj_type_t machine_i2c_type;
void i2c_init0(void);
#endif // I2C_H__

View File

@ -1,155 +0,0 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2013-2016 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 "py/runtime.h"
#include "mphalport.h"
#include "led.h"
#include "mpconfigboard.h"
#if MICROPY_HW_HAS_LED
#define LED_OFF(led) {(MICROPY_HW_LED_PULLUP) ? hal_gpio_pin_set(0, led) : hal_gpio_pin_clear(0, led); }
#define LED_ON(led) {(MICROPY_HW_LED_PULLUP) ? hal_gpio_pin_clear(0, led) : hal_gpio_pin_set(0, led); }
typedef struct _pyb_led_obj_t {
mp_obj_base_t base;
mp_uint_t led_id;
mp_uint_t hw_pin;
uint8_t hw_pin_port;
} pyb_led_obj_t;
STATIC const pyb_led_obj_t pyb_led_obj[] = {
#if MICROPY_HW_LED_TRICOLOR
{{&pyb_led_type}, PYB_LED_RED, MICROPY_HW_LED_RED},
{{&pyb_led_type}, PYB_LED_GREEN, MICROPY_HW_LED_GREEN},
{{&pyb_led_type}, PYB_LED_BLUE, MICROPY_HW_LED_BLUE},
#elif (MICROPY_HW_LED_COUNT == 1)
{{&pyb_led_type}, PYB_LED1, MICROPY_HW_LED1},
#elif (MICROPY_HW_LED_COUNT == 2)
{{&pyb_led_type}, PYB_LED1, MICROPY_HW_LED1},
{{&pyb_led_type}, PYB_LED2, MICROPY_HW_LED2},
#else
{{&pyb_led_type}, PYB_LED1, MICROPY_HW_LED1},
{{&pyb_led_type}, PYB_LED2, MICROPY_HW_LED2},
{{&pyb_led_type}, PYB_LED3, MICROPY_HW_LED3},
{{&pyb_led_type}, PYB_LED4, MICROPY_HW_LED4},
#endif
};
#define NUM_LEDS MP_ARRAY_SIZE(pyb_led_obj)
void led_state(pyb_led_obj_t * led_obj, int state) {
if (state == 1) {
LED_ON(led_obj->hw_pin);
} else {
LED_OFF(led_obj->hw_pin);
}
}
void led_toggle(pyb_led_obj_t * led_obj) {
hal_gpio_pin_toggle(0, led_obj->hw_pin);
}
/******************************************************************************/
/* MicroPython bindings */
void led_obj_print(const mp_print_t *print, mp_obj_t self_in, mp_print_kind_t kind) {
pyb_led_obj_t *self = self_in;
mp_printf(print, "LED(%lu)", self->led_id);
}
/// \classmethod \constructor(id)
/// Create an LED object associated with the given LED:
///
/// - `id` is the LED number, 1-4.
STATIC mp_obj_t led_obj_make_new(const mp_obj_type_t *type, size_t n_args, size_t n_kw, const mp_obj_t *args) {
// check arguments
mp_arg_check_num(n_args, n_kw, 1, 1, false);
// get led number
mp_int_t led_id = mp_obj_get_int(args[0]);
// check led number
if (!(1 <= led_id && led_id <= NUM_LEDS)) {
nlr_raise(mp_obj_new_exception_msg_varg(&mp_type_ValueError, "LED(%d) does not exist", led_id));
}
hal_gpio_cfg_pin(0, pyb_led_obj[led_id - 1].hw_pin, HAL_GPIO_MODE_OUTPUT, HAL_GPIO_PULL_DISABLED);
LED_OFF(pyb_led_obj[led_id - 1].hw_pin);
// return static led object
return (mp_obj_t)&pyb_led_obj[led_id - 1];
}
/// \method on()
/// Turn the LED on.
mp_obj_t led_obj_on(mp_obj_t self_in) {
pyb_led_obj_t *self = self_in;
led_state(self, 1);
return mp_const_none;
}
/// \method off()
/// Turn the LED off.
mp_obj_t led_obj_off(mp_obj_t self_in) {
pyb_led_obj_t *self = self_in;
led_state(self, 0);
return mp_const_none;
}
/// \method toggle()
/// Toggle the LED between on and off.
mp_obj_t led_obj_toggle(mp_obj_t self_in) {
pyb_led_obj_t *self = self_in;
led_toggle(self);
return mp_const_none;
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(led_obj_on_obj, led_obj_on);
STATIC MP_DEFINE_CONST_FUN_OBJ_1(led_obj_off_obj, led_obj_off);
STATIC MP_DEFINE_CONST_FUN_OBJ_1(led_obj_toggle_obj, led_obj_toggle);
STATIC const mp_rom_map_elem_t led_locals_dict_table[] = {
{ MP_ROM_QSTR(MP_QSTR_on), MP_ROM_PTR(&led_obj_on_obj) },
{ MP_ROM_QSTR(MP_QSTR_off), MP_ROM_PTR(&led_obj_off_obj) },
{ MP_ROM_QSTR(MP_QSTR_toggle), MP_ROM_PTR(&led_obj_toggle_obj) },
};
STATIC MP_DEFINE_CONST_DICT(led_locals_dict, led_locals_dict_table);
const mp_obj_type_t pyb_led_type = {
{ &mp_type_type },
.name = MP_QSTR_LED,
.print = led_obj_print,
.make_new = led_obj_make_new,
.locals_dict = (mp_obj_dict_t*)&led_locals_dict,
};
#endif // MICROPY_HW_HAS_LED

View File

@ -1,53 +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.
*/
#ifndef LED_H
#define LED_H
typedef enum {
#if MICROPY_HW_LED_TRICOLOR
PYB_LED_RED = 1,
PYB_LED_GREEN = 2,
PYB_LED_BLUE = 3
#elif (MICROPY_HW_LED_COUNT == 1)
PYB_LED1 = 1,
#elif (MICROPY_HW_LED_COUNT == 2)
PYB_LED1 = 1,
PYB_LED2 = 2,
#else
PYB_LED1 = 1,
PYB_LED2 = 2,
PYB_LED3 = 3,
PYB_LED4 = 4
#endif
} pyb_led_t;
void led_init(void);
extern const mp_obj_type_t pyb_led_type;
#endif // LED_H

View File

@ -1,244 +0,0 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2013-2015 Damien P. George
* Copyright (c) 2016 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 <stdio.h>
#include "modmachine.h"
#include "py/gc.h"
#include "py/runtime.h"
#include "py/mphal.h"
#include "extmod/machine_mem.h"
#include "extmod/machine_pulse.h"
#include "extmod/machine_i2c.h"
#include "lib/utils/pyexec.h"
#include "lib/oofatfs/ff.h"
#include "lib/oofatfs/diskio.h"
#include "gccollect.h"
#include "pin.h"
#include "uart.h"
#include "spi.h"
#include "i2c.h"
#include "timer.h"
#if MICROPY_PY_MACHINE_HW_PWM
#include "pwm.h"
#endif
#if MICROPY_PY_MACHINE_ADC
#include "adc.h"
#endif
#if MICROPY_PY_MACHINE_TEMP
#include "temp.h"
#endif
#if MICROPY_PY_MACHINE_RTC
#include "rtc.h"
#endif
#define PYB_RESET_HARD (0)
#define PYB_RESET_WDT (1)
#define PYB_RESET_SOFT (2)
#define PYB_RESET_LOCKUP (3)
#define PYB_RESET_POWER_ON (16)
#define PYB_RESET_LPCOMP (17)
#define PYB_RESET_DIF (18)
#define PYB_RESET_NFC (19)
STATIC uint32_t reset_cause;
void machine_init(void) {
uint32_t state = NRF_POWER->RESETREAS;
if (state & POWER_RESETREAS_RESETPIN_Msk) {
reset_cause = PYB_RESET_HARD;
} else if (state & POWER_RESETREAS_DOG_Msk) {
reset_cause = PYB_RESET_WDT;
} else if (state & POWER_RESETREAS_SREQ_Msk) {
reset_cause = PYB_RESET_SOFT;
} else if (state & POWER_RESETREAS_LOCKUP_Msk) {
reset_cause = PYB_RESET_LOCKUP;
} else if (state & POWER_RESETREAS_OFF_Msk) {
reset_cause = PYB_RESET_POWER_ON;
} else if (state & POWER_RESETREAS_LPCOMP_Msk) {
reset_cause = PYB_RESET_LPCOMP;
} else if (state & POWER_RESETREAS_DIF_Msk) {
reset_cause = PYB_RESET_DIF;
#if NRF52
} else if (state & POWER_RESETREAS_NFC_Msk) {
reset_cause = PYB_RESET_NFC;
#endif
}
// clear reset reason
NRF_POWER->RESETREAS = (1 << reset_cause);
}
// machine.info([dump_alloc_table])
// Print out lots of information about the board.
STATIC mp_obj_t machine_info(mp_uint_t n_args, const mp_obj_t *args) {
// to print info about memory
{
printf("_etext=%p\n", &_etext);
printf("_sidata=%p\n", &_sidata);
printf("_sdata=%p\n", &_sdata);
printf("_edata=%p\n", &_edata);
printf("_sbss=%p\n", &_sbss);
printf("_ebss=%p\n", &_ebss);
printf("_estack=%p\n", &_estack);
printf("_ram_start=%p\n", &_ram_start);
printf("_heap_start=%p\n", &_heap_start);
printf("_heap_end=%p\n", &_heap_end);
printf("_ram_end=%p\n", &_ram_end);
}
// qstr info
{
mp_uint_t n_pool, n_qstr, n_str_data_bytes, n_total_bytes;
qstr_pool_info(&n_pool, &n_qstr, &n_str_data_bytes, &n_total_bytes);
printf("qstr:\n n_pool=" UINT_FMT "\n n_qstr=" UINT_FMT "\n n_str_data_bytes=" UINT_FMT "\n n_total_bytes=" UINT_FMT "\n", n_pool, n_qstr, n_str_data_bytes, n_total_bytes);
}
// GC info
{
gc_info_t info;
gc_info(&info);
printf("GC:\n");
printf(" " UINT_FMT " total\n", info.total);
printf(" " UINT_FMT " : " UINT_FMT "\n", info.used, info.free);
printf(" 1=" UINT_FMT " 2=" UINT_FMT " m=" UINT_FMT "\n", info.num_1block, info.num_2block, info.max_block);
}
if (n_args == 1) {
// arg given means dump gc allocation table
gc_dump_alloc_table();
}
return mp_const_none;
}
MP_DEFINE_CONST_FUN_OBJ_VAR_BETWEEN(machine_info_obj, 0, 1, machine_info);
// Resets the pyboard in a manner similar to pushing the external RESET button.
STATIC mp_obj_t machine_reset(void) {
NVIC_SystemReset();
return mp_const_none;
}
MP_DEFINE_CONST_FUN_OBJ_0(machine_reset_obj, machine_reset);
STATIC mp_obj_t machine_soft_reset(void) {
pyexec_system_exit = PYEXEC_FORCED_EXIT;
nlr_raise(mp_obj_new_exception(&mp_type_SystemExit));
}
MP_DEFINE_CONST_FUN_OBJ_0(machine_soft_reset_obj, machine_soft_reset);
STATIC mp_obj_t machine_sleep(void) {
__WFE();
return mp_const_none;
}
MP_DEFINE_CONST_FUN_OBJ_0(machine_sleep_obj, machine_sleep);
STATIC mp_obj_t machine_deepsleep(void) {
__WFI();
return mp_const_none;
}
MP_DEFINE_CONST_FUN_OBJ_0(machine_deepsleep_obj, machine_deepsleep);
STATIC mp_obj_t machine_reset_cause(void) {
return MP_OBJ_NEW_SMALL_INT(reset_cause);
}
STATIC MP_DEFINE_CONST_FUN_OBJ_0(machine_reset_cause_obj, machine_reset_cause);
STATIC mp_obj_t machine_enable_irq(void) {
#ifndef BLUETOOTH_SD
__enable_irq();
#else
#endif
return mp_const_none;
}
MP_DEFINE_CONST_FUN_OBJ_0(machine_enable_irq_obj, machine_enable_irq);
// Resets the pyboard in a manner similar to pushing the external RESET button.
STATIC mp_obj_t machine_disable_irq(void) {
#ifndef BLUETOOTH_SD
__disable_irq();
#else
#endif
return mp_const_none;
}
MP_DEFINE_CONST_FUN_OBJ_0(machine_disable_irq_obj, machine_disable_irq);
STATIC const mp_rom_map_elem_t machine_module_globals_table[] = {
{ MP_ROM_QSTR(MP_QSTR___name__), MP_ROM_QSTR(MP_QSTR_umachine) },
{ MP_ROM_QSTR(MP_QSTR_info), MP_ROM_PTR(&machine_info_obj) },
{ MP_ROM_QSTR(MP_QSTR_reset), MP_ROM_PTR(&machine_reset_obj) },
{ MP_ROM_QSTR(MP_QSTR_soft_reset), MP_ROM_PTR(&machine_soft_reset_obj) },
{ MP_ROM_QSTR(MP_QSTR_enable_irq), MP_ROM_PTR(&machine_enable_irq_obj) },
{ MP_ROM_QSTR(MP_QSTR_disable_irq), MP_ROM_PTR(&machine_disable_irq_obj) },
#if MICROPY_HW_ENABLE_RNG
{ MP_ROM_QSTR(MP_QSTR_rng), MP_ROM_PTR(&pyb_rng_get_obj) },
#endif
{ MP_ROM_QSTR(MP_QSTR_sleep), MP_ROM_PTR(&machine_sleep_obj) },
{ MP_ROM_QSTR(MP_QSTR_deepsleep), MP_ROM_PTR(&machine_deepsleep_obj) },
{ MP_ROM_QSTR(MP_QSTR_reset_cause), MP_ROM_PTR(&machine_reset_cause_obj) },
{ MP_ROM_QSTR(MP_QSTR_Pin), MP_ROM_PTR(&pin_type) },
{ MP_ROM_QSTR(MP_QSTR_UART), MP_ROM_PTR(&machine_hard_uart_type) },
#if MICROPY_PY_MACHINE_HW_SPI
{ MP_ROM_QSTR(MP_QSTR_SPI), MP_ROM_PTR(&machine_hard_spi_type) },
#endif
#if MICROPY_PY_MACHINE_I2C
{ MP_ROM_QSTR(MP_QSTR_I2C), MP_ROM_PTR(&machine_i2c_type) },
#endif
#if MICROPY_PY_MACHINE_ADC
{ MP_ROM_QSTR(MP_QSTR_ADC), MP_ROM_PTR(&machine_adc_type) },
#endif
#if MICROPY_PY_MACHINE_RTC
{ MP_ROM_QSTR(MP_QSTR_RTC), MP_ROM_PTR(&machine_rtc_type) },
#endif
#if MICROPY_PY_MACHINE_TIMER
{ MP_ROM_QSTR(MP_QSTR_Timer), MP_ROM_PTR(&machine_timer_type) },
#endif
#if MICROPY_PY_MACHINE_HW_PWM
{ MP_ROM_QSTR(MP_QSTR_PWM), MP_ROM_PTR(&machine_hard_pwm_type) },
#endif
#if MICROPY_PY_MACHINE_TEMP
{ MP_ROM_QSTR(MP_QSTR_Temp), MP_ROM_PTR(&machine_temp_type) },
#endif
{ MP_ROM_QSTR(MP_QSTR_HARD_RESET), MP_ROM_INT(PYB_RESET_HARD) },
{ MP_ROM_QSTR(MP_QSTR_WDT_RESET), MP_ROM_INT(PYB_RESET_WDT) },
{ MP_ROM_QSTR(MP_QSTR_SOFT_RESET), MP_ROM_INT(PYB_RESET_SOFT) },
{ MP_ROM_QSTR(MP_QSTR_LOCKUP_RESET), MP_ROM_INT(PYB_RESET_LOCKUP) },
{ MP_ROM_QSTR(MP_QSTR_PWRON_RESET), MP_ROM_INT(PYB_RESET_POWER_ON) },
{ MP_ROM_QSTR(MP_QSTR_LPCOMP_RESET), MP_ROM_INT(PYB_RESET_LPCOMP) },
{ MP_ROM_QSTR(MP_QSTR_DEBUG_IF_RESET), MP_ROM_INT(PYB_RESET_DIF) },
#if NRF52
{ MP_ROM_QSTR(MP_QSTR_NFC_RESET), MP_ROM_INT(PYB_RESET_NFC) },
#endif
};
STATIC MP_DEFINE_CONST_DICT(machine_module_globals, machine_module_globals_table);
const mp_obj_module_t machine_module = {
.base = { &mp_type_module },
.globals = (mp_obj_dict_t*)&machine_module_globals,
};

View File

@ -1,42 +0,0 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2013-2015 Damien P. George
* Copyright (c) 2016 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.
*/
#ifndef __MICROPY_INCLUDED_NRF5_MODMACHINE_H__
#define __MICROPY_INCLUDED_NRF5_MODMACHINE_H__
#include "py/mpstate.h"
#include "py/nlr.h"
#include "py/obj.h"
void machine_init(void);
MP_DECLARE_CONST_FUN_OBJ_VAR_BETWEEN(machine_info_obj);
MP_DECLARE_CONST_FUN_OBJ_0(machine_reset_obj);
MP_DECLARE_CONST_FUN_OBJ_0(machine_sleep_obj);
MP_DECLARE_CONST_FUN_OBJ_0(machine_deepsleep_obj);
#endif // __MICROPY_INCLUDED_NRF5_MODMACHINE_H__

View File

@ -1,695 +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) 2016 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 <stdio.h>
#include <stdint.h>
#include <string.h>
#include "py/nlr.h"
#include "py/runtime.h"
#include "py/mphal.h"
#include "pin.h"
/// \moduleref pyb
/// \class Pin - control I/O pins
///
/// A pin is the basic object to control I/O pins. It has methods to set
/// the mode of the pin (input, output, etc) and methods to get and set the
/// digital logic level. For analog control of a pin, see the ADC class.
///
/// Usage Model:
///
/// All Board Pins are predefined as pyb.Pin.board.Name
///
/// x1_pin = pyb.Pin.board.X1
///
/// g = pyb.Pin(pyb.Pin.board.X1, pyb.Pin.IN)
///
/// CPU pins which correspond to the board pins are available
/// as `pyb.cpu.Name`. For the CPU pins, the names are the port letter
/// followed by the pin number. On the PYBv1.0, `pyb.Pin.board.X1` and
/// `pyb.Pin.cpu.B6` are the same pin.
///
/// You can also use strings:
///
/// g = pyb.Pin('X1', pyb.Pin.OUT_PP)
///
/// Users can add their own names:
///
/// MyMapperDict = { 'LeftMotorDir' : pyb.Pin.cpu.C12 }
/// pyb.Pin.dict(MyMapperDict)
/// g = pyb.Pin("LeftMotorDir", pyb.Pin.OUT_OD)
///
/// and can query mappings
///
/// pin = pyb.Pin("LeftMotorDir")
///
/// Users can also add their own mapping function:
///
/// def MyMapper(pin_name):
/// if pin_name == "LeftMotorDir":
/// return pyb.Pin.cpu.A0
///
/// pyb.Pin.mapper(MyMapper)
///
/// So, if you were to call: `pyb.Pin("LeftMotorDir", pyb.Pin.OUT_PP)`
/// then `"LeftMotorDir"` is passed directly to the mapper function.
///
/// To summarise, the following order determines how things get mapped into
/// an ordinal pin number:
///
/// 1. Directly specify a pin object
/// 2. User supplied mapping function
/// 3. User supplied mapping (object must be usable as a dictionary key)
/// 4. Supply a string which matches a board pin
/// 5. Supply a string which matches a CPU port/pin
///
/// You can set `pyb.Pin.debug(True)` to get some debug information about
/// how a particular object gets mapped to a pin.
// Pin class variables
STATIC bool pin_class_debug;
// Forward declare function
void gpio_irq_event_callback(hal_gpio_event_channel_t channel);
void pin_init0(void) {
MP_STATE_PORT(pin_class_mapper) = mp_const_none;
MP_STATE_PORT(pin_class_map_dict) = mp_const_none;
pin_class_debug = false;
hal_gpio_register_callback(gpio_irq_event_callback);
}
// C API used to convert a user-supplied pin name into an ordinal pin number.
const pin_obj_t *pin_find(mp_obj_t user_obj) {
const pin_obj_t *pin_obj;
// If a pin was provided, then use it
if (MP_OBJ_IS_TYPE(user_obj, &pin_type)) {
pin_obj = user_obj;
if (pin_class_debug) {
printf("Pin map passed pin ");
mp_obj_print((mp_obj_t)pin_obj, PRINT_STR);
printf("\n");
}
return pin_obj;
}
if (MP_STATE_PORT(pin_class_mapper) != mp_const_none) {
pin_obj = mp_call_function_1(MP_STATE_PORT(pin_class_mapper), user_obj);
if (pin_obj != mp_const_none) {
if (!MP_OBJ_IS_TYPE(pin_obj, &pin_type)) {
mp_raise_ValueError("Pin.mapper didn't return a Pin object");
}
if (pin_class_debug) {
printf("Pin.mapper maps ");
mp_obj_print(user_obj, PRINT_REPR);
printf(" to ");
mp_obj_print((mp_obj_t)pin_obj, PRINT_STR);
printf("\n");
}
return pin_obj;
}
// The pin mapping function returned mp_const_none, fall through to
// other lookup methods.
}
if (MP_STATE_PORT(pin_class_map_dict) != mp_const_none) {
mp_map_t *pin_map_map = mp_obj_dict_get_map(MP_STATE_PORT(pin_class_map_dict));
mp_map_elem_t *elem = mp_map_lookup(pin_map_map, user_obj, MP_MAP_LOOKUP);
if (elem != NULL && elem->value != NULL) {
pin_obj = elem->value;
if (pin_class_debug) {
printf("Pin.map_dict maps ");
mp_obj_print(user_obj, PRINT_REPR);
printf(" to ");
mp_obj_print((mp_obj_t)pin_obj, PRINT_STR);
printf("\n");
}
return pin_obj;
}
}
// See if the pin name matches a board pin
pin_obj = pin_find_named_pin(&pin_board_pins_locals_dict, user_obj);
if (pin_obj) {
if (pin_class_debug) {
printf("Pin.board maps ");
mp_obj_print(user_obj, PRINT_REPR);
printf(" to ");
mp_obj_print((mp_obj_t)pin_obj, PRINT_STR);
printf("\n");
}
return pin_obj;
}
// See if the pin name matches a cpu pin
pin_obj = pin_find_named_pin(&pin_cpu_pins_locals_dict, user_obj);
if (pin_obj) {
if (pin_class_debug) {
printf("Pin.cpu maps ");
mp_obj_print(user_obj, PRINT_REPR);
printf(" to ");
mp_obj_print((mp_obj_t)pin_obj, PRINT_STR);
printf("\n");
}
return pin_obj;
}
nlr_raise(mp_obj_new_exception_msg_varg(&mp_type_ValueError, "pin '%s' not a valid pin identifier", mp_obj_str_get_str(user_obj)));
}
/// \method __str__()
/// Return a string describing the pin object.
STATIC void pin_print(const mp_print_t *print, mp_obj_t self_in, mp_print_kind_t kind) {
pin_obj_t *self = self_in;
// pin name
mp_printf(print, "Pin(Pin.cpu.%q, mode=Pin.", self->name);
mp_printf(print, "port=0x%x, ", self->port);
mp_printf(print, "pin=0x%x, ", self->pin);
// mp_printf(print, "pin_mask=0x%x,", self->pin_mask);
/*
uint32_t mode = pin_get_mode(self);
if (mode == GPIO_MODE_ANALOG) {
// analog
mp_print_str(print, "ANALOG)");
} else {
// IO mode
bool af = false;
qstr mode_qst;
if (mode == GPIO_MODE_INPUT) {
mode_qst = MP_QSTR_IN;
} else if (mode == GPIO_MODE_OUTPUT_PP) {
mode_qst = MP_QSTR_OUT;
} else if (mode == GPIO_MODE_OUTPUT_OD) {
mode_qst = MP_QSTR_OPEN_DRAIN;
} else {
af = true;
if (mode == GPIO_MODE_AF_PP) {
mode_qst = MP_QSTR_ALT;
} else {
mode_qst = MP_QSTR_ALT_OPEN_DRAIN;
}
}
mp_print_str(print, qstr_str(mode_qst));
// pull mode
qstr pull_qst = MP_QSTR_NULL;
uint32_t pull = pin_get_pull(self);
if (pull == GPIO_PULLUP) {
pull_qst = MP_QSTR_PULL_UP;
} else if (pull == GPIO_PULLDOWN) {
pull_qst = MP_QSTR_PULL_DOWN;
}
if (pull_qst != MP_QSTR_NULL) {
mp_printf(print, ", pull=Pin.%q", pull_qst);
}
// AF mode
if (af) {
mp_uint_t af_idx = pin_get_af(self);
const pin_af_obj_t *af_obj = pin_find_af_by_index(self, af_idx);
if (af_obj == NULL) {
mp_printf(print, ", af=%d)", af_idx);
} else {
mp_printf(print, ", af=Pin.%q)", af_obj->name);
}
} else {
*/
mp_print_str(print, ")");
/* }
}*/
}
STATIC mp_obj_t pin_obj_init_helper(const pin_obj_t *pin, mp_uint_t n_args, const mp_obj_t *args, mp_map_t *kw_args);
/// \classmethod \constructor(id, ...)
/// Create a new Pin object associated with the id. If additional arguments are given,
/// they are used to initialise the pin. See `init`.
STATIC mp_obj_t pin_make_new(const mp_obj_type_t *type, mp_uint_t n_args, mp_uint_t n_kw, const mp_obj_t *args) {
mp_arg_check_num(n_args, n_kw, 1, MP_OBJ_FUN_ARGS_MAX, true);
// Run an argument through the mapper and return the result.
const pin_obj_t *pin = pin_find(args[0]);
if (n_args > 1 || n_kw > 0) {
// pin mode given, so configure this GPIO
mp_map_t kw_args;
mp_map_init_fixed_table(&kw_args, n_kw, args + n_args);
pin_obj_init_helper(pin, n_args - 1, args + 1, &kw_args);
}
return (mp_obj_t)pin;
}
// fast method for getting/setting pin value
STATIC mp_obj_t pin_call(mp_obj_t self_in, mp_uint_t n_args, mp_uint_t n_kw, const mp_obj_t *args) {
mp_arg_check_num(n_args, n_kw, 0, 1, false);
pin_obj_t *self = self_in;
if (n_args == 0) {
// get pin
return MP_OBJ_NEW_SMALL_INT(mp_hal_pin_read(self));
} else {
// set pin
mp_hal_pin_write(self, mp_obj_is_true(args[0]));
return mp_const_none;
}
}
STATIC mp_obj_t pin_off(mp_obj_t self_in) {
pin_obj_t *self = self_in;
mp_hal_pin_low(self);
return mp_const_none;
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(pin_off_obj, pin_off);
STATIC mp_obj_t pin_on(mp_obj_t self_in) {
pin_obj_t *self = self_in;
mp_hal_pin_high(self);
return mp_const_none;
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(pin_on_obj, pin_on);
/// \classmethod mapper([fun])
/// Get or set the pin mapper function.
STATIC mp_obj_t pin_mapper(mp_uint_t n_args, const mp_obj_t *args) {
if (n_args > 1) {
MP_STATE_PORT(pin_class_mapper) = args[1];
return mp_const_none;
}
return MP_STATE_PORT(pin_class_mapper);
}
STATIC MP_DEFINE_CONST_FUN_OBJ_VAR_BETWEEN(pin_mapper_fun_obj, 1, 2, pin_mapper);
STATIC MP_DEFINE_CONST_CLASSMETHOD_OBJ(pin_mapper_obj, (mp_obj_t)&pin_mapper_fun_obj);
/// \classmethod dict([dict])
/// Get or set the pin mapper dictionary.
STATIC mp_obj_t pin_map_dict(mp_uint_t n_args, const mp_obj_t *args) {
if (n_args > 1) {
MP_STATE_PORT(pin_class_map_dict) = args[1];
return mp_const_none;
}
return MP_STATE_PORT(pin_class_map_dict);
}
STATIC MP_DEFINE_CONST_FUN_OBJ_VAR_BETWEEN(pin_map_dict_fun_obj, 1, 2, pin_map_dict);
STATIC MP_DEFINE_CONST_CLASSMETHOD_OBJ(pin_map_dict_obj, (mp_obj_t)&pin_map_dict_fun_obj);
/// \classmethod af_list()
/// Returns an array of alternate functions available for this pin.
STATIC mp_obj_t pin_af_list(mp_obj_t self_in) {
pin_obj_t *self = self_in;
mp_obj_t result = mp_obj_new_list(0, NULL);
const pin_af_obj_t *af = self->af;
for (mp_uint_t i = 0; i < self->num_af; i++, af++) {
mp_obj_list_append(result, (mp_obj_t)af);
}
return result;
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(pin_af_list_obj, pin_af_list);
/// \classmethod debug([state])
/// Get or set the debugging state (`True` or `False` for on or off).
STATIC mp_obj_t pin_debug(mp_uint_t n_args, const mp_obj_t *args) {
if (n_args > 1) {
pin_class_debug = mp_obj_is_true(args[1]);
return mp_const_none;
}
return mp_obj_new_bool(pin_class_debug);
}
STATIC MP_DEFINE_CONST_FUN_OBJ_VAR_BETWEEN(pin_debug_fun_obj, 1, 2, pin_debug);
STATIC MP_DEFINE_CONST_CLASSMETHOD_OBJ(pin_debug_obj, (mp_obj_t)&pin_debug_fun_obj);
// init(mode, pull=None, af=-1, *, value, alt)
STATIC mp_obj_t pin_obj_init_helper(const pin_obj_t *self, mp_uint_t n_args, const mp_obj_t *pos_args, mp_map_t *kw_args) {
static const mp_arg_t allowed_args[] = {
{ MP_QSTR_mode, MP_ARG_REQUIRED | MP_ARG_INT },
{ MP_QSTR_pull, MP_ARG_OBJ, {.u_obj = mp_const_none}},
{ MP_QSTR_af, MP_ARG_INT, {.u_int = -1}}, // legacy
{ MP_QSTR_value, MP_ARG_KW_ONLY | MP_ARG_OBJ, {.u_obj = MP_OBJ_NULL}},
{ MP_QSTR_alt, MP_ARG_KW_ONLY | MP_ARG_INT, {.u_int = -1}},
};
// parse args
mp_arg_val_t args[MP_ARRAY_SIZE(allowed_args)];
mp_arg_parse_all(n_args, pos_args, kw_args, MP_ARRAY_SIZE(allowed_args), allowed_args, args);
// get pull mode
uint pull = HAL_GPIO_PULL_DISABLED;
if (args[1].u_obj != mp_const_none) {
pull = mp_obj_get_int(args[1].u_obj);
}
// if given, set the pin value before initialising to prevent glitches
if (args[3].u_obj != MP_OBJ_NULL) {
mp_hal_pin_write(self, mp_obj_is_true(args[3].u_obj));
}
// get io mode
uint mode = args[0].u_int;
if (mode == HAL_GPIO_MODE_OUTPUT || mode == HAL_GPIO_MODE_INPUT) {
hal_gpio_cfg_pin(self->port, self->pin, mode, pull);
} else {
nlr_raise(mp_obj_new_exception_msg_varg(&mp_type_ValueError, "invalid pin mode: %d", mode));
}
return mp_const_none;
}
STATIC mp_obj_t pin_obj_init(mp_uint_t n_args, const mp_obj_t *args, mp_map_t *kw_args) {
return pin_obj_init_helper(args[0], n_args - 1, args + 1, kw_args);
}
MP_DEFINE_CONST_FUN_OBJ_KW(pin_init_obj, 1, pin_obj_init);
/// \method value([value])
/// Get or set the digital logic level of the pin:
///
/// - With no argument, return 0 or 1 depending on the logic level of the pin.
/// - With `value` given, set the logic level of the pin. `value` can be
/// anything that converts to a boolean. If it converts to `True`, the pin
/// is set high, otherwise it is set low.
STATIC mp_obj_t pin_value(mp_uint_t n_args, const mp_obj_t *args) {
return pin_call(args[0], n_args - 1, 0, args + 1);
}
STATIC MP_DEFINE_CONST_FUN_OBJ_VAR_BETWEEN(pin_value_obj, 1, 2, pin_value);
/// \method low()
/// Set the pin to a low logic level.
STATIC mp_obj_t pin_low(mp_obj_t self_in) {
pin_obj_t *self = self_in;
mp_hal_pin_low(self);
return mp_const_none;
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(pin_low_obj, pin_low);
/// \method high()
/// Set the pin to a high logic level.
STATIC mp_obj_t pin_high(mp_obj_t self_in) {
pin_obj_t *self = self_in;
mp_hal_pin_high(self);
return mp_const_none;
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(pin_high_obj, pin_high);
/// \method name()
/// Get the pin name.
STATIC mp_obj_t pin_name(mp_obj_t self_in) {
pin_obj_t *self = self_in;
return MP_OBJ_NEW_QSTR(self->name);
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(pin_name_obj, pin_name);
/// \method names()
/// Returns the cpu and board names for this pin.
STATIC mp_obj_t pin_names(mp_obj_t self_in) {
pin_obj_t *self = self_in;
mp_obj_t result = mp_obj_new_list(0, NULL);
mp_obj_list_append(result, MP_OBJ_NEW_QSTR(self->name));
mp_map_t *map = mp_obj_dict_get_map((mp_obj_t)&pin_board_pins_locals_dict);
mp_map_elem_t *elem = map->table;
for (mp_uint_t i = 0; i < map->used; i++, elem++) {
if (elem->value == self) {
mp_obj_list_append(result, elem->key);
}
}
return result;
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(pin_names_obj, pin_names);
/// \method port()
/// Get the pin port.
STATIC mp_obj_t pin_port(mp_obj_t self_in) {
pin_obj_t *self = self_in;
return MP_OBJ_NEW_SMALL_INT(self->port);
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(pin_port_obj, pin_port);
/// \method pin()
/// Get the pin number.
STATIC mp_obj_t pin_pin(mp_obj_t self_in) {
pin_obj_t *self = self_in;
return MP_OBJ_NEW_SMALL_INT(self->pin);
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(pin_pin_obj, pin_pin);
/// \method gpio()
/// Returns the base address of the GPIO block associated with this pin.
STATIC mp_obj_t pin_gpio(mp_obj_t self_in) {
pin_obj_t *self = self_in;
return MP_OBJ_NEW_SMALL_INT((mp_int_t)self->gpio);
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(pin_gpio_obj, pin_gpio);
/// \method mode()
/// Returns the currently configured mode of the pin. The integer returned
/// will match one of the allowed constants for the mode argument to the init
/// function.
STATIC mp_obj_t pin_mode(mp_obj_t self_in) {
return mp_const_none; // TODO: MP_OBJ_NEW_SMALL_INT(pin_get_mode(self_in));
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(pin_mode_obj, pin_mode);
/// \method pull()
/// Returns the currently configured pull of the pin. The integer returned
/// will match one of the allowed constants for the pull argument to the init
/// function.
STATIC mp_obj_t pin_pull(mp_obj_t self_in) {
return mp_const_none; // TODO: MP_OBJ_NEW_SMALL_INT(pin_get_pull(self_in));
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(pin_pull_obj, pin_pull);
/// \method af()
/// Returns the currently configured alternate-function of the pin. The
/// integer returned will match one of the allowed constants for the af
/// argument to the init function.
STATIC mp_obj_t pin_af(mp_obj_t self_in) {
return mp_const_none; // TODO: MP_OBJ_NEW_SMALL_INT(pin_get_af(self_in));
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(pin_af_obj, pin_af);
STATIC mp_obj_t pin_irq(size_t n_args, const mp_obj_t *pos_args, mp_map_t *kw_args) {
static const mp_arg_t allowed_args[] = {
{ MP_QSTR_handler, MP_ARG_OBJ, {.u_obj = mp_const_none} },
{ MP_QSTR_trigger, MP_ARG_INT, {.u_int = HAL_GPIO_POLARITY_EVENT_TOGGLE} },
{ MP_QSTR_wake, MP_ARG_BOOL, {.u_bool = false} },
};
pin_obj_t *self = MP_OBJ_TO_PTR(pos_args[0]);
mp_arg_val_t args[MP_ARRAY_SIZE(allowed_args)];
mp_arg_parse_all(n_args - 1, pos_args + 1, kw_args, MP_ARRAY_SIZE(allowed_args), allowed_args, args);
(void)self;
// return the irq object
return mp_const_none;
}
STATIC MP_DEFINE_CONST_FUN_OBJ_KW(pin_irq_obj, 1, pin_irq);
STATIC const mp_rom_map_elem_t pin_locals_dict_table[] = {
// instance methods
{ MP_ROM_QSTR(MP_QSTR_init), MP_ROM_PTR(&pin_init_obj) },
{ MP_ROM_QSTR(MP_QSTR_value), MP_ROM_PTR(&pin_value_obj) },
{ MP_ROM_QSTR(MP_QSTR_off), MP_ROM_PTR(&pin_off_obj) },
{ MP_ROM_QSTR(MP_QSTR_on), MP_ROM_PTR(&pin_on_obj) },
{ MP_ROM_QSTR(MP_QSTR_low), MP_ROM_PTR(&pin_low_obj) },
{ MP_ROM_QSTR(MP_QSTR_high), MP_ROM_PTR(&pin_high_obj) },
{ MP_ROM_QSTR(MP_QSTR_name), MP_ROM_PTR(&pin_name_obj) },
{ MP_ROM_QSTR(MP_QSTR_names), MP_ROM_PTR(&pin_names_obj) },
{ MP_ROM_QSTR(MP_QSTR_af_list), MP_ROM_PTR(&pin_af_list_obj) },
{ MP_ROM_QSTR(MP_QSTR_port), MP_ROM_PTR(&pin_port_obj) },
{ MP_ROM_QSTR(MP_QSTR_pin), MP_ROM_PTR(&pin_pin_obj) },
{ MP_ROM_QSTR(MP_QSTR_gpio), MP_ROM_PTR(&pin_gpio_obj) },
{ MP_ROM_QSTR(MP_QSTR_mode), MP_ROM_PTR(&pin_mode_obj) },
{ MP_ROM_QSTR(MP_QSTR_pull), MP_ROM_PTR(&pin_pull_obj) },
{ MP_ROM_QSTR(MP_QSTR_af), MP_ROM_PTR(&pin_af_obj) },
{ MP_ROM_QSTR(MP_QSTR_irq), MP_ROM_PTR(&pin_irq_obj) },
// class methods
{ MP_ROM_QSTR(MP_QSTR_mapper), MP_ROM_PTR(&pin_mapper_obj) },
{ MP_ROM_QSTR(MP_QSTR_dict), MP_ROM_PTR(&pin_map_dict_obj) },
{ MP_ROM_QSTR(MP_QSTR_debug), MP_ROM_PTR(&pin_debug_obj) },
// class attributes
{ MP_ROM_QSTR(MP_QSTR_board), MP_ROM_PTR(&pin_board_pins_obj_type) },
{ MP_ROM_QSTR(MP_QSTR_cpu), MP_ROM_PTR(&pin_cpu_pins_obj_type) },
// class constants
{ MP_ROM_QSTR(MP_QSTR_IN), MP_ROM_INT(HAL_GPIO_MODE_INPUT) },
{ MP_ROM_QSTR(MP_QSTR_OUT), MP_ROM_INT(HAL_GPIO_MODE_OUTPUT) },
/*
{ MP_ROM_QSTR(MP_QSTR_OPEN_DRAIN), MP_ROM_INT(GPIO_MODE_OUTPUT_OD) },
{ MP_ROM_QSTR(MP_QSTR_ALT), MP_ROM_INT(GPIO_MODE_AF_PP) },
{ MP_ROM_QSTR(MP_QSTR_ALT_OPEN_DRAIN), MP_ROM_INT(GPIO_MODE_AF_OD) },
{ MP_ROM_QSTR(MP_QSTR_ANALOG), MP_ROM_INT(GPIO_MODE_ANALOG) },
*/
{ MP_ROM_QSTR(MP_QSTR_PULL_DISABLED), MP_ROM_INT(HAL_GPIO_PULL_DISABLED) },
{ MP_ROM_QSTR(MP_QSTR_PULL_UP), MP_ROM_INT(HAL_GPIO_PULL_UP) },
{ MP_ROM_QSTR(MP_QSTR_PULL_DOWN), MP_ROM_INT(HAL_GPIO_PULL_DOWN) },
// IRQ triggers, can be or'd together
{ MP_ROM_QSTR(MP_QSTR_IRQ_RISING), MP_ROM_INT(HAL_GPIO_POLARITY_EVENT_LOW_TO_HIGH) },
{ MP_ROM_QSTR(MP_QSTR_IRQ_FALLING), MP_ROM_INT(HAL_GPIO_POLARITY_EVENT_HIGH_TO_LOW) },
/*
// legacy class constants
{ MP_ROM_QSTR(MP_QSTR_OUT_PP), MP_ROM_INT(GPIO_MODE_OUTPUT_PP) },
{ MP_ROM_QSTR(MP_QSTR_OUT_OD), MP_ROM_INT(GPIO_MODE_OUTPUT_OD) },
{ MP_ROM_QSTR(MP_QSTR_AF_PP), MP_ROM_INT(GPIO_MODE_AF_PP) },
{ MP_ROM_QSTR(MP_QSTR_AF_OD), MP_ROM_INT(GPIO_MODE_AF_OD) },
{ MP_ROM_QSTR(MP_QSTR_PULL_NONE), MP_ROM_INT(GPIO_NOPULL) },
*/
//#include "genhdr/pins_af_const.h"
};
STATIC MP_DEFINE_CONST_DICT(pin_locals_dict, pin_locals_dict_table);
const mp_obj_type_t pin_type = {
{ &mp_type_type },
.name = MP_QSTR_Pin,
.print = pin_print,
.make_new = pin_make_new,
.call = pin_call,
.locals_dict = (mp_obj_dict_t*)&pin_locals_dict,
};
/// \moduleref pyb
/// \class PinAF - Pin Alternate Functions
///
/// A Pin represents a physical pin on the microcprocessor. Each pin
/// can have a variety of functions (GPIO, I2C SDA, etc). Each PinAF
/// object represents a particular function for a pin.
///
/// Usage Model:
///
/// x3 = pyb.Pin.board.X3
/// x3_af = x3.af_list()
///
/// x3_af will now contain an array of PinAF objects which are availble on
/// pin X3.
///
/// For the pyboard, x3_af would contain:
/// [Pin.AF1_TIM2, Pin.AF2_TIM5, Pin.AF3_TIM9, Pin.AF7_USART2]
///
/// Normally, each peripheral would configure the af automatically, but sometimes
/// the same function is available on multiple pins, and having more control
/// is desired.
///
/// To configure X3 to expose TIM2_CH3, you could use:
/// pin = pyb.Pin(pyb.Pin.board.X3, mode=pyb.Pin.AF_PP, af=pyb.Pin.AF1_TIM2)
/// or:
/// pin = pyb.Pin(pyb.Pin.board.X3, mode=pyb.Pin.AF_PP, af=1)
/// \method __str__()
/// Return a string describing the alternate function.
STATIC void pin_af_obj_print(const mp_print_t *print, mp_obj_t self_in, mp_print_kind_t kind) {
pin_af_obj_t *self = self_in;
mp_printf(print, "Pin.%q", self->name);
}
/// \method index()
/// Return the alternate function index.
STATIC mp_obj_t pin_af_index(mp_obj_t self_in) {
pin_af_obj_t *af = self_in;
return MP_OBJ_NEW_SMALL_INT(af->idx);
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(pin_af_index_obj, pin_af_index);
/// \method name()
/// Return the name of the alternate function.
STATIC mp_obj_t pin_af_name(mp_obj_t self_in) {
pin_af_obj_t *af = self_in;
return MP_OBJ_NEW_QSTR(af->name);
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(pin_af_name_obj, pin_af_name);
/// \method reg()
/// Return the base register associated with the peripheral assigned to this
/// alternate function.
STATIC mp_obj_t pin_af_reg(mp_obj_t self_in) {
pin_af_obj_t *af = self_in;
return MP_OBJ_NEW_SMALL_INT((mp_uint_t)af->reg);
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(pin_af_reg_obj, pin_af_reg);
STATIC const mp_rom_map_elem_t pin_af_locals_dict_table[] = {
{ MP_ROM_QSTR(MP_QSTR_index), MP_ROM_PTR(&pin_af_index_obj) },
{ MP_ROM_QSTR(MP_QSTR_name), MP_ROM_PTR(&pin_af_name_obj) },
{ MP_ROM_QSTR(MP_QSTR_reg), MP_ROM_PTR(&pin_af_reg_obj) },
};
STATIC MP_DEFINE_CONST_DICT(pin_af_locals_dict, pin_af_locals_dict_table);
const mp_obj_type_t pin_af_type = {
{ &mp_type_type },
.name = MP_QSTR_PinAF,
.print = pin_af_obj_print,
.locals_dict = (mp_obj_dict_t*)&pin_af_locals_dict,
};
/******************************************************************************/
// Pin IRQ object
void gpio_irq_event_callback(hal_gpio_event_channel_t channel) {
// printf("### gpio irq received on channel %d\n", (uint16_t)channel);
}
typedef struct _pin_irq_obj_t {
mp_obj_base_t base;
pin_obj_t pin;
} pin_irq_obj_t;
// STATIC const mp_obj_type_t pin_irq_type;
/*STATIC mp_obj_t pin_irq_call(mp_obj_t self_in, size_t n_args, size_t n_kw, const mp_obj_t *args) {
pin_irq_obj_t *self = self_in;
(void)self;
return mp_const_none;
}*/
/*STATIC mp_obj_t pin_irq_trigger(size_t n_args, const mp_obj_t *args) {
pin_irq_obj_t *self = args[0];
(void)self;
return mp_const_none;
}*/
// STATIC MP_DEFINE_CONST_FUN_OBJ_VAR_BETWEEN(pin_irq_trigger_obj, 1, 2, pin_irq_trigger);
// STATIC const mp_rom_map_elem_t pin_irq_locals_dict_table[] = {
// { MP_ROM_QSTR(MP_QSTR_trigger), MP_ROM_PTR(&pin_irq_trigger_obj) },
// };
// STATIC MP_DEFINE_CONST_DICT(pin_irq_locals_dict, pin_irq_locals_dict_table);
/*STATIC const mp_obj_type_t pin_irq_type = {
{ &mp_type_type },
.name = MP_QSTR_IRQ,
.call = pin_irq_call,
.locals_dict = (mp_obj_dict_t*)&pin_irq_locals_dict,
};*/

View File

@ -1,112 +0,0 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2013, 2014 Damien P. George
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#ifndef __MICROPY_INCLUDED_NRF5_PIN_H__
#define __MICROPY_INCLUDED_NRF5_PIN_H__
// This file requires pin_defs_xxx.h (which has port specific enums and
// defines, so we include it here. It should never be included directly
#include MICROPY_PIN_DEFS_PORT_H
#include "py/obj.h"
typedef struct {
mp_obj_base_t base;
qstr name;
uint8_t idx;
uint8_t fn;
uint8_t unit;
uint8_t type;
union {
void *reg;
};
} pin_af_obj_t;
typedef struct {
mp_obj_base_t base;
qstr name;
uint32_t port : 1;
uint32_t pin : 5; // Some ARM processors use 32 bits/PORT
uint32_t num_af : 4;
uint32_t adc_channel : 4; // 0 is no ADC, ADC channel from 1 to 8
// uint32_t pin_mask;
pin_gpio_t *gpio;
const pin_af_obj_t *af;
uint32_t pull;
} pin_obj_t;
// Adafruit
extern const mp_obj_type_t mcu_pin_type;
extern const mp_obj_type_t pin_type;
extern const mp_obj_type_t pin_af_type;
typedef struct {
const char *name;
const pin_obj_t *pin;
} pin_named_pin_t;
extern const pin_named_pin_t pin_board_pins[];
extern const pin_named_pin_t pin_cpu_pins[];
//extern pin_map_obj_t pin_map_obj;
typedef struct {
mp_obj_base_t base;
qstr name;
const pin_named_pin_t *named_pins;
} pin_named_pins_obj_t;
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;
// 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);
void pin_init0(void);
uint32_t pin_get_mode(const pin_obj_t *pin);
uint32_t pin_get_pull(const pin_obj_t *pin);
uint32_t pin_get_af(const pin_obj_t *pin);
const pin_obj_t *pin_find(mp_obj_t user_obj);
const pin_obj_t *pin_find_named_pin(const mp_obj_dict_t *named_pins, mp_obj_t name);
const pin_af_obj_t *pin_find_af(const pin_obj_t *pin, uint8_t fn, uint8_t unit);
const pin_af_obj_t *pin_find_af_by_index(const pin_obj_t *pin, mp_uint_t af_idx);
const pin_af_obj_t *pin_find_af_by_name(const pin_obj_t *pin, const char *name);
#endif // __MICROPY_INCLUDED_NRF5_PIN_H__

View File

@ -1,333 +0,0 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2016 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 <stdio.h>
#include <string.h>
#include "py/nlr.h"
#include "py/runtime.h"
#include "py/mphal.h"
#if MICROPY_PY_MACHINE_HW_PWM
#include "pin.h"
//#include "genhdr/pins.h"
#include "pins.h"
#include "pwm.h"
#if NRF52
// Use PWM hardware.
#include "hal_pwm.h"
#endif
#ifdef MICROPY_HW_PWM0_NAME
PWM_HandleTypeDef PWMHandle0 = {.instance = NULL};
#endif
STATIC const pyb_pwm_obj_t machine_pwm_obj[] = {
#ifdef MICROPY_HW_PWM0_NAME
{{&machine_hard_pwm_type}, &PWMHandle0},
#else
{{&machine_hard_pwm_type}, NULL},
#endif
};
void pwm_init0(void) {
// reset the PWM handles
#ifdef MICROPY_HW_PWM0_NAME
memset(&PWMHandle0, 0, sizeof(PWM_HandleTypeDef));
PWMHandle0.instance = PWM0;
#endif
}
STATIC int pwm_find(mp_obj_t id) {
if (MP_OBJ_IS_STR(id)) {
// given a string id
const char *port = mp_obj_str_get_str(id);
if (0) {
#ifdef MICROPY_HW_PWM0_NAME
} else if (strcmp(port, MICROPY_HW_PWM0_NAME) == 0) {
return 1;
#endif
}
nlr_raise(mp_obj_new_exception_msg_varg(&mp_type_ValueError,
"PWM(%s) does not exist", port));
} else {
// given an integer id
int pwm_id = mp_obj_get_int(id);
if (pwm_id >= 0 && pwm_id <= MP_ARRAY_SIZE(machine_pwm_obj)
&& machine_pwm_obj[pwm_id].pwm != NULL) {
return pwm_id;
}
nlr_raise(mp_obj_new_exception_msg_varg(&mp_type_ValueError,
"PWM(%d) does not exist", pwm_id));
}
}
void pwm_init(PWM_HandleTypeDef *pwm) {
// start pwm
hal_pwm_start(pwm->instance);
}
void pwm_deinit(PWM_HandleTypeDef *pwm) {
// stop pwm
hal_pwm_stop(pwm->instance);
}
STATIC void pwm_print(const mp_print_t *print, PWM_HandleTypeDef *pwm, bool legacy) {
uint pwm_num = 0; // default to PWM0
mp_printf(print, "PWM(%u)", pwm_num);
}
/******************************************************************************/
/* MicroPython bindings for machine API */
// for make_new
enum {
ARG_NEW_id,
ARG_NEW_pin,
ARG_NEW_freq,
ARG_NEW_period,
ARG_NEW_duty,
ARG_NEW_pulse_width,
ARG_NEW_mode
};
// for init
enum {
ARG_INIT_pin
};
// for freq
enum {
ARG_FREQ_freq
};
STATIC mp_obj_t machine_hard_pwm_make_new(mp_arg_val_t *args);
STATIC void machine_hard_pwm_init(mp_obj_t self, mp_arg_val_t *args);
STATIC void machine_hard_pwm_deinit(mp_obj_t self);
STATIC mp_obj_t machine_hard_pwm_freq(mp_obj_t self, mp_arg_val_t *args);
/* common code for both soft and hard implementations *************************/
STATIC mp_obj_t machine_pwm_make_new(const mp_obj_type_t *type, size_t n_args, size_t n_kw, const mp_obj_t *all_args) {
static const mp_arg_t allowed_args[] = {
{ MP_QSTR_id, MP_ARG_OBJ, {.u_obj = MP_OBJ_NEW_SMALL_INT(-1)} },
{ MP_QSTR_pin, MP_ARG_OBJ, {.u_obj = MP_OBJ_NULL} },
{ MP_QSTR_freq, MP_ARG_KW_ONLY | MP_ARG_OBJ, {.u_obj = MP_OBJ_NULL} },
{ MP_QSTR_period, MP_ARG_KW_ONLY | MP_ARG_OBJ, {.u_obj = MP_OBJ_NULL} },
{ MP_QSTR_duty, MP_ARG_KW_ONLY | MP_ARG_OBJ, {.u_obj = MP_OBJ_NULL} },
{ MP_QSTR_pulse_width, MP_ARG_KW_ONLY | MP_ARG_OBJ, {.u_obj = MP_OBJ_NULL} },
{ MP_QSTR_mode, MP_ARG_KW_ONLY | MP_ARG_OBJ, {.u_obj = MP_OBJ_NULL} },
};
// parse args
mp_arg_val_t args[MP_ARRAY_SIZE(allowed_args)];
mp_arg_parse_all_kw_array(n_args, n_kw, all_args, MP_ARRAY_SIZE(allowed_args), allowed_args, args);
if (args[ARG_NEW_id].u_obj == MP_OBJ_NEW_SMALL_INT(-1)) {
// TODO: implement soft PWM
// return machine_soft_pwm_make_new(args);
return mp_const_none;
} else {
// hardware peripheral id given
return machine_hard_pwm_make_new(args);
}
}
STATIC mp_obj_t machine_pwm_init(size_t n_args, const mp_obj_t *pos_args, mp_map_t *kw_args) {
static const mp_arg_t allowed_args[] = {
{ MP_QSTR_pin, MP_ARG_KW_ONLY | MP_ARG_OBJ, {.u_obj = MP_OBJ_NULL} }
};
// parse args
mp_obj_t self = pos_args[0];
mp_arg_val_t args[MP_ARRAY_SIZE(allowed_args)];
mp_arg_parse_all(n_args - 1, pos_args + 1, kw_args, MP_ARRAY_SIZE(allowed_args), allowed_args, args);
// dispatch to specific implementation
if (mp_obj_get_type(self) == &machine_hard_pwm_type) {
machine_hard_pwm_init(self, args);
}
return mp_const_none;
}
STATIC MP_DEFINE_CONST_FUN_OBJ_KW(machine_pwm_init_obj, 1, machine_pwm_init);
STATIC mp_obj_t machine_pwm_deinit(mp_obj_t self) {
// dispatch to specific implementation
if (mp_obj_get_type(self) == &machine_hard_pwm_type) {
machine_hard_pwm_deinit(self);
}
return mp_const_none;
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(machine_pwm_deinit_obj, machine_pwm_deinit);
STATIC mp_obj_t machine_pwm_freq(size_t n_args, const mp_obj_t *pos_args, mp_map_t *kw_args) {
static const mp_arg_t allowed_args[] = {
{ MP_QSTR_freq, MP_ARG_INT, {.u_int = -1} },
};
mp_obj_t self = pos_args[0];
mp_arg_val_t args[MP_ARRAY_SIZE(allowed_args)];
mp_arg_parse_all(n_args - 1, pos_args + 1, kw_args, MP_ARRAY_SIZE(allowed_args), allowed_args, args);
if (mp_obj_get_type(self) == &machine_hard_pwm_type) {
machine_hard_pwm_freq(self, args);
} else {
// soft pwm
}
return mp_const_none;
}
STATIC MP_DEFINE_CONST_FUN_OBJ_KW(mp_machine_pwm_freq_obj, 1, machine_pwm_freq);
STATIC mp_obj_t machine_pwm_period(size_t n_args, const mp_obj_t *args) {
return mp_const_none;
}
STATIC MP_DEFINE_CONST_FUN_OBJ_VAR_BETWEEN(mp_machine_pwm_period_obj, 1, 2, machine_pwm_period);
STATIC mp_obj_t machine_pwm_duty(size_t n_args, const mp_obj_t *args) {
return mp_const_none;
}
STATIC MP_DEFINE_CONST_FUN_OBJ_VAR_BETWEEN(mp_machine_pwm_duty_obj, 1, 2, machine_pwm_duty);
STATIC const mp_rom_map_elem_t machine_pwm_locals_dict_table[] = {
{ MP_ROM_QSTR(MP_QSTR_init), MP_ROM_PTR(&machine_pwm_init_obj) },
{ MP_ROM_QSTR(MP_QSTR_deinit), MP_ROM_PTR(&machine_pwm_deinit_obj) },
{ MP_ROM_QSTR(MP_QSTR_freq), MP_ROM_PTR(&mp_machine_pwm_freq_obj) },
{ MP_ROM_QSTR(MP_QSTR_period), MP_ROM_PTR(&mp_machine_pwm_period_obj) },
{ MP_ROM_QSTR(MP_QSTR_duty), MP_ROM_PTR(&mp_machine_pwm_duty_obj) },
{ MP_ROM_QSTR(MP_QSTR_FREQ_16MHZ), MP_ROM_INT(HAL_PWM_FREQ_16Mhz) },
{ MP_ROM_QSTR(MP_QSTR_FREQ_8MHZ), MP_ROM_INT(HAL_PWM_FREQ_8Mhz) },
{ MP_ROM_QSTR(MP_QSTR_FREQ_4MHZ), MP_ROM_INT(HAL_PWM_FREQ_4Mhz) },
{ MP_ROM_QSTR(MP_QSTR_FREQ_2MHZ), MP_ROM_INT(HAL_PWM_FREQ_2Mhz) },
{ MP_ROM_QSTR(MP_QSTR_FREQ_1MHZ), MP_ROM_INT(HAL_PWM_FREQ_1Mhz) },
{ MP_ROM_QSTR(MP_QSTR_FREQ_500KHZ), MP_ROM_INT(HAL_PWM_FREQ_500khz) },
{ MP_ROM_QSTR(MP_QSTR_FREQ_250KHZ), MP_ROM_INT(HAL_PWM_FREQ_250khz) },
{ MP_ROM_QSTR(MP_QSTR_FREQ_125KHZ), MP_ROM_INT(HAL_PWM_FREQ_125khz) },
{ MP_ROM_QSTR(MP_QSTR_MODE_LOW_HIGH), MP_ROM_INT(HAL_PWM_MODE_LOW_HIGH) },
{ MP_ROM_QSTR(MP_QSTR_MODE_HIGH_LOW), MP_ROM_INT(HAL_PWM_MODE_HIGH_LOW) },
};
STATIC MP_DEFINE_CONST_DICT(machine_pwm_locals_dict, machine_pwm_locals_dict_table);
/* code for hard implementation ***********************************************/
STATIC const machine_hard_pwm_obj_t machine_hard_pwm_obj[] = {
{{&machine_hard_pwm_type}, &machine_pwm_obj[0]},
};
STATIC void machine_hard_pwm_print(const mp_print_t *print, mp_obj_t self_in, mp_print_kind_t kind) {
machine_hard_pwm_obj_t *self = self_in;
pwm_print(print, self->pyb->pwm, false);
}
STATIC mp_obj_t machine_hard_pwm_make_new(mp_arg_val_t *args) {
// get static peripheral object
int pwm_id = pwm_find(args[ARG_NEW_id].u_obj);
const machine_hard_pwm_obj_t *self = &machine_hard_pwm_obj[pwm_id];
// check if PWM pin is set
if (args[ARG_NEW_pin].u_obj != MP_OBJ_NULL) {
pin_obj_t *pin_obj = args[ARG_NEW_pin].u_obj;
self->pyb->pwm->init.pwm_pin = pin_obj->pin;
} else {
// TODO: raise exception.
}
if (args[ARG_NEW_freq].u_obj != MP_OBJ_NULL) {
self->pyb->pwm->init.freq = mp_obj_get_int(args[ARG_NEW_freq].u_obj);
} else {
self->pyb->pwm->init.freq = 50; // 50 Hz by default.
}
if (args[ARG_NEW_period].u_obj != MP_OBJ_NULL) {
self->pyb->pwm->init.period = mp_obj_get_int(args[ARG_NEW_period].u_obj);
} else {
nlr_raise(mp_obj_new_exception_msg_varg(&mp_type_ValueError,
"PWM period has to be within 16000 frequence cycles", self->pyb->pwm->init.period));
}
if (args[ARG_NEW_duty].u_obj != MP_OBJ_NULL) {
self->pyb->pwm->init.duty = mp_obj_get_int(args[ARG_NEW_duty].u_obj);
} else {
self->pyb->pwm->init.duty = 50; // 50% by default.
}
if (args[ARG_NEW_pulse_width].u_obj != MP_OBJ_NULL) {
self->pyb->pwm->init.pulse_width = mp_obj_get_int(args[ARG_NEW_pulse_width].u_obj);
} else {
self->pyb->pwm->init.pulse_width = 0;
}
if (args[ARG_NEW_mode].u_obj != MP_OBJ_NULL) {
self->pyb->pwm->init.mode = mp_obj_get_int(args[ARG_NEW_mode].u_obj);
} else {
self->pyb->pwm->init.mode = HAL_PWM_MODE_HIGH_LOW;
}
hal_pwm_init(self->pyb->pwm->instance, &self->pyb->pwm->init);
return MP_OBJ_FROM_PTR(self);
}
STATIC void machine_hard_pwm_init(mp_obj_t self_in, mp_arg_val_t *args) {
machine_hard_pwm_obj_t *self = self_in;
pwm_init(self->pyb->pwm);
}
STATIC void machine_hard_pwm_deinit(mp_obj_t self_in) {
machine_hard_pwm_obj_t *self = self_in;
pwm_deinit(self->pyb->pwm);
}
STATIC mp_obj_t machine_hard_pwm_freq(mp_obj_t self_in, mp_arg_val_t *args) {
machine_hard_pwm_obj_t *self = self_in;
if (args[ARG_FREQ_freq].u_int != -1) {
self->pyb->pwm->init.freq = args[ARG_FREQ_freq].u_int;
hal_pwm_init(self->pyb->pwm->instance, &self->pyb->pwm->init);
} else {
return MP_OBJ_NEW_SMALL_INT(self->pyb->pwm->init.freq);
}
return mp_const_none;
}
const mp_obj_type_t machine_hard_pwm_type = {
{ &mp_type_type },
.name = MP_QSTR_PWM,
.print = machine_hard_pwm_print,
.make_new = machine_pwm_make_new,
.locals_dict = (mp_obj_dict_t*)&machine_pwm_locals_dict,
};
#endif // MICROPY_PY_MACHINE_HW_PWM

View File

@ -1,41 +0,0 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2016 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 "hal_pwm.h"
typedef struct _pyb_pwm_obj_t {
mp_obj_base_t base;
PWM_HandleTypeDef *pwm;
} pyb_pwm_obj_t;
typedef struct _machine_hard_pwm_obj_t {
mp_obj_base_t base;
const pyb_pwm_obj_t *pyb;
} machine_hard_pwm_obj_t;
void pwm_init0(void);
extern const mp_obj_type_t machine_hard_pwm_type;

View File

@ -1,178 +0,0 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2016 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 <stdio.h>
#include <string.h>
#include "py/nlr.h"
#include "py/runtime.h"
#include "py/mphal.h"
#include "rtc.h"
#include "hal_rtc.h"
#if MICROPY_PY_MACHINE_RTC
typedef struct _machine_rtc_obj_t {
mp_obj_base_t base;
hal_rtc_conf_t * p_config;
mp_obj_t callback;
mp_int_t period;
mp_int_t mode;
} machine_rtc_obj_t;
static hal_rtc_conf_t rtc_config0 = {.id = 0};
static hal_rtc_conf_t rtc_config1 = {.id = 1};
#if NRF52
static hal_rtc_conf_t rtc_config2 = {.id = 2};
#endif
STATIC machine_rtc_obj_t machine_rtc_obj[] = {
{{&machine_rtc_type}, &rtc_config0},
{{&machine_rtc_type}, &rtc_config1},
#if NRF52
{{&machine_rtc_type}, &rtc_config2},
#endif
};
STATIC void hal_interrupt_handle(uint8_t id) {
machine_rtc_obj_t * self = &machine_rtc_obj[id];;
mp_call_function_1(self->callback, self);
if (self != NULL) {
hal_rtc_stop(id);
if (self->mode == 1) {
hal_rtc_start(id);
}
}
}
void rtc_init0(void) {
hal_rtc_callback_set(hal_interrupt_handle);
}
STATIC int rtc_find(mp_obj_t id) {
// given an integer id
int rtc_id = mp_obj_get_int(id);
if (rtc_id >= 0 && rtc_id <= MP_ARRAY_SIZE(machine_rtc_obj)
&& machine_rtc_obj[rtc_id].p_config != NULL) {
return rtc_id;
}
nlr_raise(mp_obj_new_exception_msg_varg(&mp_type_ValueError,
"RTC(%d) does not exist", rtc_id));
}
STATIC void rtc_print(const mp_print_t *print, mp_obj_t o, mp_print_kind_t kind) {
machine_rtc_obj_t *self = o;
mp_printf(print, "RTC(%u)", self->p_config->id);
}
/******************************************************************************/
/* MicroPython bindings for machine API */
STATIC mp_obj_t machine_rtc_make_new(const mp_obj_type_t *type, size_t n_args, size_t n_kw, const mp_obj_t *all_args) {
static const mp_arg_t allowed_args[] = {
{ MP_QSTR_id, MP_ARG_OBJ, {.u_obj = MP_OBJ_NEW_SMALL_INT(-1)} },
{ MP_QSTR_period, MP_ARG_KW_ONLY | MP_ARG_INT, {.u_int = 1000} },
{ MP_QSTR_mode, MP_ARG_KW_ONLY | MP_ARG_INT, {.u_int = 1} },
{ MP_QSTR_callback, MP_ARG_KW_ONLY | MP_ARG_OBJ, {.u_obj = mp_const_none} },
};
// parse args
mp_arg_val_t args[MP_ARRAY_SIZE(allowed_args)];
mp_arg_parse_all_kw_array(n_args, n_kw, all_args, MP_ARRAY_SIZE(allowed_args), allowed_args, args);
// get static peripheral object
int rtc_id = rtc_find(args[0].u_obj);
// unconst machine object in order to set a callback.
machine_rtc_obj_t * self = (machine_rtc_obj_t *)&machine_rtc_obj[rtc_id];
self->p_config->period = args[1].u_int;
self->mode = args[2].u_int;
if (args[3].u_obj != mp_const_none) {
self->callback = args[3].u_obj;
}
#ifdef NRF51
self->p_config->irq_priority = 3;
#else
self->p_config->irq_priority = 6;
#endif
hal_rtc_init(self->p_config);
return MP_OBJ_FROM_PTR(self);
}
/// \method start(period)
/// Start the RTC timer. Timeout occurs after number of periods
/// in the configured frequency has been reached.
///
STATIC mp_obj_t machine_rtc_start(mp_obj_t self_in) {
machine_rtc_obj_t * self = MP_OBJ_TO_PTR(self_in);
hal_rtc_start(self->p_config->id);
return mp_const_none;
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(machine_rtc_start_obj, machine_rtc_start);
/// \method stop()
/// Stop the RTC timer.
///
STATIC mp_obj_t machine_rtc_stop(mp_obj_t self_in) {
machine_rtc_obj_t * self = MP_OBJ_TO_PTR(self_in);
hal_rtc_stop(self->p_config->id);
return mp_const_none;
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(machine_rtc_stop_obj, machine_rtc_stop);
STATIC const mp_rom_map_elem_t machine_rtc_locals_dict_table[] = {
{ MP_ROM_QSTR(MP_QSTR_start), MP_ROM_PTR(&machine_rtc_start_obj) },
{ MP_ROM_QSTR(MP_QSTR_stop), MP_ROM_PTR(&machine_rtc_stop_obj) },
// constants
{ MP_ROM_QSTR(MP_QSTR_ONESHOT), MP_ROM_INT(0) },
{ MP_ROM_QSTR(MP_QSTR_PERIODIC), MP_ROM_INT(1) },
};
STATIC MP_DEFINE_CONST_DICT(machine_rtc_locals_dict, machine_rtc_locals_dict_table);
const mp_obj_type_t machine_rtc_type = {
{ &mp_type_type },
.name = MP_QSTR_RTC,
.print = rtc_print,
.make_new = machine_rtc_make_new,
.locals_dict = (mp_obj_dict_t*)&machine_rtc_locals_dict
};
#endif // MICROPY_PY_MACHINE_RTC

View File

@ -1,36 +0,0 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2016 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.
*/
#ifndef RTC_H__
#define RTC_H__
#include "hal_rtc.h"
extern const mp_obj_type_t machine_rtc_type;
void rtc_init0(void);
#endif // RTC_H__

View File

@ -1,378 +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) 2016 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 <stdio.h>
#include <string.h>
#include "py/nlr.h"
#include "py/runtime.h"
#include "py/mphal.h"
#include "extmod/machine_spi.h"
#include "pin.h"
//#include "genhdr/pins.h"
#include "pins.h"
#include "spi.h"
#include "hal_spi.h"
#if MICROPY_PY_MACHINE_HW_SPI
/// \moduleref pyb
/// \class SPI - a master-driven serial protocol
///
/// SPI is a serial protocol that is driven by a master. At the physical level
/// there are 3 lines: SCK, MOSI, MISO.
///
/// See usage model of I2C; SPI is very similar. Main difference is
/// parameters to init the SPI bus:
///
/// from pyb import SPI
/// spi = SPI(1, SPI.MASTER, baudrate=600000, polarity=1, phase=0, crc=0x7)
///
/// Only required parameter is mode, SPI.MASTER or SPI.SLAVE. Polarity can be
/// 0 or 1, and is the level the idle clock line sits at. Phase can be 0 or 1
/// to sample data on the first or second clock edge respectively. Crc can be
/// None for no CRC, or a polynomial specifier.
///
/// Additional method for SPI:
///
/// data = spi.send_recv(b'1234') # send 4 bytes and receive 4 bytes
/// buf = bytearray(4)
/// spi.send_recv(b'1234', buf) # send 4 bytes and receive 4 into buf
/// spi.send_recv(buf, buf) # send/recv 4 bytes from/to buf
SPI_HandleTypeDef SPIHandle0 = {.instance = NULL};
SPI_HandleTypeDef SPIHandle1 = {.instance = NULL};
#if NRF52
SPI_HandleTypeDef SPIHandle2 = {.instance = NULL};
#if NRF52840_XXAA
SPI_HandleTypeDef SPIHandle3 = {.instance = NULL}; // 32 Mbs master only
#endif // NRF52840_XXAA
#endif // NRF52
STATIC const machine_hard_spi_obj_t machine_hard_spi_obj[] = {
{{&machine_hard_spi_type}, &SPIHandle0},
{{&machine_hard_spi_type}, &SPIHandle1},
#if NRF52
{{&machine_hard_spi_type}, &SPIHandle2},
#if NRF52840_XXAA
{{&machine_hard_spi_type}, &SPIHandle3},
#endif // NRF52840_XXAA
#endif // NRF52
};
void spi_init0(void) {
// reset the SPI handles
memset(&SPIHandle0, 0, sizeof(SPI_HandleTypeDef));
SPIHandle0.instance = SPI_BASE(0);
memset(&SPIHandle1, 0, sizeof(SPI_HandleTypeDef));
SPIHandle1.instance = SPI_BASE(1);
#if NRF52
memset(&SPIHandle2, 0, sizeof(SPI_HandleTypeDef));
SPIHandle2.instance = SPI_BASE(2);
#if NRF52840_XXAA
memset(&SPIHandle3, 0, sizeof(SPI_HandleTypeDef));
SPIHandle3.instance = SPI_BASE(3);
#endif // NRF52840_XXAA
#endif // NRF52
}
STATIC int spi_find(mp_obj_t id) {
if (MP_OBJ_IS_STR(id)) {
// given a string id
const char *port = mp_obj_str_get_str(id);
if (0) {
#ifdef MICROPY_HW_SPI0_NAME
} else if (strcmp(port, MICROPY_HW_SPI0_NAME) == 0) {
return 1;
#endif
}
nlr_raise(mp_obj_new_exception_msg_varg(&mp_type_ValueError,
"SPI(%s) does not exist", port));
} else {
// given an integer id
int spi_id = mp_obj_get_int(id);
if (spi_id >= 0 && spi_id <= MP_ARRAY_SIZE(machine_hard_spi_obj)
&& machine_hard_spi_obj[spi_id].spi != NULL) {
return spi_id;
}
nlr_raise(mp_obj_new_exception_msg_varg(&mp_type_ValueError,
"SPI(%d) does not exist", spi_id));
}
}
void spi_init(SPI_HandleTypeDef *spi, bool enable_nss_pin) {
}
void spi_deinit(SPI_HandleTypeDef *spi) {
}
STATIC void spi_transfer(const machine_hard_spi_obj_t * self, size_t len, const void * src, void * dest) {
hal_spi_master_tx_rx(self->spi->instance, len, src, dest);
}
STATIC void spi_print(const mp_print_t *print, SPI_HandleTypeDef *spi, bool legacy) {
uint spi_num = 0; // default to SPI1
mp_printf(print, "SPI(%u)", spi_num);
}
/******************************************************************************/
/* MicroPython bindings for machine API */
// for make_new
enum {
ARG_NEW_id,
ARG_NEW_baudrate,
ARG_NEW_polarity,
ARG_NEW_phase,
ARG_NEW_bits,
ARG_NEW_firstbit,
ARG_NEW_sck,
ARG_NEW_mosi,
ARG_NEW_miso
};
// for init
enum {
ARG_INIT_baudrate,
ARG_INIT_polarity,
ARG_INIT_phase,
ARG_INIT_bits,
ARG_INIT_firstbit
};
STATIC mp_obj_t machine_hard_spi_make_new(mp_arg_val_t *args);
STATIC void machine_hard_spi_init(mp_obj_t self, mp_arg_val_t *args);
STATIC void machine_hard_spi_deinit(mp_obj_t self);
/* common code for both soft and hard implementations *************************/
STATIC mp_obj_t machine_spi_make_new(const mp_obj_type_t *type, size_t n_args, size_t n_kw, const mp_obj_t *all_args) {
static const mp_arg_t allowed_args[] = {
{ MP_QSTR_id, MP_ARG_OBJ, {.u_obj = MP_OBJ_NEW_SMALL_INT(-1)} },
{ MP_QSTR_baudrate, MP_ARG_INT, {.u_int = 500000} },
{ MP_QSTR_polarity, MP_ARG_KW_ONLY | MP_ARG_INT, {.u_int = 0} },
{ MP_QSTR_phase, MP_ARG_KW_ONLY | MP_ARG_INT, {.u_int = 0} },
{ MP_QSTR_bits, MP_ARG_KW_ONLY | MP_ARG_INT, {.u_int = 8} },
{ MP_QSTR_firstbit, MP_ARG_KW_ONLY | MP_ARG_INT, {.u_int = 0 /* SPI_FIRSTBIT_MSB */} },
{ MP_QSTR_sck, MP_ARG_KW_ONLY | MP_ARG_OBJ, {.u_obj = MP_OBJ_NULL} },
{ MP_QSTR_mosi, MP_ARG_KW_ONLY | MP_ARG_OBJ, {.u_obj = MP_OBJ_NULL} },
{ MP_QSTR_miso, MP_ARG_KW_ONLY | MP_ARG_OBJ, {.u_obj = MP_OBJ_NULL} },
};
// parse args
mp_arg_val_t args[MP_ARRAY_SIZE(allowed_args)];
mp_arg_parse_all_kw_array(n_args, n_kw, all_args, MP_ARRAY_SIZE(allowed_args), allowed_args, args);
if (args[ARG_NEW_id].u_obj == MP_OBJ_NEW_SMALL_INT(-1)) {
// TODO: implement soft SPI
// return machine_soft_spi_make_new(args);
return mp_const_none;
} else {
// hardware peripheral id given
return machine_hard_spi_make_new(args);
}
}
STATIC mp_obj_t machine_spi_init(size_t n_args, const mp_obj_t *pos_args, mp_map_t *kw_args) {
static const mp_arg_t allowed_args[] = {
{ MP_QSTR_baudrate, MP_ARG_KW_ONLY | MP_ARG_INT, {.u_int = -1} },
{ MP_QSTR_polarity, MP_ARG_KW_ONLY | MP_ARG_INT, {.u_int = -1} },
{ MP_QSTR_phase, MP_ARG_KW_ONLY | MP_ARG_INT, {.u_int = -1} },
{ MP_QSTR_bits, MP_ARG_KW_ONLY | MP_ARG_INT, {.u_int = -1} },
{ MP_QSTR_firstbit, MP_ARG_KW_ONLY | MP_ARG_INT, {.u_int = -1} },
};
// parse args
mp_obj_t self = pos_args[0];
mp_arg_val_t args[MP_ARRAY_SIZE(allowed_args)];
mp_arg_parse_all(n_args - 1, pos_args + 1, kw_args, MP_ARRAY_SIZE(allowed_args), allowed_args, args);
// dispatch to specific implementation
if (mp_obj_get_type(self) == &machine_hard_spi_type) {
machine_hard_spi_init(self, args);
}
return mp_const_none;
}
STATIC MP_DEFINE_CONST_FUN_OBJ_KW(machine_spi_init_obj, 1, machine_spi_init);
STATIC mp_obj_t machine_spi_deinit(mp_obj_t self) {
// dispatch to specific implementation
if (mp_obj_get_type(self) == &machine_hard_spi_type) {
machine_hard_spi_deinit(self);
}
return mp_const_none;
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(machine_spi_deinit_obj, machine_spi_deinit);
STATIC const mp_rom_map_elem_t machine_spi_locals_dict_table[] = {
{ MP_ROM_QSTR(MP_QSTR_init), MP_ROM_PTR(&machine_spi_init_obj) },
{ MP_ROM_QSTR(MP_QSTR_deinit), MP_ROM_PTR(&machine_spi_deinit_obj) },
{ MP_ROM_QSTR(MP_QSTR_read), MP_ROM_PTR(&mp_machine_spi_read_obj) },
{ MP_ROM_QSTR(MP_QSTR_readinto), MP_ROM_PTR(&mp_machine_spi_readinto_obj) },
{ MP_ROM_QSTR(MP_QSTR_write), MP_ROM_PTR(&mp_machine_spi_write_obj) },
{ MP_ROM_QSTR(MP_QSTR_write_readinto), MP_ROM_PTR(&mp_machine_spi_write_readinto_obj) },
{ MP_ROM_QSTR(MP_QSTR_MSB), MP_ROM_INT(HAL_SPI_MSB_FIRST) }, // SPI_FIRSTBIT_MSB
{ MP_ROM_QSTR(MP_QSTR_LSB), MP_ROM_INT(HAL_SPI_LSB_FIRST) }, // SPI_FIRSTBIT_LSB
};
STATIC MP_DEFINE_CONST_DICT(machine_spi_locals_dict, machine_spi_locals_dict_table);
/* code for hard implementation ***********************************************/
STATIC void machine_hard_spi_print(const mp_print_t *print, mp_obj_t self_in, mp_print_kind_t kind) {
machine_hard_spi_obj_t *self = self_in;
spi_print(print, self->spi, false);
}
STATIC mp_obj_t machine_hard_spi_make_new(mp_arg_val_t *args) {
// get static peripheral object
int spi_id = spi_find(args[ARG_NEW_id].u_obj);
const machine_hard_spi_obj_t *self = &machine_hard_spi_obj[spi_id];
// here we would check the sck/mosi/miso pins and configure them
if (args[ARG_NEW_sck].u_obj != MP_OBJ_NULL
&& args[ARG_NEW_mosi].u_obj != MP_OBJ_NULL
&& args[ARG_NEW_miso].u_obj != MP_OBJ_NULL) {
self->spi->init.clk_pin = args[ARG_NEW_sck].u_obj;
self->spi->init.mosi_pin = args[ARG_NEW_mosi].u_obj;
self->spi->init.miso_pin = args[ARG_NEW_miso].u_obj;
} else {
self->spi->init.clk_pin = &MICROPY_HW_SPI0_SCK;
self->spi->init.mosi_pin = &MICROPY_HW_SPI0_MOSI;
self->spi->init.miso_pin = &MICROPY_HW_SPI0_MISO;
}
int baudrate = args[ARG_NEW_baudrate].u_int;
if (baudrate <= 125000) {
self->spi->init.freq = HAL_SPI_FREQ_125_Kbps;
} else if (baudrate <= 250000) {
self->spi->init.freq = HAL_SPI_FREQ_250_Kbps;
} else if (baudrate <= 500000) {
self->spi->init.freq = HAL_SPI_FREQ_500_Kbps;
} else if (baudrate <= 1000000) {
self->spi->init.freq = HAL_SPI_FREQ_1_Mbps;
} else if (baudrate <= 2000000) {
self->spi->init.freq = HAL_SPI_FREQ_2_Mbps;
} else if (baudrate <= 4000000) {
self->spi->init.freq = HAL_SPI_FREQ_4_Mbps;
} else if (baudrate <= 8000000) {
self->spi->init.freq = HAL_SPI_FREQ_8_Mbps;
#if NRF52840_XXAA
} else if (baudrate <= 16000000) {
self->spi->init.freq = HAL_SPI_FREQ_16_Mbps;
} else if (baudrate <= 32000000) {
self->spi->init.freq = HAL_SPI_FREQ_32_Mbps;
#endif
} else { // Default
self->spi->init.freq = HAL_SPI_FREQ_1_Mbps;
}
#ifdef NRF51
self->spi->init.irq_priority = 3;
#else
self->spi->init.irq_priority = 6;
#endif
self->spi->init.mode = HAL_SPI_MODE_CPOL0_CPHA0;
self->spi->init.firstbit = (args[ARG_NEW_firstbit].u_int == 0) ? HAL_SPI_MSB_FIRST : HAL_SPI_LSB_FIRST;;
hal_spi_master_init(self->spi->instance, &self->spi->init);
return MP_OBJ_FROM_PTR(self);
}
STATIC void machine_hard_spi_init(mp_obj_t self_in, mp_arg_val_t *args) {
}
STATIC void machine_hard_spi_deinit(mp_obj_t self_in) {
machine_hard_spi_obj_t *self = self_in;
spi_deinit(self->spi);
}
STATIC void machine_hard_spi_transfer(mp_obj_base_t *self_in, size_t len, const uint8_t *src, uint8_t *dest) {
machine_hard_spi_obj_t *self = (machine_hard_spi_obj_t*)self_in;
spi_transfer(self, len, src, dest);
}
STATIC mp_obj_t mp_machine_spi_read(size_t n_args, const mp_obj_t *args) {
vstr_t vstr;
vstr_init_len(&vstr, mp_obj_get_int(args[1]));
memset(vstr.buf, n_args == 3 ? mp_obj_get_int(args[2]) : 0, vstr.len);
spi_transfer(args[0], vstr.len, vstr.buf, vstr.buf);
return mp_obj_new_str_from_vstr(&mp_type_bytes, &vstr);
}
MP_DEFINE_CONST_FUN_OBJ_VAR_BETWEEN(mp_machine_spi_read_obj, 2, 3, mp_machine_spi_read);
STATIC mp_obj_t mp_machine_spi_readinto(size_t n_args, const mp_obj_t *args) {
mp_buffer_info_t bufinfo;
mp_get_buffer_raise(args[1], &bufinfo, MP_BUFFER_WRITE);
memset(bufinfo.buf, n_args == 3 ? mp_obj_get_int(args[2]) : 0, bufinfo.len);
spi_transfer(args[0], bufinfo.len, bufinfo.buf, bufinfo.buf);
return mp_const_none;
}
MP_DEFINE_CONST_FUN_OBJ_VAR_BETWEEN(mp_machine_spi_readinto_obj, 2, 3, mp_machine_spi_readinto);
STATIC mp_obj_t mp_machine_spi_write(mp_obj_t self, mp_obj_t wr_buf) {
mp_buffer_info_t src;
mp_get_buffer_raise(wr_buf, &src, MP_BUFFER_READ);
spi_transfer(self, src.len, (const uint8_t*)src.buf, NULL);
return mp_const_none;
}
MP_DEFINE_CONST_FUN_OBJ_2(mp_machine_spi_write_obj, mp_machine_spi_write);
STATIC mp_obj_t mp_machine_spi_write_readinto(mp_obj_t self, mp_obj_t wr_buf, mp_obj_t rd_buf) {
mp_buffer_info_t src;
mp_get_buffer_raise(wr_buf, &src, MP_BUFFER_READ);
mp_buffer_info_t dest;
mp_get_buffer_raise(rd_buf, &dest, MP_BUFFER_WRITE);
if (src.len != dest.len) {
mp_raise_ValueError("buffers must be the same length");
}
spi_transfer(self, src.len, src.buf, dest.buf);
return mp_const_none;
}
MP_DEFINE_CONST_FUN_OBJ_3(mp_machine_spi_write_readinto_obj, mp_machine_spi_write_readinto);
STATIC const mp_machine_spi_p_t machine_hard_spi_p = {
.transfer = machine_hard_spi_transfer,
};
const mp_obj_type_t machine_hard_spi_type = {
{ &mp_type_type },
.name = MP_QSTR_SPI,
.print = machine_hard_spi_print,
.make_new = machine_spi_make_new,
.protocol = &machine_hard_spi_p,
.locals_dict = (mp_obj_dict_t*)&machine_spi_locals_dict,
};
#endif // MICROPY_PY_MACHINE_HW_SPI

View File

@ -1,96 +0,0 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2017 Bander F. Ajba
*
* 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 <stdio.h>
#include <string.h>
#include "py/nlr.h"
#include "py/runtime.h"
#include "py/mphal.h"
#include "temp.h"
#include "hal_temp.h"
#if MICROPY_PY_MACHINE_TEMP
typedef struct _machine_temp_obj_t {
mp_obj_base_t base;
} machine_temp_obj_t;
/// \method __str__()
/// Return a string describing the Temp object.
STATIC void machine_temp_print(const mp_print_t *print, mp_obj_t o, mp_print_kind_t kind) {
machine_temp_obj_t *self = o;
(void)self;
mp_printf(print, "Temp");
}
/******************************************************************************/
/* MicroPython bindings for machine API */
STATIC mp_obj_t machine_temp_make_new(const mp_obj_type_t *type, size_t n_args, size_t n_kw, const mp_obj_t *all_args) {
static const mp_arg_t allowed_args[] = {
{ },
};
// parse args
mp_arg_val_t args[MP_ARRAY_SIZE(allowed_args)];
mp_arg_parse_all_kw_array(n_args, n_kw, all_args, MP_ARRAY_SIZE(allowed_args), allowed_args, args);
machine_temp_obj_t *self = m_new_obj(machine_temp_obj_t);
self->base.type = &machine_temp_type;
return MP_OBJ_FROM_PTR(self);
}
/// \method read()
/// Get temperature.
STATIC mp_obj_t machine_temp_read(mp_uint_t n_args, const mp_obj_t *args) {
return MP_OBJ_NEW_SMALL_INT(hal_temp_read());
}
STATIC MP_DEFINE_CONST_FUN_OBJ_VAR_BETWEEN(mp_machine_temp_read_obj, 0, 1, machine_temp_read);
STATIC const mp_rom_map_elem_t machine_temp_locals_dict_table[] = {
// instance methods
// class methods
{ MP_ROM_QSTR(MP_QSTR_read), MP_ROM_PTR(&mp_machine_temp_read_obj) },
};
STATIC MP_DEFINE_CONST_DICT(machine_temp_locals_dict, machine_temp_locals_dict_table);
const mp_obj_type_t machine_temp_type = {
{ &mp_type_type },
.name = MP_QSTR_Temp,
.make_new = machine_temp_make_new,
.locals_dict = (mp_obj_dict_t*)&machine_temp_locals_dict,
.print = machine_temp_print,
};
#endif // MICROPY_PY_MACHINE_TEMP

View File

@ -1,34 +0,0 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2017 Bander F. Ajba
*
* 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 TEMP_H__
#define TEMP_H__
extern const mp_obj_type_t machine_temp_type;
int32_t temp_read(void);
#endif // TEMP_H__

View File

@ -1,194 +0,0 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2016 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 <stdio.h>
#include <string.h>
#include "py/nlr.h"
#include "py/runtime.h"
#include "py/mphal.h"
#include "timer.h"
#include "hal_timer.h"
#if MICROPY_PY_MACHINE_TIMER
typedef struct _machine_timer_obj_t {
mp_obj_base_t base;
hal_timer_conf_t * p_config;
mp_obj_t callback;
mp_int_t period;
mp_int_t mode;
} machine_timer_obj_t;
static hal_timer_conf_t timer_config0 = {.id = 0};
static hal_timer_conf_t timer_config1 = {.id = 1};
static hal_timer_conf_t timer_config2 = {.id = 2};
#if NRF52
static hal_timer_conf_t timer_config3 = {.id = 3};
static hal_timer_conf_t timer_config4 = {.id = 4};
#endif
STATIC machine_timer_obj_t machine_timer_obj[] = {
{{&machine_timer_type}, &timer_config0},
{{&machine_timer_type}, &timer_config1},
{{&machine_timer_type}, &timer_config2},
#if NRF52
{{&machine_timer_type}, &timer_config3},
{{&machine_timer_type}, &timer_config4},
#endif
};
STATIC void hal_interrupt_handle(uint8_t id) {
machine_timer_obj_t * self = &machine_timer_obj[id];
mp_call_function_1(self->callback, self);
if (self != NULL) {
hal_timer_stop(id);
if (self->mode == 1) {
hal_timer_start(id);
}
}
}
void timer_init0(void) {
hal_timer_callback_set(hal_interrupt_handle);
}
STATIC int timer_find(mp_obj_t id) {
// given an integer id
int timer_id = mp_obj_get_int(id);
if (timer_id >= 0 && timer_id < MP_ARRAY_SIZE(machine_timer_obj)
&& machine_timer_obj[timer_id].p_config != NULL) {
return timer_id;
}
nlr_raise(mp_obj_new_exception_msg_varg(&mp_type_ValueError,
"Timer(%d) does not exist", timer_id));
}
STATIC void timer_print(const mp_print_t *print, mp_obj_t o, mp_print_kind_t kind) {
machine_timer_obj_t *self = o;
mp_printf(print, "Timer(%u)", self->p_config->id);
}
/******************************************************************************/
/* MicroPython bindings for machine API */
STATIC mp_obj_t machine_timer_make_new(const mp_obj_type_t *type, size_t n_args, size_t n_kw, const mp_obj_t *all_args) {
static const mp_arg_t allowed_args[] = {
{ MP_QSTR_id, MP_ARG_OBJ, {.u_obj = MP_OBJ_NEW_SMALL_INT(-1)} },
{ MP_QSTR_period, MP_ARG_KW_ONLY | MP_ARG_INT, {.u_int = 1000} },
{ MP_QSTR_mode, MP_ARG_KW_ONLY | MP_ARG_INT, {.u_int = 1} },
{ MP_QSTR_callback, MP_ARG_KW_ONLY | MP_ARG_OBJ, {.u_obj = mp_const_none} },
};
// parse args
mp_arg_val_t args[MP_ARRAY_SIZE(allowed_args)];
mp_arg_parse_all_kw_array(n_args, n_kw, all_args, MP_ARRAY_SIZE(allowed_args), allowed_args, args);
// get static peripheral object
int timer_id = timer_find(args[0].u_obj);
#if BLUETOOTH_SD
if (timer_id == 0) {
nlr_raise(mp_obj_new_exception_msg_varg(&mp_type_ValueError,
"Timer(%d) reserved by Bluetooth LE stack.", timer_id));
}
#endif
#if MICROPY_PY_MACHINE_SOFT_PWM
if (timer_id == 1) {
nlr_raise(mp_obj_new_exception_msg_varg(&mp_type_ValueError,
"Timer(%d) reserved by ticker driver.", timer_id));
}
#endif
machine_timer_obj_t *self = &machine_timer_obj[timer_id];
self->p_config->period = args[1].u_int;
self->mode = args[2].u_int;
if (args[3].u_obj != mp_const_none) {
self->callback = args[3].u_obj;
}
#ifdef NRF51
self->p_config->irq_priority = 3;
#else
self->p_config->irq_priority = 6;
#endif
hal_timer_init(self->p_config);
return MP_OBJ_FROM_PTR(self);
}
/// \method start(period)
/// Start the timer.
///
STATIC mp_obj_t machine_timer_start(mp_obj_t self_in) {
machine_timer_obj_t * self = MP_OBJ_TO_PTR(self_in);
hal_timer_start(self->p_config->id);
return mp_const_none;
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(machine_timer_start_obj, machine_timer_start);
/// \method stop()
/// Stop the timer.
///
STATIC mp_obj_t machine_timer_stop(mp_obj_t self_in) {
machine_timer_obj_t * self = MP_OBJ_TO_PTR(self_in);
hal_timer_stop(self->p_config->id);
return mp_const_none;
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(machine_timer_stop_obj, machine_timer_stop);
STATIC const mp_rom_map_elem_t machine_timer_locals_dict_table[] = {
{ MP_ROM_QSTR(MP_QSTR_start), MP_ROM_PTR(&machine_timer_start_obj) },
{ MP_ROM_QSTR(MP_QSTR_stop), MP_ROM_PTR(&machine_timer_stop_obj) },
// constants
{ MP_ROM_QSTR(MP_QSTR_ONESHOT), MP_ROM_INT(0) },
{ MP_ROM_QSTR(MP_QSTR_PERIODIC), MP_ROM_INT(1) },
};
STATIC MP_DEFINE_CONST_DICT(machine_timer_locals_dict, machine_timer_locals_dict_table);
const mp_obj_type_t machine_timer_type = {
{ &mp_type_type },
.name = MP_QSTR_Timer,
.print = timer_print,
.make_new = machine_timer_make_new,
.locals_dict = (mp_obj_dict_t*)&machine_timer_locals_dict
};
#endif // MICROPY_PY_MACHINE_TIMER

View File

@ -1,36 +0,0 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2016 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.
*/
#ifndef TIMER_H__
#define TIMER_H__
#include "hal_timer.h"
extern const mp_obj_type_t machine_timer_type;
void timer_init0(void);
#endif // TIMER_H__

View File

@ -1,385 +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 <stdbool.h>
#include <string.h>
#include <stdarg.h>
#include "py/nlr.h"
#include "py/runtime.h"
#include "py/stream.h"
#include "py/mperrno.h"
#include "py/mphal.h"
#include "pin.h"
//#include "genhdr/pins.h"
#include "pins.h"
#include "uart.h"
#include "mpconfigboard.h"
#include "nrf.h"
#include "mphalport.h"
#include "hal_uart.h"
typedef struct _machine_hard_uart_obj_t {
mp_obj_base_t base;
UART_HandleTypeDef * uart;
byte char_width; // 0 for 7,8 bit chars, 1 for 9 bit chars
} machine_hard_uart_obj_t;
UART_HandleTypeDef UARTHandle0 = {.p_instance = NULL, .init.id = 0};
#if NRF52840_XXAA
UART_HandleTypeDef UARTHandle1 = {.p_instance = NULL, .init.id = 1};
#endif
STATIC machine_hard_uart_obj_t machine_hard_uart_obj[] = {
{{&machine_hard_uart_type}, &UARTHandle0},
#if NRF52840_XXAA
{{&machine_hard_uart_type}, &UARTHandle1},
#endif
};
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);
#endif
}
STATIC int uart_find(mp_obj_t id) {
// given an integer id
int uart_id = mp_obj_get_int(id);
if (uart_id >= 0 && uart_id <= MP_ARRAY_SIZE(machine_hard_uart_obj)
&& machine_hard_uart_obj[uart_id].uart != NULL) {
return uart_id;
}
nlr_raise(mp_obj_new_exception_msg_varg(&mp_type_ValueError,
"UART(%d) does not exist", 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 hal_uart_available(uart_obj->uart->p_instance) > 0;
}
int uart_rx_char(machine_hard_uart_obj_t * self) {
uint8_t ch;
hal_uart_char_read(self->uart->p_instance, &ch);
return (int)ch;
}
STATIC hal_uart_error_t uart_tx_char(machine_hard_uart_obj_t * self, int c) {
return hal_uart_char_write(self->uart->p_instance, (char)c);
}
void uart_tx_strn(machine_hard_uart_obj_t *uart_obj, const char *str, uint len) {
for (const char *top = str + len; str < top; str++) {
uart_tx_char(uart_obj, *str);
}
}
void uart_tx_strn_cooked(machine_hard_uart_obj_t *uart_obj, const char *str, uint len) {
for (const char *top = str + len; str < top; str++) {
if (*str == '\n') {
uart_tx_char(uart_obj, '\r');
}
uart_tx_char(uart_obj, *str);
}
}
/******************************************************************************/
/* MicroPython bindings */
STATIC void machine_hard_uart_print(const mp_print_t *print, mp_obj_t self_in, mp_print_kind_t kind) {
}
/// \method init(baudrate, bits=8, parity=None, stop=1, *, timeout=1000, timeout_char=0, read_buf_len=64)
///
/// Initialise the UART bus with the given parameters:
/// - `id`is bus id.
/// - `baudrate` is the clock rate.
/// - `bits` is the number of bits per byte, 7, 8 or 9.
/// - `parity` is the parity, `None`, 0 (even) or 1 (odd).
/// - `stop` is the number of stop bits, 1 or 2.
/// - `timeout` is the timeout in milliseconds to wait for the first character.
/// - `timeout_char` is the timeout in milliseconds to wait between characters.
/// - `read_buf_len` is the character length of the read buffer (0 to disable).
STATIC mp_obj_t machine_hard_uart_make_new(const mp_obj_type_t *type, size_t n_args, size_t n_kw, const mp_obj_t *all_args) {
static const mp_arg_t allowed_args[] = {
{ MP_QSTR_id, MP_ARG_REQUIRED | MP_ARG_OBJ },
{ MP_QSTR_baudrate, MP_ARG_REQUIRED | MP_ARG_INT, {.u_int = 9600} },
{ MP_QSTR_bits, MP_ARG_INT, {.u_int = 8} },
{ MP_QSTR_parity, MP_ARG_OBJ, {.u_obj = mp_const_none} },
{ MP_QSTR_stop, MP_ARG_INT, {.u_int = 1} },
{ MP_QSTR_flow, MP_ARG_KW_ONLY | MP_ARG_INT, {.u_int = 0} },
{ MP_QSTR_timeout, MP_ARG_KW_ONLY | MP_ARG_INT, {.u_int = 1000} },
{ MP_QSTR_timeout_char, MP_ARG_KW_ONLY | MP_ARG_INT, {.u_int = 0} },
{ MP_QSTR_read_buf_len, MP_ARG_KW_ONLY | MP_ARG_INT, {.u_int = 64} },
};
// parse args
mp_arg_val_t args[MP_ARRAY_SIZE(allowed_args)];
mp_arg_parse_all_kw_array(n_args, n_kw, all_args, MP_ARRAY_SIZE(allowed_args), allowed_args, args);
// get static peripheral object
int uart_id = uart_find(args[0].u_obj);
machine_hard_uart_obj_t * self = &machine_hard_uart_obj[uart_id];
hal_uart_init_t * init = &self->uart->init;
// flow control
init->flow_control = args[5].u_int;
#if MICROPY_HW_UART1_HWFC
init->flow_control = true;
#else
init->flow_control = false;
#endif
init->use_parity = false;
#if (BLUETOOTH_SD == 100)
init->irq_priority = 3;
#else
init->irq_priority = 6;
#endif
switch (args[1].u_int) {
case 1200:
init->baud_rate = HAL_UART_BAUD_1K2;
break;
case 2400:
init->baud_rate = HAL_UART_BAUD_2K4;
break;
case 4800:
init->baud_rate = HAL_UART_BAUD_4K8;
break;
case 9600:
init->baud_rate = HAL_UART_BAUD_9K6;
break;
case 14400:
init->baud_rate = HAL_UART_BAUD_14K4;
break;
case 19200:
init->baud_rate = HAL_UART_BAUD_19K2;
break;
case 28800:
init->baud_rate = HAL_UART_BAUD_28K8;
break;
case 38400:
init->baud_rate = HAL_UART_BAUD_38K4;
break;
case 57600:
init->baud_rate = HAL_UART_BAUD_57K6;
break;
case 76800:
init->baud_rate = HAL_UART_BAUD_76K8;
break;
case 115200:
init->baud_rate = HAL_UART_BAUD_115K2;
break;
case 230400:
init->baud_rate = HAL_UART_BAUD_230K4;
break;
case 250000:
init->baud_rate = HAL_UART_BAUD_250K0;
break;
case 500000:
init->baud_rate = HAL_UART_BAUD_500K0;
break;
case 1000000:
init->baud_rate = HAL_UART_BAUD_1M0;
break;
default:
nlr_raise(mp_obj_new_exception_msg_varg(&mp_type_ValueError,
"UART baudrate not supported, %ul", init->baud_rate));
break;
}
init->rx_pin = &MICROPY_HW_UART1_RX;
init->tx_pin = &MICROPY_HW_UART1_TX;
#if MICROPY_HW_UART1_HWFC
init->rts_pin = &MICROPY_HW_UART1_RTS;
init->cts_pin = &MICROPY_HW_UART1_CTS;
#endif
hal_uart_init(self->uart->p_instance, init);
return MP_OBJ_FROM_PTR(self);
}
/// \method writechar(char)
/// Write a single character on the bus. `char` is an integer to write.
/// Return value: `None`.
STATIC mp_obj_t machine_hard_uart_writechar(mp_obj_t self_in, mp_obj_t char_in) {
machine_hard_uart_obj_t *self = self_in;
// get the character to write (might be 9 bits)
uint16_t data = mp_obj_get_int(char_in);
hal_uart_error_t err = 0;
for (int i = 0; i < 2; i++) {
err = uart_tx_char(self, (int)(&data)[i]);
}
HAL_StatusTypeDef status = self->uart->p_instance->EVENTS_ERROR;
if (err != HAL_UART_ERROR_NONE) {
mp_hal_raise(status);
}
return mp_const_none;
}
STATIC MP_DEFINE_CONST_FUN_OBJ_2(machine_hard_uart_writechar_obj, machine_hard_uart_writechar);
/// \method readchar()
/// Receive a single character on the bus.
/// Return value: The character read, as an integer. Returns -1 on timeout.
STATIC mp_obj_t machine_hard_uart_readchar(mp_obj_t self_in) {
machine_hard_uart_obj_t *self = self_in;
return MP_OBJ_NEW_SMALL_INT(uart_rx_char(self));
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(machine_hard_uart_readchar_obj, machine_hard_uart_readchar);
// uart.sendbreak()
STATIC mp_obj_t machine_hard_uart_sendbreak(mp_obj_t self_in) {
return mp_const_none;
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(machine_hard_uart_sendbreak_obj, machine_hard_uart_sendbreak);
STATIC const mp_rom_map_elem_t machine_hard_uart_locals_dict_table[] = {
// instance methods
/// \method read([nbytes])
{ MP_ROM_QSTR(MP_QSTR_read), MP_ROM_PTR(&mp_stream_read_obj) },
/// \method readline()
{ MP_ROM_QSTR(MP_QSTR_readline), MP_ROM_PTR(&mp_stream_unbuffered_readline_obj) },
/// \method readinto(buf[, nbytes])
{ MP_ROM_QSTR(MP_QSTR_readinto), MP_ROM_PTR(&mp_stream_readinto_obj) },
/// \method writechar(buf)
{ MP_ROM_QSTR(MP_QSTR_writechar), MP_ROM_PTR(&machine_hard_uart_writechar_obj) },
{ MP_ROM_QSTR(MP_QSTR_readchar), MP_ROM_PTR(&machine_hard_uart_readchar_obj) },
{ MP_ROM_QSTR(MP_QSTR_sendbreak), MP_ROM_PTR(&machine_hard_uart_sendbreak_obj) },
// class constants
/*
{ MP_ROM_QSTR(MP_QSTR_RTS), MP_ROM_INT(UART_HWCONTROL_RTS) },
{ MP_ROM_QSTR(MP_QSTR_CTS), MP_ROM_INT(UART_HWCONTROL_CTS) },
*/
};
STATIC MP_DEFINE_CONST_DICT(machine_hard_uart_locals_dict, machine_hard_uart_locals_dict_table);
STATIC mp_uint_t machine_hard_uart_read(mp_obj_t self_in, void *buf_in, mp_uint_t size, int *errcode) {
machine_hard_uart_obj_t *self = self_in;
byte *buf = buf_in;
// check that size is a multiple of character width
if (size & self->char_width) {
*errcode = MP_EIO;
return MP_STREAM_ERROR;
}
// convert byte size to char size
size >>= self->char_width;
// make sure we want at least 1 char
if (size == 0) {
return 0;
}
// read the data
byte * orig_buf = buf;
for (;;) {
int data = uart_rx_char(self);
*buf++ = data;
if (--size == 0) {
// return number of bytes read
return buf - orig_buf;
}
}
}
STATIC mp_uint_t machine_hard_uart_write(mp_obj_t self_in, const void *buf_in, mp_uint_t size, int *errcode) {
machine_hard_uart_obj_t *self = self_in;
const byte *buf = buf_in;
// check that size is a multiple of character width
if (size & self->char_width) {
*errcode = MP_EIO;
return MP_STREAM_ERROR;
}
hal_uart_error_t err = 0;
for (int i = 0; i < size; i++) {
err = uart_tx_char(self, (int)((uint8_t *)buf)[i]);
}
if (err == HAL_UART_ERROR_NONE) {
// return number of bytes written
return size;
} else {
*errcode = mp_hal_status_to_errno_table[err];
return MP_STREAM_ERROR;
}
}
STATIC mp_uint_t machine_hard_uart_ioctl(mp_obj_t self_in, mp_uint_t request, uintptr_t arg, int *errcode) {
machine_hard_uart_obj_t *self = self_in;
(void)self;
return MP_STREAM_ERROR;
}
STATIC const mp_stream_p_t uart_stream_p = {
.read = machine_hard_uart_read,
.write = machine_hard_uart_write,
.ioctl = machine_hard_uart_ioctl,
.is_text = false,
};
const mp_obj_type_t machine_hard_uart_type = {
{ &mp_type_type },
.name = MP_QSTR_UART,
.print = machine_hard_uart_print,
.make_new = machine_hard_uart_make_new,
.getiter = mp_identity_getiter,
.iternext = mp_stream_unbuffered_iter,
.protocol = &uart_stream_p,
.locals_dict = (mp_obj_dict_t*)&machine_hard_uart_locals_dict,
};

View File

@ -1,48 +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.
*/
#ifndef UART_H__
#define UART_H__
typedef enum {
PYB_UART_NONE = 0,
PYB_UART_1 = 1,
} pyb_uart_t;
typedef struct _machine_hard_uart_obj_t machine_hard_uart_obj_t;
extern const mp_obj_type_t machine_hard_uart_type;
void uart_init0(void);
void uart_deinit(void);
void uart_irq_handler(mp_uint_t uart_id);
bool uart_rx_any(machine_hard_uart_obj_t * uart_obj);
int uart_rx_char(machine_hard_uart_obj_t * uart_obj);
void uart_tx_strn(machine_hard_uart_obj_t * uart_obj, const char *str, uint len);
void uart_tx_strn_cooked(machine_hard_uart_obj_t *uart_obj, const char *str, uint len);
#endif

View File

@ -1,517 +0,0 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2015 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 "py/mphal.h"
#if MICROPY_PY_MUSIC
// #include "microbitobj.h"
// #include "microbitmusic.h"
#include "py/obj.h"
#include "py/runtime.h"
#include "py/objstr.h"
#include "modmusic.h"
#include "musictunes.h"
#include "softpwm.h"
#include "ticker.h"
#include "pin.h"
#include "genhdr/pins.h"
#define DEFAULT_BPM 120
#define DEFAULT_TICKS 4 // i.e. 4 ticks per beat
#define DEFAULT_OCTAVE 4 // C4 is middle C
#define DEFAULT_DURATION 4 // Crotchet
#define ARTICULATION_MS 10 // articulation between notes in milliseconds
typedef struct _music_data_t {
uint16_t bpm;
uint16_t ticks;
// store these to simplify the writing process
uint8_t last_octave;
uint8_t last_duration;
// Asynchronous parts.
volatile uint8_t async_state;
bool async_loop;
uint32_t async_wait_ticks;
uint16_t async_notes_len;
uint16_t async_notes_index;
const pin_obj_t *async_pin;
mp_obj_t async_note;
} music_data_t;
enum {
ASYNC_MUSIC_STATE_IDLE,
ASYNC_MUSIC_STATE_NEXT_NOTE,
ASYNC_MUSIC_STATE_ARTICULATE,
};
#define music_data MP_STATE_PORT(music_data)
extern volatile uint32_t ticks;
STATIC uint32_t start_note(const char *note_str, size_t note_len, const pin_obj_t *pin);
void microbit_music_init0(void) {
softpwm_init();
ticker_init(microbit_music_tick);
ticker_start();
pwm_start();
}
void microbit_music_tick(void) {
if (music_data == NULL) {
// music module not yet imported
return;
}
if (music_data->async_state == ASYNC_MUSIC_STATE_IDLE) {
// nothing to do
return;
}
if (ticks < music_data->async_wait_ticks) {
// need to wait for timeout to expire
return;
}
if (music_data->async_state == ASYNC_MUSIC_STATE_ARTICULATE) {
// turn off output and rest
pwm_set_duty_cycle(music_data->async_pin->pin, 0); // TODO: remove pin setting.
music_data->async_wait_ticks = ticks + ARTICULATION_MS;
music_data->async_state = ASYNC_MUSIC_STATE_NEXT_NOTE;
} else if (music_data->async_state == ASYNC_MUSIC_STATE_NEXT_NOTE) {
// play next note
if (music_data->async_notes_index >= music_data->async_notes_len) {
if (music_data->async_loop) {
music_data->async_notes_index = 0;
} else {
music_data->async_state = ASYNC_MUSIC_STATE_IDLE;
// TODO: microbit_obj_pin_free(music_data->async_pin);
music_data->async_pin = NULL;
return;
}
}
mp_obj_t note;
if (music_data->async_notes_len == 1) {
note = music_data->async_note;
} else {
note = ((mp_obj_t*)music_data->async_note)[music_data->async_notes_index];
}
if (note == mp_const_none) {
// a rest (is this even used anymore?)
pwm_set_duty_cycle(music_data->async_pin->pin, 0); // TODO: remove pin setting.
music_data->async_wait_ticks = 60000 / music_data->bpm;
music_data->async_state = ASYNC_MUSIC_STATE_NEXT_NOTE;
} else {
// a note
mp_uint_t note_len;
const char *note_str = mp_obj_str_get_data(note, &note_len);
uint32_t delay_on = start_note(note_str, note_len, music_data->async_pin);
music_data->async_wait_ticks = ticks + delay_on;
music_data->async_notes_index += 1;
music_data->async_state = ASYNC_MUSIC_STATE_ARTICULATE;
}
}
}
STATIC void wait_async_music_idle(void) {
// wait for the async music state to become idle
while (music_data->async_state != ASYNC_MUSIC_STATE_IDLE) {
// allow CTRL-C to stop the music
if (MP_STATE_VM(mp_pending_exception) != MP_OBJ_NULL) {
music_data->async_state = ASYNC_MUSIC_STATE_IDLE;
pwm_set_duty_cycle(music_data->async_pin->pin, 0); // TODO: remove pin setting.
break;
}
}
}
STATIC uint32_t start_note(const char *note_str, size_t note_len, const pin_obj_t *pin) {
pwm_set_duty_cycle(pin->pin, 128); // TODO: remove pin setting.
// [NOTE](#|b)(octave)(:length)
// technically, c4 is middle c, so we'll go with that...
// if we define A as 0 and G as 7, then we can use the following
// array of us periods
// these are the periods of note4 (the octave ascending from middle c) from A->B then C->G
STATIC uint16_t periods_us[] = {2273, 2025, 3822, 3405, 3034, 2863, 2551};
// A#, -, C#, D#, -, F#, G#
STATIC uint16_t periods_sharps_us[] = {2145, 0, 3608, 3214, 0, 2703, 2408};
// we'll represent the note as an integer (A=0, G=6)
// TODO: validate the note
uint8_t note_index = (note_str[0] & 0x1f) - 1;
// TODO: the duration and bpm should be persistent between notes
uint32_t ms_per_tick = (60000 / music_data->bpm) / music_data->ticks;
int8_t octave = 0;
bool sharp = false;
size_t current_position = 1;
// parse sharp or flat
if (current_position < note_len && (note_str[current_position] == '#' || note_str[current_position] == 'b')) {
if (note_str[current_position] == 'b') {
// make sure we handle wrapping round gracefully
if (note_index == 0) {
note_index = 6;
} else {
note_index--;
}
// handle the unusual edge case of Cb
if (note_index == 1) {
octave--;
}
}
sharp = true;
current_position++;
}
// parse the octave
if (current_position < note_len && note_str[current_position] != ':') {
// currently this will only work with a one digit number
// use +=, since the sharp/flat code changes octave to compensate.
music_data->last_octave = (note_str[current_position] & 0xf);
current_position++;
}
octave += music_data->last_octave;
// parse the duration
if (current_position < note_len && note_str[current_position] == ':') {
// I'll make this handle up to two digits for the time being.
current_position++;
if (current_position < note_len) {
music_data->last_duration = note_str[current_position] & 0xf;
current_position++;
if (current_position < note_len) {
music_data->last_duration *= 10;
music_data->last_duration += note_str[current_position] & 0xf;
}
} else {
// technically, this should be a syntax error, since this means
// that no duration has been specified. For the time being,
// we'll let you off :D
}
}
// play the note!
// make the octave relative to octave 4
octave -= 4;
// 18 is 'r' or 'R'
if (note_index < 10) {
uint32_t period;
if (sharp) {
if (octave >= 0) {
period = periods_sharps_us[note_index] >> octave;
}
else {
period = periods_sharps_us[note_index] << -octave;
}
} else {
if (octave >= 0) {
period = periods_us[note_index] >> octave;
}
else {
period = periods_us[note_index] << -octave;
}
}
pwm_set_period_us(period);
} else {
pwm_set_duty_cycle(pin->pin, 0); // TODO: remove pin setting.
}
// Cut off a short time from end of note so we hear articulation.
mp_int_t gap_ms = (ms_per_tick * music_data->last_duration) - ARTICULATION_MS;
if (gap_ms < ARTICULATION_MS) {
gap_ms = ARTICULATION_MS;
}
return gap_ms;
}
STATIC mp_obj_t microbit_music_reset(void) {
music_data->bpm = DEFAULT_BPM;
music_data->ticks = DEFAULT_TICKS;
music_data->last_octave = DEFAULT_OCTAVE;
music_data->last_duration = DEFAULT_DURATION;
return mp_const_none;
}
MP_DEFINE_CONST_FUN_OBJ_0(microbit_music_reset_obj, microbit_music_reset);
STATIC mp_obj_t microbit_music_get_tempo(void) {
mp_obj_t tempo_tuple[2];
tempo_tuple[0] = mp_obj_new_int(music_data->bpm);
tempo_tuple[1] = mp_obj_new_int(music_data->ticks);
return mp_obj_new_tuple(2, tempo_tuple);
}
MP_DEFINE_CONST_FUN_OBJ_0(microbit_music_get_tempo_obj, microbit_music_get_tempo);
STATIC mp_obj_t microbit_music_stop(mp_uint_t n_args, const mp_obj_t *args) {
const pin_obj_t *pin;
if (n_args == 0) {
#ifdef MICROPY_HW_MUSIC_PIN
pin = &MICROPY_HW_MUSIC_PIN;
#else
mp_raise_ValueError("pin parameter not given");
#endif
} else {
pin = (pin_obj_t *)args[0];
}
(void)pin;
// Raise exception if the pin we are trying to stop is not in a compatible mode.
// TODO: microbit_obj_pin_acquire(pin, microbit_pin_mode_music);
pwm_set_duty_cycle(pin->pin, 0); // TODO: remove pin setting.
// TODO: microbit_obj_pin_free(pin);
music_data->async_pin = NULL;
music_data->async_state = ASYNC_MUSIC_STATE_IDLE;
return mp_const_none;
}
MP_DEFINE_CONST_FUN_OBJ_VAR_BETWEEN(microbit_music_stop_obj, 0, 1, microbit_music_stop);
STATIC mp_obj_t microbit_music_play(mp_uint_t n_args, const mp_obj_t *pos_args, mp_map_t *kw_args) {
static const mp_arg_t allowed_args[] = {
{ MP_QSTR_music, MP_ARG_REQUIRED | MP_ARG_OBJ, {.u_obj = MP_OBJ_NULL} },
{ MP_QSTR_pin, MP_ARG_OBJ, {.u_obj = MP_OBJ_NULL} },
{ MP_QSTR_wait, MP_ARG_BOOL, {.u_bool = true} },
{ MP_QSTR_loop, MP_ARG_BOOL, {.u_bool = false} },
};
// parse args
mp_arg_val_t args[MP_ARRAY_SIZE(allowed_args)];
mp_arg_parse_all(n_args, pos_args, kw_args, MP_ARRAY_SIZE(allowed_args), allowed_args, args);
// reset octave and duration so tunes always play the same
music_data->last_octave = DEFAULT_OCTAVE;
music_data->last_duration = DEFAULT_DURATION;
// get either a single note or a list of notes
mp_uint_t len;
mp_obj_t *items;
if (MP_OBJ_IS_STR_OR_BYTES(args[0].u_obj)) {
len = 1;
items = &args[0].u_obj;
} else {
mp_obj_get_array(args[0].u_obj, &len, &items);
}
// Release the previous pin
// TODO: microbit_obj_pin_free(music_data->async_pin);
music_data->async_pin = NULL;
// get the pin to play on
const pin_obj_t *pin;
if (args[1].u_obj == MP_OBJ_NULL) {
#ifdef MICROPY_HW_MUSIC_PIN
pin = &MICROPY_HW_MUSIC_PIN;
#else
mp_raise_ValueError("pin parameter not given");
#endif
} else {
pin = (pin_obj_t *)args[1].u_obj;
}
// TODO: microbit_obj_pin_acquire(pin, microbit_pin_mode_music);
// start the tune running in the background
music_data->async_state = ASYNC_MUSIC_STATE_IDLE;
music_data->async_wait_ticks = ticks;
music_data->async_loop = args[3].u_bool;
music_data->async_notes_len = len;
music_data->async_notes_index = 0;
if (len == 1) {
// If a string was passed as a single note then we can't store a pointer
// to args[0].u_obj, so instead store the single string directly (also
// works if a tuple/list of one element was passed).
music_data->async_note = items[0];
} else {
music_data->async_note = items;
}
music_data->async_pin = pin;
music_data->async_state = ASYNC_MUSIC_STATE_NEXT_NOTE;
if (args[2].u_bool) {
// wait for tune to finish
wait_async_music_idle();
}
return mp_const_none;
}
MP_DEFINE_CONST_FUN_OBJ_KW(microbit_music_play_obj, 0, microbit_music_play);
STATIC mp_obj_t microbit_music_pitch(mp_uint_t n_args, const mp_obj_t *pos_args, mp_map_t *kw_args) {
static const mp_arg_t allowed_args[] = {
{ MP_QSTR_frequency, MP_ARG_REQUIRED | MP_ARG_INT, {.u_int = 0} },
{ MP_QSTR_duration, MP_ARG_INT, {.u_int = -1} },
{ MP_QSTR_pin, MP_ARG_OBJ, {.u_obj = MP_OBJ_NULL} },
{ MP_QSTR_wait, MP_ARG_BOOL, {.u_bool = true} },
};
// parse args
mp_arg_val_t args[MP_ARRAY_SIZE(allowed_args)];
mp_arg_parse_all(n_args, pos_args, kw_args, MP_ARRAY_SIZE(allowed_args), allowed_args, args);
// get the parameters
mp_uint_t frequency = args[0].u_int;
mp_int_t duration = args[1].u_int;
// get the pin to play on
const pin_obj_t *pin;
if (args[2].u_obj == MP_OBJ_NULL) {
#ifdef MICROPY_HW_MUSIC_PIN
pin = &MICROPY_HW_MUSIC_PIN;
#else
mp_raise_ValueError("pin parameter not given");
#endif
} else {
pin = (pin_obj_t *)args[2].u_obj;
}
// Update pin modes
//TODO: microbit_obj_pin_free(music_data->async_pin);
music_data->async_pin = NULL;
//TODO: microbit_obj_pin_acquire(pin, microbit_pin_mode_music);
bool wait = args[3].u_bool;
pwm_set_duty_cycle(pin->pin, 128); // TODO: remove pin setting.
if (frequency == 0) {
//TODO: pwm_release(pin->name);
} else if (pwm_set_period_us(1000000/frequency)) {
pwm_release(pin->pin); // TODO: remove pin setting.
mp_raise_ValueError("invalid pitch");
}
if (duration >= 0) {
// use async machinery to stop the pitch after the duration
music_data->async_state = ASYNC_MUSIC_STATE_IDLE;
music_data->async_wait_ticks = ticks + duration;
music_data->async_loop = false;
music_data->async_notes_len = 0;
music_data->async_notes_index = 0;
music_data->async_note = NULL;
music_data->async_pin = pin;
music_data->async_state = ASYNC_MUSIC_STATE_ARTICULATE;
if (wait) {
// wait for the pitch to finish
wait_async_music_idle();
}
} else {
// don't block here, since there's no reason to leave a pitch forever in a blocking C function
}
return mp_const_none;
}
MP_DEFINE_CONST_FUN_OBJ_KW(microbit_music_pitch_obj, 0, microbit_music_pitch);
STATIC mp_obj_t microbit_music_set_tempo(mp_uint_t n_args, const mp_obj_t *pos_args, mp_map_t *kw_args) {
static const mp_arg_t allowed_args[] = {
{ MP_QSTR_ticks, MP_ARG_KW_ONLY | MP_ARG_INT, {.u_int = 0} },
{ MP_QSTR_bpm, MP_ARG_KW_ONLY | MP_ARG_INT, {.u_int = 0} },
};
mp_arg_val_t args[MP_ARRAY_SIZE(allowed_args)];
mp_arg_parse_all(n_args, pos_args, kw_args, MP_ARRAY_SIZE(allowed_args), allowed_args, args);
if (args[0].u_int != 0) {
// set ticks
music_data->ticks = args[0].u_int;
}
if (args[1].u_int != 0) {
music_data->bpm = args[1].u_int;
}
return mp_const_none;
}
MP_DEFINE_CONST_FUN_OBJ_KW(microbit_music_set_tempo_obj, 0, microbit_music_set_tempo);
static mp_obj_t music_init(void) {
microbit_music_init0();
music_data = m_new_obj(music_data_t);
music_data->bpm = DEFAULT_BPM;
music_data->ticks = DEFAULT_TICKS;
music_data->last_octave = DEFAULT_OCTAVE;
music_data->last_duration = DEFAULT_DURATION;
music_data->async_state = ASYNC_MUSIC_STATE_IDLE;
music_data->async_pin = NULL;
music_data->async_note = NULL;
return mp_const_none;
}
MP_DEFINE_CONST_FUN_OBJ_0(music___init___obj, music_init);
STATIC const mp_rom_map_elem_t microbit_music_locals_dict_table[] = {
{ MP_ROM_QSTR(MP_QSTR___init__), MP_ROM_PTR(&music___init___obj) },
{ MP_ROM_QSTR(MP_QSTR_reset), MP_ROM_PTR(&microbit_music_reset_obj) },
{ MP_ROM_QSTR(MP_QSTR_set_tempo), MP_ROM_PTR(&microbit_music_set_tempo_obj) },
{ MP_ROM_QSTR(MP_QSTR_get_tempo), MP_ROM_PTR(&microbit_music_get_tempo_obj) },
{ MP_ROM_QSTR(MP_QSTR_play), MP_ROM_PTR(&microbit_music_play_obj) },
{ MP_ROM_QSTR(MP_QSTR_pitch), MP_ROM_PTR(&microbit_music_pitch_obj) },
{ MP_ROM_QSTR(MP_QSTR_stop), MP_ROM_PTR(&microbit_music_stop_obj) },
{ MP_ROM_QSTR(MP_QSTR_DADADADUM), MP_ROM_PTR(&microbit_music_tune_dadadadum_obj) },
{ MP_ROM_QSTR(MP_QSTR_ENTERTAINER), MP_ROM_PTR(&microbit_music_tune_entertainer_obj) },
{ MP_ROM_QSTR(MP_QSTR_PRELUDE), MP_ROM_PTR(&microbit_music_tune_prelude_obj) },
{ MP_ROM_QSTR(MP_QSTR_ODE), MP_ROM_PTR(&microbit_music_tune_ode_obj) },
{ MP_ROM_QSTR(MP_QSTR_NYAN), MP_ROM_PTR(&microbit_music_tune_nyan_obj) },
{ MP_ROM_QSTR(MP_QSTR_RINGTONE), MP_ROM_PTR(&microbit_music_tune_ringtone_obj) },
{ MP_ROM_QSTR(MP_QSTR_FUNK), MP_ROM_PTR(&microbit_music_tune_funk_obj) },
{ MP_ROM_QSTR(MP_QSTR_BLUES), MP_ROM_PTR(&microbit_music_tune_blues_obj) },
{ MP_ROM_QSTR(MP_QSTR_BIRTHDAY), MP_ROM_PTR(&microbit_music_tune_birthday_obj) },
{ MP_ROM_QSTR(MP_QSTR_WEDDING), MP_ROM_PTR(&microbit_music_tune_wedding_obj) },
{ MP_ROM_QSTR(MP_QSTR_FUNERAL), MP_ROM_PTR(&microbit_music_tune_funeral_obj) },
{ MP_ROM_QSTR(MP_QSTR_PUNCHLINE), MP_ROM_PTR(&microbit_music_tune_punchline_obj) },
{ MP_ROM_QSTR(MP_QSTR_PYTHON), MP_ROM_PTR(&microbit_music_tune_python_obj) },
{ MP_ROM_QSTR(MP_QSTR_BADDY), MP_ROM_PTR(&microbit_music_tune_baddy_obj) },
{ MP_ROM_QSTR(MP_QSTR_CHASE), MP_ROM_PTR(&microbit_music_tune_chase_obj) },
{ MP_ROM_QSTR(MP_QSTR_BA_DING), MP_ROM_PTR(&microbit_music_tune_ba_ding_obj) },
{ MP_ROM_QSTR(MP_QSTR_WAWAWAWAA), MP_ROM_PTR(&microbit_music_tune_wawawawaa_obj) },
{ MP_ROM_QSTR(MP_QSTR_JUMP_UP), MP_ROM_PTR(&microbit_music_tune_jump_up_obj) },
{ MP_ROM_QSTR(MP_QSTR_JUMP_DOWN), MP_ROM_PTR(&microbit_music_tune_jump_down_obj) },
{ MP_ROM_QSTR(MP_QSTR_POWER_UP), MP_ROM_PTR(&microbit_music_tune_power_up_obj) },
{ MP_ROM_QSTR(MP_QSTR_POWER_DOWN), MP_ROM_PTR(&microbit_music_tune_power_down_obj) },
};
STATIC MP_DEFINE_CONST_DICT(microbit_music_locals_dict, microbit_music_locals_dict_table);
const mp_obj_module_t music_module = {
.base = { &mp_type_module },
.globals = (mp_obj_dict_t*)&microbit_music_locals_dict,
};
#endif // MICROPY_PY_MUSIC

View File

@ -1,7 +0,0 @@
#ifndef __MICROPY_INCLUDED_MICROBIT_MUSIC_H__
#define __MICROPY_INCLUDED_MICROBIT_MUSIC_H__
void microbit_music_init0(void);
void microbit_music_tick(void);
#endif // __MICROPY_INCLUDED_MICROBIT_MUSIC_H__

View File

@ -1,164 +0,0 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The music encoded herein is either in the public domain, composed by
* Nicholas H.Tollervey or the composer is untraceable and covered by fair
* (educational) use.
*
* The MIT License (MIT)
*
* Copyright (c) 2015 Damien P. George
* Copyright (c) 2015 Nicholas H. Tollervey
*
* 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 "py/objtuple.h"
#if MICROPY_PY_MUSIC
#define N(q) MP_ROM_QSTR(MP_QSTR_ ## q)
#define T(name, ...) const mp_obj_tuple_t microbit_music_tune_ ## name ## _obj = {{&mp_type_tuple}, .len = (sizeof((mp_obj_t[]){__VA_ARGS__})/sizeof(mp_obj_t)), .items = {__VA_ARGS__}};
T(dadadadum,
N(r4_colon_2), N(g), N(g), N(g), N(eb_colon_8), N(r_colon_2), N(f), N(f),
N(f), N(d_colon_8));
T(entertainer,
N(d4_colon_1), N(d_hash_), N(e), N(c5_colon_2), N(e4_colon_1),
N(c5_colon_2), N(e4_colon_1), N(c5_colon_3), N(c_colon_1), N(d),
N(d_hash_), N(e), N(c), N(d), N(e_colon_2), N(b4_colon_1), N(d5_colon_2),
N(c_colon_4));
T(prelude,
N(c4_colon_1), N(e), N(g), N(c5), N(e), N(g4), N(c5), N(e), N(c4), N(e),
N(g), N(c5), N(e), N(g4), N(c5), N(e), N(c4), N(d), N(g), N(d5), N(f),
N(g4), N(d5), N(f), N(c4), N(d), N(g), N(d5), N(f), N(g4), N(d5), N(f),
N(b3), N(d4), N(g), N(d5), N(f), N(g4), N(d5), N(f), N(b3), N(d4), N(g),
N(d5), N(f), N(g4), N(d5), N(f), N(c4), N(e), N(g), N(c5), N(e), N(g4),
N(c5), N(e), N(c4), N(e), N(g), N(c5), N(e), N(g4), N(c5), N(e));
T(ode,
N(e4), N(e), N(f), N(g), N(g), N(f), N(e), N(d), N(c), N(c), N(d), N(e),
N(e_colon_6), N(d_colon_2), N(d_colon_8), N(e_colon_4), N(e), N(f), N(g),
N(g), N(f), N(e), N(d), N(c), N(c), N(d), N(e), N(d_colon_6),
N(c_colon_2), N(c_colon_8));
T(nyan,
N(f_hash_5_colon_2), N(g_hash_), N(c_hash__colon_1), N(d_hash__colon_2),
N(b4_colon_1), N(d5_colon_1), N(c_hash_), N(b4_colon_2), N(b),
N(c_hash_5), N(d), N(d_colon_1), N(c_hash_), N(b4_colon_1),
N(c_hash_5_colon_1), N(d_hash_), N(f_hash_), N(g_hash_), N(d_hash_),
N(f_hash_), N(c_hash_), N(d), N(b4), N(c_hash_5), N(b4),
N(d_hash_5_colon_2), N(f_hash_), N(g_hash__colon_1), N(d_hash_),
N(f_hash_), N(c_hash_), N(d_hash_), N(b4), N(d5), N(d_hash_), N(d),
N(c_hash_), N(b4), N(c_hash_5), N(d_colon_2), N(b4_colon_1), N(c_hash_5),
N(d_hash_), N(f_hash_), N(c_hash_), N(d), N(c_hash_), N(b4),
N(c_hash_5_colon_2), N(b4), N(c_hash_5), N(b4), N(f_hash__colon_1),
N(g_hash_), N(b_colon_2), N(f_hash__colon_1), N(g_hash_), N(b),
N(c_hash_5), N(d_hash_), N(b4), N(e5), N(d_hash_), N(e), N(f_hash_),
N(b4_colon_2), N(b), N(f_hash__colon_1), N(g_hash_), N(b), N(f_hash_),
N(e5), N(d_hash_), N(c_hash_), N(b4), N(f_hash_), N(d_hash_), N(e),
N(f_hash_), N(b_colon_2), N(f_hash__colon_1), N(g_hash_), N(b_colon_2),
N(f_hash__colon_1), N(g_hash_), N(b), N(b), N(c_hash_5), N(d_hash_),
N(b4), N(f_hash_), N(g_hash_), N(f_hash_), N(b_colon_2), N(b_colon_1),
N(a_hash_), N(b), N(f_hash_), N(g_hash_), N(b), N(e5), N(d_hash_), N(e),
N(f_hash_), N(b4_colon_2), N(c_hash_5));
T(ringtone,
N(c4_colon_1), N(d), N(e_colon_2), N(g), N(d_colon_1), N(e), N(f_colon_2),
N(a), N(e_colon_1), N(f), N(g_colon_2), N(b), N(c5_colon_4));
T(funk,
N(c2_colon_2), N(c), N(d_hash_), N(c_colon_1), N(f_colon_2), N(c_colon_1),
N(f_colon_2), N(f_hash_), N(g), N(c), N(c), N(g), N(c_colon_1),
N(f_hash__colon_2), N(c_colon_1), N(f_hash__colon_2), N(f), N(d_hash_));
T(blues,
N(c2_colon_2), N(e), N(g), N(a), N(a_hash_), N(a), N(g), N(e),
N(c2_colon_2), N(e), N(g), N(a), N(a_hash_), N(a), N(g), N(e), N(f), N(a),
N(c3), N(d), N(d_hash_), N(d), N(c), N(a2), N(c2_colon_2), N(e), N(g),
N(a), N(a_hash_), N(a), N(g), N(e), N(g), N(b), N(d3), N(f), N(f2), N(a),
N(c3), N(d_hash_), N(c2_colon_2), N(e), N(g), N(e), N(g), N(f), N(e),
N(d));
T(birthday,
N(c4_colon_3), N(c_colon_1), N(d_colon_4), N(c_colon_4), N(f),
N(e_colon_8), N(c_colon_3), N(c_colon_1), N(d_colon_4), N(c_colon_4),
N(g), N(f_colon_8), N(c_colon_3), N(c_colon_1), N(c5_colon_4), N(a4),
N(f), N(e), N(d), N(a_hash__colon_3), N(a_hash__colon_1), N(a_colon_4),
N(f), N(g), N(f_colon_8));
T(wedding,
N(c4_colon_4), N(f_colon_3), N(f_colon_1), N(f_colon_8), N(c_colon_4),
N(g_colon_3), N(e_colon_1), N(f_colon_8), N(c_colon_4), N(f_colon_3),
N(a_colon_1), N(c5_colon_4), N(a4_colon_3), N(f_colon_1), N(f_colon_4),
N(e_colon_3), N(f_colon_1), N(g_colon_8));
T(funeral,
N(c3_colon_4), N(c_colon_3), N(c_colon_1), N(c_colon_4),
N(d_hash__colon_3), N(d_colon_1), N(d_colon_3), N(c_colon_1),
N(c_colon_3), N(b2_colon_1), N(c3_colon_4));
T(punchline,
N(c4_colon_3), N(g3_colon_1), N(f_hash_), N(g), N(g_hash__colon_3), N(g),
N(r), N(b), N(c4));
T(python,
N(d5_colon_1), N(b4), N(r), N(b), N(b), N(a_hash_), N(b), N(g5), N(r),
N(d), N(d), N(r), N(b4), N(c5), N(r), N(c), N(c), N(r), N(d),
N(e_colon_5), N(c_colon_1), N(a4), N(r), N(a), N(a), N(g_hash_), N(a),
N(f_hash_5), N(r), N(e), N(e), N(r), N(c), N(b4), N(r), N(b), N(b), N(r),
N(c5), N(d_colon_5), N(d_colon_1), N(b4), N(r), N(b), N(b), N(a_hash_),
N(b), N(b5), N(r), N(g), N(g), N(r), N(d), N(c_hash_), N(r), N(a), N(a),
N(r), N(a), N(a_colon_5), N(g_colon_1), N(f_hash__colon_2), N(a_colon_1),
N(a), N(g_hash_), N(a), N(e_colon_2), N(a_colon_1), N(a), N(g_hash_),
N(a), N(d), N(r), N(c_hash_), N(d), N(r), N(c_hash_), N(d_colon_2),
N(r_colon_3));
T(baddy,
N(c3_colon_3), N(r), N(d_colon_2), N(d_hash_), N(r), N(c), N(r), N(f_hash__colon_8), );
T(chase,
N(a4_colon_1), N(b), N(c5), N(b4), N(a_colon_2), N(r), N(a_colon_1), N(b), N(c5), N(b4), N(a_colon_2), N(r), N(a_colon_2), N(e5), N(d_hash_), N(e), N(f), N(e), N(d_hash_), N(e), N(b4_colon_1), N(c5), N(d), N(c), N(b4_colon_2), N(r), N(b_colon_1), N(c5), N(d), N(c), N(b4_colon_2), N(r), N(b_colon_2), N(e5), N(d_hash_), N(e), N(f), N(e), N(d_hash_), N(e), );
T(ba_ding,
N(b5_colon_1), N(e6_colon_3), );
T(wawawawaa,
N(e3_colon_3), N(r_colon_1), N(d_hash__colon_3), N(r_colon_1), N(d_colon_4), N(r_colon_1), N(c_hash__colon_8), );
T(jump_up,
N(c5_colon_1), N(d), N(e), N(f), N(g), );
T(jump_down,
N(g5_colon_1), N(f), N(e), N(d), N(c), );
T(power_up,
N(g4_colon_1), N(c5), N(e), N(g_colon_2), N(e_colon_1), N(g_colon_3), );
T(power_down,
N(g5_colon_1), N(d_hash_), N(c), N(g4_colon_2), N(b_colon_1), N(c5_colon_3), );
#undef N
#undef T
#endif // MICROPY_PY_MUSIC

View File

@ -1,52 +0,0 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2017 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.
*/
#ifndef MUSIC_TUNES_H__
#define MUSIC_TUNES_H__
extern const struct _mp_obj_tuple_t microbit_music_tune_dadadadum_obj;
extern const struct _mp_obj_tuple_t microbit_music_tune_entertainer_obj;
extern const struct _mp_obj_tuple_t microbit_music_tune_prelude_obj;
extern const struct _mp_obj_tuple_t microbit_music_tune_ode_obj;
extern const struct _mp_obj_tuple_t microbit_music_tune_nyan_obj;
extern const struct _mp_obj_tuple_t microbit_music_tune_ringtone_obj;
extern const struct _mp_obj_tuple_t microbit_music_tune_funk_obj;
extern const struct _mp_obj_tuple_t microbit_music_tune_blues_obj;
extern const struct _mp_obj_tuple_t microbit_music_tune_birthday_obj;
extern const struct _mp_obj_tuple_t microbit_music_tune_wedding_obj;
extern const struct _mp_obj_tuple_t microbit_music_tune_funeral_obj;
extern const struct _mp_obj_tuple_t microbit_music_tune_punchline_obj;
extern const struct _mp_obj_tuple_t microbit_music_tune_python_obj;
extern const struct _mp_obj_tuple_t microbit_music_tune_baddy_obj;
extern const struct _mp_obj_tuple_t microbit_music_tune_chase_obj;
extern const struct _mp_obj_tuple_t microbit_music_tune_ba_ding_obj;
extern const struct _mp_obj_tuple_t microbit_music_tune_wawawawaa_obj;
extern const struct _mp_obj_tuple_t microbit_music_tune_jump_up_obj;
extern const struct _mp_obj_tuple_t microbit_music_tune_jump_down_obj;
extern const struct _mp_obj_tuple_t microbit_music_tune_power_up_obj;
extern const struct _mp_obj_tuple_t microbit_music_tune_power_down_obj;
#endif // MUSIC_TUNES_H__

View File

@ -1,55 +0,0 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* 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 "py/builtin.h"
#include "lib/utils/pyexec.h"
#include "py/runtime.h"
#include "py/obj.h"
#include "led.h"
#include "nrf.h" // TODO: figure out where to put this import
#include "pin.h"
#if MICROPY_HW_HAS_LED
#define PYB_LED_MODULE { MP_ROM_QSTR(MP_QSTR_LED), MP_ROM_PTR(&pyb_led_type) },
#else
#define PYB_LED_MODULE
#endif
STATIC const mp_rom_map_elem_t pyb_module_globals_table[] = {
{ MP_ROM_QSTR(MP_QSTR___name__), MP_ROM_QSTR(MP_QSTR_pyb) },
{ MP_ROM_QSTR(MP_QSTR_repl_info), MP_ROM_PTR(&pyb_set_repl_info_obj) },
{ MP_ROM_QSTR(MP_QSTR_Pin), MP_ROM_PTR(&pin_type) },
PYB_LED_MODULE
/* { MP_ROM_QSTR(MP_QSTR_main), MP_ROM_PTR(&pyb_main_obj) }*/
};
STATIC MP_DEFINE_CONST_DICT(pyb_module_globals, pyb_module_globals_table);
const mp_obj_module_t pyb_module = {
.base = { &mp_type_module },
.globals = (mp_obj_dict_t*)&pyb_module_globals,
};

View File

@ -1,53 +0,0 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2016 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 <stdio.h>
#include <string.h>
#include NRF5_HAL_H
#include "py/nlr.h"
#include "py/smallint.h"
#include "py/obj.h"
#include "extmod/utime_mphal.h"
/// \module time - time related functions
///
/// The `time` module provides functions for getting the current time and date,
/// and for sleeping.
STATIC const mp_rom_map_elem_t time_module_globals_table[] = {
{ MP_ROM_QSTR(MP_QSTR___name__), MP_ROM_QSTR(MP_QSTR_utime) },
{ MP_ROM_QSTR(MP_QSTR_sleep_ms), MP_ROM_PTR(&mp_utime_sleep_ms_obj) },
{ MP_ROM_QSTR(MP_QSTR_sleep_us), MP_ROM_PTR(&mp_utime_sleep_us_obj) },
};
STATIC MP_DEFINE_CONST_DICT(time_module_globals, time_module_globals_table);
const mp_obj_module_t mp_module_utime = {
.base = { &mp_type_module },
.globals = (mp_obj_dict_t*)&time_module_globals,
};

View File

@ -121,12 +121,7 @@
#define MICROPY_PY_URE (0)
#define MICROPY_PY_UHEAPQ (0)
#define MICROPY_PY_UHASHLIB (1)
#define MICROPY_PY_UTIME_MP_HAL (1)
#define MICROPY_PY_STRUCT (0)
#define MICROPY_PY_MACHINE (1)
#define MICROPY_PY_MACHINE_PULSE (0)
#define MICROPY_PY_MACHINE_I2C_MAKE_NEW machine_hard_i2c_make_new
#define MICROPY_PY_MACHINE_SPI (0)
#define MICROPY_PY_FRAMEBUF (1)
#define MICROPY_KBD_EXCEPTION (1)
@ -139,43 +134,10 @@
#define MICROPY_HW_LED_PULLUP (0)
#endif
#ifndef MICROPY_PY_MUSIC
#define MICROPY_PY_MUSIC (0)
#endif
#ifndef MICROPY_PY_MACHINE_ADC
#define MICROPY_PY_MACHINE_ADC (0)
#endif
#ifndef MICROPY_PY_MACHINE_I2C
#define MICROPY_PY_MACHINE_I2C (0)
#endif
#ifndef MICROPY_PY_MACHINE_HW_SPI
#define MICROPY_PY_MACHINE_HW_SPI (1)
#endif
#ifndef MICROPY_PY_MACHINE_HW_PWM
#define MICROPY_PY_MACHINE_HW_PWM (0)
#endif
#ifndef MICROPY_PY_MACHINE_SOFT_PWM
#define MICROPY_PY_MACHINE_SOFT_PWM (0)
#endif
#ifndef MICROPY_PY_MACHINE_TIMER
#define MICROPY_PY_MACHINE_TIMER (0)
#endif
#ifndef MICROPY_PY_MACHINE_RTC
#define MICROPY_PY_MACHINE_RTC (0)
#endif
#ifndef MICROPY_PY_HW_RNG
#define MICROPY_PY_HW_RNG (1)
#endif
#define MICROPY_ENABLE_EMERGENCY_EXCEPTION_BUF (1)
#define MICROPY_EMERGENCY_EXCEPTION_BUF_SIZE (0)
@ -228,21 +190,11 @@ extern const struct _mp_obj_module_t time_module;
extern const struct _mp_obj_module_t supervisor_module;
extern const struct _mp_obj_module_t gamepad_module;
extern const struct _mp_obj_module_t pyb_module;
extern const struct _mp_obj_module_t machine_module;
extern const struct _mp_obj_module_t mp_module_utime;
extern const struct _mp_obj_module_t mp_module_ubluepy;
extern const struct _mp_obj_module_t music_module;
extern const struct _mp_obj_module_t random_module;
extern const struct _mp_obj_module_t ble_module;
#if MICROPY_PY_MUSIC
#define MUSIC_MODULE { MP_ROM_QSTR(MP_QSTR_music), MP_ROM_PTR(&music_module) },
#else
#define MUSIC_MODULE
#endif
#if MICROPY_PY_HW_RNG
#define RANDOM_MODULE { MP_ROM_QSTR(MP_QSTR_random), MP_ROM_PTR(&random_module) },
#else
@ -277,17 +229,10 @@ extern const struct _mp_obj_module_t ble_module;
{ MP_OBJ_NEW_QSTR (MP_QSTR_supervisor ), (mp_obj_t)&supervisor_module }, \
{ MP_OBJ_NEW_QSTR (MP_QSTR_gamepad ), (mp_obj_t)&gamepad_module }, \
{ MP_OBJ_NEW_QSTR (MP_QSTR_time ), (mp_obj_t)&time_module }, \
{ MP_ROM_QSTR (MP_QSTR_pyb ), MP_ROM_PTR(&pyb_module) }, \
{ MP_ROM_QSTR (MP_QSTR_utime ), MP_ROM_PTR(&mp_module_utime) }, \
MUSIC_MODULE \
RANDOM_MODULE \
BLE_MODULE \
UBLUEPY_MODULE \
#define MICROPY_PORT_BUILTIN_MODULE_WEAK_LINKS \
{ MP_ROM_QSTR (MP_QSTR_time ), MP_ROM_PTR(&mp_module_utime) }, \
// extra built in names to add to the global namespace
#define MICROPY_PORT_BUILTINS \
{ MP_ROM_QSTR (MP_QSTR_help), MP_ROM_PTR(&mp_builtin_help_obj) }, \
@ -296,33 +241,12 @@ extern const struct _mp_obj_module_t ble_module;
// extra constants
#define MICROPY_PORT_CONSTANTS \
{ MP_ROM_QSTR (MP_QSTR_pyb ), MP_ROM_PTR(&pyb_module) }, \
{ MP_ROM_QSTR (MP_QSTR_machine ), MP_ROM_PTR(&machine_module) }, \
BLE_MODULE \
#define MP_STATE_PORT MP_STATE_VM
#define MICROPY_PORT_ROOT_POINTERS \
const char *readline_hist[8]; \
mp_obj_t pyb_config_main; \
mp_obj_t pin_class_mapper; \
mp_obj_t pin_class_map_dict; \
/* Used to do callbacks to Python code on interrupt */ \
struct _pyb_timer_obj_t *pyb_timer_obj_all[14]; \
\
/* stdio is repeated on this UART object if it's not null */ \
struct _machine_hard_uart_obj_t *pyb_stdio_uart; \
\
/* pointers to all UART objects (if they have been created) */ \
struct _machine_hard_uart_obj_t *pyb_uart_obj_all[1]; \
\
/* list of registered NICs */ \
mp_obj_list_t mod_network_nic_list; \
\
/* microbit modules */ \
struct _music_data_t *music_data; \
const struct _pwm_events *pwm_active_events; \
const struct _pwm_events *pwm_pending_events; \
mp_obj_t gamepad_singleton; \
#define MP_PLAT_PRINT_STRN(str, len) mp_hal_stdout_tx_strn_cooked(str, len)
@ -330,7 +254,6 @@ extern const struct _mp_obj_module_t ble_module;
// We need to provide a declaration/definition of alloca()
#include <alloca.h>
#define MICROPY_PIN_DEFS_PORT_H "pin_defs_nrf5.h"
#define CIRCUITPY_BOOT_OUTPUT_FILE "/boot_out.txt"
//#define CIRCUITPY_BOOT_OUTPUT_FILE "/boot_out.txt"
#endif

View File

@ -1,48 +1,48 @@
P0_00,P0_00
P0_01,P0_01
P0_02,P0_02
P0_03,P0_03
P0_04,P0_04
P0_05,P0_05
P0_06,P0_06
P0_07,P0_07
P0_08,P0_08
P0_09,P0_09
P0_10,P0_10
P0_11,P0_11
P0_12,P0_12
P0_13,P0_13
P0_14,P0_14
P0_15,P0_15
P0_16,P0_16
P0_17,P0_17
P0_18,P0_18
P0_19,P0_19
P0_20,P0_20
P0_21,P0_21
P0_22,P0_22
P0_23,P0_23
P0_24,P0_24
P0_25,P0_25
P0_26,P0_26
P0_27,P0_27
P0_28,P0_28
P0_29,P0_29
P0_30,P0_30
P0_31,P0_31
P1_00,P1_00
P1_01,P1_01
P1_02,P1_02
P1_03,P1_03
P1_04,P1_04
P1_05,P1_05
P1_06,P1_06
P1_07,P1_07
P1_08,P1_08
P1_09,P1_09
P1_10,P1_10
P1_11,P1_11
P1_12,P1_12
P1_13,P1_13
P1_14,P1_14
P1_15,P1_15
P0_00
P0_01
P0_02,AIN0
P0_03,AIN1
P0_04,AIN2
P0_05,AIN3
P0_06
P0_07
P0_08
P0_09
P0_10
P0_11
P0_12
P0_13
P0_14
P0_15
P0_16
P0_17
P0_18
P0_19
P0_20
P0_21
P0_22
P0_23
P0_24
P0_25
P0_26
P0_27
P0_28,AIN4
P0_29,AIN5
P0_30,AIN6
P0_31,AIN7
P1_00
P1_01
P1_02
P1_03
P1_04
P1_05
P1_06
P1_07
P1_08
P1_09
P1_10
P1_11
P1_12
P1_13
P1_14
P1_15

1 P0_00 P0_00
2 P0_01 P0_01
3 P0_02 P0_02,AIN0 P0_02
4 P0_03 P0_03,AIN1 P0_03
5 P0_04 P0_04,AIN2 P0_04
6 P0_05 P0_05,AIN3 P0_05
7 P0_06 P0_06
8 P0_07 P0_07
9 P0_08 P0_08
10 P0_09 P0_09
11 P0_10 P0_10
12 P0_11 P0_11
13 P0_12 P0_12
14 P0_13 P0_13
15 P0_14 P0_14
16 P0_15 P0_15
17 P0_16 P0_16
18 P0_17 P0_17
19 P0_18 P0_18
20 P0_19 P0_19
21 P0_20 P0_20
22 P0_21 P0_21
23 P0_22 P0_22
24 P0_23 P0_23
25 P0_24 P0_24
26 P0_25 P0_25
27 P0_26 P0_26
28 P0_27 P0_27
29 P0_28 P0_28,AIN4 P0_28
30 P0_29 P0_29,AIN5 P0_29
31 P0_30 P0_30,AIN6 P0_30
32 P0_31 P0_31,AIN7 P0_31
33 P1_00 P1_00
34 P1_01 P1_01
35 P1_02 P1_02
36 P1_03 P1_03
37 P1_04 P1_04
38 P1_05 P1_05
39 P1_06 P1_06
40 P1_07 P1_07
41 P1_08 P1_08
42 P1_09 P1_09
43 P1_10 P1_10
44 P1_11 P1_11
45 P1_12 P1_12
46 P1_13 P1_13
47 P1_14 P1_14
48 P1_15 P1_15

1
ports/nrf/nrfx Submodule

@ -0,0 +1 @@
Subproject commit 293f553ed9551c1fdfd05eac48e75bbdeb4e7290

View File

@ -4,7 +4,6 @@
* The MIT License (MIT)
*
* Copyright (c) 2013, 2014 Damien P. George
* Copyright (c) 2016 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
@ -24,15 +23,21 @@
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#ifndef __MICROPY_INCLUDED_NRF5_PIN_H__
#define __MICROPY_INCLUDED_NRF5_PIN_H__
#include "py/obj.h"
#include "hal_spi.h"
typedef struct _machine_hard_spi_obj_t {
typedef struct {
mp_obj_base_t base;
SPI_HandleTypeDef *spi;
} machine_hard_spi_obj_t;
qstr name;
extern const mp_obj_type_t machine_hard_spi_type;
uint32_t port : 1;
uint32_t pin : 5; // Some ARM processors use 32 bits/PORT
uint32_t adc_channel : 4; // 0 is no ADC, ADC channel from 1 to 8
} pin_obj_t;
void spi_init0(void);
extern const mp_obj_type_t mcu_pin_type;
#endif // __MICROPY_INCLUDED_NRF5_PIN_H__

View File

@ -1,36 +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) 2016 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.
*/
// This file contains pin definitions that are specific to the nrf port.
// This file should only ever be #included by pin.h and not directly.
enum {
PORT_0,
PORT_1,
};
typedef NRF_GPIO_Type pin_gpio_t;

View File

@ -1,92 +0,0 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2013, 2014 Damien P. George
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#include <stdio.h>
#include <string.h>
#include "py/runtime.h"
#include "py/mphal.h"
#include "pin.h"
STATIC void pin_named_pins_obj_print(const mp_print_t *print, mp_obj_t self_in, mp_print_kind_t kind) {
pin_named_pins_obj_t *self = self_in;
mp_printf(print, "<Pin.%q>", self->name);
}
const mp_obj_type_t pin_cpu_pins_obj_type = {
{ &mp_type_type },
.name = MP_QSTR_cpu,
.print = pin_named_pins_obj_print,
.locals_dict = (mp_obj_t)&pin_cpu_pins_locals_dict,
};
const mp_obj_type_t pin_board_pins_obj_type = {
{ &mp_type_type },
.name = MP_QSTR_board,
.print = pin_named_pins_obj_print,
.locals_dict = (mp_obj_t)&pin_board_pins_locals_dict,
};
const pin_obj_t *pin_find_named_pin(const mp_obj_dict_t *named_pins, mp_obj_t name) {
mp_map_t *named_map = mp_obj_dict_get_map((mp_obj_t)named_pins);
mp_map_elem_t *named_elem = mp_map_lookup(named_map, name, MP_MAP_LOOKUP);
if (named_elem != NULL && named_elem->value != NULL) {
return named_elem->value;
}
return NULL;
}
const pin_af_obj_t *pin_find_af(const pin_obj_t *pin, uint8_t fn, uint8_t unit) {
const pin_af_obj_t *af = pin->af;
for (mp_uint_t i = 0; i < pin->num_af; i++, af++) {
if (af->fn == fn && af->unit == unit) {
return af;
}
}
return NULL;
}
const pin_af_obj_t *pin_find_af_by_index(const pin_obj_t *pin, mp_uint_t af_idx) {
const pin_af_obj_t *af = pin->af;
for (mp_uint_t i = 0; i < pin->num_af; i++, af++) {
if (af->idx == af_idx) {
return af;
}
}
return NULL;
}
/* unused
const pin_af_obj_t *pin_find_af_by_name(const pin_obj_t *pin, const char *name) {
const pin_af_obj_t *af = pin->af;
for (mp_uint_t i = 0; i < pin->num_af; i++, af++) {
if (strcmp(name, qstr_str(af->name)) == 0) {
return af;
}
}
return NULL;
}
*/

View File

@ -67,7 +67,6 @@ void reset_port(void) {
void HardFault_Handler(void)
{
#if NRF52
// static volatile uint32_t reg;
// static volatile uint32_t reg2;
// static volatile uint32_t bfar;
@ -80,6 +79,5 @@ void HardFault_Handler(void)
// (void)reg2;
// (void)bfar;
// }
#endif
}