From 85f898142982ddffdd499d583ef2822c5f9c5f63 Mon Sep 17 00:00:00 2001 From: iabdalkader Date: Tue, 5 Jul 2022 22:13:17 +0200 Subject: [PATCH 1/4] drivers: Add HTS221 humidity sensor driver. --- drivers/hts221.py | 91 +++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 91 insertions(+) create mode 100644 drivers/hts221.py diff --git a/drivers/hts221.py b/drivers/hts221.py new file mode 100644 index 0000000000000..fec52a7389a98 --- /dev/null +++ b/drivers/hts221.py @@ -0,0 +1,91 @@ +""" +The MIT License (MIT) + +Copyright (c) 2013-2022 Ibrahim Abdelkader +Copyright (c) 2013-2022 Kwabena W. Agyeman + +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. + +HTS221 driver driver for MicroPython. +Original source: https://github.com/ControlEverythingCommunity/HTS221/blob/master/Python/HTS221.py + +Example usage: + +import time +import hts221 +from machine import Pin, I2C + +bus = I2C(1, scl=Pin(15), sda=Pin(14)) +hts = hts221.HTS221(bus) + +while (True): + rH = hts.humidity() + temp = hts.temperature() + print ("rH: %.2f%% T: %.2fC" %(rH, temp)) + time.sleep_ms(100) +""" + +import struct + + +class HTS221: + def __init__(self, i2c, data_rate=1, address=0x5F): + self.bus = i2c + self.odr = data_rate + self.slv_addr = address + + # Set configuration register + # Humidity and temperature average configuration + self.bus.writeto_mem(self.slv_addr, 0x10, b"\x1B") + + # Set control register + # PD | BDU | ODR + cfg = 0x80 | 0x04 | (self.odr & 0x3) + self.bus.writeto_mem(self.slv_addr, 0x20, bytes([cfg])) + + # Read Calibration values from non-volatile memory of the device + # Humidity Calibration values + self.H0 = self._read_reg(0x30, 1) / 2 + self.H1 = self._read_reg(0x31, 1) / 2 + self.H2 = self._read_reg(0x36, 2) + self.H3 = self._read_reg(0x3A, 2) + + # Temperature Calibration values + raw = self._read_reg(0x35, 1) + self.T0 = ((raw & 0x03) * 256) + self._read_reg(0x32, 1) + self.T1 = ((raw & 0x0C) * 64) + self._read_reg(0x33, 1) + self.T2 = self._read_reg(0x3C, 2) + self.T3 = self._read_reg(0x3E, 2) + + def _read_reg(self, reg_addr, size): + fmt = "B" if size == 1 else "H" + reg_addr = reg_addr if size == 1 else reg_addr | 0x80 + return struct.unpack(fmt, self.bus.readfrom_mem(self.slv_addr, reg_addr, size))[0] + + def humidity(self): + rH = self._read_reg(0x28, 2) + return (self.H1 - self.H0) * (rH - self.H2) / (self.H3 - self.H2) + self.H0 + + def temperature(self): + temp = self._read_reg(0x2A, 2) + if temp > 32767: + temp -= 65536 + return ((self.T1 - self.T0) / 8.0) * (temp - self.T2) / (self.T3 - self.T2) + ( + self.T0 / 8.0 + ) From 3dfca96033700498a82d3e80e5fc5767cb9a5ced Mon Sep 17 00:00:00 2001 From: iabdalkader Date: Tue, 5 Jul 2022 22:14:10 +0200 Subject: [PATCH 2/4] drivers: Add LSM9DS1 IMU driver. --- drivers/lsm9ds1.py | 189 +++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 189 insertions(+) create mode 100644 drivers/lsm9ds1.py diff --git a/drivers/lsm9ds1.py b/drivers/lsm9ds1.py new file mode 100644 index 0000000000000..5d9942a7b3469 --- /dev/null +++ b/drivers/lsm9ds1.py @@ -0,0 +1,189 @@ +""" +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. + + +LSM9DS1 - 9DOF inertial sensor of STMicro driver for MicroPython. +The sensor contains an accelerometer / gyroscope / magnetometer +Uses the internal FIFO to store up to 16 gyro/accel data, use the iter_accel_gyro generator to access it. + +Example usage: + +import time +from lsm9ds1 import LSM9DS1 +from machine import Pin, I2C + +lsm = LSM9DS1(I2C(1, scl=Pin(15), sda=Pin(14))) + +while (True): + #for g,a in lsm.iter_accel_gyro(): print(g,a) # using fifo + print('Accelerometer: x:{:>8.3f} y:{:>8.3f} z:{:>8.3f}'.format(*lsm.accel())) + print('Magnetometer: x:{:>8.3f} y:{:>8.3f} z:{:>8.3f}'.format(*lsm.magnet())) + print('Gyroscope: x:{:>8.3f} y:{:>8.3f} z:{:>8.3f}'.format(*lsm.gyro())) + print("") + time.sleep_ms(100) +""" +import array + + +_WHO_AM_I = const(0xF) +_CTRL_REG1_G = const(0x10) +_INT_GEN_SRC_G = const(0x14) +_OUT_TEMP = const(0x15) +_OUT_G = const(0x18) +_CTRL_REG4_G = const(0x1E) +_STATUS_REG = const(0x27) +_OUT_XL = const(0x28) +_FIFO_CTRL_REG = const(0x2E) +_FIFO_SRC = const(0x2F) +_OFFSET_REG_X_M = const(0x05) +_CTRL_REG1_M = const(0x20) +_OUT_M = const(0x28) +_SCALE_GYRO = const(((245, 0), (500, 1), (2000, 3))) +_SCALE_ACCEL = const(((2, 0), (4, 2), (8, 3), (16, 1))) + + +class LSM9DS1: + def __init__(self, i2c, address_gyro=0x6B, address_magnet=0x1E): + self.i2c = i2c + self.address_gyro = address_gyro + self.address_magnet = address_magnet + # check id's of accelerometer/gyro and magnetometer + if (self.magent_id() != b"=") or (self.gyro_id() != b"h"): + raise OSError( + "Invalid LSM9DS1 device, using address {}/{}".format(address_gyro, address_magnet) + ) + # allocate scratch buffer for efficient conversions and memread op's + self.scratch = array.array("B", [0, 0, 0, 0, 0, 0]) + self.scratch_int = array.array("h", [0, 0, 0]) + self.init_gyro_accel() + self.init_magnetometer() + + def init_gyro_accel(self, sample_rate=6, scale_gyro=0, scale_accel=0): + """Initalizes Gyro and Accelerator. + sample rate: 0-6 (off, 14.9Hz, 59.5Hz, 119Hz, 238Hz, 476Hz, 952Hz) + scale_gyro: 0-2 (245dps, 500dps, 2000dps ) + scale_accel: 0-3 (+/-2g, +/-4g, +/-8g, +-16g) + """ + assert sample_rate <= 6, "invalid sampling rate: %d" % sample_rate + assert scale_gyro <= 2, "invalid gyro scaling: %d" % scale_gyro + assert scale_accel <= 3, "invalid accelerometer scaling: %d" % scale_accel + + i2c = self.i2c + addr = self.address_gyro + mv = memoryview(self.scratch) + # angular control registers 1-3 / Orientation + mv[0] = ((sample_rate & 0x07) << 5) | ((_SCALE_GYRO[scale_gyro][1] & 0x3) << 3) + mv[1:4] = b"\x00\x00\x00" + i2c.writeto_mem(addr, _CTRL_REG1_G, mv[:5]) + # ctrl4 - enable x,y,z, outputs, no irq latching, no 4D + # ctrl5 - enable all axes, no decimation + # ctrl6 - set scaling and sample rate of accel + # ctrl7,8 - leave at default values + # ctrl9 - FIFO enabled + mv[0] = mv[1] = 0x38 + mv[2] = ((sample_rate & 7) << 5) | ((_SCALE_ACCEL[scale_accel][1] & 0x3) << 3) + mv[3] = 0x00 + mv[4] = 0x4 + mv[5] = 0x2 + i2c.writeto_mem(addr, _CTRL_REG4_G, mv[:6]) + + # fifo: use continous mode (overwrite old data if overflow) + i2c.writeto_mem(addr, _FIFO_CTRL_REG, b"\x00") + i2c.writeto_mem(addr, _FIFO_CTRL_REG, b"\xc0") + + self.scale_gyro = 32768 / _SCALE_GYRO[scale_gyro][0] + self.scale_accel = 32768 / _SCALE_ACCEL[scale_accel][0] + + def init_magnetometer(self, sample_rate=7, scale_magnet=0): + """ + sample rates = 0-7 (0.625, 1.25, 2.5, 5, 10, 20, 40, 80Hz) + scaling = 0-3 (+/-4, +/-8, +/-12, +/-16 Gauss) + """ + assert sample_rate < 8, "invalid sample rate: %d (0-7)" % sample_rate + assert scale_magnet < 4, "invalid scaling: %d (0-3)" % scale_magnet + i2c = self.i2c + addr = self.address_magnet + mv = memoryview(self.scratch) + mv[0] = 0x40 | (sample_rate << 2) # ctrl1: high performance mode + mv[1] = scale_magnet << 5 # ctrl2: scale, normal mode, no reset + mv[2] = 0x00 # ctrl3: continous conversion, no low power, I2C + mv[3] = 0x08 # ctrl4: high performance z-axis + mv[4] = 0x00 # ctr5: no fast read, no block update + i2c.writeto_mem(addr, _CTRL_REG1_M, mv[:5]) + self.scale_factor_magnet = 32768 / ((scale_magnet + 1) * 4) + + def calibrate_magnet(self, offset): + """ + offset is a magnet vecor that will be substracted by the magnetometer + for each measurement. It is written to the magnetometer's offset register + """ + offset = [int(i * self.scale_factor_magnet) for i in offset] + mv = memoryview(self.scratch) + mv[0] = offset[0] & 0xFF + mv[1] = offset[0] >> 8 + mv[2] = offset[1] & 0xFF + mv[3] = offset[1] >> 8 + mv[4] = offset[2] & 0xFF + mv[5] = offset[2] >> 8 + self.i2c.writeto_mem(self.address_magnet, _OFFSET_REG_X_M, mv[:6]) + + def gyro_id(self): + return self.i2c.readfrom_mem(self.address_gyro, _WHO_AM_I, 1) + + def magent_id(self): + return self.i2c.readfrom_mem(self.address_magnet, _WHO_AM_I, 1) + + def magnet(self): + """Returns magnetometer vector in gauss. + raw_values: if True, the non-scaled adc values are returned + """ + mv = memoryview(self.scratch_int) + f = self.scale_factor_magnet + self.i2c.readfrom_mem_into(self.address_magnet, _OUT_M | 0x80, mv) + return (mv[0] / f, mv[1] / f, mv[2] / f) + + def gyro(self): + """Returns gyroscope vector in degrees/sec.""" + mv = memoryview(self.scratch_int) + f = self.scale_gyro + self.i2c.readfrom_mem_into(self.address_gyro, _OUT_G | 0x80, mv) + return (mv[0] / f, mv[1] / f, mv[2] / f) + + def accel(self): + """Returns acceleration vector in gravity units (9.81m/s^2).""" + mv = memoryview(self.scratch_int) + f = self.scale_accel + self.i2c.readfrom_mem_into(self.address_gyro, _OUT_XL | 0x80, mv) + return (mv[0] / f, mv[1] / f, mv[2] / f) + + def iter_accel_gyro(self): + """A generator that returns tuples of (gyro,accelerometer) data from the fifo.""" + while True: + fifo_state = int.from_bytes( + self.i2c.readfrom_mem(self.address_gyro, _FIFO_SRC, 1), "big" + ) + if fifo_state & 0x3F: + # print("Available samples=%d" % (fifo_state & 0x1f)) + yield self.gyro(), self.accel() + else: + break From 06ac31b840d9c243bd243c811bb718d2c972403d Mon Sep 17 00:00:00 2001 From: iabdalkader Date: Tue, 5 Jul 2022 22:14:48 +0200 Subject: [PATCH 3/4] drivers: Add LPS22HB/HH pressure sensor driver. --- drivers/lps22h.py | 117 ++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 117 insertions(+) create mode 100644 drivers/lps22h.py diff --git a/drivers/lps22h.py b/drivers/lps22h.py new file mode 100644 index 0000000000000..8d90b29178677 --- /dev/null +++ b/drivers/lps22h.py @@ -0,0 +1,117 @@ +""" +The MIT License (MIT) + +Copyright (c) 2016-2019 shaoziyang +Copyright (c) 2022 Ibrahim Abdelkader + +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. + +LPS22HB/HH pressure sensor driver for MicroPython. + +Example usage: + +import time +from lps22h import LPS22H +from machine import Pin, I2C + +bus = I2C(1, scl=Pin(15), sda=Pin(14)) +lps = LPS22H(bus, oneshot=False) + +while (True): + print("Pressure: %.2f hPa Temperature: %.2f C"%(lps.pressure(), lps.temperature())) + time.sleep_ms(10) +""" +import machine + +_LPS22_CTRL_REG1 = const(0x10) +_LPS22_CTRL_REG2 = const(0x11) +_LPS22_STATUS = const(0x27) +_LPS22_TEMP_OUT_L = const(0x2B) +_LPS22_PRESS_OUT_XL = const(0x28) +_LPS22_PRESS_OUT_L = const(0x29) + + +class LPS22H: + def __init__(self, i2c, address=0x5C, oneshot=False): + self.i2c = i2c + self.addr = address + self.oneshot = oneshot + self.buf = bytearray(1) + + if hasattr(machine, "idle"): + self._go_idle = machine.idle() + else: + import time + + self._go_idle = lambda: time.sleep_ms(1) + + # ODR=1 EN_LPFP=1 BDU=1 + self._write_reg(_LPS22_CTRL_REG1, 0x1A) + self.set_oneshot_mode(self.oneshot) + + def _int16(self, d): + return d if d < 0x8000 else d - 0x10000 + + def _write_reg(self, reg, dat): + self.buf[0] = dat + self.i2c.writeto_mem(self.addr, reg, self.buf) + + def _read_reg(self, reg, width=8): + self.i2c.readfrom_mem_into(self.addr, reg, self.buf) + val = self.buf[0] + if width == 16: + val |= self._read_reg(reg + 1) << 8 + return val + + def _tigger_oneshot(self, b): + if self.oneshot: + self._write_reg(_LPS22_CTRL_REG2, self._read_reg(_LPS22_CTRL_REG2) | 0x01) + self._read_reg(0x28 + b * 2) + while True: + if self._read_reg(_LPS22_STATUS) & b: + return + self._go_idle() + + def set_oneshot_mode(self, oneshot): + self._read_reg(_LPS22_CTRL_REG1) + self.oneshot = oneshot + if oneshot: + self.buf[0] &= 0x0F + else: + self.buf[0] |= 0x10 + self._write_reg(_LPS22_CTRL_REG1, self.buf[0]) + + def pressure(self): + if self.oneshot: + self._tigger_oneshot(1) + return ( + self._read_reg(_LPS22_PRESS_OUT_XL) + self._read_reg(_LPS22_PRESS_OUT_L, 16) * 256 + ) / 4096 + + def temperature(self): + if self.oneshot: + self._tigger_oneshot(2) + return self._int16(self._read_reg(_LPS22_TEMP_OUT_L, 16)) / 100 + + def altitude(self): + return ( + (((1013.25 / self.pressure()) ** (1 / 5.257)) - 1.0) + * (self.temperature() + 273.15) + / 0.0065 + ) From 542b992ecdd2f5d0f15d5b03560ca39b9b62d09d Mon Sep 17 00:00:00 2001 From: iabdalkader Date: Thu, 21 Apr 2022 11:49:12 +0200 Subject: [PATCH 4/4] nrf: Add support for Arduino Nano 33 BLE 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 0000000000000..954639756bc27 --- /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 0000000000000..9488c75f8419e --- /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 0000000000000..a2d08f2c81328 --- /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 0000000000000..adc61d9cc94ae --- /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.py") +freeze("$(MPY_DIR)/drivers/", "lps22h.py") +freeze("$(MPY_DIR)/drivers/", "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 0000000000000..eeef032330f9a --- /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 0000000000000..cb2ff5c6b81cd --- /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 0000000000000..209a1d447afb1 --- /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 0000000000000..9d931634f627d --- /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