From 5c31a6c0235b25dd2199825e378f4e18f8db1bc0 Mon Sep 17 00:00:00 2001 From: iabdalkader Date: Thu, 21 Apr 2022 11:49:12 +0200 Subject: [PATCH] nrf/boards/arduino_nano_33_ble: Add Arduino Nano 33 BLE sense board. --- .../boards/arduino_nano_33_ble_sense/board.c | 67 +++++++++++++++++ .../arduino_nano_33_ble_sense/board.json | 25 +++++++ .../arduino_nano_33_ble_sense/deploy.md | 23 ++++++ .../arduino_nano_33_ble_sense/manifest.py | 4 + .../arduino_nano_33_ble_sense/mpconfigboard.h | 75 +++++++++++++++++++ .../mpconfigboard.mk | 12 +++ .../nano_bootloader.ld | 1 + .../boards/arduino_nano_33_ble_sense/pins.csv | 50 +++++++++++++ 8 files changed, 257 insertions(+) create mode 100644 ports/nrf/boards/arduino_nano_33_ble_sense/board.c create mode 100644 ports/nrf/boards/arduino_nano_33_ble_sense/board.json create mode 100644 ports/nrf/boards/arduino_nano_33_ble_sense/deploy.md create mode 100644 ports/nrf/boards/arduino_nano_33_ble_sense/manifest.py create mode 100644 ports/nrf/boards/arduino_nano_33_ble_sense/mpconfigboard.h create mode 100644 ports/nrf/boards/arduino_nano_33_ble_sense/mpconfigboard.mk create mode 100644 ports/nrf/boards/arduino_nano_33_ble_sense/nano_bootloader.ld create mode 100644 ports/nrf/boards/arduino_nano_33_ble_sense/pins.csv diff --git a/ports/nrf/boards/arduino_nano_33_ble_sense/board.c b/ports/nrf/boards/arduino_nano_33_ble_sense/board.c new file mode 100644 index 0000000000..954639756b --- /dev/null +++ b/ports/nrf/boards/arduino_nano_33_ble_sense/board.c @@ -0,0 +1,67 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2022 Arduino SA + * + * 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 "nrf.h" +#include "nrf_gpio.h" +#include "nrf_rtc.h" + +#define PIN_ENABLE_SENSORS_3V3 (22u) +#define PIN_ENABLE_I2C_PULLUP (32u) +#define DFU_MAGIC_SERIAL_ONLY_RESET (0xb0) + +void NANO33_board_early_init(void) { + // Errata Nano33BLE - I2C pullup is on SWO line, need to disable TRACE + // was being enabled by nrfx_clock_anomaly_132 + CoreDebug->DEMCR = 0; + NRF_CLOCK->TRACECONFIG = 0; + + // Bootloader enables interrupt on COMPARE[0], which we don't handle + // Disable it here to avoid getting stuck when OVERFLOW irq is triggered + nrf_rtc_event_disable(NRF_RTC1, NRF_RTC_INT_COMPARE0_MASK); + nrf_rtc_int_disable(NRF_RTC1, NRF_RTC_INT_COMPARE0_MASK); + + // Always enable I2C pullup and power on startup + // Change for maximum powersave + nrf_gpio_cfg_output(PIN_ENABLE_SENSORS_3V3); + nrf_gpio_cfg_output(PIN_ENABLE_I2C_PULLUP); + + nrf_gpio_pin_set(PIN_ENABLE_SENSORS_3V3); + nrf_gpio_pin_set(PIN_ENABLE_I2C_PULLUP); +} + +void NANO33_board_deinit(void) { + nrf_gpio_cfg_output(PIN_ENABLE_SENSORS_3V3); + nrf_gpio_cfg_output(PIN_ENABLE_I2C_PULLUP); + + nrf_gpio_pin_clear(PIN_ENABLE_SENSORS_3V3); + nrf_gpio_pin_clear(PIN_ENABLE_I2C_PULLUP); +} + +void NANO33_board_enter_bootloader(void) { + __disable_irq(); + NRF_POWER->GPREGRET = DFU_MAGIC_SERIAL_ONLY_RESET; + NVIC_SystemReset(); +} diff --git a/ports/nrf/boards/arduino_nano_33_ble_sense/board.json b/ports/nrf/boards/arduino_nano_33_ble_sense/board.json new file mode 100644 index 0000000000..9488c75f84 --- /dev/null +++ b/ports/nrf/boards/arduino_nano_33_ble_sense/board.json @@ -0,0 +1,25 @@ +{ + "deploy": [ + "./deploy.md" + ], + "docs": "", + "features": [ + "Bluetooth 5.0", + "IMU LSM9DS1", + "Humidity sensor HTS221", + "Pressure sensor LPS22H", + "Proximity, Light, RGB sensor APDS-9960", + "Microphone MPM3610", + "Crypto IC ARM CC310", + "USB-MICRO", + "Breadboard Friendly" + ], + "images": [ + "ABX00031_01.iso_998x749.jpg" + ], + "mcu": "nRF52840", + "product": "Arduino Nano 33 BLE Sense", + "thumbnail": "", + "url": "https://store.arduino.cc/products/arduino-nano-33-ble-sense", + "vendor": "Arduino" +} diff --git a/ports/nrf/boards/arduino_nano_33_ble_sense/deploy.md b/ports/nrf/boards/arduino_nano_33_ble_sense/deploy.md new file mode 100644 index 0000000000..a2d08f2c81 --- /dev/null +++ b/ports/nrf/boards/arduino_nano_33_ble_sense/deploy.md @@ -0,0 +1,23 @@ +### Update the bootloader + +Before deploying any firmware, make sure you have the updated Arduino Nano 33 BLE bootloader, which relocates the bootloader so the softdevice doesn't overwrite it. Please see: + +https://docs.arduino.cc/tutorials/nano-33-ble/getting-started-omv + +### Via Arduino bootloader and BOSSA + +Download BOSSA from https://github.com/shumatech/BOSSA/ and double tap reset button to enter the Arduino bootloader + +```bash +bossac -e -w --offset=0x16000 --port=ttyACM0 -i -d -U -R build-arduino_nano_33_ble_sense-s140/firmware.bin +``` + +Alternatively, a Linux binary can be found here: https://github.com/openmv/openmv/blob/master/tools/bossac + +### Via nrfprog + +This board can also be programmed via nrfjprog (with Jlink for example), from MicroPython source repository: + +```bash +make -j8 BOARD=arduino_nano_33_ble_sense SD=s140 deploy +``` diff --git a/ports/nrf/boards/arduino_nano_33_ble_sense/manifest.py b/ports/nrf/boards/arduino_nano_33_ble_sense/manifest.py new file mode 100644 index 0000000000..dbc8104dc2 --- /dev/null +++ b/ports/nrf/boards/arduino_nano_33_ble_sense/manifest.py @@ -0,0 +1,4 @@ +include("$(PORT_DIR)/modules/manifest.py") +freeze("$(MPY_DIR)/drivers/hts221", "hts221.py") +freeze("$(MPY_DIR)/drivers/lps22h", "lps22h.py") +freeze("$(MPY_DIR)/drivers/lsm9ds1", "lsm9ds1.py") diff --git a/ports/nrf/boards/arduino_nano_33_ble_sense/mpconfigboard.h b/ports/nrf/boards/arduino_nano_33_ble_sense/mpconfigboard.h new file mode 100644 index 0000000000..4a16b6110b --- /dev/null +++ b/ports/nrf/boards/arduino_nano_33_ble_sense/mpconfigboard.h @@ -0,0 +1,75 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * The MIT License (MIT) + * Copyright (c) 2022 Arduino SA + */ + +#define MICROPY_HW_BOARD_NAME "Arduino Nano 33 BLE Sense" +#define MICROPY_HW_MCU_NAME "NRF52840" + +#define MICROPY_MBFS (1) + +#define MICROPY_BOARD_EARLY_INIT NANO33_board_early_init +#define MICROPY_BOARD_DEINIT NANO33_board_deinit +#define MICROPY_BOARD_ENTER_BOOTLOADER(nargs, args) NANO33_board_enter_bootloader() + +#define MICROPY_PY_MACHINE_UART (1) +#define MICROPY_PY_MACHINE_HW_PWM (1) +#define MICROPY_PY_MACHINE_HW_SPI (1) +#define MICROPY_PY_MACHINE_TIMER (1) +#define MICROPY_PY_MACHINE_RTCOUNTER (1) +#define MICROPY_PY_MACHINE_I2C (1) +#define MICROPY_PY_MACHINE_ADC (1) +#define MICROPY_PY_MACHINE_TEMP (1) + +#define MICROPY_HW_USB_CDC (1) +#define MICROPY_HW_HAS_LED (1) +#define MICROPY_HW_HAS_SWITCH (0) +#define MICROPY_HW_HAS_FLASH (0) +#define MICROPY_HW_HAS_SDCARD (0) +#define MICROPY_HW_HAS_MMA7660 (0) +#define MICROPY_HW_HAS_LIS3DSH (0) +#define MICROPY_HW_HAS_LCD (0) +#define MICROPY_HW_ENABLE_RNG (1) +#define MICROPY_HW_ENABLE_RTC (1) +#define MICROPY_HW_ENABLE_TIMER (0) +#define MICROPY_HW_ENABLE_SERVO (0) +#define MICROPY_HW_ENABLE_DAC (0) +#define MICROPY_HW_ENABLE_CAN (0) + +// LEDs config +#define MICROPY_HW_LED_COUNT (4) // 3 RGB + 1 Yellow +#define MICROPY_HW_LED_PULLUP (1) // RGB LED is active low +#define MICROPY_HW_LED4_PULLUP (0) // Yellow is active high +#define MICROPY_HW_LED1 (24) // RED +#define MICROPY_HW_LED2 (16) // GREEN +#define MICROPY_HW_LED3 (6) // BLUE +#define MICROPY_HW_LED4 (13) // Yellow +#define HELP_TEXT_BOARD_LED "1,2,3,4" + +// UART config +#define MICROPY_HW_UART1_TX (32 + 3) +#define MICROPY_HW_UART1_RX (32 + 10) +// #define MICROPY_HW_UART1_CTS (7) +// #define MICROPY_HW_UART1_RTS (5) +// #define MICROPY_HW_UART1_HWFC (1) + +// SPI0 config +#define MICROPY_HW_SPI0_NAME "SPI0" +#define MICROPY_HW_SPI0_SCK (13) +#define MICROPY_HW_SPI0_MOSI (32 + 1) +#define MICROPY_HW_SPI0_MISO (32 + 8) + +// PWM config +#define MICROPY_HW_PWM0_NAME "PWM0" +#define MICROPY_HW_PWM1_NAME "PWM1" +#define MICROPY_HW_PWM2_NAME "PWM2" +#define MICROPY_HW_PWM3_NAME "PWM3" + +#define MICROPY_HW_USB_VID (0x2341) +#define MICROPY_HW_USB_PID (0x025A) +#define MICROPY_HW_USB_CDC_1200BPS_TOUCH (1) + +void NANO33_board_early_init(void); +void NANO33_board_deinit(void); +void NANO33_board_enter_bootloader(void); diff --git a/ports/nrf/boards/arduino_nano_33_ble_sense/mpconfigboard.mk b/ports/nrf/boards/arduino_nano_33_ble_sense/mpconfigboard.mk new file mode 100644 index 0000000000..cb2ff5c6b8 --- /dev/null +++ b/ports/nrf/boards/arduino_nano_33_ble_sense/mpconfigboard.mk @@ -0,0 +1,12 @@ +MCU_SERIES = m4 +MCU_VARIANT = nrf52 +MCU_SUB_VARIANT = nrf52840 +SOFTDEV_VERSION = 6.1.1 +SD=s140 + +LD_FILES += boards/arduino_nano_33_ble_sense/nano_bootloader.ld boards/nrf52840_1M_256k.ld + +NRF_DEFINES += -DNRF52840_XXAA + +MICROPY_VFS_LFS2 = 1 +FROZEN_MANIFEST ?= $(BOARD_DIR)/manifest.py diff --git a/ports/nrf/boards/arduino_nano_33_ble_sense/nano_bootloader.ld b/ports/nrf/boards/arduino_nano_33_ble_sense/nano_bootloader.ld new file mode 100644 index 0000000000..209a1d447a --- /dev/null +++ b/ports/nrf/boards/arduino_nano_33_ble_sense/nano_bootloader.ld @@ -0,0 +1 @@ +_flash_start = 0xe0000; diff --git a/ports/nrf/boards/arduino_nano_33_ble_sense/pins.csv b/ports/nrf/boards/arduino_nano_33_ble_sense/pins.csv new file mode 100644 index 0000000000..9d931634f6 --- /dev/null +++ b/ports/nrf/boards/arduino_nano_33_ble_sense/pins.csv @@ -0,0 +1,50 @@ +P0,P0 +P1,P1 +P2,P2,ADC0_IN0 +P3,P3,ADC0_IN1 +P4,P4,ADC0_IN2 +P5,P5,ADC0_IN3 +P6,P6 +P7,P7 +P8,P8 +P9,P9 +P10,P10 +P11,P11 +P12,P12 +P13,P13 +P14,P14 +P15,P15 +P16,P16 +P17,P17 +P18,P18 +P19,P19 +P20,P20 +P21,P21 +P22,P22 +P23,P23 +P24,P24 +P25,P25 +P26,P26 +P27,P27 +P28,P28,ADC0_IN4 +P29,P29,ADC0_IN5 +P30,P30,ADC0_IN6 +P31,P31,ADC0_IN7 +P32,P32 +P33,P33 +P34,P34 +P35,P35 +P36,P36 +P37,P37 +P38,P38 +P39,P39 +P40,P40 +P41,P41 +P42,P42 +P43,P43 +P44,P44 +P45,P45 +P46,P46 +P47,P47 +I2C_SCL,P2 +I2C_SDA,P31